Need help with using robot namespace for drone 2D navigation with rtabmap

In Gazebo, I have launched a drone with a namespace. Then I launched rtabmap and move_base. It runs rtabmap successfully, however it fails to register any navigation goals with move_base. Can anyone please help me figure out why?

All my code is based off The Construct’s drone course and repository for quadrotor_navigation, found here: Bitbucket.

Here is my rtabmap/move_base launch file, which works fine if no namespace is specified:

<launch>
  
  <arg name="database_path"     default="rtabmap.db"/>
  <arg name="args"              default=""/>
  <arg name="ns"                default=""/>
  <arg name="ns_set"            default="false"/>
  
  <arg name="wait_for_transform"  default="0.2"/> 
  

  <group if="$(arg ns_set)">
    
    <group ns="$(arg ns)">
      <include file="$(find quadrotor_navigation)/launch/quadrotor_move_base_rtab.launch">
        <arg name="base_frame_id"   value="$(arg ns)/base_footprint"/>
        <arg name="global_frame_id" value="$(arg ns)/map"/>
        <arg name="odom_topic" value="/$(arg ns)/ground_truth/state" />
        <arg name="laser_topic" value="/$(arg ns)/scan" />
        <arg name="cmd_vel_topic" value="/$(arg ns)/cmd_vel"/>
      </include>
    </group>

  </group>

  <group unless="$(arg ns_set)">
    
      <include file="$(find quadrotor_navigation)/launch/quadrotor_move_base_rtab.launch"/>

  </group>
  
  <!-- Mapping -->
  <group ns="rtabmap">

    <node name="rtabmap_$(arg ns)" pkg="rtabmap_slam" type="rtabmap" output="screen" args="$(arg args)">
      <param name="database_path"       type="string" value="$(arg database_path)"/>
      <param name="frame_id"            type="string" value="$(arg ns)/base_link"/>
      <param name="odom_frame_id"       type="string" value="world"/>
      <param name="wait_for_transform_duration"  type="double"   value="$(arg wait_for_transform)"/>
      <param name="subscribe_depth"     type="bool"   value="true"/>
      <param name="subscribe_scan"      type="bool"   value="true"/>
    
      <!-- inputs -->
      <remap from="scan"            to="/$(arg ns)/scan"/>
      <remap from="rgb/image"       to="/$(arg ns)/camera/rgb/image_raw"/>
      <remap from="depth/image"     to="/$(arg ns)/camera/depth/image_raw"/>
      <remap from="rgb/camera_info" to="/$(arg ns)/camera/rgb/camera_info"/>
      
      <!-- output -->
      <remap from="grid_map" to="$(arg ns)/map"/>
    
      <!-- RTAB-Map's parameters: do "rosrun rtabmap rtabmap (double-dash)params" to see the list of available parameters. -->
      <param name="RGBD/ProximityBySpace"        type="string" value="true"/>   
      <param name="RGBD/OptimizeFromGraphEnd"    type="string" value="false"/>  
      <param name="Kp/MaxDepth"                  type="string" value="4.0"/>
      <param name="Reg/Strategy"                 type="string" value="1"/>      
      <param name="Icp/CoprrespondenceRatio"     type="string" value="0.3"/>
      <param name="Vis/MinInliers"               type="string" value="5"/>      
      <param name="Vis/InlierDistance"           type="string" value="0.1"/>    
      <param name="RGBD/AngularUpdate"           type="string" value="0.1"/>    
      <param name="RGBD/LinearUpdate"            type="string" value="0.1"/>    
      <param name="Rtabmap/TimeThr"              type="string" value="700"/>
      <param name="Mem/RehearsalSimilarity"      type="string" value="0.30"/>
      <param name="Optimizer/Slam2D"             type="string" value="true"/>
      <param name="Reg/Force3DoF"                type="string" value="true"/>
      
    </node>
   
  </group>
</launch>

Here is the dependent quadrotor_move_base_rtab.launch file:

