0
$\begingroup$

I’m working with ROS1 Noetic on Ubuntu 20.04 and am using a TurtleBot3 with 360 Laser Distance Sensor LDS-01 (for creating a map and global path planning). I want to create a local costmap from an occupancy grid map published on /robot_hld_classifier/map and use it with the move_base package for local path planning.

Setup Details: Occupancy Grid Map Topic: /robot_hld_classifier/map

  • Value of 100 for completely occupied space
  • Value of 0 for free space
  • Intermediate values (0-100) for varying occupancy levels
  • Value of -1 for unknown space

I’ve modified turtlebot3_navigation.launch and move_base.launch files, and my local costmap configuration (modified_local_costmap.yaml) is as follows:

modified_turtlebot3_navigation.launch

<launch>
  <!-- Arguments -->
  <arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
  <arg name="map_file" default="/home/mi/Desktop/map_staffroom.yaml"/>
  <arg name="open_rviz" default="true"/>
  <arg name="move_forward_only" default="false"/>

  <!-- Turtlebot3 -->
  <include file="$(find turtlebot3_bringup)/launch/turtlebot3_remote.launch">
    <arg name="model" value="$(arg model)" />
  </include>

  <!-- Map server -->
  <node pkg="map_server" name="map_server" type="map_server" args="$(arg map_file)"/>

  <!-- AMCL -->
  <include file="$(find turtlebot3_navigation)/launch/amcl.launch"/>

  <!-- move_base -->
  <include file="$(find turtlebot3_navigation)/launch/modified_move_base.launch">
    <arg name="model" value="$(arg model)" />
    <arg name="move_forward_only" value="$(arg move_forward_only)"/>
  </include>

  <!-- rviz -->
  <group if="$(arg open_rviz)"> 
<node pkg="rviz" type="rviz" name="rviz" required="true"
      args="-d $(find turtlebot3_navigation)/rviz/turtlebot3_navigation.rviz"/>
  </group>
</launch>

modified_move_base.launch

<launch>
  <!-- Arguments -->
  <arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
  <arg name="cmd_vel_topic" default="/cmd_vel" />
  <arg name="odom_topic" default="odom" />
  <arg name="move_forward_only" default="false"/>

  <!-- move_base -->
  <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
    <param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" />
    <rosparam file="$(find turtlebot3_navigation)/param/costmap_common_params_$(arg model).yaml" command="load" ns="global_costmap" />
    <rosparam file="$(find turtlebot3_navigation)/param/modified_local_costmap.yaml" command="load" />
<rosparam file="$(find turtlebot3_navigation)/param/global_costmap_params.yaml" command="load" />
    <rosparam file="$(find turtlebot3_navigation)/param/move_base_params.yaml" command="load" />
<rosparam file="$(find turtlebot3_navigation)/param/dwa_local_planner_params_$(arg model).yaml" command="load" />
<remap from="cmd_vel" to="$(arg cmd_vel_topic)"/>
    <remap from="odom" to="$(arg odom_topic)"/>
<param name="DWAPlannerROS/min_vel_x" value="0.0" if="$(arg move_forward_only)" />
  </node>
</launch>

modified_local_costmap.yaml

local_costmap:
  global_frame: odom
  robot_base_frame: base_footprint
  update_frequency: 10.0
  publish_frequency: 10.0
  transform_tolerance: 0.5
  static_map: false
  rolling_window: true
  map_topic: "/robot_hld_classifier/map"
  subscribe_to_updates: true
  track_unknown_space: true
  unknown_cost_value: -1
  width: 4.0
  height: 4.0
  resolution: 0.02
  plugins:
    - {name: inflation_layer, type: "costmap_2d::InflationLayer"}

inflation_layer:
  inflation_radius: 1.0
  cost_scaling_factor: 3.0

Launch Output: Everything appears to load correctly. However, when I start the navigation, local path planning does not seem to work as expected.

... logging to /home/mi/.ros/log/dc22050a-a27c-11ef-ae32-73676f9bbf45/roslaunch-mi-workspace-36488.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

