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.

339 lines
11 KiB

  1. ## Example 10
  2. !!! note
  3. ROS 2 tutorials are still under active development.
  4. This tutorial provides you with an idea of what tf2 can do in the Python track. We will elaborate on how to create a tf2 static broadcaster and listener.
  5. ## tf2 Static Broadcaster
  6. 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.
  7. Begin by starting up the stretch driver launch file.
  8. ```{.bash .shell-prompt}
  9. ros2 launch stretch_core stretch_driver.launch.py
  10. ```
  11. Open RViz in another terminal and add the RobotModel and TF plugins in the left hand panel
  12. ```{.bash .shell-prompt}
  13. ros2 run rviz2 rviz2
  14. ```
  15. Then run the tf2 broadcaster node to visualize three static frames.
  16. ```{.bash .shell-prompt}
  17. ros2 run stretch_ros_tutorials tf_broadcaster
  18. ```
  19. The GIF below visualizes what happens when running the previous node.
  20. <p align="center">
  21. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/noetic/images/tf2_broadcaster.gif"/>
  22. </p>
  23. **OPTIONAL**: If you would like to see how the static frames update while the robot is in motion, run the stow command node and observe the tf frames in RViz.
  24. ```{.bash .shell-prompt}
  25. ros2 run stretch_ros_tutorials stow_command
  26. ```
  27. <p align="center">
  28. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/noetic/images/tf2_broadcaster_with_stow.gif"/>
  29. </p>
  30. ### The Code
  31. ```python
  32. #!/usr/bin/env python
  33. import rclpy
  34. from rclpy.node import Node
  35. from tf2_ros import TransformBroadcaster
  36. import tf_transformations
  37. from geometry_msgs.msg import TransformStamped
  38. # This node publishes three child static frames in reference to their parent frames as below:
  39. # parent -> link_mast child -> fk_link_mast
  40. # parent -> link_lift child -> fk_link_lift
  41. # parent -> link_wrist_yaw child -> fk_link_wrist_yaw
  42. class FixedFrameBroadcaster(Node):
  43. def __init__(self):
  44. super().__init__('stretch_tf_broadcaster')
  45. self.br = TransformBroadcaster(self)
  46. time_period = 0.1 # seconds
  47. self.timer = self.create_timer(time_period, self.broadcast_timer_callback)
  48. self.mast = TransformStamped()
  49. self.mast.header.frame_id = 'link_mast'
  50. self.mast.child_frame_id = 'fk_link_mast'
  51. self.mast.transform.translation.x = 0.0
  52. self.mast.transform.translation.y = 0.0
  53. self.mast.transform.translation.z = 0.0
  54. q = tf_transformations.quaternion_from_euler(1.5707, 0, -1.5707)
  55. self.mast.transform.rotation.x = q[0]
  56. self.mast.transform.rotation.y = q[1]
  57. self.mast.transform.rotation.z = q[2]
  58. self.mast.transform.rotation.w = q[3]
  59. self.lift = TransformStamped()
  60. self.lift.header.stamp = self.get_clock().now().to_msg()
  61. self.lift.header.frame_id = 'link_lift'
  62. self.lift.child_frame_id = 'fk_link_lift'
  63. self.lift.transform.translation.x = 0.0
  64. self.lift.transform.translation.y = 2.0
  65. self.lift.transform.translation.z = 0.0
  66. q = tf_transformations.quaternion_from_euler(1.5707, 0, -1.5707)
  67. self.lift.transform.rotation.x = q[0]
  68. self.lift.transform.rotation.y = q[1]
  69. self.lift.transform.rotation.z = q[2]
  70. self.lift.transform.rotation.w = q[3]
  71. self.br.sendTransform(self.lift)
  72. self.wrist = TransformStamped()
  73. self.wrist.header.stamp = self.get_clock().now().to_msg()
  74. self.wrist.header.frame_id = 'link_wrist_yaw'
  75. self.wrist.child_frame_id = 'fk_link_wrist_yaw'
  76. self.wrist.transform.translation.x = 0.0
  77. self.wrist.transform.translation.y = 2.0
  78. self.wrist.transform.translation.z = 0.0
  79. q = tf_transformations.quaternion_from_euler(1.5707, 0, -1.5707)
  80. self.wrist.transform.rotation.x = q[0]
  81. self.wrist.transform.rotation.y = q[1]
  82. self.wrist.transform.rotation.z = q[2]
  83. self.wrist.transform.rotation.w = q[3]
  84. self.br.sendTransform(self.wrist)
  85. self.get_logger().info("Publishing Tf frames. Use RViz to visualize.")
  86. def broadcast_timer_callback(self):
  87. self.mast.header.stamp = self.get_clock().now().to_msg()
  88. self.br.sendTransform(self.mast)
  89. self.lift.header.stamp = self.get_clock().now().to_msg()
  90. self.br.sendTransform(self.lift)
  91. self.wrist.header.stamp = self.get_clock().now().to_msg()
  92. self.br.sendTransform(self.wrist)
  93. def main(args=None):
  94. rclpy.init(args=args)
  95. tf_broadcaster = FixedFrameBroadcaster()
  96. rclpy.spin(tf_broadcaster)
  97. tf_broadcaster.destroy_node()
  98. rclpy.shutdown()
  99. if __name__ == '__main__':
  100. main()
  101. ```
  102. ### The Code Explained
  103. Now let's break the code down.
  104. ```python
  105. #!/usr/bin/env python3
  106. ```
  107. Every Python ROS [Node](http://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools/Understanding-ROS2-Nodes/Understanding-ROS2-Nodes.html) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
  108. ```python
  109. import rclpy
  110. from rclpy.node import Node
  111. from tf2_ros import TransformBroadcaster
  112. import tf_transformations
  113. from geometry_msgs.msg import TransformStamped
  114. ```
  115. You need to import rclpy if you are writing a ROS 2 node. 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 `TransformBroadcaster.` to help make the task of publishing transforms easier.
  116. ```python
  117. class FixedFrameBroadcaster(Node):
  118. def __init__(self):
  119. super().__init__('stretch_tf_broadcaster')
  120. self.br = TransformBroadcaster(self)
  121. ```
  122. Here we create a `TransformStamped` object which will be the message we will send over once populated.
  123. ```python
  124. self.lift = TransformStamped()
  125. self.lift.header.stamp = self.get_clock().now().to_msg()
  126. self.lift.header.frame_id = 'link_lift'
  127. self.lift.child_frame_id = 'fk_link_lift'
  128. ```
  129. We need to give the transform being published a timestamp, we'll just stamp it with the current time, `self.get_clock().now().to_msg()`. Then, we need to set the name of the parent frame of the link we're creating, in this case *link_lift*. 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_lift*.
  130. ```python
  131. self.mast.transform.translation.x = 0.0
  132. self.mast.transform.translation.y = 0.0
  133. self.mast.transform.translation.z = 0.0
  134. ```
  135. Set the translation values for the child frame.
  136. ```python
  137. q = tf_transformations.quaternion_from_euler(1.5707, 0, -1.5707)
  138. self.lift.transform.rotation.x = q[0]
  139. self.lift.transform.rotation.y = q[1]
  140. self.lift.transform.rotation.z = q[2]
  141. self.lift.transform.rotation.w = q[3]
  142. ```
  143. 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.
  144. This process will be completed for the *link_mast* and *link_wrist_yaw* as well.
  145. ```python
  146. self.br.sendTransform(self.lift)
  147. ```
  148. Send the three transforms using the `sendTransform()` function.
  149. ```python
  150. def main(args=None):
  151. rclpy.init(args=args)
  152. tf_broadcaster = FixedFrameBroadcaster()
  153. ```
  154. Instantiate the `FixedFrameBroadcaster()` class.
  155. ```python
  156. rclpy.spin(tf_broadcaster)
  157. ```
  158. Give control to ROS. This will allow the callback to be called whenever new
  159. messages come in. If we don't put this line in, then the node will not work,
  160. and ROS will not process any messages.
  161. ## tf2 Static Listener
  162. 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*.
  163. Begin by starting up the stretch driver launch file.
  164. ```{.bash .shell-prompt}
  165. ros2 launch stretch_core stretch_driver.launch.py
  166. ```
  167. Then run the tf2 broadcaster node to create the three static frames.
  168. ```{.bash .shell-prompt}
  169. ros2 run stretch_ros_tutorials tf_broadcaster
  170. ```
  171. Finally, run the tf2 listener node to print the transform between two links.
  172. ```{.bash .shell-prompt}
  173. ros2 run stretch_ros_tutorials tf_listener
  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. import rclpy
  194. from rclpy.node import Node
  195. from rclpy.time import Time
  196. from tf2_ros import TransformException
  197. from tf2_ros.buffer import Buffer
  198. from tf2_ros.transform_listener import TransformListener
  199. class FrameListener(Node):
  200. def __init__(self):
  201. super().__init__('stretch_tf_listener')
  202. self.declare_parameter('target_frame', 'link_grasp_center')
  203. self.target_frame = self.get_parameter(
  204. 'target_frame').get_parameter_value().string_value
  205. self.tf_buffer = Buffer()
  206. self.tf_listener = TransformListener(self.tf_buffer, self)
  207. time_period = 1.0 # seconds
  208. self.timer = self.create_timer(time_period, self.on_timer)
  209. def on_timer(self):
  210. from_frame_rel = self.target_frame
  211. to_frame_rel = 'fk_link_mast'
  212. try:
  213. now = Time()
  214. trans = self.tf_buffer.lookup_transform(
  215. to_frame_rel,
  216. from_frame_rel,
  217. now)
  218. except TransformException as ex:
  219. self.get_logger().info(
  220. f'Could not transform {to_frame_rel} to {from_frame_rel}: {ex}')
  221. return
  222. self.get_logger().info(
  223. f'the pose of target frame {from_frame_rel} with reference to {to_frame_rel} is: {trans}')
  224. def main():
  225. rclpy.init()
  226. node = FrameListener()
  227. try:
  228. rclpy.spin(node)
  229. except KeyboardInterrupt:
  230. pass
  231. rclpy.shutdown()
  232. if __name__ == '__main__':
  233. main()
  234. ```
  235. ### The Code Explained
  236. ```python
  237. self.tf_buffer = Buffer()
  238. self.tf_listener = TransformListener(self.tf_buffer, self)
  239. ```
  240. 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.
  241. ```python
  242. from_frame_rel = self.target_frame
  243. to_frame_rel = 'fk_link_mast'
  244. ```
  245. Store frame names in variables that will be used to compute transformations.
  246. ```python
  247. try:
  248. now = Time()
  249. trans = self.tf_buffer.lookup_transform(
  250. to_frame_rel,
  251. from_frame_rel,
  252. now)
  253. except TransformException as ex:
  254. self.get_logger().info(
  255. f'Could not transform {to_frame_rel} to {from_frame_rel}: {ex}')
  256. return
  257. ```
  258. 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.