1. Obtaining RPLidar Data
1.1. Install and compile the RPLidar ROS package
The installation process is described here: Install the Slamtec RPLidar ROS package
This process clones the RPLidar ROS package git repository into the catkin_ws/src/
of your git repository. Hence the nodes of the RPLidar ROS package are available after a catkin_make
, i.e.,:
cd ~/asclinic-system/catkin_ws
catkin_make
1.2. Launch the RPLidar node
The RPLidar ROS package provide a node named rplidarNode
that reads data from the RPLidar device and publishes it to the topic /scan
. As the RPLidar ROS package is part of your catkin workspace, you can launch an rplidarNode
in the same way you would launch any other node. The following is a complete launch file for launching the rplidarNode
into the group namespace /asc
:
<launch>
<group ns="asc">
<!-- LAUNCH A RPLIDAR NODE -->
<!-- Note: for model A1/A2 use baudrate 115200 -->
<!-- for model A3 use baudrate 256000 -->
<node
pkg = "rplidar_ros"
name = "rplidarNode"
output = "screen"
type = "rplidarNode"
>
<param name="serial_port" type="string" value="/dev/rplidar"/>
<param name="serial_baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
</node>
</group>
</launch>
For example, you can place this launch file at the location:
~/asclinic-system/catkin_ws/src/asclinic_pkg/launch/rplidar.launch
And then launch it with the following command:
roslaunch asclinic_pkg rplidar.launch
The following are some important details about launching an rplidarNode
in this way:
As launch file uses the group namespace
/asc
, the data published to by therplidarNode
is available on the topic/asc/scan
You can add the
<node>...</node>
part of the launch file to any other launch file you have.- If you need to know some detail about what the
rplidarNode
is doing, then simply look at the source code located at:catkin_ws/src/rplidar_ros/src/node.cpp
This one file is the whole not, it is a reasonable length, and it is reasonably easy to parse. You can also view the rplidarNode code on the RPLidar git hub.
Note
For more information about ROS launch file, see the Run, launch, and interrogate nodes page.
1.3. Format of the RPLidar scan data
The rplidarNode
publishes one message of type sensor_msgs::LaserScan
for every complete rotation of the Lidar device.
The definition of the LaserScan message type shows that it contains the following properties:
angle_min
- this is the angle at the start of the scan, i.e., the angle of the first measurement in theranges
property. In units of [radians].angle_max
- this is the angle at the end of the scan, i.e., the angle of the last measurement in theranges
property. In units of [radians].angle_increment
- this is the angular distance between measurements. In units of [radians].time_increment
- this is the time between measurements. In units of [seconds].scan_time
- this is the time between scans, i.e., the time between the first measurement of this scan and the first measurement of the previous scan. In units of [seconds].range_min
- this is the minimum range value. In units of [meters].range_max
- this is the maximum range value. In units of [meters].ranges
- this is an array property that contains the range data of each measurement. The length of this array should be number of time thatangle_increment
fits in betweenangle_min
andangle_max
, i.e., the measurementranges[0]
was taken atangle_min
, and the measurementsranges[i]
were taken at(angle_min + i*angle_increment)
Note
Values in the ranges
array should be discarded if they are less than the range_min
or greater than the range_max
property.
1.4. Subscribe to the RPLidar scan data
Step 1. include the header that defines the message type.
For C++: the LaserScan include is:
#include "sensor_msgs/LaserScan.h"For Python: the LaserScan import is:
from sensor_msgs.msg import LaserScan
Step 2. Add a ROS subscriber to the /scan
topic.
For C++: the topic subscriber is:
// Initialise a node handle to the group namespace ros::NodeHandle nh_for_asc_group("/asc); // Initialise a subscriber to the RPLidar scan ros::Subscriber rplidar_scan_subscriber = nh_for_asc_group.subscribe("scan", 10, laserScanSubscriberCallback);For Python: the topic subscriber is:
# Initialise a subscriber to the RPLidar scan rospy.Subscriber("/asc"+"/scan", LaserScan, self.laserScanSubscriberCallback)
Step 3. Implement the subscriber callback to process the scan data.
For C++: the subscriber callback is:
// Respond to subscriber receiving a message void laserScanSubscriberCallback(const sensor_msgs::LaserScan& msg) { ROS_INFO_STREAM("Message received with angle_min = " << msg.angle_min << " [rad], angle_max = " << msg.angle_max << " [rad], range_min = " << msg.range_min << " [m], range_max = " << msg.range_max << " [m]"); // Now process the msg.ranges data to // interpret the robot's surroundings }For Python: the subscriber callback is:
# Respond to subscriber receiving a message def laserScanSubscriberCallback(self, msg): rospy.loginfo("Message receieved with angle_min = " + str(msg.angle_min) + " [rad], angle_max = " + str(msg.angle_max) + " [rad], range_min = " + str(msg.range_min) + " [m], range_max = " + str(msg.range_max) + " [m]") # Now process the msg.ranges data to # interpret the robot's surroundings
Step 4. Ensure that the sensor_msgs
are made available via the pacakge.xml
and CMakeLists.txt
at the path:
~/asclinic-system/catkin_ws/src/asclinic_pkg/Simply copy the syntax and directives used for adding the
std_msgs
to these two files.For the
pacakge.xml
, add the following lines:<build_depend>sensor_msgs</build_depend> <build_export_depend>sensor_msgs</build_export_depend> <exec_depend>sensor_msgs</exec_depend>For the
CMakeLists.txt
, add the lines that are highlighted in the following:find_package(catkin REQUIRED COMPONENTS message_generation roscpp rospy std_msgs geometry_msgs sensor_msgs genmsg roslib )## Generate added messages and services with any dependencies listed here generate_messages( DEPENDENCIES std_msgs geometry_msgs sensor_msgs )
1.5. External links
The launch process recommended above is based on the launch file found here in the RPlidar ROS package