-
Notifications
You must be signed in to change notification settings - Fork 74
Description
ROS2 Humble,
Ubuntu 22.04,
I'm using the last released multi-robot simulation in the main branch.
I'm able to spawn more than one create correctly namespaced.
I had the necessity of adding a lidar sensor on top of the creates in order to use the NAV2 localization and navigation.
I just added a xacro lidar description to the create urdf and namespaced it in the plugin section, I report the script below:
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="lidar_sensor" params="gazebo namespace">
<material name="black">
<color rgba="0 0 0 1"/>
</material>
<link name="lidar_link">
<inertial>
<mass value="0.0001"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
</inertial>
<visual>
<origin xyz="0 0 0.008" rpy="0 0 1.57"/>
<geometry>
<mesh filename="package://irobot_create_description/meshes/turtlebot4/rplidar.dae"/>
</geometry>
<material name="black"/>
</visual>
</link>
<joint name="lidar_joint" type="fixed">
<parent link="base_link"/>
<child link="lidar_link"/>
<origin xyz="-0.05 0 0.175" rpy="0 0 0"/>
</joint>
<gazebo reference="lidar_joint">
<preserveFixedJoint>true</preserveFixedJoint>
</gazebo>
<gazebo reference="lidar_link">
<material>Gazebo/Black</material>
<sensor type="ray" name="lidar_link">
<always_on>true</always_on>
<visualize>false</visualize>
<pose>0.0 0 0 0 0 0</pose>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1.000000</resolution>
<min_angle>-3.14</min_angle>
<max_angle>3.14</max_angle>
</horizontal>
</scan>
<range>
<min>0.3</min>
<max>12.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<xacro:if value="${gazebo == 'classic'}">
<plugin name="gazebo_lidar" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace>${namespace}</namespace>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>lidar_link</frame_name>
</plugin>
</xacro:if>
</sensor>
</gazebo>
</xacro:macro>
</robot>
and in the create3 description just:
<xacro:include filename="$(find irobot_create_description)/urdf/sensors/lidar_sensor.xacro"/><xacro:lidar_sensor gazebo="$(arg gazebo)" namespace="$(arg namespace)"></xacro:lidar_sensor>I have the following issue:
The first create that I spawn has the lidar with the /robot1/scan topic visible and working correctly, once I add the second robot to the simulation:
ros2 launch irobot_create_gazebo_bringup create3_spawn.launch.py namespace:=robot2 x:=1.0it spawn with the lidar visuals but there's no /robot2/scan topic published.
As far as I could have seen with the ros2 topic info /robot1/scan there are two publisher on the first topic:
Publisher count: 2
Node name: gazebo_lidar
Node namespace: /robot1
Topic type: sensor_msgs/msg/LaserScan
Endpoint type: PUBLISHER
GID: 01.0f.5e.ca.61.6a.27.14.01.00.00.00.00.01.20.03.00.00.00.00.00.00.00.00
QoS profile:
Reliability: RELIABLE
History (Depth): UNKNOWN
Durability: VOLATILE
Lifespan: Infinite
Deadline: Infinite
Liveliness: AUTOMATIC
Liveliness lease duration: Infinite
Node name: gazebo_lidar
Node namespace: /robot1
Topic type: sensor_msgs/msg/LaserScan
Endpoint type: PUBLISHER
GID: 01.0f.5e.ca.61.6a.27.14.01.00.00.00.00.02.ed.03.00.00.00.00.00.00.00.00
QoS profile:
Reliability: RELIABLE
History (Depth): UNKNOWN
Durability: VOLATILE
Lifespan: Infinite
Deadline: Infinite
Liveliness: AUTOMATIC
Liveliness lease duration: Infinite
but apart from the scan the second robot is well namespaced as /robot2
I Know that's probably not a create3 issue, I was just wondering if you solved this while creating the Turtlebot4 urdf description.
Thanks in advance for your help, if it's off-topic I'll close this.