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.

344 lines
13 KiB

2 years ago
  1. # Example 10
  2. This tutorial provides you an idea of what tf2 can do in the Python track. We will elaborate how to create a tf2 static broadcaster and listener.
  3. ## tf2 Static Broadcaster
  4. For the tf2 static broadcaster node, we will be publishing three child static frames in reference to the *link_mast*, *link_lift*, and *link_wrist_yaw* frames.
  5. Begin by starting up the stretch driver launch file.
  6. ```bash
  7. # Terminal 1
  8. roslaunch stretch_core stretch_driver.launch
  9. ```
  10. Within this tutorial package, there is an [RViz config file](https://github.com/hello-robot/stretch_tutorials/blob/main/rviz/tf2_broadcaster_example.rviz) with the topics for transform frames in the Display tree. You can visualize these topics and the robot model by running the command below in a new terminal.
  11. ```bash
  12. # Terminal 2
  13. rosrun rviz rviz -d /home/hello-robot/catkin_ws/src/stretch_tutorials/rviz/tf2_broadcaster_example.rviz
  14. ```
  15. Then run the [tf2_broadcaster.py](https://github.com/hello-robot/stretch_tutorials/blob/main/src/tf2_broadcaster.py) node to visualize three static frames.
  16. ```bash
  17. # Terminal 3
  18. cd catkin_ws/src/stretch_tutorials/src/
  19. python tf2_broadcaster.py
  20. ```
  21. The gif below visualizes what happens when running the previous node.
  22. <p align="center">
  23. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/main/images/tf2_broadcaster.gif"/>
  24. </p>
  25. **OPTIONAL**: If you would like to see how the static frames update while the robot is in motion, run the [stow_command_node.py](https://github.com/hello-robot/stretch_tutorials/blob/main/src/stow_command.py) and observe the tf frames in RViz.
  26. ```bash
  27. # Terminal 4
  28. cd catkin_ws/src/stretch_tutorials/src/
  29. python stow_command.py
  30. ```
  31. <p align="center">
  32. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/main/images/tf2_broadcaster_with_stow.gif"/>
  33. </p>
  34. ### The Code
  35. ```python
  36. #!/usr/bin/env python
  37. import rospy
  38. import tf.transformations
  39. from geometry_msgs.msg import TransformStamped
  40. from tf2_ros import StaticTransformBroadcaster
  41. class FixedFrameBroadcaster():
  42. """
  43. This node publishes three child static frames in reference to their parent frames as below:
  44. parent -> link_mast child -> fk_link_mast
  45. parent -> link_lift child -> fk_link_lift
  46. parent -> link_wrist_yaw child -> fk_link_wrist_yaw
  47. """
  48. def __init__(self):
  49. """
  50. A function that creates a broadcast node and publishes three new transform
  51. frames.
  52. :param self: The self reference.
  53. """
  54. self.br = StaticTransformBroadcaster()
  55. self.mast = TransformStamped()
  56. self.mast.header.stamp = rospy.Time.now()
  57. self.mast.header.frame_id = 'link_mast'
  58. self.mast.child_frame_id = 'fk_link_mast'
  59. self.mast.transform.translation.x = 0.0
  60. self.mast.transform.translation.y = 2.0
  61. self.mast.transform.translation.z = 0.0
  62. q = tf.transformations.quaternion_from_euler(1.5707, 0, -1.5707)
  63. self.mast.transform.rotation.x = q[0]
  64. self.mast.transform.rotation.y = q[1]
  65. self.mast.transform.rotation.z = q[2]
  66. self.mast.transform.rotation.w = q[3]
  67. self.lift = TransformStamped()
  68. self.lift.header.stamp = rospy.Time.now()
  69. self.lift.header.frame_id = 'link_lift'
  70. self.lift.child_frame_id = 'fk_link_lift'
  71. self.lift.transform.translation.x = 0.0
  72. self.lift.transform.translation.y = 1.0
  73. self.lift.transform.translation.z = 0.0
  74. q = tf.transformations.quaternion_from_euler(1.5707, 0, -1.5707)
  75. self.lift.transform.rotation.x = q[0]
  76. self.lift.transform.rotation.y = q[1]
  77. self.lift.transform.rotation.z = q[2]
  78. self.lift.transform.rotation.w = q[3]
  79. self.wrist = TransformStamped()
  80. self.wrist.header.stamp = rospy.Time.now()
  81. self.wrist.header.frame_id = 'link_wrist_yaw'
  82. self.wrist.child_frame_id = 'fk_link_wrist_yaw'
  83. self.wrist.transform.translation.x = 0.0
  84. self.wrist.transform.translation.y = 1.0
  85. self.wrist.transform.translation.z = 0.0
  86. q = tf.transformations.quaternion_from_euler(1.5707, 0, -1.5707)
  87. self.wrist.transform.rotation.x = q[0]
  88. self.wrist.transform.rotation.y = q[1]
  89. self.wrist.transform.rotation.z = q[2]
  90. self.wrist.transform.rotation.w = q[3]
  91. self.br.sendTransform([self.mast, self.lift, self.wrist])
  92. rospy.loginfo('Publishing TF frames. Use RViz to visualize')
  93. if __name__ == '__main__':
  94. rospy.init_node('tf2_broadcaster')
  95. FixedFrameBroadcaster()
  96. rospy.spin()
  97. ```
  98. ### The Code Explained
  99. Now let's break the code down.
  100. ```python
  101. #!/usr/bin/env python
  102. ```
  103. 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.
  104. ```python
  105. import rospy
  106. import tf.transformations
  107. from geometry_msgs.msg import TransformStamped
  108. from tf2_ros import StaticTransformBroadcaster
  109. ```
  110. You need to import rospy if you are writing a ROS [Node](http://wiki.ros.org/Nodes). Import `tf.transformations` to get quaternion values from Euler angles. Import the `TransformStamped` from the `geometry_msgs.msg` package because we will be publishing static frames and it requires this message type. The `tf2_ros` package provides an implementation of a `tf2_ros.StaticTransformBroadcaster` to help make the task of publishing transforms easier.
  111. ```python
  112. def __init__(self):
  113. """
  114. A function that creates a broadcast node and publishes three new transform
  115. frames.
  116. :param self: The self reference.
  117. """
  118. self.br = StaticTransformBroadcaster()
  119. ```
  120. Here we create a `TransformStamped` object which will be the message we will send over once populated.
  121. ```python
  122. self.mast = TransformStamped()
  123. self.mast.header.stamp = rospy.Time.now()
  124. self.mast.header.frame_id = 'link_mast'
  125. self.mast.child_frame_id = 'fk_link_mast'
  126. ```
  127. We need to give the transform being published a timestamp, we'll just stamp it with the current time, `rospy.Time.now()`. Then, we need to set the name of the parent frame of the link we're creating, in this case *link_mast*. Finally, we need to set the name of the child frame of the link we're creating. In this instance, the child frame is *fk_link_mast*.
  128. ```python
  129. self.mast.transform.translation.x = 0.0
  130. self.mast.transform.translation.y = 2.0
  131. self.mast.transform.translation.z = 0.0
  132. ```
  133. Set the translation values for the child frame.
  134. ```python
  135. q = tf.transformations.quaternion_from_euler(1.5707, 0, -1.5707)
  136. self.wrist.transform.rotation.x = q[0]
  137. self.wrist.transform.rotation.y = q[1]
  138. self.wrist.transform.rotation.z = q[2]
  139. self.wrist.transform.rotation.w = q[3]
  140. ```
  141. The `quaternion_from_euler()` function takes in a Euler angle argument and returns a quaternion values. Then set the rotation values to the transformed quaternions.
  142. This process will be completed for the *link_lift* and *link_wrist_yaw* as well.
  143. ```python
  144. self.br.sendTransform([self.mast, self.lift, self.wrist])
  145. ```
  146. Send the three transforms using the `sendTransform()` function.
  147. ```python
  148. rospy.init_node('tf2_broadcaster')
  149. FixedFrameBroadcaster()
  150. ```
  151. 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 "/".
  152. Instantiate the `FixedFrameBroadcaster()` class.
  153. ```python
  154. rospy.spin()
  155. ```
  156. Give control to ROS. This will allow the callback to be called whenever new
  157. messages come in. If we don't put this line in, then the node will not work,
  158. and ROS will not process any messages.
  159. ## tf2 Static Listener
  160. In the previous section of the tutorial, we created a tf2 broadcaster to publish three static transform frames. In this section we will create a tf2 listener that will find the transform between *fk_link_lift* and *link_grasp_center*.
  161. Begin by starting up the stretch driver launch file.
  162. ```bash
  163. # Terminal 1
  164. roslaunch stretch_core stretch_driver.launch
  165. ```
  166. Then run the [tf2_broadcaster.py](https://github.com/hello-robot/stretch_tutorials/blob/main/src/tf2_broadcaster.py) node to create the three static frames.
  167. ```bash
  168. # Terminal 2
  169. cd catkin_ws/src/stretch_tutorials/src/
  170. python tf2_broadcaster.py
  171. ```
  172. Finally, run the [tf2_listener.py](https://github.com/hello-robot/stretch_tutorials/blob/main/src/tf2_listener.py) node to print the transform between two links.
  173. ```bash
  174. # Terminal 3
  175. cd catkin_ws/src/stretch_tutorials/src/
  176. python tf2_listener.py
  177. ```
  178. Within the terminal the transform will be printed every 1 second. Below is an example of what will be printed in the terminal. There is also an image for reference of the two frames.
  179. ```bash
  180. [INFO] [1659551318.098168]: The pose of target frame link_grasp_center with reference from fk_link_lift is:
  181. translation:
  182. x: 1.08415191335
  183. y: -0.176147838153
  184. z: 0.576720021135
  185. rotation:
  186. x: -0.479004489528
  187. y: -0.508053545368
  188. z: -0.502884087254
  189. w: 0.509454501243
  190. ```
  191. <p align="center">
  192. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/main/images/tf2_listener.png"/>
  193. </p>
  194. ### The Code
  195. ```python
  196. #!/usr/bin/env python
  197. import rospy
  198. from geometry_msgs.msg import TransformStamped
  199. import tf2_ros
  200. class FrameListener():
  201. """
  202. This Class prints the transformation between the fk_link_mast frame and the
  203. target frame, link_grasp_center.
  204. """
  205. def __init__(self):
  206. """
  207. A function that initializes the variables and looks up a transformation
  208. between a target and source frame.
  209. :param self: The self reference.
  210. """
  211. tf_buffer = tf2_ros.Buffer()
  212. listener = tf2_ros.TransformListener(tf_buffer)
  213. from_frame_rel = 'link_grasp_center'
  214. to_frame_rel = 'fk_link_lift'
  215. rospy.sleep(1.0)
  216. rate = rospy.Rate(1)
  217. while not rospy.is_shutdown():
  218. try:
  219. trans = tf_buffer.lookup_transform(to_frame_rel,
  220. from_frame_rel,
  221. rospy.Time())
  222. rospy.loginfo('The pose of target frame %s with reference from %s is: \n %s', from_frame_rel, to_frame_rel, trans.transform)
  223. except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException):
  224. rospy.logwarn(' Could not transform %s from %s ', to_frame_rel, from_frame_rel)
  225. rate.sleep()
  226. if __name__ == '__main__':
  227. rospy.init_node('tf2_listener')
  228. FrameListener()
  229. rospy.spin()
  230. ```
  231. ### The Code Explained
  232. Now let's break the code down.
  233. ```python
  234. #!/usr/bin/env python
  235. ```
  236. 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.
  237. ```python
  238. import rospy
  239. from geometry_msgs.msg import TransformStamped
  240. import tf2_ros
  241. ```
  242. You need to import rospy if you are writing a ROS [Node](http://wiki.ros.org/Nodes). Import the `TransformStamped` from the `geometry_msgs.msg` package because we will be publishing static frames and it requires this message type. The `tf2_ros` package provides an implementation of a `tf2_ros.TransformListener` to help make the task of receiving transforms easier.
  243. ```python
  244. tf_buffer = tf2_ros.Buffer()
  245. listener = tf2_ros.TransformListener(tf_buffer)
  246. ```
  247. Here, we create a `TransformListener` object. Once the listener is created, it starts receiving tf2 transformations over the wire, and buffers them for up to 10 seconds.
  248. ```python
  249. from_frame_rel = 'link_grasp_center'
  250. to_frame_rel = 'fk_link_lift'
  251. ```
  252. Store frame names in variables that will be used to compute transformations.
  253. ```python
  254. rospy.sleep(1.0)
  255. rate = rospy.Rate(1)
  256. ```
  257. The first line gives the listener some time to accumulate transforms. The second line is the rate the node is going to publish information (1 Hz).
  258. ```python
  259. try:
  260. trans = tf_buffer.lookup_transform(to_frame_rel,
  261. from_frame_rel,
  262. rospy.Time())
  263. rospy.loginfo('The pose of target frame %s with reference from %s is: \n %s', from_frame_rel, to_frame_rel, trans.transform)
  264. except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException):
  265. rospy.logwarn(' Could not transform %s from %s ', to_frame_rel, from_frame_rel)
  266. ```
  267. Try to look up the transform we want. Use a try-except block, since it may fail on any single call, due to internal timing issues in the transform publishers. Look up transform between *from_frame_rel* and *to_frame_rel* frames with the `lookup_transform()` function.
  268. ```python
  269. rospy.init_node('tf2_listener')
  270. FrameListener()
  271. ```
  272. 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 "/".
  273. Instantiate the `FrameListener()` class.
  274. ```python
  275. rospy.spin()
  276. ```
  277. Give control to ROS. 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.