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.

357 lines
13 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
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 10
  2. This tutorial we will explain 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 .shell-prompt}
  7. roslaunch stretch_core stretch_driver.launch
  8. ```
  9. Within this tutorial package, there is an [RViz config file](https://github.com/hello-robot/stretch_tutorials/blob/noetic/rviz/tf2_broadcaster_example.rviz) with the topics for the transform frames in the Display tree. You can visualize these topics and the robot model by running the command below in a new terminal.
  10. ```{.bash .shell-prompt}
  11. rosrun rviz rviz -d /home/hello-robot/catkin_ws/src/stretch_tutorials/rviz/tf2_broadcaster_example.rviz
  12. ```
  13. Then run the [tf2_broadcaster.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/tf2_broadcaster.py) node to visualize three static frames. In a new terminal, execute:
  14. ```{.bash .shell-prompt}
  15. cd catkin_ws/src/stretch_tutorials/src/
  16. python3 tf2_broadcaster.py
  17. ```
  18. The GIF below visualizes what happens when running the previous node.
  19. <p align="center">
  20. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/noetic/images/tf2_broadcaster.gif"/>
  21. </p>
  22. !!! tip
  23. 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/noetic/src/stow_command.py) and observe the tf frames in RViz.
  24. In a terminal, execute:
  25. ```{.bash .shell-prompt}
  26. cd catkin_ws/src/stretch_tutorials/src/
  27. python3 stow_command.py
  28. ```
  29. <p align="center">
  30. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/noetic/images/tf2_broadcaster_with_stow.gif"/>
  31. </p>
  32. ### The Code
  33. ```python
  34. #!/usr/bin/env python3
  35. import rospy
  36. import tf.transformations
  37. from geometry_msgs.msg import TransformStamped
  38. from tf2_ros import StaticTransformBroadcaster
  39. class FixedFrameBroadcaster():
  40. """
  41. This node publishes three child static frames in reference to their parent frames as below:
  42. parent -> link_mast child -> fk_link_mast
  43. parent -> link_lift child -> fk_link_lift
  44. parent -> link_wrist_yaw child -> fk_link_wrist_yaw
  45. """
  46. def __init__(self):
  47. """
  48. A function that creates a broadcast node and publishes three new transform
  49. frames.
  50. :param self: The self reference.
  51. """
  52. self.br = StaticTransformBroadcaster()
  53. self.mast = TransformStamped()
  54. self.mast.header.stamp = rospy.Time.now()
  55. self.mast.header.frame_id = 'link_mast'
  56. self.mast.child_frame_id = 'fk_link_mast'
  57. self.mast.transform.translation.x = 0.0
  58. self.mast.transform.translation.y = 2.0
  59. self.mast.transform.translation.z = 0.0
  60. q = tf.transformations.quaternion_from_euler(1.5707, 0, -1.5707)
  61. self.mast.transform.rotation.x = q[0]
  62. self.mast.transform.rotation.y = q[1]
  63. self.mast.transform.rotation.z = q[2]
  64. self.mast.transform.rotation.w = q[3]
  65. self.lift = TransformStamped()
  66. self.lift.header.stamp = rospy.Time.now()
  67. self.lift.header.frame_id = 'link_lift'
  68. self.lift.child_frame_id = 'fk_link_lift'
  69. self.lift.transform.translation.x = 0.0
  70. self.lift.transform.translation.y = 1.0
  71. self.lift.transform.translation.z = 0.0
  72. q = tf.transformations.quaternion_from_euler(1.5707, 0, -1.5707)
  73. self.lift.transform.rotation.x = q[0]
  74. self.lift.transform.rotation.y = q[1]
  75. self.lift.transform.rotation.z = q[2]
  76. self.lift.transform.rotation.w = q[3]
  77. self.wrist = TransformStamped()
  78. self.wrist.header.stamp = rospy.Time.now()
  79. self.wrist.header.frame_id = 'link_wrist_yaw'
  80. self.wrist.child_frame_id = 'fk_link_wrist_yaw'
  81. self.wrist.transform.translation.x = 0.0
  82. self.wrist.transform.translation.y = 1.0
  83. self.wrist.transform.translation.z = 0.0
  84. q = tf.transformations.quaternion_from_euler(1.5707, 0, -1.5707)
  85. self.wrist.transform.rotation.x = q[0]
  86. self.wrist.transform.rotation.y = q[1]
  87. self.wrist.transform.rotation.z = q[2]
  88. self.wrist.transform.rotation.w = q[3]
  89. self.br.sendTransform([self.mast, self.lift, self.wrist])
  90. rospy.loginfo('Publishing TF frames. Use RViz to visualize')
  91. if __name__ == '__main__':
  92. rospy.init_node('tf2_broadcaster')
  93. FixedFrameBroadcaster()
  94. rospy.spin()
  95. ```
  96. ### The Code Explained
  97. Now let's break the code down.
  98. ```python
  99. #!/usr/bin/env python3
  100. ```
  101. 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.
  102. ```python
  103. import rospy
  104. import tf.transformations
  105. from geometry_msgs.msg import TransformStamped
  106. from tf2_ros import StaticTransformBroadcaster
  107. ```
  108. 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.
  109. ```python
  110. def __init__(self):
  111. """
  112. A function that creates a broadcast node and publishes three new transform
  113. frames.
  114. :param self: The self reference.
  115. """
  116. self.br = StaticTransformBroadcaster()
  117. ```
  118. Here we create a `TransformStamped` object which will be the message we will send over once populated.
  119. ```python
  120. self.mast = TransformStamped()
  121. self.mast.header.stamp = rospy.Time.now()
  122. self.mast.header.frame_id = 'link_mast'
  123. self.mast.child_frame_id = 'fk_link_mast'
  124. ```
  125. 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`.
  126. ```python
  127. self.mast.transform.translation.x = 0.0
  128. self.mast.transform.translation.y = 2.0
  129. self.mast.transform.translation.z = 0.0
  130. ```
  131. Set the translation values for the child frame.
  132. ```python
  133. q = tf.transformations.quaternion_from_euler(1.5707, 0, -1.5707)
  134. self.wrist.transform.rotation.x = q[0]
  135. self.wrist.transform.rotation.y = q[1]
  136. self.wrist.transform.rotation.z = q[2]
  137. self.wrist.transform.rotation.w = q[3]
  138. ```
  139. The `quaternion_from_euler()` function takes in an Euler angle as an argument and returns a quaternion. Then set the rotation values to the transformed quaternions.
  140. This process will be completed for the `link_lift` and `link_wrist_yaw` as well.
  141. ```python
  142. self.br.sendTransform([self.mast, self.lift, self.wrist])
  143. ```
  144. Send the three transforms using the `sendTransform()` function.
  145. ```python
  146. rospy.init_node('tf2_broadcaster')
  147. FixedFrameBroadcaster()
  148. ```
  149. 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.
  150. !!! note
  151. 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. roslaunch stretch_core stretch_driver.launch
  164. ```
  165. Then run the [tf2_broadcaster.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/tf2_broadcaster.py) node in a new terminal to create the three static frames.
  166. ```bash
  167. cd catkin_ws/src/stretch_tutorials/src/
  168. python3 tf2_broadcaster.py
  169. ```
  170. Finally, run the [tf2_listener.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/tf2_listener.py) node in a separate terminal to print the transform between two links.
  171. ```bash
  172. cd catkin_ws/src/stretch_tutorials/src/
  173. python3 tf2_listener.py
  174. ```
  175. 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.
  176. ```{.bash .no-copy}
  177. [INFO] [1659551318.098168]: The pose of target frame link_grasp_center with reference from fk_link_lift is:
  178. translation:
  179. x: 1.08415191335
  180. y: -0.176147838153
  181. z: 0.576720021135
  182. rotation:
  183. x: -0.479004489528
  184. y: -0.508053545368
  185. z: -0.502884087254
  186. w: 0.509454501243
  187. ```
  188. <p align="center">
  189. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/noetic/images/tf2_listener.png"/>
  190. </p>
  191. ### The Code
  192. ```python
  193. #!/usr/bin/env python3
  194. import rospy
  195. from geometry_msgs.msg import TransformStamped
  196. import tf2_ros
  197. class FrameListener():
  198. """
  199. This Class prints the transformation between the fk_link_mast frame and the
  200. target frame, link_grasp_center.
  201. """
  202. def __init__(self):
  203. """
  204. A function that initializes the variables and looks up a transformation
  205. between a target and source frame.
  206. :param self: The self reference.
  207. """
  208. tf_buffer = tf2_ros.Buffer()
  209. listener = tf2_ros.TransformListener(tf_buffer)
  210. from_frame_rel = 'link_grasp_center'
  211. to_frame_rel = 'fk_link_lift'
  212. rospy.sleep(1.0)
  213. rate = rospy.Rate(1)
  214. while not rospy.is_shutdown():
  215. try:
  216. trans = tf_buffer.lookup_transform(to_frame_rel,
  217. from_frame_rel,
  218. rospy.Time())
  219. rospy.loginfo('The pose of target frame %s with reference from %s is: \n %s', from_frame_rel, to_frame_rel, trans.transform)
  220. except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException):
  221. rospy.logwarn(' Could not transform %s from %s ', to_frame_rel, from_frame_rel)
  222. rate.sleep()
  223. if __name__ == '__main__':
  224. rospy.init_node('tf2_listener')
  225. FrameListener()
  226. rospy.spin()
  227. ```
  228. ### The Code Explained
  229. Now let's break the code down.
  230. ```python
  231. #!/usr/bin/env python3
  232. ```
  233. 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.
  234. ```python
  235. import rospy
  236. from geometry_msgs.msg import TransformStamped
  237. import tf2_ros
  238. ```
  239. 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.
  240. ```python
  241. tf_buffer = tf2_ros.Buffer()
  242. listener = tf2_ros.TransformListener(tf_buffer)
  243. ```
  244. Here, we create a `TransformListener` object. Once the listener is created, it starts receiving tf2 transformations and buffers them for up to 10 seconds.
  245. ```python
  246. from_frame_rel = 'link_grasp_center'
  247. to_frame_rel = 'fk_link_lift'
  248. ```
  249. Store frame names in variables that will be used to compute transformations.
  250. ```python
  251. rospy.sleep(1.0)
  252. rate = rospy.Rate(1)
  253. ```
  254. The first line gives the listener some time to accumulate transforms. The second line is the rate at which the node is going to publish information (1 Hz).
  255. ```python
  256. try:
  257. trans = tf_buffer.lookup_transform(to_frame_rel,
  258. from_frame_rel,
  259. rospy.Time())
  260. rospy.loginfo('The pose of target frame %s with reference from %s is: \n %s', from_frame_rel, to_frame_rel, trans.transform)
  261. except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException):
  262. rospy.logwarn(' Could not transform %s from %s ', to_frame_rel, from_frame_rel)
  263. ```
  264. Try to look up the transformation 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.
  265. ```python
  266. rospy.init_node('tf2_listener')
  267. FrameListener()
  268. ```
  269. 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.
  270. !!! note
  271. The name must be a base name, i.e. it cannot contain any slashes "/".
  272. Instantiate the `FrameListener()` class.
  273. ```python
  274. rospy.spin()
  275. ```
  276. 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.