xacro: in-order processing became default in ROS Melodic. You can drop the option.
started roslaunch server http://192.168.1.118:37475/

SUMMARY
========

PARAMETERS
 * /amcl/base_frame_id: base_footprint
 * /amcl/gui_publish_rate: 50.0
 * /amcl/initial_pose_a: 0.0
 * /amcl/initial_pose_x: 0.0
 * /amcl/initial_pose_y: 0.0
 * /amcl/kld_err: 0.02
 * /amcl/laser_lambda_short: 0.1
 * /amcl/laser_likelihood_max_dist: 2.0
 * /amcl/laser_max_beams: 180
 * /amcl/laser_max_range: 3.5
 * /amcl/laser_model_type: likelihood_field
 * /amcl/laser_sigma_hit: 0.2
 * /amcl/laser_z_hit: 0.5
 * /amcl/laser_z_max: 0.05
 * /amcl/laser_z_rand: 0.5
 * /amcl/laser_z_short: 0.05
 * /amcl/max_particles: 3000
 * /amcl/min_particles: 500
 * /amcl/odom_alpha1: 0.1
 * /amcl/odom_alpha2: 0.1
 * /amcl/odom_alpha3: 0.1
 * /amcl/odom_alpha4: 0.1
 * /amcl/odom_frame_id: odom
 * /amcl/odom_model_type: diff
 * /amcl/recovery_alpha_fast: 0.0
 * /amcl/recovery_alpha_slow: 0.0
 * /amcl/resample_interval: 1
 * /amcl/transform_tolerance: 0.5
 * /amcl/update_min_a: 0.2
 * /amcl/update_min_d: 0.2
 * /move_base/DWAPlannerROS/acc_lim_theta: 3.2
 * /move_base/DWAPlannerROS/acc_lim_x: 2.5
 * /move_base/DWAPlannerROS/acc_lim_y: 0.0
 * /move_base/DWAPlannerROS/controller_frequency: 10.0
 * /move_base/DWAPlannerROS/forward_point_distance: 0.325
 * /move_base/DWAPlannerROS/goal_distance_bias: 20.0
 * /move_base/DWAPlannerROS/latch_xy_goal_tolerance: False
 * /move_base/DWAPlannerROS/max_scaling_factor: 0.2
 * /move_base/DWAPlannerROS/max_vel_theta: 2.75
 * /move_base/DWAPlannerROS/max_vel_trans: 0.22
 * /move_base/DWAPlannerROS/max_vel_x: 0.22
 * /move_base/DWAPlannerROS/max_vel_y: 0.0
 * /move_base/DWAPlannerROS/min_vel_theta: 1.37
 * /move_base/DWAPlannerROS/min_vel_trans: 0.11
 * /move_base/DWAPlannerROS/min_vel_x: -0.22
 * /move_base/DWAPlannerROS/min_vel_y: 0.0
 * /move_base/DWAPlannerROS/occdist_scale: 0.02
 * /move_base/DWAPlannerROS/oscillation_reset_dist: 0.05
 * /move_base/DWAPlannerROS/path_distance_bias: 32.0
 * /move_base/DWAPlannerROS/publish_cost_grid_pc: True
 * /move_base/DWAPlannerROS/publish_traj_pc: True
 * /move_base/DWAPlannerROS/scaling_speed: 0.25
 * /move_base/DWAPlannerROS/sim_time: 1.5
 * /move_base/DWAPlannerROS/stop_time_buffer: 0.2
 * /move_base/DWAPlannerROS/vth_samples: 40
 * /move_base/DWAPlannerROS/vx_samples: 20
 * /move_base/DWAPlannerROS/vy_samples: 0
 * /move_base/DWAPlannerROS/xy_goal_tolerance: 0.05
 * /move_base/DWAPlannerROS/yaw_goal_tolerance: 0.17
 * /move_base/base_local_planner: dwa_local_planner...
 * /move_base/conservative_reset_dist: 3.0
 * /move_base/controller_frequency: 10.0
 * /move_base/controller_patience: 15.0
 * /move_base/global_costmap/cost_scaling_factor: 3.0
 * /move_base/global_costmap/footprint: [[-0.105, -0.105]...
 * /move_base/global_costmap/global_frame: map
 * /move_base/global_costmap/inflation_radius: 1.0
 * /move_base/global_costmap/map_type: costmap
 * /move_base/global_costmap/observation_sources: scan
 * /move_base/global_costmap/obstacle_range: 3.0
 * /move_base/global_costmap/publish_frequency: 10.0
 * /move_base/global_costmap/raytrace_range: 3.5
 * /move_base/global_costmap/robot_base_frame: base_footprint
 * /move_base/global_costmap/scan/clearing: True
 * /move_base/global_costmap/scan/data_type: LaserScan
 * /move_base/global_costmap/scan/marking: True
 * /move_base/global_costmap/scan/sensor_frame: base_scan
 * /move_base/global_costmap/scan/topic: scan
 * /move_base/global_costmap/static_map: True
 * /move_base/global_costmap/transform_tolerance: 0.5
 * /move_base/global_costmap/update_frequency: 10.0
 * /move_base/inflation_layer/cost_scaling_factor: 3.0
 * /move_base/inflation_layer/inflation_radius: 1.0
 * /move_base/local_costmap/global_frame: odom
 * /move_base/local_costmap/height: 4.0
 * /move_base/local_costmap/map_topic: /robot_hld_classi...
 * /move_base/local_costmap/origin_x: 2.0
 * /move_base/local_costmap/plugins: [{'name': 'inflat...
 * /move_base/local_costmap/publish_frequency: 10.0
 * /move_base/local_costmap/resolution: 0.02
 * /move_base/local_costmap/robot_base_frame: base_footprint
 * /move_base/local_costmap/rolling_window: True
 * /move_base/local_costmap/static_map: False
 * /move_base/local_costmap/subscribe_to_updates: True
 * /move_base/local_costmap/track_unknown_space: True
 * /move_base/local_costmap/transform_tolerance: 0.5
 * /move_base/local_costmap/unknown_cost_value: -1
 * /move_base/local_costmap/update_frequency: 10.0
 * /move_base/local_costmap/width: 4.0
 * /move_base/oscillation_distance: 0.2
 * /move_base/oscillation_timeout: 10.0
 * /move_base/planner_frequency: 5.0
 * /move_base/planner_patience: 5.0
 * /move_base/shutdown_costmaps: False
 * /robot_description: <?xml version="1....
 * /robot_state_publisher/publish_frequency: 50.0
 * /robot_state_publisher/tf_prefix: 
 * /rosdistro: noetic
 * /rosversion: 1.17.0

NODES
  /
    amcl (amcl/amcl)
    map_server (map_server/map_server)
    move_base (move_base/move_base)
    robot_state_publisher (robot_state_publisher/robot_state_publisher)
    rviz (rviz/rviz)

ROS_MASTER_URI=http://192.168.1.118:11311

process[robot_state_publisher-1]: started with pid [36504]
process[map_server-2]: started with pid [36505]
process[amcl-3]: started with pid [36506]
process[move_base-4]: started with pid [36507]
process[rviz-5]: started with pid [36517]
[ WARN] [1731584778.101289050]: global_costmap: Pre-Hydro parameter "static_map" unused since "plugins" is provided
[ WARN] [1731584778.104913292]: global_costmap: Pre-Hydro parameter "map_type" unused since "plugins" is provided
[ INFO] [1731584778.106191761]: global_costmap: Using plugin "static_layer"
[ INFO] [1731584778.121213555]: Requesting the map...
[ INFO] [1731584778.330141569]: Resizing costmap to 384 X 384 at 0.050000 m/pix
[ INFO] [1731584778.429826064]: Received a 384 X 384 map at 0.050000 m/pix
[ INFO] [1731584778.438539819]: global_costmap: Using plugin "obstacle_layer"
[ INFO] [1731584778.446082828]:     Subscribed to Topics: scan
[ INFO] [1731584778.470803235]: global_costmap: Using plugin "inflation_layer"
[ WARN] [1731584778.536830359]: local_costmap: Pre-Hydro parameter "static_map" unused since "plugins" is provided
[ INFO] [1731584778.539320009]: local_costmap: Using plugin "inflation_layer"
[ INFO] [1731584778.609957304]: Created local_planner dwa_local_planner/DWAPlannerROS
[ INFO] [1731584778.623354015]: Sim period is set to 0.10
[ INFO] [1731584778.811499811]: Recovery behavior will clear layer 'obstacles'
[ INFO] [1731584778.822124612]: Recovery behavior will clear layer 'obstacles'
[ INFO] [1731584778.877805121]: odom received!

What I’ve Tried:

  1. Verified that the /robot_hld_classifier/map topic is active and publishing nav_msgs::OccupancyGrid messages.
  2. Set map_topic in the local costmap to /robot_hld_classifier/map to use my custom occupancy grid map for local planning. After starting the navigation

Question: How can I set up move_base to use my occupancy grid map as a local costmap for path planning? Is there something I’m missing in my configuration?

Updated: I now use the configuration below to create the local costmap, and the local costmap is successfully published. However, it seems to be using the /map topic from map_server instead of the custom topic /robot_hld_classifier/map as intended. (The /robot_hld_classifier/map is generated from depth camera data in front of the robot, so its costmap should display only the region directly ahead of the robot.)

local_costmap:
  global_frame: odom
  robot_base_frame: base_footprint
  update_frequency: 10.0
  publish_frequency: 10.0
  transform_tolerance: 0.5
  static_map: false
  rolling_window: true
  width: 4.0
  height: 4.0
  resolution: 0.02
  
  plugins:
    - {name: terrain_layer, type: "costmap_2d::StaticLayer"}
    - {name: inflation_layer, type: "costmap_2d::InflationLayer"}
    
terrain_layer:
  map_topic: "/robot_hld_classifier/map"
  subscribe_to_updates: true
  track_unknown_space: true
  unknown_cost_value: -1

inflation_layer:
  inflation_radius: 1.0
  cost_scaling_factor: 3.0

Wrong local costmap

Node graph

Updated Question: How can I configure the costmap to properly use the /robot_hld_classifier/map topic as its source instead of /map? Is there any additional configuration or debugging step I am missing?

$\endgroup$

1 Answer 1

0
$\begingroup$

You should be using the static_layer plugin for the move_base Local Costmap, and it should be the first layer.

You must provide accurate frame_id info so that the spatial relationship between your data and the (global) map frame can be determined. Assuming you have rolling_window set to true, the local costmap code will use the robot's current map x,y position (not pose!) and the costmap dimensions to select a small region from the larger map you provide.

$\endgroup$
6
  • $\begingroup$ I followed the steps you suggested, and the costmap is now running. However, it seems to be using the /map topic instead of the custom topic I intended to use, which is /robot_hld_classifier/map. Could you advise on how I can configure move_base or the costmap parameters to ensure it uses my /robot_hld_classifier/map topic instead of /map? $\endgroup$ Commented Nov 20 at 5:16
  • $\begingroup$ Is your map_topic property a child of the static_layer configuration? It should not be an immediate child of local_costmap like you show above. $\endgroup$
    – Mike973
    Commented Nov 20 at 11:58
  • $\begingroup$ I have already set the map_topic, which is /robot_hld_classifier/map, as a child of the static_layer. However, it still pulls /map from the map_server instead. I have verified that /robot_hld_classifier/map is still active. $\endgroup$ Commented Nov 20 at 12:25
  • $\begingroup$ We use this feature with our robots in noetic, so I know it works. Please edit your post to append your new local_costmap config (Keep the original so future readers can see it.) $\endgroup$
    – Mike973
    Commented Nov 20 at 12:43
  • $\begingroup$ Thank you very much for your kind suggestion. I’ve updated the post to include the new local_costmap configuration while keeping the original for reference. I’d greatly appreciate it if you could take a look and help me troubleshoot this issue. $\endgroup$ Commented Nov 21 at 5:42

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.