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.

161 lines
5.4 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
2 years ago
2 years ago
  1. ## Example 1
  2. <p align="center">
  3. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/noetic/images/move_stretch.gif"/>
  4. </p>
  5. The goal of this example is to give you an enhanced understanding of how to control the mobile base by sending `Twist` messages to a Stretch robot.
  6. Begin by running the following command in a new terminal.
  7. ```{.bash .shell-prompt}
  8. roslaunch stretch_core stretch_driver.launch
  9. ```
  10. Switch to `navigation` mode using a rosservice call. Then, in a new terminal, drive the robot forward with the [move.py](https://github.com/hello-robot/stretch_tutorials/tree/noetic/src/move.py) node.
  11. ```{.bash .shell-prompt}
  12. rosservice call /switch_to_navigation_mode
  13. cd catkin_ws/src/stretch_tutorials/src/
  14. python3 move.py
  15. ```
  16. To stop the node from sending twist messages, type `Ctrl` + `c`.
  17. ### The Code
  18. Below is the code which will send `Twist` messages to drive the robot forward.
  19. ```python
  20. #!/usr/bin/env python3
  21. import rospy
  22. from geometry_msgs.msg import Twist
  23. class Move:
  24. """
  25. A class that sends Twist messages to move the Stretch robot forward.
  26. """
  27. def __init__(self):
  28. """
  29. Function that initializes the subscriber.
  30. :param self: The self reference.
  31. """
  32. self.pub = rospy.Publisher('/stretch/cmd_vel', Twist, queue_size=1) #/stretch_diff_drive_controller/cmd_vel for gazebo
  33. def move_forward(self):
  34. """
  35. Function that publishes Twist messages
  36. :param self: The self reference.
  37. :publishes command: Twist message.
  38. """
  39. command = Twist()
  40. command.linear.x = 0.1
  41. command.linear.y = 0.0
  42. command.linear.z = 0.0
  43. command.angular.x = 0.0
  44. command.angular.y = 0.0
  45. command.angular.z = 0.0
  46. self.pub.publish(command)
  47. if __name__ == '__main__':
  48. rospy.init_node('move')
  49. base_motion = Move()
  50. rate = rospy.Rate(10)
  51. while not rospy.is_shutdown():
  52. base_motion.move_forward()
  53. rate.sleep()
  54. ```
  55. ### The Code Explained
  56. Now let's break the code down.
  57. ```python
  58. #!/usr/bin/env python3
  59. ```
  60. 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.
  61. ```python
  62. import rospy
  63. from geometry_msgs.msg import Twist
  64. ```
  65. You need to import `rospy` if you are writing a ROS [Node](http://wiki.ros.org/Nodes). The `geometry_msgs.msg` import is so that we can send velocity commands to the robot.
  66. ```python
  67. class Move:
  68. def __init__(self):
  69. self.pub = rospy.Publisher('/stretch/cmd_vel', Twist, queue_size=1)#/stretch_diff_drive_controller/cmd_vel for gazebo
  70. ```
  71. This section of 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`. The `queue_size` argument limits the amount of queued messages if any subscriber is not receiving them fast enough.
  72. ```Python
  73. command = Twist()
  74. ```
  75. Make a `Twist` message. We're going to set all of the elements since we can't depend on them defaulting to safe values.
  76. ```python
  77. command.linear.x = 0.1
  78. command.linear.y = 0.0
  79. command.linear.z = 0.0
  80. ```
  81. A `Twist` data structure has three linear velocities (in meters per second), along each of the axes. For Stretch, it will only pay attention to the x velocity, since it can't directly move in the y or the z direction.
  82. ```python
  83. command.angular.x = 0.0
  84. command.angular.y = 0.0
  85. command.angular.z = 0.0
  86. ```
  87. A `Twist` message also has three rotational velocities (in radians per second). Stretch will only respond to rotations around the z (vertical) axis.
  88. ```python
  89. self.pub.publish(command)
  90. ```
  91. Publish the `Twist` commands in the previously defined topic name `/stretch/cmd_vel`.
  92. ```Python
  93. rospy.init_node('move')
  94. base_motion = Move()
  95. rate = rospy.Rate(10)
  96. ```
  97. 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.
  98. !!! note
  99. the name must be a base name, i.e. it cannot contain any slashes "/".
  100. The `rospy.Rate()` function creates a Rate object. With the help of its method `sleep()`, it offers a convenient way for looping at the desired rate. With its argument of 10, we should expect to go through the loop 10 times per second (as long as our processing time does not exceed 1/10th of a second!).
  101. ```python
  102. while not rospy.is_shutdown():
  103. base_motion.move_forward()
  104. rate.sleep()
  105. ```
  106. This loop is a fairly standard rospy construct: checking the `rospy.is_shutdown()` flag and then doing work. You have to check `is_shutdown()` to check if your program should exit (e.g. if there is a `Ctrl-C` event or otherwise). The loop calls `rate.sleep()`, which sleeps just long enough to maintain the desired rate through the loop.
  107. ## Move Stretch in Simulation
  108. <p align="center">
  109. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/noetic/images/move.gif"/>
  110. </p>
  111. Using your preferred text editor, modify the topic name of the published `Twist` messages. Please review the edit in the **move.py** script below.
  112. ```python
  113. self.pub = rospy.Publisher('/stretch_diff_drive_controller/cmd_vel', Twist, queue_size=1)
  114. ```
  115. After saving the edited node, bring up [Stretch in the empty world simulation](gazebo_basics.md). To drive the robot with the node, type the following in a new terminal
  116. ```{.bash .shell-prompt}
  117. cd catkin_ws/src/stretch_tutorials/src/
  118. python3 move.py
  119. ```
  120. To stop the node from sending twist messages, type `Ctrl` + `c`.