Intro

https://articulatedrobotics.xyz/tutorials/mobile-robot/hardware/lidar/#setting-up-the-real-lidar

Having a LiDAR attached to our robot means we’ll be able to use SLAM algorithms to generate a map of the environment around our robot and map it autonomously.

Setting up the real Lidar

https://articulatedrobotics.xyz/tutorials/mobile-robot/hardware/lidar/#setting-up-the-real-lidar

  • Install the ROS package
sudo apt install ros-humble-rplidar-ros
  • Run the driver
ros2 run rplidar_ros rplidar_composition --ros-args -p serial_port:=/dev/ttyUSB0 -p frame_id:=lidar_link -p angle_compensate:=true -p scan_mode:=Standard -p serial_baudrate:=115200

Timeout error

See discussionfor error: [ERROR] [1757263079.315106400] [rplidar_node]: Error, operation time out. SL_RESULT_OPERATION_TIMEOUT! [ros2run]: Process exited with failure 255

Solution: @JamesRonald 6 months ago With Humble RPLIDAR SDK Version:2.0.0, I also had to specify “-p serial_baudrate:=115200”

[INFO] [1757263146.744873466] [rplidar_node]: RPLidar running on ROS2 package rplidar_ros. RPLIDAR SDK Version:2.0.0
[INFO] [1757263146.799026597] [rplidar_node]: RPLidar S/N: 6AEFEDF9C7E29BCEA7E39EF2FA3C4304
[INFO] [1757263146.799255457] [rplidar_node]: Firmware Ver: 1.29
[INFO] [1757263146.799315728] [rplidar_node]: Hardware Rev: 7
[INFO] [1757263146.850736404] [rplidar_node]: RPLidar health status : 0
[INFO] [1757263146.851010222] [rplidar_node]: RPLidar health status : OK.
[INFO] [1757263146.851140816] [rplidar_node]: Start
[INFO] [1757263148.923909476] [rplidar_node]: current scan mode: Standard, sample rate: 2 Khz, max_distance: 12.0 m, scan frequency:10.0 Hz,
  • View a sensor_msgs/msg/LaserScan message
ros2 topic echo /scan --once

Create a launch file

Create a Package

In this case, we will make a standalone ROS package just to launch the Lidar node (See Create an empty Python package)

  • make robot_ws\src
mkdir -p robot_ws/src && cd robot_ws/src
  • Create an empty python package
ros2 pkg create --build-type ament_python my_rplidar_launch
  • Create launch file
mkdir -p my_rplidar_launch/launch
nano my_rplidar_launch/launch/rplidar_launch.py
  • Paste in launch code
from launch import LaunchDescription
from launch_ros.actions import Node
 
def generate_launch_description():
    return LaunchDescription([
        Node(
            package='rplidar_ros',
            executable='rplidar_composition',
            output='screen',
            parameters=[{
                'serial_port': '/dev/serial/by-path/platform-fd500000.pcie-pci-0000:01:00.0-usb-0:1.3:1.0-port0',
                'serial_baudrate': 115200,
                'frame_id': 'lidar_link',
                'angle_compensate': True,
                'scan_mode': 'Standard'
            }]
        )
    ])
 
  • Update setup.py
from setuptools import find_packages, setup
import os
from glob import glob
 
package_name = 'my_rplidar_launch'
 
setup(
    name=package_name,
    version='0.0.0',
    packages=find_packages(exclude=['test']),
    data_files=[
        ('share/ament_index/resource_index/packages', ['resource/' + package_name]),
        ('share/' + package_name, ['package.xml']),
        (os.path.join('share', package_name, 'launch'), glob('launch/*.py')),
    ],
    install_requires=['setuptools'],
    zip_safe=True,
    maintainer='bluepi4',
    maintainer_email='bluepi4@todo.todo',
    description='Launch package for RPLidar',
    license='Apache License 2.0',
    tests_require=['pytest'],
    entry_points={'console_scripts': []},
)
 
  • Build the package
cd ~/robot_ws
colcon build
source install/setup.bash
  • Launch node
ros2 launch my_rplidar_launch rplidar_launch.py
[INFO] [launch]: All log files can be found below /home/bluepi4/.ros/log/2025-09-07-10-48-11-290393-bluepi4-4416
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [rplidar_composition-1]: process started with pid [4418]
[rplidar_composition-1] [INFO] [1757267291.927304560] [rplidar_node]: RPLidar running on ROS2 package rplidar_ros. RPLIDAR SDK Version:2.0.0
[rplidar_composition-1] [INFO] [1757267291.988674135] [rplidar_node]: RPLidar S/N: 6AEFEDF9C7E29BCEA7E39EF2FA3C4304
[rplidar_composition-1] [INFO] [1757267291.989083552] [rplidar_node]: Firmware Ver: 1.29
[rplidar_composition-1] [INFO] [1757267291.989179698] [rplidar_node]: Hardware Rev: 7
[rplidar_composition-1] [INFO] [1757267292.040837241] [rplidar_node]: RPLidar health status : 0
[rplidar_composition-1] [INFO] [1757267292.041212252] [rplidar_node]: RPLidar health status : OK.
[rplidar_composition-1] [INFO] [1757267292.041328212] [rplidar_node]: Start
[rplidar_composition-1] [INFO] [1757267294.126660717] [rplidar_node]: current scan mode: Standard, sample rate: 2 Khz, max_distance: 12.0 m, scan frequency:10.0 Hz,

Visualize LiDAR data

Rviz2

  • Display LaserScan messages in Rviz
    • If robot_state_publisher isn’t running, then specify lidar_link as the fixed frame

Foxglove

.