ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

Spawning multiple robots in Gazebo and assinging namespaces

asked 2021-05-27 11:59:20 -0500

NotARobot gravatar image

In my application I want to spawn multiple robots in the Gazebo world and also keep namespaces for each robot in order to use tools as SLAM, navigation or exploration for each robot individually.

Thanks to Zahi Kakish and the splitting of Gazebo map with robot models I am now able to spawn robots in my world at arbitrary positions.

However, I face a problem with my namespace configuration. When spawning robots with the code shown below I will receive a rqt_graph as shown in the picture.

for position in positions:
        # Set their respective variables via gazebo service call /spawn_entity
        robots.append(
            Node(
                package="my_sim_robot_spawner",
                executable="spawn_robot",
                name="robot_spawner",
                namespace="robot"+str(robot_cnt),
                output="screen",
                arguments=['robot'+str(robot_cnt),
                           'robot'+str(robot_cnt),
                           str(position['x']),
                           str(position['y']),
                           str(position['z'])
                ],
                remappings=[
                    ("/tf", "/robot" + str(robot_cnt) + "/tf"),
                ]
            )
        )
    # Generate state publishers for each robot
    robots.append(
        Node(
            package="robot_state_publisher",
            executable="robot_state_publisher",
            name="state_publisher",
            namespace="robot"+str(robot_cnt),
            output="screen",
            parameters=[
                {
                    'use_sim_time': use_sim_time,
                    'robot_description': robot_desc,
                    #'tf_prefix': "robot"+str(robot_cnt)
                }
            ],
            arguments=[urdf],
            remappings=[
                ("/tf", "/robot" + str(robot_cnt) + "/tf"),
                ("/tf_static", "/robot" + str(robot_cnt) + "/tf_static"),
            ]
        )
    )

    # Initialize online SLAM for each robot via slam_toolbox online_sync_launch
    robots.append(
        Node(
            package="slam_toolbox",
            executable="sync_slam_toolbox_node",
            name="slam_toolbox",
            namespace="robot"+str(robot_cnt),
            output="screen",
            parameters=[
                get_package_share_directory("my_sim_slam_toolbox") + '/config/my_mapper_params_online_sync.yaml',
                #get_package_share_directory("slam_toolbox") + '/config/my_mapper_params_online_sync.yaml',
                {'use_sim_time': use_sim_time}
            ],
            remappings=[
                ("/scan", "/robot"+str(robot_cnt)+"/scan"),
                ("/tf", "/robot"+str(robot_cnt)+"/tf"),
                ("/tf_static", "/robot"+str(robot_cnt)+"/tf_static"),
                ("/map_metadata", "/robot"+str(robot_cnt)+"/map_metadata"),
                ("/map", "/robot"+str(robot_cnt)+"/map")
            ]
        )
    )

    robots.append(
        Node(
            package='rviz2',
            executable='rviz2',
            name='rviz2',
            namespace="robot"+str(robot_cnt),
            output='screen',
            # arguments=''
        )
    )

image description

My original problem is, that the message filter drops messages from base_scan like so

[sync_slam_toolbox_node-6] [INFO] [1622133119.029122539] [robot0.slam_toolbox]: Message Filter dropping message: frame 'base_scan' at time 1694.763 for reason 'Unknown'>

Therefore I digged deeper and came to the hypothesis that the tf tree outside my robots namespace is probably the source of this behavior, due to missing transformations which may cause the message filter for SLAM toolbox troubles.

I searched the code for additional possibilities where I may have forgotten to define the namespace but I was unable to find where. Probably inside the turtlebot3_diff_drive as it is the only node, which I haven't found the configuration for, except within the model.sdf of the robot, in which I have defined

<plugin name="turtlebot3_diff_drive" filename="libgazebo_ros_diff_drive.so">
      <ros>
          namespace>/robot0</namespace>
      </ros>
   <update_rate>30</update_rate>
   <!-- wheels -->
   <left_joint>wheel_left_joint</left_joint>

as it is a Gazebo plugin.

So, I would be glad if someone can point me in the right direction, regarding how to make SLAM toolbox work with my namespace configuration, or even if I am on the right track with my problem analysis?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-11-25 00:36:59 -0500

charlie92 gravatar image

I think your problem is indeed with your tf tree. Each robot should have a separated tf tree, e.g /robot1/tf, /robot2/tf, etc. So indeed you need to do that remapping in the .sdf of the robot. Look at the example with 2 robots from the navigation2 folks: https://github.com/ros-planning/navigation2/blob/galactic/nav2_bringup/nav2_gazebo_spawner/nav2_gazebo_spawner/nav2_gazebo_spawner.py#L75 They modify the .sdf for each robot they want to spawn. Did you solve this?

edit flag offensive delete link more

Comments

Yes, the issue is within gazebo and their /tf tree. Shortly after I asked the question here I stumbled upon a git issue addressing that the remapping via spawner was not possible and open to be fixed. At that time the issue was less then a week old - unfortunately I can't find it that fast to link it here. However it seems Mr.Macenski found a workaround. [ros2] gazebo plugins should publish /tf topic as /namespace/tf if the robot is spawned with namespace #1301. This workaround seems to be the answer your giving :)

Have you tried it out? Is it working? - I haven't solved the issue yet, but I would be glad if you could give me feedback if that workaround solves the problem. As for now, I have not that much time to try it out due to my PHD studies, but I will test it ...(more)

NotARobot gravatar image NotARobot  ( 2021-11-25 02:15:32 -0500 )edit

Yes, I could manage to run multiple robots with multiple slam_toolbox instances that way, which is using a namespace for each robot. One more thing on the slam_toolbox launch file, as mention by the link you cited, the following remappings need to be done so the namespace can be preprended to those topics

remappings = [
    ("/map", "map"),
    ("/scan", "scan"),
    ("/tf", "tf"),
    ("/tf_static", "tf_static"),
]

Hope it helps

charlie92 gravatar image charlie92  ( 2021-11-25 09:13:13 -0500 )edit

Thank you very much! I'll try it asap. :)

NotARobot gravatar image NotARobot  ( 2021-11-25 09:15:00 -0500 )edit

@NotARobot Did you get your example project to work correctly? Can you maybe share it on GitHub or similar? I am in the same place as you previously, I think, with the same problems ):

ljaniec gravatar image ljaniec  ( 2022-02-02 08:13:49 -0500 )edit
1

@ljaniec I have not tried it for now. ATM I am working on SEIF SLAM - however this will eventually become important again when I test my multi-robot slam. For now it is on hold on my end.

NotARobot gravatar image NotARobot  ( 2022-02-07 06:24:12 -0500 )edit

Question Tools

4 followers

Stats

Asked: 2021-05-27 11:59:20 -0500

Seen: 1,267 times

Last updated: Nov 25 '21