Skip to main content
Version: ROS 2 Humble

2D Lidar

Two dimensional LiDARs provide a single planar scan, which is pusblished as a sensor_msgs/LaserScan message. It is important to accurately position the scanner in the visual description of the robot to ensure that the scanned plane is accurate with respect to the robot.

Hokuyo UST

lidar2d:
- model: hokuyo_ust
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
urg_node:
laser_frame_id: lidar2d_0_laser
ip_address: 192.168.131.20
ip_port: 10940
angle_min: -2.356
angle_max: 2.356

Package and Setup

The Hokuyo UST uses the urg_node ROS 2 package. The driver is open source, maintained by the ROS community, and hosted on GitHub.

For more specifics on the way the Clearpath's configuration system launches the driver, see the Hokuyo UST launch file and the default parameter file in clearpath_sensors.

SICK LMS1xx

lidar2d:
- model: sick_lms1xx
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
lms1xx:
frame_id: lidar2d_0_laser
host: 192.168.131.20
port: 2111

Package and Setup

The SICK LMS1xx laser scan uses the lms1xx ROS 2 package. The driver is open source, maintained by Clearpath, and hosted on GitHub.

For more specifics on the way Clearpath's configuration system launches the lms1xx driver, see the SICK LMS1xx launch file and the default parameter file in clearpath_sensors.