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.

403 lines
16 KiB

2 years ago
2 years ago
  1. # Example 12
  2. For this example, we will send follow joint trajectory commands for the head camera to search and locate an ArUco tag. In this instance, a Stretch robot will try to locate the docking station's ArUco tag.
  3. ## Modifying Stretch Marker Dictionary YAML File.
  4. When defining the ArUco markers on Stretch, hello robot utilizes a YAML file, [stretch_marker_dict.yaml](https://github.com/hello-robot/stretch_ros/blob/master/stretch_core/config/stretch_marker_dict.yaml), that holds the information about the markers. A further breakdown of the yaml file can be found in our [Aruco Marker Detection](aruco_marker_detection.md) tutorial.
  5. Below is what the needs to be included in the [stretch_marker_dict.yaml](https://github.com/hello-robot/stretch_ros/blob/master/stretch_core/config/stretch_marker_dict.yaml) file so the [detect_aruco_markers](https://github.com/hello-robot/stretch_ros/blob/master/stretch_core/nodes/detect_aruco_markers) node can find the docking station's ArUco tag.
  6. ```yaml
  7. '245':
  8. 'length_mm': 88.0
  9. 'use_rgb_only': False
  10. 'name': 'docking_station'
  11. 'link': None
  12. ```
  13. ## Getting Started
  14. Begin by running the stretch driver launch file.
  15. ```bash
  16. # Terminal 1
  17. roslaunch stretch_core stretch_driver.launch
  18. ```
  19. To activate the RealSense camera and publish topics to be visualized, run the following launch file in a new terminal.
  20. ```bash
  21. # Terminal 2
  22. roslaunch stretch_core d435i_high_resolution.launch
  23. ```
  24. Next, run the stretch ArUco launch file which will bring up the [detect_aruco_markers](https://github.com/hello-robot/stretch_ros/blob/master/stretch_core/nodes/detect_aruco_markers) node.
  25. ```bash
  26. # Terminal 3
  27. roslaunch stretch_core stretch_aruco.launch
  28. ```
  29. Within this tutorial package, there is an [RViz config file](https://github.com/hello-robot/stretch_tutorials/blob/main/rviz/aruco_detector_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.
  30. ```bash
  31. # Terminal 4
  32. rosrun rviz rviz -d /home/hello-robot/catkin_ws/src/stretch_tutorials/rviz/aruco_detector_example.rviz
  33. ```
  34. Then run the [aruco_tag_locator.py](https://github.com/hello-robot/stretch_tutorials/blob/main/src/aruco_tag_locator.py) node.
  35. ```bash
  36. # Terminal 5
  37. cd catkin_ws/src/stretch_tutorials/src/
  38. python aruco_tag_locator.py
  39. ```
  40. <p align="center">
  41. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/main/images/aruco_locator.gif"/>
  42. </p>
  43. ### The Code
  44. ```python
  45. #! /usr/bin/env python
  46. import rospy
  47. import time
  48. import tf2_ros
  49. import numpy as np
  50. from math import pi
  51. import hello_helpers.hello_misc as hm
  52. from sensor_msgs.msg import JointState
  53. from control_msgs.msg import FollowJointTrajectoryGoal
  54. from trajectory_msgs.msg import JointTrajectoryPoint
  55. from geometry_msgs.msg import TransformStamped
  56. class LocateArUcoTag(hm.HelloNode):
  57. """
  58. A class that actuates the RealSense camera to find the docking station's
  59. ArUco tag and returns a Transform between the `base_link` and the requested tag.
  60. """
  61. def __init__(self):
  62. """
  63. A function that initializes the subscriber and other needed variables.
  64. :param self: The self reference.
  65. """
  66. hm.HelloNode.__init__(self)
  67. self.joint_states_sub = rospy.Subscriber('/stretch/joint_states', JointState, self.joint_states_callback)
  68. self.transform_pub = rospy.Publisher('ArUco_transform', TransformStamped, queue_size=10)
  69. self.joint_state = None
  70. self.min_pan_position = -4.10
  71. self.max_pan_position = 1.50
  72. self.pan_num_steps = 10
  73. self.pan_step_size = abs(self.min_pan_position - self.max_pan_position)/self.pan_num_steps
  74. self.min_tilt_position = -0.75
  75. self.tilt_num_steps = 3
  76. self.tilt_step_size = pi/16
  77. self.rot_vel = 0.5 # radians per sec
  78. def joint_states_callback(self, msg):
  79. """
  80. A callback function that stores Stretch's joint states.
  81. :param self: The self reference.
  82. :param msg: The JointState message type.
  83. """
  84. self.joint_state = msg
  85. def send_command(self, command):
  86. '''
  87. Handles single joint control commands by constructing a FollowJointTrajectoryGoal
  88. message and sending it to the trajectory_client created in hello_misc.
  89. :param self: The self reference.
  90. :param command: A dictionary message type.
  91. '''
  92. if (self.joint_state is not None) and (command is not None):
  93. joint_name = command['joint']
  94. trajectory_goal = FollowJointTrajectoryGoal()
  95. trajectory_goal.trajectory.joint_names = [joint_name]
  96. point = JointTrajectoryPoint()
  97. if 'delta' in command:
  98. joint_index = self.joint_state.name.index(joint_name)
  99. joint_value = self.joint_state.position[joint_index]
  100. delta = command['delta']
  101. new_value = joint_value + delta
  102. point.positions = [new_value]
  103. elif 'position' in command:
  104. point.positions = [command['position']]
  105. point.velocities = [self.rot_vel]
  106. trajectory_goal.trajectory.points = [point]
  107. trajectory_goal.trajectory.header.stamp = rospy.Time(0.0)
  108. trajectory_goal.trajectory.header.frame_id = 'base_link'
  109. self.trajectory_client.send_goal(trajectory_goal)
  110. self.trajectory_client.wait_for_result()
  111. def find_tag(self, tag_name='docking_station'):
  112. """
  113. A function that actuates the camera to search for a defined ArUco tag
  114. marker. Then the function returns the pose
  115. :param self: The self reference.
  116. :param tag_name: A string value of the ArUco marker name.
  117. :returns transform: The docking station's TransformStamped message.
  118. """
  119. pan_command = {'joint': 'joint_head_pan', 'position': self.min_pan_position}
  120. self.send_command(pan_command)
  121. tilt_command = {'joint': 'joint_head_tilt', 'position': self.min_tilt_position}
  122. self.send_command(tilt_command)
  123. for i in range(self.tilt_num_steps):
  124. for j in range(self.pan_num_steps):
  125. pan_command = {'joint': 'joint_head_pan', 'delta': self.pan_step_size}
  126. self.send_command(pan_command)
  127. rospy.sleep(0.2)
  128. try:
  129. transform = self.tf_buffer.lookup_transform('base_link',
  130. tag_name,
  131. rospy.Time())
  132. rospy.loginfo("Found Requested Tag: \n%s", transform)
  133. self.transform_pub.publish(transform)
  134. return transform
  135. except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException):
  136. continue
  137. pan_command = {'joint': 'joint_head_pan', 'position': self.min_pan_position}
  138. self.send_command(pan_command)
  139. tilt_command = {'joint': 'joint_head_tilt', 'delta': self.tilt_step_size}
  140. self.send_command(tilt_command)
  141. rospy.sleep(.25)
  142. rospy.loginfo("The requested tag '%s' was not found", tag_name)
  143. def main(self):
  144. """
  145. Function that initiates the issue_command function.
  146. :param self: The self reference.
  147. """
  148. hm.HelloNode.main(self, 'aruco_tag_locator', 'aruco_tag_locator', wait_for_first_pointcloud=False)
  149. self.static_broadcaster = tf2_ros.StaticTransformBroadcaster()
  150. self.tf_buffer = tf2_ros.Buffer()
  151. self.listener = tf2_ros.TransformListener(self.tf_buffer)
  152. rospy.sleep(1.0)
  153. rospy.loginfo('Searching for docking ArUco tag.')
  154. pose = self.find_tag("docking_station")
  155. if __name__ == '__main__':
  156. try:
  157. node = LocateArUcoTag()
  158. node.main()
  159. except KeyboardInterrupt:
  160. rospy.loginfo('interrupt received, so shutting down')
  161. ```
  162. ### The Code Explained
  163. Now let's break the code down.
  164. ```python
  165. #!/usr/bin/env python
  166. ```
  167. 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.
  168. ```python
  169. import rospy
  170. import time
  171. import tf2_ros
  172. import numpy as np
  173. from math import pi
  174. import hello_helpers.hello_misc as hm
  175. from sensor_msgs.msg import JointState
  176. from control_msgs.msg import FollowJointTrajectoryGoal
  177. from trajectory_msgs.msg import JointTrajectoryPoint
  178. from geometry_msgs.msg import TransformStamped
  179. ```
  180. You need to import `rospy` if you are writing a ROS [Node](http://wiki.ros.org/Nodes). Import other python modules needed for this node. 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.
  181. ```python
  182. def __init__(self):
  183. """
  184. A function that initializes the subscriber and other needed variables.
  185. :param self: The self reference.
  186. """
  187. hm.HelloNode.__init__(self)
  188. self.joint_states_sub = rospy.Subscriber('/stretch/joint_states', JointState, self.joint_states_callback)
  189. self.transform_pub = rospy.Publisher('ArUco_transform', TransformStamped, queue_size=10)
  190. self.joint_state = None
  191. ```
  192. The `LocateArUcoTag` class inherits the `HelloNode` class from `hm` and is instantiated.
  193. Set up a subscriber with `rospy.Subscriber('/stretch/joint_states', JointState, self.joint_states_callback)`. We're going to subscribe to the topic "*stretch/joint_states*", looking for `JointState` messages. When a message comes in, ROS is going to pass it to the function `joint_states_callback()` automatically.
  194. `rospy.Publisher('ArUco_transform', TransformStamped, queue_size=10)` declares that your node is publishing to the *ArUco_transform* topic using the message type `TransformStamped`. The `queue_size` argument limits the amount of queued messages if any subscriber is not receiving them fast enough.
  195. ```python
  196. self.min_pan_position = -4.10
  197. self.max_pan_position = 1.50
  198. self.pan_num_steps = 10
  199. self.pan_step_size = abs(self.min_pan_position - self.max_pan_position)/self.pan_num_steps
  200. ```
  201. Provide the minimum and maximum joint positions for the head pan. These values are needed for sweeping the head to search for the ArUco tag. We also define the number of steps for the sweep, then create the step size for the head pan joint.
  202. ```python
  203. self.min_tilt_position = -0.75
  204. self.tilt_num_steps = 3
  205. self.tilt_step_size = pi/16
  206. ```
  207. Set the minimum position of the tilt joint, the number of steps, and the size of each step.
  208. ```python
  209. self.rot_vel = 0.5 # radians per sec
  210. ```
  211. Define the head actuation rotational velocity.
  212. ```python
  213. def joint_states_callback(self, msg):
  214. """
  215. A callback function that stores Stretch's joint states.
  216. :param self: The self reference.
  217. :param msg: The JointState message type.
  218. """
  219. self.joint_state = msg
  220. ```
  221. The `joint_states_callback()` function stores Stretch's joint states.
  222. ```python
  223. def send_command(self, command):
  224. '''
  225. Handles single joint control commands by constructing a FollowJointTrajectoryGoal
  226. message and sending it to the trajectory_client created in hello_misc.
  227. :param self: The self reference.
  228. :param command: A dictionary message type.
  229. '''
  230. if (self.joint_state is not None) and (command is not None):
  231. joint_name = command['joint']
  232. trajectory_goal = FollowJointTrajectoryGoal()
  233. trajectory_goal.trajectory.joint_names = [joint_name]
  234. point = JointTrajectoryPoint()
  235. ```
  236. Assign *trajectory_goal* as a `FollowJointTrajectoryGoal` message type. Then extract the string value from the `joint` key. Also, assign *point* as a `JointTrajectoryPoint` message type.
  237. ```python
  238. if 'delta' in command:
  239. joint_index = self.joint_state.name.index(joint_name)
  240. joint_value = self.joint_state.position[joint_index]
  241. delta = command['delta']
  242. new_value = joint_value + delta
  243. point.positions = [new_value]
  244. ```
  245. Check to see if `delta` is a key in the command dictionary. Then get the current position of the joint and add the delta as a a new position value.
  246. ```python
  247. elif 'position' in command:
  248. point.positions = [command['position']]
  249. ```
  250. Check to see if `position`is a key in the command dictionary. Then extract the position value.
  251. ```python
  252. point.velocities = [self.rot_vel]
  253. trajectory_goal.trajectory.points = [point]
  254. trajectory_goal.trajectory.header.stamp = rospy.Time(0.0)
  255. trajectory_goal.trajectory.header.frame_id = 'base_link'
  256. self.trajectory_client.send_goal(trajectory_goal)
  257. self.trajectory_client.wait_for_result()
  258. ```
  259. Then `trajectory_goal.trajectory.points` is defined by the positions set in *point*. Specify the coordinate frame that we want (*base_link*) and set the time to be now. Make the action call and send the goal. The last line of code waits for the result before it exits the python script.
  260. ```python
  261. def find_tag(self, tag_name='docking_station'):
  262. """
  263. A function that actuates the camera to search for a defined ArUco tag
  264. marker. Then the function returns the pose
  265. :param self: The self reference.
  266. :param tag_name: A string value of the ArUco marker name.
  267. :returns transform: The docking station's TransformStamped message.
  268. """
  269. pan_command = {'joint': 'joint_head_pan', 'position': self.min_pan_position}
  270. self.send_command(pan_command)
  271. tilt_command = {'joint': 'joint_head_tilt', 'position': self.min_tilt_position}
  272. self.send_command(tilt_command)
  273. ```
  274. Create a dictionaries to get the head in its initial position for its search and send the commands the the `send_command()` function.
  275. ```python
  276. for i in range(self.tilt_num_steps):
  277. for j in range(self.pan_num_steps):
  278. pan_command = {'joint': 'joint_head_pan', 'delta': self.pan_step_size}
  279. self.send_command(pan_command)
  280. rospy.sleep(0.5)
  281. ```
  282. Utilize nested for loop to sweep the pan and tilt in increments. Then update the *joint_head_pan* position by the *pan_step_size*.
  283. Use `rospy.sleep()` function to give time for system to do a Transform lookup before next step.
  284. ```python
  285. try:
  286. transform = self.tf_buffer.lookup_transform('base_link',
  287. tag_name,
  288. rospy.Time())
  289. rospy.loginfo("Found Requested Tag: \n%s", transform)
  290. self.transform_pub.publish(transform)
  291. return transform
  292. except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException):
  293. continue
  294. ```
  295. Use a try-except block to look up the transform between the *base_link* and requested ArUco tag. Then publish and return the `TransformStamped` message.
  296. ```python
  297. pan_command = {'joint': 'joint_head_pan', 'position': self.min_pan_position}
  298. self.send_command(pan_command)
  299. tilt_command = {'joint': 'joint_head_tilt', 'delta': self.tilt_step_size}
  300. self.send_command(tilt_command)
  301. rospy.sleep(.25)
  302. ```
  303. Begin sweep with new tilt angle.
  304. ```python
  305. def main(self):
  306. """
  307. Function that initiates the issue_command function.
  308. :param self: The self reference.
  309. """
  310. hm.HelloNode.main(self, 'aruco_tag_locator', 'aruco_tag_locator', wait_for_first_pointcloud=False)
  311. ```
  312. Create a funcion, `main()`, to do all of the setup for the `hm.HelloNode` class and initialize the `aruco_tag_locator` node.
  313. ```python
  314. self.static_broadcaster = tf2_ros.StaticTransformBroadcaster()
  315. self.tf_buffer = tf2_ros.Buffer()
  316. self.listener = tf2_ros.TransformListener(self.tf_buffer)
  317. rospy.sleep(1.0)
  318. ```
  319. Create a StaticTranformBoradcaster Node. Also, start a tf buffer that will store the tf information for a few seconds.Then set up a tf listener, which will subscribe to all of the relevant tf topics, and keep track of the information. Include `rospy.sleep(1.0)` to give the listener some time to accumulate transforms.
  320. ```python
  321. rospy.loginfo('Searching for docking ArUco tag.')
  322. pose = self.find_tag("docking_station")
  323. ```
  324. Notify Stretch is searching for the ArUco tag with a `rospy.loginfo()` function. Then search for the ArUco marker for the docking station.
  325. ```python
  326. if __name__ == '__main__':
  327. try:
  328. node = LocateArUcoTag()
  329. node.main()
  330. except KeyboardInterrupt:
  331. rospy.loginfo('interrupt received, so shutting down')
  332. ```
  333. Declare `LocateArUcoTag` object. Then run the `main()` method.