]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
tune slam gmapping
authorErik Andresen <erik@vontaene.de>
Sat, 7 Jan 2017 19:43:02 +0000 (20:43 +0100)
committerErik Andresen <erik@vontaene.de>
Sat, 7 Jan 2017 19:43:02 +0000 (20:43 +0100)
config/base_local_planner_params.yaml
config/costmap_common_params.yaml
config/costmap_exploration.yaml
launch/exploration.launch
launch/gmapping.launch [new file with mode: 0644]
launch/model.launch [deleted file]
launch/move_base.launch

index b48a72f681513ff5b6cad33745371744141ac0ad..0ce322b1d25fd45cc313cccf30f7c46c5a1682cb 100644 (file)
@@ -8,14 +8,21 @@ TrajectoryPlannerROS:
 
   acc_lim_x: 10.07
   acc_lim_y: 0.0
-  acc_lim_theta: 12.00
+  acc_lim_theta: 6.00
 
   holonomic_robot: false
+  # gdist_scale and pdist_scale parameters should assume meters
   meter_scoring: true
 
   xy_goal_tolerance: 0.20
   yaw_goal_tolerance: 0.3
 
+  # The weighting for how much the controller should attempt to avoid obstacles, default: 0.01
+  occdist_scale: 0.02
+
+  # Whether to score based on the robot's heading to the path or its distance from the path, default: false
+  heading_scoring: true
+
 DWAPlannerROS:
   acc_lim_x: 10.07
   acc_lim_y: 0.0
index 674c1cc85d29ce5678b54b597dabab4edaeffc2a..566291241a7ace3e40b29f20fbe6bc3088a9d6a0 100644 (file)
@@ -7,7 +7,7 @@ obstacle_layer:
   laser_scan_sensor: {sensor_frame: camera_depth_frame, data_type: LaserScan, topic: scan, marking: true, clearing: true}
 
 inflation_layer:
-  inflation_radius: 0.25
+  inflation_radius: 0.20
 
 range_layer:
   topics: ["/range_forward", "/range_backward", "/range_left", "/range_right"]
index 63685630a384cd62a8d03a2bfd64f966d3b0d831..84c88efd4e137b9993a1b3f08568377e93588739 100644 (file)
@@ -22,13 +22,8 @@ static_layer:
   # map_topic: move_base/global_costmap/costmap
   subscribe_to_updates: true
 
-range_layer:
-  topics: ["/range_forward", "/range_backward"]
-  no_readings_timeout: 1.0
-  clear_on_max_reading: true
-
 explore_boundary:
   resize_to_boundary: false
   frontier_travel_point: middle
   # set to false for gmapping, true if re-exploring a known area
-  explore_clear_space: true
+  explore_clear_space: false
index 4df3aee234597a87baba7087f398d80195b0da0e..6d8e4de71e126dd123f52ecbde5518c69e0de6a9 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="2.0"/>
+               <param name="frequency" type="double" value="10.0"/>
                <!-- Should be less than sensor range -->
                <param name="goal_aliasing" type="double" value="1.0"/>
 
diff --git a/launch/gmapping.launch b/launch/gmapping.launch
new file mode 100644 (file)
index 0000000..03ce798
--- /dev/null
@@ -0,0 +1,36 @@
+<?xml version="1.0"?>
+<launch>
+       <arg name="use_sim_time" default="false" />
+       <param name="/use_sim_time" value="$(arg use_sim_time)"/>
+
+       <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping">
+               <param name="scan" value="scan" />
+               <param name="delta" value="0.01" />
+               <param name="map_update_interval" value="10.0" />
+               <param name="xmin" value="-5.0"/>
+               <param name="ymin" value="-5.0"/>
+               <param name="xmax" value="5.0"/>
+               <param name="ymax" value="5.0"/>
+               <param name="odom_frame" value="odom"/>
+               <!-- The maximum usable range of the laser. A beam is cropped to this value. -->
+               <param name="maxUrange" value="3.5"/>
+               <!-- The maximum range of the sensor. If regions with no obstacles within the range of the sensor should appear as free -->
+               <param name="maxRange" value="10.0"/>
+               <!-- Minimum score for considering the outcome of the scan matching good. Can avoid jumping pose, default: 0.0, max: 600+ -->
+               <param name="minimumScore" value="0"/>
+               <!-- Process a scan each time the robot translates this far -->
+               <param name="linearUpdate" value="0.30"/>
+               <!-- Process a scan each time the robot rotates this far -->
+               <param name="angularUpdate" value="0.436"/> <!-- 25 deg -->
+               <!-- Number of particles in the filter, default: 30 -->
+               <param name="particles" value="65"/>
+               <!-- Odometry error in translation as a function of translation (rho/rho) -->
+               <param name="srr" value="0.01"/>
+               <!-- Odometry error in translation as a function of rotation (rho/theta) -->
+               <param name="srt" value="0.03"/>
+               <!-- Odometry error in rotation as a function of translation (theta/rho) -->
+               <param name="str" value="0.0"/>
+               <!-- Odometry error in rotation as a function of rotation (theta/theta) -->
+               <param name="stt" value="0.0"/>
+       </node>
+</launch>
diff --git a/launch/model.launch b/launch/model.launch
deleted file mode 100644 (file)
index 8e4079b..0000000
+++ /dev/null
@@ -1,9 +0,0 @@
-<?xml version="1.0"?>
-<launch>
-       <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro"/>
-
-       <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen"/>
-
-       <!-- Spawn a robot into Gazebo -->
-       <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model wild_thumper" />
-</launch>
index 3c1880d8d4ae09f3cb55a9c49ae91ed4d6db21db..88705b986a889311881e490c8ca7496b26754f96 100644 (file)
                <param name="amcl/base_frame_id" value="base_footprint" />
        </group>
 
-       <node pkg="gmapping" type="slam_gmapping" name="slap_gmapping" if="$(arg slam_gmapping)">
-               <param name="scan" value="scan" />
-               <param name="delta" value="0.01" />
-               <param name="map_update_interval" value="5.0" />
-               <param name="linearUpdate" value="0.5" />
-               <param name="angularUpdate" value="0.25" />
-               <param name="xmin" value="-5.0"/>
-               <param name="ymin" value="-5.0"/>
-               <param name="xmax" value="5.0"/>
-               <param name="ymax" value="5.0"/>
-               <param name="odom_frame" value="odom"/>
-               <param name="maxUrange" value="6.0"/>
-               <param name="maxRange" value="8.0"/>
-               <param name="minimumScore" value="200"/>
-               <param name="linearUpdate" value="0.5"/>
-               <param name="particles" value="80"/>
-       </node>
+       <include file="$(find wild_thumper)/launch/gmapping.launch" if="$(arg slam_gmapping)" />
 
        <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
                <param name="base_local_planner" value="$(arg base_local_planner)"/>