You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

181 lines
7.8 KiB

2 years ago
  1. ## Example 2
  2. !!! note
  3. ROS 2 tutorials are still under active development.
  4. This example aims to provide instructions on how to filter scan messages.
  5. For robots with laser scanners, ROS provides a special Message type in the [sensor_msgs](https://github.com/ros2/common_interfaces/tree/humble/sensor_msgs) package called [LaserScan](https://github.com/ros2/common_interfaces/blob/humble/sensor_msgs/msg/LaserScan.msg) to hold information about a given scan. Let's take a look at the message specification itself:
  6. ```{.bash .no-copy}
  7. # Laser scans angles are measured counter clockwise,
  8. # with Stretch's LiDAR having both angle_min and angle_max facing forward
  9. # (very closely along the x-axis) of the device frame
  10. #
  11. std_msgs/Header header # timestamp data in a particular coordinate frame
  12. float32 angle_min # start angle of the scan [rad]
  13. float32 angle_max # end angle of the scan [rad]
  14. float32 angle_increment # angular distance between measurements [rad]
  15. float32 time_increment # time between measurements [seconds]
  16. float32 scan_time # time between scans [seconds]
  17. float32 range_min # minimum range value [m]
  18. float32 range_max # maximum range value [m]
  19. float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded)
  20. float32[] intensities # intensity data [device-specific units]
  21. ```
  22. The above message tells you everything you need to know about a scan. Most importantly, you have the angle of each hit and its distance (range) from the scanner. If you want to work with raw range data, then the above message is all you need. There is also an image below that illustrates the components of the message type.
  23. <p align="center">
  24. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/ROS2/images/lidar.png"/>
  25. </p>
  26. For a Stretch robot the start angle of the scan, `angle_min`, and
  27. end angle, `angle_max`, are closely located along the x-axis of Stretch's frame. `angle_min` and `angle_max` are set at **-3.1416** and **3.1416**, respectively. This is illustrated by the images below.
  28. <p align="center">
  29. <img height=500 src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/ROS2/images/stretch_axes.png"/>
  30. <img height=500 src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/ROS2/images/scan_angles.png"/>
  31. </p>
  32. Knowing the orientation of the LiDAR allows us to filter the scan values for a desired range. In this case, we are only considering the scan ranges in front of the stretch robot.
  33. First, open a terminal and run the stretch driver launch file.
  34. ```{.bash .shell-prompt}
  35. ros2 launch stretch_core stretch_driver.launch.py
  36. ```
  37. Then in a new terminal run the rplidar launch file from `stretch_core`.
  38. ```{.bash .shell-prompt}
  39. ros2 launch stretch_core rplidar.launch.py
  40. ```
  41. To filter the lidar scans for ranges that are directly in front of Stretch (width of 1 meter) run the scan filter node by typing the following in a new terminal.
  42. ```{.bash .shell-prompt}
  43. ros2 run stretch_ros_tutorials scan_filter
  44. ```
  45. Then run the following command to bring up a simple RViz configuration of the Stretch robot.
  46. ```{.bash .shell-prompt}
  47. ros2 run rviz2 rviz2 -d `ros2 pkg prefix stretch_calibration`/share/stretch_calibration/rviz/stretch_simple_test.rviz
  48. ```
  49. !!! note
  50. If the laser scan points published by the scan or the scan_filtered topic are not visible in RViz, you can visualize them by adding them using the 'Add' button in the left panel, selecting the 'By topic' tab, and then selecting the scan or scan_filtered topic.
  51. Change the topic name from the LaserScan display from */scan* to */filter_scan*.
  52. <p align="center">
  53. <img height=600 src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/ROS2/images/scanfilter.gif"/>
  54. </p>
  55. ### The Code
  56. ```python
  57. #!/usr/bin/env python3
  58. import rclpy
  59. from rclpy.node import Node
  60. from numpy import linspace, inf
  61. from math import sin
  62. from sensor_msgs.msg import LaserScan
  63. class ScanFilter(Node):
  64. def __init__(self):
  65. super().__init__('stretch_scan_filter')
  66. self.pub = self.create_publisher(LaserScan, '/filtered_scan', 10)
  67. self.sub = self.create_subscription(LaserScan, '/scan', self.scan_filter_callback, 10)
  68. self.width = 1
  69. self.extent = self.width / 2.0
  70. self.get_logger().info("Publishing the filtered_scan topic. Use RViz to visualize.")
  71. def scan_filter_callback(self,msg):
  72. angles = linspace(msg.angle_min, msg.angle_max, len(msg.ranges))
  73. points = [r * sin(theta) if (theta < -2.5 or theta > 2.5) else inf for r,theta in zip(msg.ranges, angles)]
  74. new_ranges = [r if abs(y) < self.extent else inf for r,y in zip(msg.ranges, points)]
  75. msg.ranges = new_ranges
  76. self.pub.publish(msg)
  77. def main(args=None):
  78. rclpy.init(args=args)
  79. scan_filter = ScanFilter()
  80. rclpy.spin(scan_filter)
  81. scan_filter.destroy_node()
  82. rclpy.shutdown()
  83. if __name__ == '__main__':
  84. main()
  85. ```
  86. ### The Code Explained
  87. Now let's break the code down.
  88. ```python
  89. #!/usr/bin/env python3
  90. ```
  91. Every Python ROS [Node](http://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools/Understanding-ROS2-Nodes/Understanding-ROS2-Nodes.html) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
  92. ```python
  93. import rclpy
  94. from rclpy.node import Node
  95. from numpy import linspace, inf
  96. from math import sin
  97. from sensor_msgs.msg import LaserScan
  98. ```
  99. You need to import rclpy if you are writing a ROS Node. There are functions from numpy and math that are required within this code, that's why linspace, inf, and sin are imported. The sensor_msgs.msg import is so that we can subscribe and publish LaserScan messages.
  100. ```python
  101. self.width = 1
  102. self.extent = self.width / 2.0
  103. ```
  104. We're going to assume that the robot is pointing up the x-axis, so that any points with y coordinates further than half of the defined width (1 meter) from the axis are not considered.
  105. ```python
  106. self.sub = self.create_subscription(LaserScan, '/scan', self.scan_filter_callback, 10)
  107. ```
  108. Set up a subscriber. We're going to subscribe to the topic "/scan", looking for LaserScan messages. When a message comes in, ROS is going to pass it to the function "callback" automatically.
  109. ```python
  110. self.pub = self.create_publisher(LaserScan, '/filtered_scan', 10)
  111. ```
  112. This declares that your node is publishing to the *filtered_scan* topic using the message type LaserScan. This lets any nodes listening on *filtered_scan* that we are going to publish data on that topic.
  113. ```python
  114. angles = linspace(msg.angle_min, msg.angle_max, len(msg.ranges))
  115. ```
  116. This line of code utilizes linspace to compute each angle of the subscribed scan.
  117. ```python
  118. points = [r * sin(theta) if (theta < -2.5 or theta > 2.5) else inf for r,theta in zip(msg.ranges, angles)]
  119. ```
  120. Here we are computing the y coordinates of the ranges that are **below -2.5** and **above 2.5** radians of the scan angles. These limits are sufficient for considering scan ranges in front of Stretch, but these values can be altered to your preference.
  121. ```python
  122. new_ranges = [r if abs(y) < self.extent else inf for r,y in zip(msg.ranges, points)]
  123. ```
  124. If the absolute value of a point's y-coordinate is under *self.extent* then keep the range, otherwise use inf, which means "no return".
  125. ```python
  126. msg.ranges = new_ranges
  127. self.pub.publish(msg)
  128. ```
  129. Substitute the new ranges in the original message, and republish it.
  130. ```python
  131. def main(args=None):
  132. rclpy.init(args=args)
  133. scan_filter = ScanFilter()
  134. ```
  135. The next line, rclpy.init_node initializes the node. In this case, your node will take on the name 'stretch_scan_filter'. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/".
  136. Setup Scanfilter class with `scan_filter = Scanfilter()`
  137. ```python
  138. rclpy.spin(scan_filter)
  139. ```
  140. Give control to ROS. This will allow the callback to be called whenever new
  141. messages come in. If we don't put this line in, then the node will not work,
  142. and ROS will not process any messages.