<launch>
  
  <arg name="odom_frame_id"   default="world"/>
  <arg name="base_frame_id"   default="base_footprint"/>
  <arg name="global_frame_id" default="map"/>
  <arg name="odom_topic" default="/ground_truth/state" />
  <arg name="laser_topic" default="/scan" />
  <arg name="cmd_vel_topic" default="/cmd_vel"/>
  <arg name="custom_param_file" default="$(find quadrotor_navigation)/param/dummy.yaml"/>

  <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
    <rosparam file="$(find quadrotor_navigation)/param/costmap_common_params.yaml" command="load" ns="global_costmap" />
    <rosparam file="$(find quadrotor_navigation)/param/costmap_common_params.yaml" command="load" ns="local_costmap" />
    <rosparam file="$(find quadrotor_navigation)/param/local_costmap_params.yaml" command="load" />
    <rosparam file="$(find quadrotor_navigation)/param/global_costmap_params.yaml" command="load" />
    <rosparam file="$(find quadrotor_navigation)/param/dwa_local_planner_params.yaml" command="load" />
    <rosparam file="$(find quadrotor_navigation)/param/move_base_params.yaml" command="load" />
    <rosparam file="$(find quadrotor_navigation)/param/global_planner_params.yaml" command="load" />
    <rosparam file="$(find quadrotor_navigation)/param/navfn_global_planner_params.yaml" command="load" />
    <!-- external params file that could be loaded into the move_base namespace -->
    <rosparam file="$(arg custom_param_file)" command="load" />

    <!-- reset frame_id parameters using user input data -->
    <param name="global_costmap/global_frame" value="$(arg global_frame_id)"/>
    <param name="global_costmap/robot_base_frame" value="$(arg base_frame_id)"/>
    <param name="local_costmap/global_frame" value="$(arg odom_frame_id)"/>
    <param name="local_costmap/robot_base_frame" value="$(arg base_frame_id)"/>
    <param name="DWAPlannerROS/global_frame_id" value="$(arg odom_frame_id)"/>
    
    <param name="global_costmap/obstacle_layer/scan/topic" value="$(arg laser_topic)"/>
    <param name="local_costmap/obstacle_layer/scan/topic" value="$(arg laser_topic)"/>


    <remap from="cmd_vel" to="$(arg cmd_vel_topic)"/>
    <remap from="odom" to="$(arg odom_topic)"/>
    <remap from="scan" to="$(arg laser_topic)"/>
  </node>
</launch>

Here is the tf_tree with a namespace:

Here is the tf_tree without a namespace, for comparison:

Here is rosnode info move_base with a namespace, which seems to indicate that it has no map information:

Node [/uav1/move_base]
Publications: 
 * /rosout [rosgraph_msgs/Log]
 * /uav1/cmd_vel [geometry_msgs/Twist]
 * /uav1/move_base/current_goal [geometry_msgs/PoseStamped]
 * /uav1/move_base/goal [move_base_msgs/MoveBaseActionGoal]
 * /uav1/move_base/recovery_status [move_base_msgs/RecoveryStatus]

Subscriptions: 
 * /clock [rosgraph_msgs/Clock]
 * /tf [tf2_msgs/TFMessage]
 * /tf_static [tf2_msgs/TFMessage]
 * /uav1/move_base_simple/goal [geometry_msgs/PoseStamped]

Services: 
 * /uav1/move_base/get_loggers
 * /uav1/move_base/set_logger_level

...

Here is rosnode info move_base with no namespace, for comparison:

Node [/move_base]
Publications: 
 * /cmd_vel [geometry_msgs/Twist]
 * /move_base/DWAPlannerROS/cost_cloud [sensor_msgs/PointCloud2]
 * /move_base/DWAPlannerROS/global_plan [nav_msgs/Path]
 * /move_base/DWAPlannerROS/local_plan [nav_msgs/Path]
 * /move_base/DWAPlannerROS/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
 * /move_base/DWAPlannerROS/parameter_updates [dynamic_reconfigure/Config]
 * /move_base/DWAPlannerROS/trajectory_cloud [sensor_msgs/PointCloud2]
 * /move_base/NavfnROS/plan [nav_msgs/Path]
 * /move_base/current_goal [geometry_msgs/PoseStamped]
 * /move_base/feedback [move_base_msgs/MoveBaseActionFeedback]
 * /move_base/global_costmap/costmap [nav_msgs/OccupancyGrid]
 * /move_base/global_costmap/costmap_updates [map_msgs/OccupancyGridUpdate]
 * /move_base/global_costmap/footprint [geometry_msgs/PolygonStamped]
 * /move_base/global_costmap/inflation_layer/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
 * /move_base/global_costmap/inflation_layer/parameter_updates [dynamic_reconfigure/Config]
 * /move_base/global_costmap/obstacle_layer/clearing_endpoints [sensor_msgs/PointCloud]
 * /move_base/global_costmap/obstacle_layer/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
 * /move_base/global_costmap/obstacle_layer/parameter_updates [dynamic_reconfigure/Config]
 * /move_base/global_costmap/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
 * /move_base/global_costmap/parameter_updates [dynamic_reconfigure/Config]
 * /move_base/global_costmap/static_layer/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
 * /move_base/global_costmap/static_layer/parameter_updates [dynamic_reconfigure/Config]
 * /move_base/goal [move_base_msgs/MoveBaseActionGoal]
 * /move_base/local_costmap/costmap [nav_msgs/OccupancyGrid]
 * /move_base/local_costmap/costmap_updates [map_msgs/OccupancyGridUpdate]
 * /move_base/local_costmap/footprint [geometry_msgs/PolygonStamped]
 * /move_base/local_costmap/inflation_layer/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
 * /move_base/local_costmap/inflation_layer/parameter_updates [dynamic_reconfigure/Config]
 * /move_base/local_costmap/obstacle_layer/clearing_endpoints [sensor_msgs/PointCloud]
 * /move_base/local_costmap/obstacle_layer/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
 * /move_base/local_costmap/obstacle_layer/parameter_updates [dynamic_reconfigure/Config]
 * /move_base/local_costmap/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
 * /move_base/local_costmap/parameter_updates [dynamic_reconfigure/Config]
 * /move_base/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
 * /move_base/parameter_updates [dynamic_reconfigure/Config]
 * /move_base/recovery_status [move_base_msgs/RecoveryStatus]
 * /move_base/result [move_base_msgs/MoveBaseActionResult]
 * /move_base/status [actionlib_msgs/GoalStatusArray]
 * /rosout [rosgraph_msgs/Log]

