Spawning multiple robots in Gazebo and assinging namespaces
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=''
)
)
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?