]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
exploration tuning
authorErik Andresen <erik@vontaene.de>
Sat, 1 Oct 2016 14:56:55 +0000 (16:56 +0200)
committerErik Andresen <erik@vontaene.de>
Sat, 1 Oct 2016 14:56:55 +0000 (16:56 +0200)
config/base_local_planner_params.yaml
config/costmap_common_params.yaml
config/costmap_exploration.yaml
data/motor_ctrl_pid_values.ods
launch/exploration.launch
launch/move_base.launch
urdf/wild_thumper.urdf.xacro

index bbd95c1c339522ef49e863a4ac614b52133d3062..b48a72f681513ff5b6cad33745371744141ac0ad 100644 (file)
@@ -1,10 +1,10 @@
 TrajectoryPlannerROS:
   min_vel_x: 0.2
-  max_vel_x: 0.3
-  min_vel_theta: -0.4
-  max_vel_theta: 0.4
+  max_vel_x: 0.5
+  min_vel_theta: -1.0
+  max_vel_theta: 1.0
   min_in_place_vel_theta: 0.4
-  max_rotational_vel: 0.5 # used by rotate recovery
+  max_rotational_vel: 1.0 # used by rotate recovery
 
   acc_lim_x: 10.07
   acc_lim_y: 0.0
@@ -28,8 +28,8 @@ DWAPlannerROS:
 
   max_trans_vel: 0.5
   min_trans_vel: 0.2
-  max_rot_vel: 0.5
+  max_rot_vel: 1.0
   min_rot_vel: 0.4
 
-  xy_goal_tolerance: 0.20
-  yaw_goal_tolerance: 0.3
+  xy_goal_tolerance: 0.1
+  yaw_goal_tolerance: 0.2
index 6e4b3709915ec67516a7e91484845b8980f21564..02ff12dc426672e9bc013215d8f4a245dcf5babf 100644 (file)
@@ -1,8 +1,10 @@
 footprint: [[0.14, 0.16], [-0.14, 0.16], [-0.14, -0.16], [0.14, -0.16]]
-inflation_radius: 0.5
 
 obstacle_layer:
   observation_sources: laser_scan_sensor
   obstacle_range: 2.5
   raytrace_range: 3.0
   laser_scan_sensor: {sensor_frame: camera_depth_frame, data_type: LaserScan, topic: scan, marking: true, clearing: true}
+
+inflation_layer:
+  inflation_radius: 0.5
index 26f38002682f8d61fe6b1917e7b57fd05dc66cbd..0f5bc4300aec73f1e88564d7b0bfe6dbf3a685d7 100644 (file)
@@ -1,20 +1,21 @@
 #must match incoming static map
 global_frame: map
-robot_base_frame: base_link
-resolution: 0.05
+robot_base_frame: base_footprint
+update_frequency: 5.0
+resolution: 0.01
 
-track_unknown_space: true
 rolling_window: false
+track_unknown_space: true
 
 plugins: 
-- {name: static,           type: "costmap_2d::StaticLayer"}            
+- {name: static_layer, type: 'costmap_2d::StaticLayer'}
 - {name: explore_boundary, type: "frontier_exploration::BoundedExploreLayer"}
 #Can disable sensor layer if gmapping is fast enough to update scans
-- {name: sensor,           type: "costmap_2d::ObstacleLayer"}
-- {name: inflation,        type: "costmap_2d::InflationLayer"}
+- {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
+- {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
 
 explore_boundary:
-  resize_to_boundary: false
+  resize_to_boundary: true
   frontier_travel_point: middle
   #set to false for gmapping, true if re-exploring a known area
-  explore_clear_space: false
+  explore_clear_space: true
index 543fa457d9bf6497c7c682fecd78704306e15934..0a1186aff0e7c8a705b6cc857d18b54a5a15c2df 100644 (file)
Binary files a/data/motor_ctrl_pid_values.ods and b/data/motor_ctrl_pid_values.ods differ
index a60826565602e09cd5f14e1fca2423e2d547fe75..0c81ea065a9b1570ed06e5070577a013703d5ab9 100644 (file)
@@ -3,7 +3,7 @@
        <node pkg="frontier_exploration" type="explore_client" name="explore_client" output="screen"/>
 
        <node pkg="frontier_exploration" type="explore_server" name="explore_server" output="screen" >
-               <param name="frequency" type="double" value="1.0"/>
+               <param name="frequency" type="double" value="2.0"/>
                <!-- Should be less than sensor range -->
                <param name="goal_aliasing" type="double" value="2.0"/>
 
index a046e6eaf60522b917730cf8d03bd001e3461702..2ee4b5a953fbcc2749296487a0adc05aa6bfb823 100644 (file)
@@ -3,7 +3,7 @@
        <arg name="slam_gmapping" default="false" />
        <arg name="map_file" default="$(find wild_thumper)/data/map.yaml" />
        <arg name="nomap" default="false" />
-       <arg name="base_local_planner" default="dwa_local_planner/DWAPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS -->
+       <arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS -->
 
        <!-- Run AMCL -->
        <group unless="$(arg nomap)">
@@ -29,6 +29,7 @@
 
        <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
                <param name="base_local_planner" value="$(arg base_local_planner)"/>
+               <param name="controller_frequency" value="10.0" />
                <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
                <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
                <rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" unless="$(arg nomap)" />
index 417123f89c611417a903a86f30c8fb4f76df3ff3..1bd641e23a0a12bc4f9d22e76627abc646ea88f5 100644 (file)
@@ -6,7 +6,7 @@
        <link name="base_footprint">
                <visual>
                        <geometry>
-                               <box size="0.28 0.31 0.0"/>
+                               <box size="0.28 0.31 0.000001"/>
                        </geometry>
                        <material name="grey">
                                <color rgba="0.5 0.5 0.5 0.5"/>