Building a Basic LaserScan Subscriber Node
Copy all the code below into your lidar_subscriber.py
file and then review the annotations to understand how it all works.
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from rclpy.signals import SignalHandlerOptions # (1)!
from sensor_msgs.msg import LaserScan # (2)!
import numpy as np # (3)!
class LidarSubscriber(Node):
def __init__(self):
super().__init__("lidar_subscriber")
self.lidar_sub = self.create_subscription(
msg_type=LaserScan,
topic="/scan",
callback=self.lidar_callback,
qos_profile=10,
) # (4)!
self.get_logger().info(f"The '{self.get_name()}' node is initialised.")
def lidar_callback(self, scan_data: LaserScan):
left_20_deg = scan_data.ranges[0:21]
right_20_deg = scan_data.ranges[-20:] # (5)!
front = np.array(left_20_deg + right_20_deg) # (6)!
valid_data = front[front != float("inf")] # (7)!
if np.shape(valid_data)[0] > 0: # (8)!
single_point_average = valid_data.mean() # (9)!
else:
single_point_average = float("nan") # (10)!
self.get_logger().info(
f"LiDAR Reading (front): {single_point_average:.3f} meters.",
throttle_duration_sec = 1,
) # (11)!
def main(args=None):
rclpy.init(
args=args,
signal_handler_options=SignalHandlerOptions.NO
)
node = LidarSubscriber()
try:
rclpy.spin(node)
except KeyboardInterrupt:
print("Shutdown request (Ctrl+C) detected...")
finally:
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
- None of this should be new to you by now. Remember from Part 2 that we're using
SignalHandlerOptions
to handle shutdown requests (triggered by Ctrl+C). - We're building a
/scan
subscriber here, and we know that this topic uses thesensor_msgs/msg/LaserScan
interface type, so we import this here. numpy
is a Python library that allows us to work with numeric data, very useful for big arrays likeranges
.- We construct a subscriber in much the same way as we have done in Parts 1 and 2, this time targetting the
/scan
topic though. -
From the front of the robot, we obtain a 20° arc of scan data either side of the x-axis (see the figure below).
-
Then, we combine the
left_20_deg
andright_20_deg
data arrays, and convert this from a Python list to anumpy
array (see the figure below). -
This illustrates one of the great features of
numpy
arrays: we can filter them.Remember that
front
is now anumpy
array containing 40 data points.Remember also, that there will typically be several
inf
values scattered around the LaserScan array, resulting from sensor readings that are outside the sensor's measurement range (i.e. greater thanrange_max
or less thanrange_min
). We need to get rid of these, so we asknumpy
to filter our array as follows:-
Of all the values in the
front
array, determine which ones are not equal toinf
:front != float("inf")
-
Use this filter to remove these
inf
values from thefront
array:front[front != float("inf")]
-
Return this as a new
numpy
array calledvalid_data
:valid_data = front[front != float("inf")]
-
-
In certain situations (i.e. in very sparse environments) all values could be equal to
inf
(imagine the "empty world" simulation). Here we're checking the size of thevalid_data
array to make sure that we haven't just removed all values through the above filtering process! -
If the array is not empty, then use the
mean()
method to determine the average of all readings within the dataset - If the array is empty, then return "not a number" (aka "nan") instead
-
Print this value to the terminal, but throttle the messages so that only one is displayed every second
Question
If we didn't throttle this, what rate would the messages be printed at?
The data processing is illustrated in the figure below: