]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
TrajectoryPlanner & gmapping tuning
authorErik Andresen <erik@vontaene.de>
Sat, 28 Jan 2017 22:00:20 +0000 (23:00 +0100)
committerErik Andresen <erik@vontaene.de>
Sat, 28 Jan 2017 22:00:20 +0000 (23:00 +0100)
config/base_local_planner_params.yaml
launch/gmapping.launch

index 0ce322b1d25fd45cc313cccf30f7c46c5a1682cb..18234088eae5148d365085886e2f23e2e6ea5819 100644 (file)
@@ -23,10 +23,13 @@ TrajectoryPlannerROS:
   # Whether to score based on the robot's heading to the path or its distance from the path, default: false
   heading_scoring: true
 
   # Whether to score based on the robot's heading to the path or its distance from the path, default: false
   heading_scoring: true
 
+  # How far to look ahead in time in seconds along the simulated trajectory when using heading scoring, default: 0.1
+  heading_scoring_timestep: 0.3
+
 DWAPlannerROS:
   acc_lim_x: 10.07
   acc_lim_y: 0.0
 DWAPlannerROS:
   acc_lim_x: 10.07
   acc_lim_y: 0.0
-  acc_lim_th: 12.00
+  acc_lim_th: 6.00
 
   max_vel_x: 0.5
   min_vel_x: 0.0 # no backward movement
 
   max_vel_x: 0.5
   min_vel_x: 0.0 # no backward movement
@@ -40,3 +43,8 @@ DWAPlannerROS:
 
   xy_goal_tolerance: 0.1
   yaw_goal_tolerance: 0.2
 
   xy_goal_tolerance: 0.1
   yaw_goal_tolerance: 0.2
+
+  # The weighting for how much the controller should attempt to avoid obstacles, default: 0.01
+  occdist_scale: 0.02
+  # The weighting for how much the controller should stay close to the path it was given, default: 32.0
+  path_distance_bias: 64.0
index 03ce7986fdac93280098c51075d6a241c26ca635..bf72788729e87865a780f5cc526f1e2e449f6a54 100644 (file)
                <!-- 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+ -->
                <!-- 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"/>
+               <param name="minimumScore" value="40"/>
                <!-- 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 -->
                <!-- 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"/>
+               <param name="particles" value="70"/>
                <!-- 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) -->
                <!-- 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) -->
@@ -32,5 +32,9 @@
                <param name="str" value="0.0"/>
                <!-- Odometry error in rotation as a function of rotation (theta/theta) -->
                <param name="stt" value="0.0"/>
                <param name="str" value="0.0"/>
                <!-- Odometry error in rotation as a function of rotation (theta/theta) -->
                <param name="stt" value="0.0"/>
+               <!-- The number of iterations of the scanmatcher, default: 5 -->
+               <param name="iterations" value="7"/>
+               <!-- The sigma of a beam used for likelihood computation, default: 0.075 -->
+               <param name="lsigma" value="0.085"/>
        </node>
 </launch>
        </node>
 </launch>