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.4 KiB

2 years ago
  1. ## Example 2
  2. The aim of this example is to provide instruction on how to filter scan messages.
  3. For robots with laser scanners, ROS provides a special Message type in the [sensor_msgs](http://wiki.ros.org/sensor_msgs) package called [LaserScan](http://docs.ros.org/en/api/sensor_msgs/html/msg/LaserScan.html) to hold information about a given scan. Let's take a look at the message specification itself:
  4. ```
  5. # Laser scans angles are measured counter clockwise, with Stretch's LiDAR having
  6. # both angle_min and angle_max facing forward (very closely along the x-axis)
  7. Header header
  8. float32 angle_min # start angle of the scan [rad]
  9. float32 angle_max # end angle of the scan [rad]
  10. float32 angle_increment # angular distance between measurements [rad]
  11. float32 time_increment # time between measurements [seconds]
  12. float32 scan_time # time between scans [seconds]
  13. float32 range_min # minimum range value [m]
  14. float32 range_max # maximum range value [m]
  15. float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded)
  16. float32[] intensities # intensity data [device-specific units]
  17. ```
  18. 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.
  19. <p align="center">
  20. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/main/images/lidar.png"/>
  21. </p>
  22. For a Stretch robot the start angle of the scan, `angle_min`, and
  23. 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.
  24. <p align="center">
  25. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/main/images/stretch_axes.png"/>
  26. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/main/images/scan_angles.png"/>
  27. </p>
  28. 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.
  29. First, open a terminal and run the stretch driver launch file.
  30. ```bash
  31. # Terminal 1
  32. roslaunch stretch_core stretch_driver.launch
  33. ```
  34. Then in a new terminal run the `rplidar.launch` file from `stretch_core`.
  35. ```bash
  36. # Terminal 2
  37. roslaunch stretch_core rplidar.launch
  38. ```
  39. To filter the lidar scans for ranges that are directly in front of Stretch (width of 1 meter) run the [scan_filter.py](https://github.com/hello-robot/stretch_tutorials/blob/main/src/scan_filter.py) node by typing the following in a new terminal.
  40. ```bash
  41. # Terminal 3
  42. cd catkin_ws/src/stretch_tutorials/src/
  43. python scan_filter.py
  44. ```
  45. Then run the following command to bring up a simple RViz configuration of the Stretch robot.
  46. ```bash
  47. # Terminal 4
  48. rosrun rviz rviz -d `rospack find stretch_core`/rviz/stretch_simple_test.rviz
  49. ```
  50. Change the topic name from the LaserScan display from */scan* to */filter_scan*.
  51. <p align="center">
  52. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/main/images/scanfilter.gif"/>
  53. </p>
  54. ### The Code
  55. ```python
  56. #!/usr/bin/env python
  57. import rospy
  58. from numpy import linspace, inf
  59. from math import sin
  60. from sensor_msgs.msg import LaserScan
  61. class ScanFilter:
  62. """
  63. A class that implements a LaserScan filter that removes all of the points
  64. that are not in front of the robot.
  65. """
  66. def __init__(self):
  67. self.width = 1.0
  68. self.extent = self.width / 2.0
  69. self.sub = rospy.Subscriber('/scan', LaserScan, self.callback)
  70. self.pub = rospy.Publisher('filtered_scan', LaserScan, queue_size=10)
  71. rospy.loginfo("Publishing the filtered_scan topic. Use RViz to visualize.")
  72. def callback(self,msg):
  73. """
  74. Callback function to deal with incoming LaserScan messages.
  75. :param self: The self reference.
  76. :param msg: The subscribed LaserScan message.
  77. :publishes msg: updated LaserScan message.
  78. """
  79. angles = linspace(msg.angle_min, msg.angle_max, len(msg.ranges))
  80. points = [r * sin(theta) if (theta < -2.5 or theta > 2.5) else inf for r,theta in zip(msg.ranges, angles)]
  81. new_ranges = [r if abs(y) < self.extent else inf for r,y in zip(msg.ranges, points)]
  82. msg.ranges = new_ranges
  83. self.pub.publish(msg)
  84. if __name__ == '__main__':
  85. rospy.init_node('scan_filter')
  86. ScanFilter()
  87. rospy.spin()
  88. ```
  89. ### The Code Explained
  90. Now let's break the code down.
  91. ```python
  92. #!/usr/bin/env python
  93. ```
  94. Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
  95. ```python
  96. import rospy
  97. from numpy import linspace, inf
  98. from math import sin
  99. from sensor_msgs.msg import LaserScan
  100. ```
  101. You need to import `rospy` if you are writing a ROS [Node](http://wiki.ros.org/Nodes). There are functions from `numpy` and `math` that are required within this code, thus why linspace, inf, and sin are imported. The `sensor_msgs.msg` import is so that we can subscribe and publish `LaserScan` messages.
  102. ```python
  103. self.width = 1
  104. self.extent = self.width / 2.0
  105. ```
  106. 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.
  107. ```python
  108. self.sub = rospy.Subscriber('/scan', LaserScan, self.callback)
  109. ```
  110. 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.
  111. ```python
  112. self.pub = rospy.Publisher('filtered_scan', LaserScan, queue_size=10)
  113. ```
  114. `pub = rospy.Publisher("filtered_scan", LaserScan, queue_size=10)` declares that your node is publishing to the *filtered_scan* topic using the message type `LaserScan`. This lets the master tell any nodes listening on *filtered_scan* that we are going to publish data on that topic.
  115. ```python
  116. angles = linspace(msg.angle_min, msg.angle_max, len(msg.ranges))
  117. ```
  118. This line of code utilizes linspace to compute each angle of the subscribed scan.
  119. ```python
  120. points = [r * sin(theta) if (theta < -2.5 or theta > 2.5) else inf for r,theta in zip(msg.ranges, angles)]
  121. ```
  122. 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.
  123. ```python
  124. new_ranges = [r if abs(y) < self.extent else inf for r,y in zip(msg.ranges, points)]
  125. ```
  126. 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".
  127. ```python
  128. msg.ranges = new_ranges
  129. self.pub.publish(msg)
  130. ```
  131. Substitute in the new ranges in the original message, and republish it.
  132. ```python
  133. rospy.init_node('scan_filter')
  134. ScanFilter()
  135. ```
  136. The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. **NOTE:** the name must be a base name, i.e. it cannot contain any slashes "/".
  137. Instantiate the class with `ScanFilter()`
  138. ```python
  139. rospy.spin()
  140. ```
  141. Give control to ROS. This will allow the callback to be called whenever new
  142. messages come in. If we don't put this line in, then the node will not work,
  143. and ROS will not process any messages.