Can't read scan topic (LaserScan) in Turtlebot3 using Gazebo, ROS2 (foxy) and rclpy

Hi guys,

for a university project I started working with Turtlebot3, ROS2 (foxy), rclpy and gazebo. While studying them, I found a lot of basic examples for ROS1 (noetic), e.g. how to subscribe and read joint_states and the scan (LaserScan) topic. I tried to convert these examples to rclpy and it worked well for reading the joint_states but it failed for reading the scan topic. To me, it looks like Turtlebot3 hasn’t fully updated the packages and the dependencies for ROS2 or rclpy (yet).

I created two videos to show you the problem:

With ROS1 (noetic), rospy and Ubuntu 20.04 the readings are working:

With ROS2 (foxy), rclpy and Ubuntu 20.04 the readings for the joint_states are working but fail when I try to read the LaserScan. In rqt for example, I can read data for the joint_states but no data is shown for the LaserScan:

Now, my Question is:
Is there a solution to read the scan topic (LaserScan) with rclpy?

Hi,
In ROS2, QoS setting could cause this issue.
Please see the issue thread below.

Hey Will,

you helped me a lot and I wish I had asked a couple days earlier which probably would have saved me a lot of time trying to figure out the problem :sweat_smile:

So, thank you very much! :smile:

If someone has the same issue and is interested in a working mvp, here is the working code (using Juypter Notebook):

import rclpy
from rclpy.node import Node
from sensor_msgs.msg import LaserScan
from rclpy.qos import qos_profile_sensor_data

def callback(msg):
    print(msg)

rclpy.init()
# subscriber
node = rclpy.create_node("sub_laser")
# qos_profile_sensor_data allows packet loss
scan_sub = node.create_subscription(LaserScan,"/scan", callback ,qos_profile=qos_profile_sensor_data) 
rclpy.spin(node)
1 Like

@EingeoelterBolt
Thank you very much for sharing your solution with community.
I’ll refer this thread whenever there’re similar inquiries.
Happy coding! :smiley: