- {name: static_layer, type: 'costmap_2d::StaticLayer'}
- {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
-inflation_layer:
- # low slope decay curve
- inflation_radius: 1.75
- cost_scaling_factor: 2.58
+ inflation_layer:
+ # low slope decay curve
+ inflation_radius: 1.75
+ cost_scaling_factor: 2.58
<launch>
<arg name="slam_gmapping" default="false" />
<arg name="map_file" default="$(find wild_thumper)/data/map.yaml" />
+ <arg name="global_utm" default="false" />
<arg name="nomap" default="false" />
<arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS -->
<!-- Specifies the expected noise in odometry's rotation estimate from translational component of the robot's motion. -->
<param name="odom_alpha2" value="0.00001" />
<!-- Specifies the expected noise in odometry's translation estimate from the translational component of the robot's motion. -->
- <param name="odom_alpha3" value="0.01" />
+ <param name="odom_alpha3" value="0.03" />
<!-- Specifies the expected noise in odometry's translation estimate from the rotational component of the robot's motion. -->
- <param name="odom_alpha4" value="0.03" />
+ <param name="odom_alpha4" value="0.001" />
<!-- How many evenly-spaced beams in each scan to be used when updating the filter. -->
<param name="laser_max_beams" value="50" />
<!-- Exponential decay rate for the slow average weight filter, used in deciding when to recover by adding random poses. -->
<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" />
- <rosparam file="$(find wild_thumper)/config/global_costmap_params_odom.yaml" command="load" if="$(arg nomap)" />
+ <rosparam file="$(find wild_thumper)/config/global_costmap_params_nomap.yaml" command="load" if="$(arg nomap)" />
+ <rosparam file="$(find wild_thumper)/config/global_costmap_params_utm.yaml" command="load" if="$(arg global_utm)" />
<rosparam file="$(find wild_thumper)/config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find wild_thumper)/config/base_local_planner_params.yaml" command="load" />
<remap from="/cmd_vel" to="move_base/cmd_vel"/>