Subscriptions: 
 * /clock [rosgraph_msgs/Clock]
 * /ground_truth/state [nav_msgs/Odometry]
 * /map [nav_msgs/OccupancyGrid]
 * /move_base/cancel [unknown type]
 * /move_base/global_costmap/footprint [geometry_msgs/PolygonStamped]
 * /move_base/goal [move_base_msgs/MoveBaseActionGoal]
 * /move_base/local_costmap/footprint [geometry_msgs/PolygonStamped]
 * /move_base_simple/goal [unknown type]
 * /scan [sensor_msgs/LaserScan]
 * /tf [tf2_msgs/TFMessage]
 * /tf_static [tf2_msgs/TFMessage]

Services: 
 * /move_base/DWAPlannerROS/set_parameters
 * /move_base/NavfnROS/make_plan
 * /move_base/clear_costmaps
 * /move_base/get_loggers
 * /move_base/global_costmap/inflation_layer/set_parameters
 * /move_base/global_costmap/obstacle_layer/set_parameters
 * /move_base/global_costmap/set_parameters
 * /move_base/global_costmap/static_layer/set_parameters
 * /move_base/local_costmap/inflation_layer/set_parameters
 * /move_base/local_costmap/obstacle_layer/set_parameters
 * /move_base/local_costmap/set_parameters
 * /move_base/make_plan
 * /move_base/set_logger_level
 * /move_base/set_parameters

...

I would greatly appreciate any help at all.

By not registering any navigation goals with move_base, do you mean you are trying to send goals through rviz? If so, then it’s probably sending that out without the namespace.

Another strange thing is that you have way less publications/subscriptions in the namespaced move_base. Are you getting errors in the launch that would explain why you don’t have all of them? Is there another non-namespaced node that has them?

Thanks for your reply. I am publishing directly to uav1/move_base_simple/goal, but I am getting no messages in the move_base terminal that say the goal has been received or it is planning anything. I should be able to check uav1/move_base/status, but that is not being published.

I was getting this warning though in the move_base terminal:

[ WARN] [1701371003.835182867, 2103.073000000]: Timed out waiting for transform from uav1/base_footprint to uav1/map to become available before running costmap, tf error: canTransform: target_frame uav1/map does not exist.. canTransform returned after 0.1 timeout was 0.1.

The map topic is rtabmap/uav1/map, so I tried changing the global_frame_id to rtabmap/uav1/map but got the same warning.

I finally removed the warning by setting the global_frame_id to map and the rtabmap “remap from=“grid_map” to=“map”/”, but I’m still getting the same unresponsive uav1/move_base and the same rosnode info uav1/move_base.

There is no other non-namespaced node that has the missing info from uav1/move_base.

I think you are confusing the map topic vs. the map frame. The frame is published by rtabmap looking at your frame tree, and it’s called just map.

The warning tells you it’s looking for a frame called uav1/map, which doesn’t exist.

The map topic is the one published once so it can be used for things like map_server and the navigation costmaps. In this case, it probably is the one with the namespace.

Personally, I would remove the namespace of everything map related, if you are using the same map (topic) for all robots, then it adds confusion to the system.

What do you mean by this: “Personally, I would remove the namespace of everything map related, if you are using the same map (topic) for all robots, then it adds confusion to the system.”

Shouldn’t I keep the map topics like uav1/map, uav2/map, ...?

Well, it’s not a matter of who you should keep the map topics, but rather how that fits with your overall system.

I argue for keeping one map topic name if the robots are using the same map for localization/nav2.

Do you have a map_server? If so, it publishes to /map by default I believe, so you’d need to modify the output of that as well as the input to nav2.

My question to you is why do you need them to be different?

I’m having a swarm of drones autonomously explore and map an unknown environment. I need their map topics to be different because, as far as I know, they can’t publish directly to the same topic. They publish to their namespace map topics, and I can either combine their maps for coordinated exploration using a map merging package, or I can just have them explore independently.

Okay, it was just a suggestion. I don’t know what is publishing your map topic, but just make sure that each nav2 system is subscribing to the correct topic, since I think /map is the default

Hi
Regarding the errors you’ve encountered, I have some suggestions for you to check in order to resolve your problems:

  1. Regarding the TF frames you provided earlier, please double-check the transformation from one frame to another using commands such as rosrun tf tf echo /map uav1/base_footprint and rosrun tf tf echo /map /base_footprint. If the first transformation doesn’t show results, it indicates a potential issue with the frame names. I recommend verifying that the frame names specified in the move_base and rtab_map launch files are correct, assuming they are /uav1/map. The namespace must be consistent.
  2. Although it’s not my preferred solution, I personally consider adding a transformation between two frames directly in the launch file to fix this issue. For instance, you can use the following line:
    <node pkg="tf" type="static_transform_publisher" name="world2worldned" args="0 0 0 0 0 0 world world_ned 100" />.
    I hope these suggestions will be helpful for you.