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.

405 lines
14 KiB

2 years ago
  1. ## FollowJointTrajectory Commands
  2. Stretch ROS driver offers a [`FollowJointTrajectory`](http://docs.ros.org/en/api/control_msgs/html/action/FollowJointTrajectory.html) action service for its arm. Within this tutorial we will have a simple FollowJointTrajectory command sent to a Stretch robot to execute.
  3. ## Stow Command Example
  4. <p align="center">
  5. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/main/images/stow_command.gif"/>
  6. </p>
  7. Begin by running the following command in the terminal in a terminal.
  8. ```bash
  9. # Terminal 1
  10. roslaunch stretch_core stretch_driver.launch
  11. ```
  12. Switch the mode to *position* mode using a rosservice call. Then run the stow command node.
  13. ```bash
  14. # Terminal 2
  15. rosservice call /switch_to_position_mode
  16. cd catkin_ws/src/stretch_tutorials/src/
  17. python stow_command.py
  18. ```
  19. This will send a `FollowJointTrajectory` command to stow Stretch's arm.
  20. ### The Code
  21. ```python
  22. #!/usr/bin/env python
  23. import rospy
  24. from control_msgs.msg import FollowJointTrajectoryGoal
  25. from trajectory_msgs.msg import JointTrajectoryPoint
  26. import hello_helpers.hello_misc as hm
  27. import time
  28. class StowCommand(hm.HelloNode):
  29. '''
  30. A class that sends a joint trajectory goal to stow the Stretch's arm.
  31. '''
  32. def __init__(self):
  33. hm.HelloNode.__init__(self)
  34. def issue_stow_command(self):
  35. '''
  36. Function that makes an action call and sends stow position goal.
  37. :param self: The self reference.
  38. '''
  39. stow_point = JointTrajectoryPoint()
  40. stow_point.time_from_start = rospy.Duration(0.000)
  41. stow_point.positions = [0.2, 0.0, 3.4]
  42. trajectory_goal = FollowJointTrajectoryGoal()
  43. trajectory_goal.trajectory.joint_names = ['joint_lift', 'wrist_extension', 'joint_wrist_yaw']
  44. trajectory_goal.trajectory.points = [stow_point]
  45. trajectory_goal.trajectory.header.stamp = rospy.Time(0.0)
  46. trajectory_goal.trajectory.header.frame_id = 'base_link'
  47. self.trajectory_client.send_goal(trajectory_goal)
  48. rospy.loginfo('Sent stow goal = {0}'.format(trajectory_goal))
  49. self.trajectory_client.wait_for_result()
  50. def main(self):
  51. '''
  52. Function that initiates stow_command function.
  53. :param self: The self reference.
  54. '''
  55. hm.HelloNode.main(self, 'stow_command', 'stow_command', wait_for_first_pointcloud=False)
  56. rospy.loginfo('stowing...')
  57. self.issue_stow_command()
  58. time.sleep(2)
  59. if __name__ == '__main__':
  60. try:
  61. node = StowCommand()
  62. node.main()
  63. except KeyboardInterrupt:
  64. rospy.loginfo('interrupt received, so shutting down')
  65. ```
  66. ### The Code Explained
  67. Now let's break the code down.
  68. ```python
  69. #!/usr/bin/env python
  70. ```
  71. 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.
  72. ```python
  73. import rospy
  74. from control_msgs.msg import FollowJointTrajectoryGoal
  75. from trajectory_msgs.msg import JointTrajectoryPoint
  76. import hello_helpers.hello_misc as hm
  77. import time
  78. ```
  79. You need to import `rospy` if you are writing a ROS [Node](http://wiki.ros.org/Nodes). Import the `FollowJointTrajectoryGoal` from the [control_msgs.msg](http://wiki.ros.org/control_msgs) package to control the Stretch robot. Import `JointTrajectoryPoint` from the [trajectory_msgs](http://wiki.ros.org/trajectory_msgs) package to define robot trajectories. The [hello_helpers](https://github.com/hello-robot/stretch_ros/tree/master/hello_helpers) package consists of a module the provides various Python scripts used across [stretch_ros](https://github.com/hello-robot/stretch_ros). In this instance we are importing the `hello_misc` script.
  80. ```python
  81. class StowCommand(hm.HelloNode):
  82. def __init__(self):
  83. hm.HelloNode.__init__(self)
  84. ```
  85. The `StowCommand ` class inherits the `HelloNode` class from `hm` and is initialized.
  86. ```python
  87. def issue_stow_command(self):
  88. stow_point = JointTrajectoryPoint()
  89. stow_point.time_from_start = rospy.Duration(0.000)
  90. stow_point.positions = [0.2, 0.0, 3.4]
  91. ```
  92. The `issue_stow_command()` is the name of the function that will stow Stretch's arm. Within the function, we set *stow_point* as a `JointTrajectoryPoint`and provide desired positions (in meters). These are the positions of the lift, wrist extension, and yaw of the wrist, respectively. These are defined in the next set of the code.
  93. ```python
  94. trajectory_goal = FollowJointTrajectoryGoal()
  95. trajectory_goal.trajectory.joint_names = ['joint_lift', 'wrist_extension', 'joint_wrist_yaw']
  96. trajectory_goal.trajectory.points = [stow_point]
  97. trajectory_goal.trajectory.header.stamp = rospy.Time(0.0)
  98. trajectory_goal.trajectory.header.frame_id = 'base_link'
  99. ```
  100. Set *trajectory_goal* as a `FollowJointTrajectoryGoal` and define the joint names as a list. Then `trajectory_goal.trajectory.points` is defined by the positions set in *stow_point*. Specify the coordinate frame that we want (*base_link*) and set the time to be now.
  101. ```python
  102. self.trajectory_client.send_goal(trajectory_goal)
  103. rospy.loginfo('Sent stow goal = {0}'.format(trajectory_goal))
  104. self.trajectory_client.wait_for_result()
  105. ```
  106. Make the action call and send the goal. The last line of code waits for the result before it exits the python script.
  107. ```python
  108. def main(self):
  109. hm.HelloNode.main(self, 'stow_command', 'stow_command', wait_for_first_pointcloud=False)
  110. rospy.loginfo('stowing...')
  111. self.issue_stow_command()
  112. time.sleep(2)
  113. ```
  114. Create a funcion, `main()`, to do all of the setup the `hm.HelloNode` class and issue the stow command.
  115. ```python
  116. if __name__ == '__main__':
  117. try:
  118. node = StowCommand()
  119. node.main()
  120. except KeyboardInterrupt:
  121. rospy.loginfo('interrupt received, so shutting down')
  122. ```
  123. Declare object, *node*, from the `StowCommand()` class. Then run the `main()` function.
  124. ## Multipoint Command Example
  125. <p align="center">
  126. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/main/images/multipoint.gif"/>
  127. </p>
  128. Begin by running the following command in the terminal in a terminal.
  129. ```bash
  130. # Terminal 1
  131. roslaunch stretch_core stretch_driver.launch
  132. ```
  133. Switch the mode to *position* mode using a rosservice call. Then run the multipoint command node.
  134. ```bash
  135. # Terminal 2
  136. rosservice call /switch_to_position_mode
  137. cd catkin_ws/src/stretch_tutorials/src/
  138. python multipoint_command.py
  139. ```
  140. This will send a list of `JointTrajectoryPoint` message types to move Stretch's arm.
  141. ### The Code
  142. ```python
  143. #!/usr/bin/env python
  144. import rospy
  145. import time
  146. from control_msgs.msg import FollowJointTrajectoryGoal
  147. from trajectory_msgs.msg import JointTrajectoryPoint
  148. import hello_helpers.hello_misc as hm
  149. class MultiPointCommand(hm.HelloNode):
  150. """
  151. A class that sends multiple joint trajectory goals to the stretch robot.
  152. """
  153. def __init__(self):
  154. hm.HelloNode.__init__(self)
  155. def issue_multipoint_command(self):
  156. """
  157. Function that makes an action call and sends multiple joint trajectory goals
  158. to the joint_lift, wrist_extension, and joint_wrist_yaw.
  159. :param self: The self reference.
  160. """
  161. point0 = JointTrajectoryPoint()
  162. point0.positions = [0.2, 0.0, 3.4]
  163. point0.velocities = [0.2, 0.2, 2.5]
  164. point0.accelerations = [1.0, 1.0, 3.5]
  165. point1 = JointTrajectoryPoint()
  166. point1.positions = [0.3, 0.1, 2.0]
  167. point2 = JointTrajectoryPoint()
  168. point2.positions = [0.5, 0.2, -1.0]
  169. point3 = JointTrajectoryPoint()
  170. point3.positions = [0.6, 0.3, 0.0]
  171. point4 = JointTrajectoryPoint()
  172. point4.positions = [0.8, 0.2, 1.0]
  173. point5 = JointTrajectoryPoint()
  174. point5.positions = [0.5, 0.1, 0.0]
  175. trajectory_goal = FollowJointTrajectoryGoal()
  176. trajectory_goal.trajectory.joint_names = ['joint_lift', 'wrist_extension', 'joint_wrist_yaw']
  177. trajectory_goal.trajectory.points = [point0, point1, point2, point3, point4, point5]
  178. trajectory_goal.trajectory.header.stamp = rospy.Time(0.0)
  179. trajectory_goal.trajectory.header.frame_id = 'base_link'
  180. self.trajectory_client.send_goal(trajectory_goal)
  181. rospy.loginfo('Sent list of goals = {0}'.format(trajectory_goal))
  182. self.trajectory_client.wait_for_result()
  183. def main(self):
  184. """
  185. Function that initiates the multipoint_command function.
  186. :param self: The self reference.
  187. """
  188. hm.HelloNode.main(self, 'multipoint_command', 'multipoint_command', wait_for_first_pointcloud=False)
  189. rospy.loginfo('issuing multipoint command...')
  190. self.issue_multipoint_command()
  191. time.sleep(2)
  192. if __name__ == '__main__':
  193. try:
  194. node = MultiPointCommand()
  195. node.main()
  196. except KeyboardInterrupt:
  197. rospy.loginfo('interrupt received, so shutting down')
  198. ```
  199. ### The Code Explained
  200. Seeing that there are similarities between the multipoint and stow command nodes, we will only breakdown the different components of the `multipoint_command` node.
  201. ```python
  202. point0 = JointTrajectoryPoint()
  203. point0.positions = [0.2, 0.0, 3.4]
  204. ```
  205. Set *point0* as a `JointTrajectoryPoint`and provide desired positions. These are the positions of the lift, wrist extension, and yaw of the wrist, respectively. The lift and wrist extension positions are expressed in meters, where as the wrist yaw is in radians.
  206. ```python
  207. point0.velocities = [0.2, 0.2, 2.5]
  208. ```
  209. Provide desired velocity of the lift (m/s), wrist extension (m/s), and wrist yaw (rad/s) for *point0*.
  210. ```python
  211. point0.accelerations = [1.0, 1.0, 3.5]
  212. ```
  213. Provide desired accelerations of the lift (m/s^2), wrist extension (m/s^2), and wrist yaw (rad/s^2).
  214. **IMPORTANT NOTE**: The lift and wrist extension can only go up to 0.2 m/s. If you do not provide any velocities or accelerations for the lift or wrist extension, then they go to their default values. However, the Velocity and Acceleration of the wrist yaw will stay the same from the previous value unless updated.
  215. ```python
  216. trajectory_goal = FollowJointTrajectoryGoal()
  217. trajectory_goal.trajectory.joint_names = ['joint_lift', 'wrist_extension', 'joint_wrist_yaw']
  218. trajectory_goal.trajectory.points = [point0, point1, point2, point3, point4, point5]
  219. trajectory_goal.trajectory.header.stamp = rospy.Time(0.0)
  220. trajectory_goal.trajectory.header.frame_id = 'base_link'
  221. ```
  222. Set *trajectory_goal* as a `FollowJointTrajectoryGoal` and define the joint names as a list. Then `trajectory_goal.trajectory.points` is defined by a list of the 6 points. Specify the coordinate frame that we want (*base_link*) and set the time to be now.
  223. ## Single Joint Actuator
  224. <p align="center">
  225. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/main/images/single_joint_actuator.gif"/>
  226. </p>
  227. You can also actuate a single joint for the Stretch. Below are the list of joints and their position limit.
  228. ```
  229. ############################# JOINT LIMITS #############################
  230. joint_lift: lower_limit = 0.15, upper_limit = 1.10 # in meters
  231. wrist_extension: lower_limit = 0.00, upper_limit = 0.50 # in meters
  232. joint_wrist_yaw: lower_limit = -1.75, upper_limit = 4.00 # in radians
  233. joint_head_pan: lower_limit = -2.80, upper_limit = 2.90 # in radians
  234. joint_head_tilt: lower_limit = -1.60, upper_limit = 0.40 # in radians
  235. joint_gripper_finger_left: lower_limit = -0.35, upper_limit = 0.165 # in radians
  236. # INCLUDED JOINTS IN POSITION MODE
  237. translate_mobile_base: No lower or upper limit. Defined by a step size in meters
  238. rotate_mobile_base: No lower or upper limit. Defined by a step size in radians
  239. ########################################################################
  240. ```
  241. Begin by running the following command in the terminal in a terminal.
  242. ```bash
  243. # Terminal 1
  244. roslaunch stretch_core stretch_driver.launch
  245. ```
  246. Switch the mode to *position* mode using a rosservice call. Then run the single joint actuator node.
  247. ```bash
  248. # Terminal 2
  249. rosservice call /switch_to_position_mode
  250. cd catkin_ws/src/stretch_tutorials/src/
  251. python single_joint_actuator.py
  252. ```
  253. This will send a list of `JointTrajectoryPoint` message types to move Stretch's arm.
  254. The joint, *joint_gripper_finger_left*, is only needed when actuating the gripper.
  255. ### The Code
  256. ```python
  257. #!/usr/bin/env python
  258. import rospy
  259. import time
  260. from control_msgs.msg import FollowJointTrajectoryGoal
  261. from trajectory_msgs.msg import JointTrajectoryPoint
  262. import hello_helpers.hello_misc as hm
  263. class SingleJointActuator(hm.HelloNode):
  264. """
  265. A class that sends multiple joint trajectory goals to a single joint.
  266. """
  267. def __init__(self):
  268. hm.HelloNode.__init__(self)
  269. def issue_command(self):
  270. """
  271. Function that makes an action call and sends joint trajectory goals
  272. to a single joint
  273. :param self: The self reference.
  274. """
  275. trajectory_goal = FollowJointTrajectoryGoal()
  276. trajectory_goal.trajectory.joint_names = ['joint_head_pan']
  277. point0 = JointTrajectoryPoint()
  278. point0.positions = [0.65]
  279. # point1 = JointTrajectoryPoint()
  280. # point1.positions = [0.5]
  281. trajectory_goal.trajectory.points = [point0]#, point1]
  282. trajectory_goal.trajectory.header.stamp = rospy.Time(0.0)
  283. trajectory_goal.trajectory.header.frame_id = 'base_link'
  284. self.trajectory_client.send_goal(trajectory_goal)
  285. rospy.loginfo('Sent goal = {0}'.format(trajectory_goal))
  286. self.trajectory_client.wait_for_result()
  287. def main(self):
  288. """
  289. Function that initiates the issue_command function.
  290. :param self: The self reference.
  291. """
  292. hm.HelloNode.main(self, 'issue_command', 'issue_command', wait_for_first_pointcloud=False)
  293. rospy.loginfo('issuing command...')
  294. self.issue_command()
  295. time.sleep(2)
  296. if __name__ == '__main__':
  297. try:
  298. node = SingleJointActuator()
  299. node.main()
  300. except KeyboardInterrupt:
  301. rospy.loginfo('interrupt received, so shutting down')
  302. ```
  303. ### The Code Explained
  304. Since the code is quite similar to the `multipoint_command` code, we will only review the parts that differ.
  305. Now let's break the code down.
  306. ```python
  307. trajectory_goal = FollowJointTrajectoryGoal()
  308. trajectory_goal.trajectory.joint_names = ['joint_head_pan']
  309. ```
  310. Here we only input joint name that we want to actuate. In this instance, we will actuate the *joint_head_pan*.
  311. ```python
  312. point0 = JointTrajectoryPoint()
  313. point0.positions = [0.65]
  314. # point1 = JointTrajectoryPoint()
  315. # point1.positions = [0.5]
  316. ```
  317. Set *point0* as a `JointTrajectoryPoint`and provide desired position. You also have the option to send multiple point positions rather than one.
  318. ```python
  319. trajectory_goal.trajectory.points = [point0]#, point1]
  320. trajectory_goal.trajectory.header.stamp = rospy.Time(0.0)
  321. trajectory_goal.trajectory.header.frame_id = 'base_link'
  322. ```
  323. Set *trajectory_goal* as a `FollowJointTrajectoryGoal` and define the joint names as a list. Then `trajectory_goal.trajectory.points` set by your list of points. Specify the coordinate frame that we want (*base_link*) and set the time to be now.