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.

165 lines
6.1 KiB

  1. ## Example 3
  2. !!! note
  3. ROS 2 tutorials are still under active development.
  4. The aim of example 3 is to combine the two previous examples and have Stretch utilize its laser scan data to avoid collision with objects as it drives forward.
  5. ```{.bash .shell-prompt}
  6. ros2 launch stretch_core stretch_driver.launch.py
  7. ```
  8. Then in a new terminal type the following to activate the LiDAR sensor.
  9. ```{.bash .shell-prompt}
  10. ros2 launch stretch_core rplidar.launch.py
  11. ```
  12. To activate the avoider node, type the following in a new terminal.
  13. ```{.bash .shell-prompt}
  14. ros2 run stretch_ros_tutorials avoider
  15. ```
  16. To stop the node from sending twist messages, type **Ctrl** + **c** in the terminal running the avoider node.
  17. <p align="center">
  18. <img height=600 src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/ROS2/images/avoider.gif"/>
  19. </p>
  20. ### The Code
  21. ```python
  22. #!/usr/bin/env python3
  23. import rclpy
  24. from rclpy.node import Node
  25. from numpy import linspace, inf, tanh
  26. from math import sin
  27. from geometry_msgs.msg import Twist
  28. from sensor_msgs.msg import LaserScan
  29. class Avoider(Node):
  30. def __init__(self):
  31. super().__init__('stretch_avoider')
  32. self.width = 1
  33. self.extent = self.width / 2.0
  34. self.distance = 0.5
  35. self.twist = Twist()
  36. self.twist.linear.x = 0.0
  37. self.twist.linear.y = 0.0
  38. self.twist.linear.z = 0.0
  39. self.twist.angular.x = 0.0
  40. self.twist.angular.y = 0.0
  41. self.twist.angular.z = 0.0
  42. self.publisher_ = self.create_publisher(Twist, '/stretch/cmd_vel', 1)
  43. self.subscriber_ = self.create_subscription(LaserScan, '/scan', self.set_speed, 10)
  44. def set_speed(self, msg):
  45. angles = linspace(msg.angle_min, msg.angle_max, len(msg.ranges))
  46. points = [r * sin(theta) if (theta < -2.5 or theta > 2.5) else inf for r,theta in zip(msg.ranges, angles)]
  47. new_ranges = [r if abs(y) < self.extent else inf for r,y in zip(msg.ranges, points)]
  48. error = min(new_ranges) - self.distance
  49. self.twist.linear.x = tanh(error) if (error > 0.05 or error < -0.05) else 0
  50. self.publisher_.publish(self.twist)
  51. def main(args=None):
  52. rclpy.init(args=args)
  53. avoider = Avoider()
  54. rclpy.spin(avoider)
  55. avoider.destroy_node()
  56. rclpy.shutdown()
  57. if __name__ == '__main__':
  58. main()
  59. ```
  60. ### The Code Explained
  61. Now let's break the code down.
  62. ```python
  63. #!/usr/bin/env python3
  64. ```
  65. 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.
  66. ```python
  67. import rclpy
  68. from rclpy.node import Node
  69. from numpy import linspace, inf, tanh
  70. from math import sin
  71. from geometry_msgs.msg import Twist
  72. from sensor_msgs.msg import LaserScan
  73. ```
  74. 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, thus linspace, inf, tanh, and sin are imported. The sensor_msgs.msg import is so that we can subscribe to LaserScan messages. The geometry_msgs.msg import is so that we can send velocity commands to the robot.
  75. ```python
  76. self.publisher_ = self.create_publisher(Twist, '/stretch/cmd_vel', 1)
  77. ```
  78. This declares that your node is publishing to the /stretch/cmd_vel topic using the message type Twist.
  79. ```python
  80. self.subscriber_ = self.create_subscription(LaserScan, '/scan', self.set_speed, 10)
  81. ```
  82. 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 "set_speed" automatically.
  83. ```python
  84. self.width = 1
  85. self.extent = self.width / 2.0
  86. self.distance = 0.5
  87. ```
  88. *self.width* is the width of the laser scan we want in front of Stretch. Since Stretch's front is pointing in the x-axis, any points with y coordinates further than half of the defined width (*self.extent*) from the x-axis are not considered. *self.distance* defines the stopping distance from an object.
  89. ```python
  90. self.twist = Twist()
  91. self.twist.linear.x = 0.0
  92. self.twist.linear.y = 0.0
  93. self.twist.linear.z = 0.0
  94. self.twist.angular.x = 0.0
  95. self.twist.angular.y = 0.0
  96. self.twist.angular.z = 0.0
  97. ```
  98. Allocate a Twist to use, and set everything to zero. We're going to do this when the class is initiating. Redefining this within the callback function, `set_speed()` can be more computationally taxing.
  99. ```python
  100. angles = linspace(msg.angle_min, msg.angle_max, len(msg.ranges))
  101. points = [r * sin(theta) if (theta < -2.5 or theta > 2.5) else inf for r,theta in zip(msg.ranges, angles)]
  102. new_ranges = [r if abs(y) < self.extent else inf for r,y in zip(msg.ranges, points)]
  103. ```
  104. This line of code utilizes linspace to compute each angle of the subscribed scan. Here we compute 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. 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".
  105. ```python
  106. error = min(new_ranges) - self.distance
  107. ```
  108. Calculate the difference of the closest measured scan and where we want the robot to stop. We define this as *error*.
  109. ```python
  110. self.twist.linear.x = tanh(error) if (error > 0.05 or error < -0.05) else 0
  111. ```
  112. Set the speed according to a tanh function. This method gives a nice smooth mapping from distance to speed, and asymptotes at +/- 1
  113. ```python
  114. self.publisher_.publish(self.twist)
  115. ```
  116. Publish the Twist message.
  117. ```python
  118. def main(args=None):
  119. rclpy.init(args=args)
  120. avoider = Avoider()
  121. rclpy.spin(avoider)
  122. avoider.destroy_node()
  123. rclpy.shutdown()
  124. ```
  125. The next line, rclpy.init() method initializes the node. In this case, your node will take on the name 'stretch_avoider'. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/".
  126. Setup Avoider class with `avoider = Avioder()`
  127. Give control to ROS with `rclpy.spin()`. This will allow the callback to be called whenever new messages come in. If we don't put this line in, then the node will not work, and ROS will not process any messages.