Get the lidar • YouTube videos • Install • Start the Node • Parameters • RViz2 • Robot integration • Benchmarking
This node is designed to work with the DToF 2D Lidar sensors LD19 made by LDRobot.
It can work also with the LD06 model, but no tests have been performed with it. LD06 cannot work outdoor.
LD19 | LD06 |
---|---|
My lidar (LD19) comes from the LDRobot kickstarter campaing ended in 2021.
LDRobot then created also an Indiegogo campaign for the LD19.
LDRobot today distributes the Lidar through third-party resellers:
- Waveshare: LD19
- Innomaker: LD19
- Other: Search on Google
LD19 Lifecycle | LD19 outdoor |
---|---|
The node is designed to work in ROS2 Humble.
Clone the repository in your ROS2 workspace:
cd ~/ros2_ws/src/ #use your current ros2 workspace folder
git clone https://github.com/Myzhar/ldrobot-lidar-ros2.git
Add dependencies:
sudo apt install libudev-dev
Install the udev rules
cd ~/ros2_ws/src/ldrobot-lidar-ros2/scripts/
./create_udev_rules.sh
Build the packages:
cd ~/ros2_ws/
rosdep install --from-paths src --ignore-src -r -y
colcon build --symlink-install --cmake-args=-DCMAKE_BUILD_TYPE=Release
Update the environment variables:
echo source $(pwd)/install/local_setup.bash >> ~/.bashrc
source ~/.bashrc
Open a terminal console and enter the following command:
ros2 run ldlidar_node ldlidar_node # <--- not recommended. Better using the launch file
the ldlidar
node is based on the ROS2 lifecycle
architecture, hence it starts in the UNCONFIGURED
state.
To configure the node, setting all the parameters to the default value, trying to estabilish a connection, and activating the scan publisher, the lifecycle services must be called.
Open a new terminal console and enter the following command:
ros2 lifecycle set /lidar_node configure
Transitioning successful
is returned if the node is correctly configured and the connection is estabilished, Transitioning failed
in case of errors. Look at the node log for information about eventual connection problems.
The node is now in the INACTIVE
state, enter the following command to activate:
ros2 lifecycle set /lidar_node activate
The node is now activated and the /ldlidar_node/scan
topic of type sensor_msgs/msg/LaserScan
is available to be subscribed.
The default values of the parameters of the node can be modified by editing the file ldlidar.yaml
.
Open a terminal console and enter the following command to start the node with customized parameters:
ros2 launch ldlidar_node ldlidar.launch.py
The ldlidar.yaml
script also starts a robot_state_publisher
node that provides the static TF transform of the LDLidar [ldlidar_base
->ldlidar_link
], and provides the ldlidar description in the /robot_description
.
Thanks to the NAV2 project it is possible to launch a lifecycle_manager
node that is taking care of processing the state transitions described above.
An example launch file is provided, ldlidar_with_mgr.launch.py
, that illustrates how to start a ldlidar_node
that loads the parameters from the ldlidar.yaml
file, and starts the lifecycle_manager
correctly configured with the file lifecycle_mgr.yaml
to manage the lifecycle processing:
ros2 launch ldlidar_node ldlidar_with_mgr.launch.py
The ldlidar_with_mgr.launch.py
script automatically starts the ldlidar_node
by including the ldlidar.launch.py
launch file.
Following the list of node parameters:
general.debug_mode
: set totrue
to activate debug messagescomm.serial_port
: the serial port pathcomm.baudrate
: the serial port baudratecomm.timeout_msec
: the serial communication timeout in millisecondslidar.model
: Lidar model [LDLiDAR_LD06, LDLiDAR_LD19, LDLiDAR_STL27L]lidar.rot_verse
: The rotation verse. Use clockwise if the lidar is mounted upsidedown. [CW, CCW]lidar.units
: distance measurement units [M, CM, MM]lidar.frame_id
: TF frame name for the lidarlidar.bins
: set to 0 for dinamic scan size according to rotation speed, set to a fixed value [e.g. 455] for compatibility with SLAM Toolboxlidar.range_min
: minimum scan distancelidar.range_max
: maximum scan distancelidar.enable_angle_crop
: enable angle croppinglidar.angle_crop_min
: minimum cropping anglelidar.angle_crop_max
: maximum cropping angle
The launch file ldlidar_rviz2.launch.py
starts the ldlidar_node
node, the lifecycle_manager
node, and a precofigured instance of RViz2 to display the 2D laser scan provided by the LDRobot sensors. This is an example to demonstrate how to correctly setup RViz2 to be used with the ldlidar_node
node.
Open a terminal console and enter the following command:
ros2 launch ldlidar_node ldlidar_rviz2.launch.py
Follow the following procedure, to integrate the ldlidar_node
in a robot configuration:
- Provide a TF transform from
base_link
toldlidar_base
, that is placed in the center of the base of the lidar scanner. Theldlidar_base
->ldlidar_link
transform is provided by therobot_state_publisher
started by theldlidar.launch.py
launch file. - Modify the
ldlidar.yaml
to match the configuration of the robot. - Include the
ldlidar.launch.py
in the bringup launch file of the robot. Follow the provided example. - Handle lifecycle to correctly start the node. You can use the Nav2
lifecycle_manager
, by including it in the bringup launch file. Follow the provided example. - Enjoy your working system
The launch file ldlidar_slam.launch.py
shows how to use the node with the SLAM Toolbox package to generate a 2D map for robot navigation.
It is possible to benchmark the node to evaluate the overall performance by using the NVIDIA® ISAAC ROS ros2_benchmark package.
First of all install the ros2_benchmark package.
Launch the benchmark:
cd ~/ros2_ws/src/ldrobot-lidar-ros2/test/
launch_test ldlidar_benchmark.py
the final result should be similar to
+--------------------------------------------------------------------------------------------+
| LD Lidar Live Benchmark |
| Final Report |
+--------------------------------------------------------------------------------------------+
| [Scan] Delta between First & Last Received Frames (ms) : 4910.833 |
| [Scan] Mean Playback Frame Rate (fps) : 10.182 |
| [Scan] Mean Frame Rate (fps) : 10.182 |
| [Scan] # of Missed Frames : 0.000 |
| [Scan] # of Frames Sent : 50.000 |
| [Scan] First Sent to First Received Latency (ms) : 0.156 |
| [Scan] Last Sent to Last Received Latency (ms) : 0.235 |
| [Scan] First Frame End-to-end Latency (ms) : 0.156 |
| [Scan] Last Frame End-to-end Latency (ms) : 0.235 |
| [Scan] Max. End-to-End Latency (ms) : 0.265 |
| [Scan] Min. End-to-End Latency (ms) : 0.093 |
| [Scan] Mean End-to-End Latency (ms) : 0.189 |
| [Scan] Max. Frame-to-Frame Jitter (ms) : 0.594 |
| [Scan] Min. Frame-to-Frame Jitter (ms) : 0.000 |
| [Scan] Mean Frame-to-Frame Jitter (ms) : 0.218 |
| [Scan] Frame-to-Frame Jitter Std. Deviation (ms) : 0.145 |
+--------------------------------------------------------------------------------------------+
| Baseline Overall CPU Utilization (%) : 8.333 |
| Max. Overall CPU Utilization (%) : 66.667 |
| Min. Overall CPU Utilization (%) : 0.000 |
| Mean Overall CPU Utilization (%) : 0.856 |
| Std Dev Overall CPU Utilization (%) : 3.420 |
+--------------------------------------------------------------------------------------------+
| [metadata] Test Name : LD Lidar Live Benchmark |
| [metadata] Test File Path : /home/walter/devel/ros2/ros2_walt/src/ldrobot-lidar-ros2/ldlidar_node/test/ldlidar_benchmark.py |
| [metadata] Test Datetime : 2024-06-25T20:05:40Z |
| [metadata] Device Hostname : walter-Legion-5-15ACH6H |
| [metadata] Device Architecture : x86_64 |
| [metadata] Device OS : Linux 6.5.0-25-generic #25~22.04.1-Ubuntu SMP PREEMPT_DYNAMIC Tue Feb 20 16:09:15 UTC 2 |
| [metadata] Idle System CPU Util. (%) : 0.500 |
| [metadata] Benchmark Mode : 3 |
+--------------------------------------------------------------------------------------------+