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.

178 lines
6.7 KiB

2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
  1. ## Example 3
  2. This example aims to combine the two previous examples and have Stretch utilize its laser scan data to avoid collision with objects as it drives forward.
  3. Begin by running the following command in a new terminal.
  4. ```{.bash .shell-prompt}
  5. roslaunch stretch_core stretch_driver.launch
  6. ```
  7. Then, in a new terminal, type the following to activate the LiDAR sensor.
  8. ```{.bash .shell-prompt}
  9. roslaunch stretch_core rplidar.launch
  10. ```
  11. To set `navigation` mode and to activate the [avoider.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/avoider.py) node, type the following in a new terminal.
  12. ```{.bash .shell-prompt}
  13. rosservice call /switch_to_navigation_mode
  14. cd catkin_ws/src/stretch_tutorials/src/
  15. python3 avoider.py
  16. ```
  17. To stop the node from sending twist messages, type `Ctrl` + `c` in the terminal running the avoider node.
  18. <p align="center">
  19. <img height=600 src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/noetic/images/avoider.gif"/>
  20. </p>
  21. ### The Code
  22. ```python
  23. #!/usr/bin/env python3
  24. import rospy
  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:
  30. """
  31. A class that implements both a LaserScan filter and base velocity control
  32. for collision avoidance.
  33. """
  34. def __init__(self):
  35. """
  36. Function that initializes the subscriber, publisher, and marker features.
  37. :param self: The self reference.
  38. """
  39. self.pub = rospy.Publisher('/stretch/cmd_vel', Twist, queue_size=1) #/stretch_diff_drive_controller/cmd_vel for gazebo
  40. self.sub = rospy.Subscriber('/scan', LaserScan, self.set_speed)
  41. self.width = 1
  42. self.extent = self.width / 2.0
  43. self.distance = 0.5
  44. self.twist = Twist()
  45. self.twist.linear.x = 0.0
  46. self.twist.linear.y = 0.0
  47. self.twist.linear.z = 0.0
  48. self.twist.angular.x = 0.0
  49. self.twist.angular.y = 0.0
  50. self.twist.angular.z = 0.0
  51. def set_speed(self,msg):
  52. """
  53. Callback function to deal with incoming LaserScan messages.
  54. :param self: The self reference.
  55. :param msg: The subscribed LaserScan message.
  56. :publishes self.twist: Twist message.
  57. """
  58. angles = linspace(msg.angle_min, msg.angle_max, len(msg.ranges))
  59. points = [r * sin(theta) if (theta < -2.5 or theta > 2.5) else inf for r,theta in zip(msg.ranges, angles)]
  60. new_ranges = [r if abs(y) < self.extent else inf for r,y in zip(msg.ranges, points)]
  61. error = min(new_ranges) - self.distance
  62. self.twist.linear.x = tanh(error) if (error > 0.05 or error < -0.05) else 0
  63. self.pub.publish(self.twist)
  64. if __name__ == '__main__':
  65. rospy.init_node('avoider')
  66. Avoider()
  67. rospy.spin()
  68. ```
  69. ### The Code Explained
  70. Now let's break the code down.
  71. ```python
  72. #!/usr/bin/env python3
  73. ```
  74. 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 Python3 script.
  75. ```python
  76. import rospy
  77. from numpy import linspace, inf, tanh
  78. from math import sin
  79. from geometry_msgs.msg import Twist
  80. from sensor_msgs.msg import LaserScan
  81. ```
  82. 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 `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.
  83. ```python
  84. self.pub = rospy.Publisher('/stretch/cmd_vel', Twist, queue_size=1)#/stretch_diff_drive_controller/cmd_vel for gazebo
  85. ```
  86. This section of the code defines the talker's interface to the rest of ROS. `pub = rospy.Publisher("/stretch/cmd_vel", Twist, queue_size=1)` declares that your node is publishing to the `/stretch/cmd_vel` topic using the message type `Twist`.
  87. ```python
  88. self.sub = rospy.Subscriber('/scan', LaserScan, self.set_speed)
  89. ```
  90. 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.
  91. ```python
  92. self.width = 1
  93. self.extent = self.width / 2.0
  94. self.distance = 0.5
  95. ```
  96. `self.width` is the width of the laser scan we want in front of Stretch. Since Stretch's front is pointing to 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.
  97. ```python
  98. self.twist = Twist()
  99. self.twist.linear.x = 0.0
  100. self.twist.linear.y = 0.0
  101. self.twist.linear.z = 0.0
  102. self.twist.angular.x = 0.0
  103. self.twist.angular.y = 0.0
  104. self.twist.angular.z = 0.0
  105. ```
  106. Allocate a `Twist` to use, and set everything to zero. We're going to do this when the class is initiated. Redefining this within the callback function, `set_speed()` can be more computationally taxing.
  107. ```python
  108. angles = linspace(msg.angle_min, msg.angle_max, len(msg.ranges))
  109. points = [r * sin(theta) if (theta < -2.5 or theta > 2.5) else inf for r,theta in zip(msg.ranges, angles)]
  110. new_ranges = [r if abs(y) < self.extent else inf for r,y in zip(msg.ranges, points)]
  111. ```
  112. 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".
  113. ```python
  114. error = min(new_ranges) - self.distance
  115. ```
  116. Calculate the difference of the closest measured scan and where we want the robot to stop. We define this as `error`.
  117. ```python
  118. self.twist.linear.x = tanh(error) if (error > 0.05 or error < -0.05) else 0
  119. ```
  120. Set the speed according to a `tanh` function. This method gives a nice smooth mapping from distance to speed, and asymptotes at +/- 1
  121. ```python
  122. self.pub.publish(self.twist)
  123. ```
  124. Publish the `Twist` message.
  125. ```python
  126. rospy.init_node('avoider')
  127. Avoider()
  128. rospy.spin()
  129. ```
  130. 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.
  131. !!! note
  132. The name must be a base name, i.e. it cannot contain any slashes "/".
  133. Instantiate class with `Avioder()`.
  134. Give control to ROS with `rospy.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.