You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I have encountered issues while using the RPLIDAR LiDAR in a TurtleBot 4 simulation:
1- I created a simple script to show the sensor’s ray beams to the obstacles. As shown in the following picture (see link below), I expected the laser to detect obstacles in front of the robot rather than on its left side: https://share.icloud.com/photos/021RYniby1GrH60R6E9ZprR5A
In file turtlebot4_description/urdf/sensors/rplidar.urdf.xacro, in the block code:
<gazebo reference="${name}_link">
<!--
GPU Ray sensor plugin only supports 180 degrees, so limig to the front arc only
-->
<xacro:ray_sensor sensor_name="${name}" gazebo="${gazebo}"
update_rate="62.0" visualize="1"
h_samples="640" h_res="1.0" h_min_angle="${-pi/2}" h_max_angle="${pi/2}"
r_min="0.164" r_max="12.0" r_res="0.01">
<plugin name="dummy" filename="dummyfile"></plugin>
</xacro:ray_sensor>
<xacro:material_darkgray/>
</gazebo>
I don’t understand the comment “GPU Ray sensor plugin only supports 180 degrees, so limig to the front arc only”. I am unsure if this was a restriction of an older plugin version because, as noted earlier, it seems to work correctly at 360°: https://share.icloud.com/photos/0540dXWCulHIEYDBZeKAlz4gA
Just execute the script and follow the directions indicated at the beginning of the script:
“This ROS 2 node subscribes to a laser scan topic, then publishes a line marker
in RViz2 for each laser beam. The line marker extends from the sensor's origin
(rplidar_link) to the point where the laser beam collides with an obstacle.
This way, you can visualize not only the hit points, but the entire ray.
Make sure to:
Update the laser frame and topic if they differ from your robot configuration.
Add the Marker display in RViz2 and select the correct topic.”
Other notes
To achive the behavior I expected I changed in file turtlebot4_description/urdf/standard/turtlebot4.urdf.xacro:
Robot Model
Turtlebot4 Standard
ROS distro
Humble
Networking Configuration
Simple Discovery
OS
Ubuntu 22.04
Built from source or installed?
Built from Source
Package version
cb6ab27
Expected behaviour
I have encountered issues while using the RPLIDAR LiDAR in a TurtleBot 4 simulation:
1- I created a simple script to show the sensor’s ray beams to the obstacles. As shown in the following picture (see link below), I expected the laser to detect obstacles in front of the robot rather than on its left side:
https://share.icloud.com/photos/021RYniby1GrH60R6E9ZprR5A
I expected the sensor to detect obstacles in front of the robot, like in:
https://share.icloud.com/photos/0c6lK4oxav0SlHNGQtOOlnk-A
2- Furthermore, according to https://clearpathrobotics.com/turtlebot-4/ the LiDAR sensor used by the TurtleBot 4 is the RPLIDAR-A1:
https://share.icloud.com/photos/024Z7m2b2NWxhDPHQnGsVIbHg
And the sensor datasheet https://www.generationrobots.com/media/rplidar-a1m8-360-degree-laser-scanner-development-kit-datasheet-1.pdf?srsltid=AfmBOoonbdcifKv_tYJq7tqdAWt-awo5LOfL2p0VlkDMR46V3LvEAeXO indicates an angular range of 360 degrees:
https://share.icloud.com/photos/030Rf3A78D82_sbODccQrUTkA
In file turtlebot4_description/urdf/sensors/rplidar.urdf.xacro, in the block code:
I don’t understand the comment “GPU Ray sensor plugin only supports 180 degrees, so limig to the front arc only”. I am unsure if this was a restriction of an older plugin version because, as noted earlier, it seems to work correctly at 360°:
https://share.icloud.com/photos/0540dXWCulHIEYDBZeKAlz4gA
Actual behaviour
As shown in https://share.icloud.com/photos/021RYniby1GrH60R6E9ZprR5A the RPLIDAR is only detecting obstacles on the robot’s left side, indicating also that it is functioning with a 180° field of view instead of 360°.
Error messages
To Reproduce
I’m using Ignition Gazebo Fortress 6.16.0 and rviz2 11.2.13
Launch the simulation executing:
ros2 launch turtlebot4_ignition_bringup turtlebot4_ignition.launch.py nav2:=true rviz:=true localization:=true
The script that prints the laser beams is not necessary. The problem can be seen watching the laser collisions with the objects.
Anyway, the script that prints the laser beams is this one:
https://github.com/pgarcia-dev/pgarcia_utils/blob/main/scripts/show_laser_beams.py
Just execute the script and follow the directions indicated at the beginning of the script:
“This ROS 2 node subscribes to a laser scan topic, then publishes a line marker
in RViz2 for each laser beam. The line marker extends from the sensor's origin
(rplidar_link) to the point where the laser beam collides with an obstacle.
This way, you can visualize not only the hit points, but the entire ray.
Make sure to:
Other notes
To achive the behavior I expected I changed in file turtlebot4_description/urdf/standard/turtlebot4.urdf.xacro:
rpy="0 0 ${pi/2}"
to
rpy="0 0 0"
And in turtlebot4_description/urdf/sensors/rplidar.urdf.xacro:
h_min_angle="${-pi/2}" h_max_angle="${pi/2}"
to
h_min_angle="${-pi}" h_max_angle="${pi}"
If I am missing any details, I would appreciate further clarification. Otherwise, if this is correct, I will be happy to submit a pull request
The text was updated successfully, but these errors were encountered: