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.

158 lines
6.8 KiB

2 years ago
  1. ## Example 5
  2. In this example, we will review a Python script that prints out the positions of a selected group of Stretch's joints. This script is helpful if you need the joint positions after you teleoperated Stretch with the Xbox controller or physically moved the robot to the desired configuration after hitting the run stop button.
  3. If you are looking for a continuous print of the joint states while Stretch is in action, then you can use the [rostopic command-line tool](http://wiki.ros.org/rostopic) shown in the [Internal State of Stretch Tutorial](internal_state_of_stretch.md).
  4. Begin by starting up the stretch driver launch file.
  5. ```bash
  6. # Terminal 1
  7. roslaunch stretch_core stretch_driver.launch
  8. ```
  9. You can then hit the run-stop button (you should hear a beep and the LED light in the button blink) and move the robot's joints to a desired configuration. Once you are satisfied with the configuration, hold the run-stop button until you hear a beep. Then run the following command to excecute the [joint_state_printer.py](https://github.com/hello-robot/stretch_tutorials/blob/main/src/joint_state_printer.py) which will print the joint positions of the lift, arm, and wrist.
  10. ```bash
  11. cd catkin_ws/src/stretch_tutorials/src/
  12. python3 joint_state_printer.py
  13. ```
  14. Your terminal will output the `position` information of the previously mentioned joints shown below.
  15. ```
  16. name: ['joint_lift', 'wrist_extension', 'joint_wrist_yaw']
  17. position: [0.6043133175850597, 0.19873586673129257, 0.017257283863713464]
  18. ```
  19. **IMPORTANT NOTE:** Stretch's arm has 4 prismatic joints and the sum of these positions gives the *wrist_extension* distance. The *wrist_extension* is needed when sending [joint trajectory commands](follow_joint_trajectory.md) to the robot. Further, you **can not** actuate an individual arm joint. Here is an image of the arm joints for reference:
  20. <p align="center">
  21. <img src="https://raw.githubusercontent.com/hello-robot/stretch_tutorials/main/images/joints.png"/>
  22. </p>
  23. ### The Code
  24. ```python
  25. #!/usr/bin/env python
  26. import rospy
  27. import sys
  28. from sensor_msgs.msg import JointState
  29. class JointStatePublisher():
  30. """
  31. A class that prints the positions of desired joints in Stretch.
  32. """
  33. def __init__(self):
  34. """
  35. Function that initializes the subscriber.
  36. :param self: The self reference.
  37. """
  38. self.sub = rospy.Subscriber('joint_states', JointState, self.callback)
  39. def callback(self, msg):
  40. """
  41. Callback function to deal with the incoming JointState messages.
  42. :param self: The self reference.
  43. :param msg: The JointState message.
  44. """
  45. self.joint_states = msg
  46. def print_states(self, joints):
  47. """
  48. print_states function to deal with the incoming JointState messages.
  49. :param self: The self reference.
  50. :param joints: A list of string values of joint names.
  51. """
  52. joint_positions = []
  53. for joint in joints:
  54. if joint == "wrist_extension":
  55. index = self.joint_states.name.index('joint_arm_l0')
  56. joint_positions.append(4*self.joint_states.position[index])
  57. continue
  58. index = self.joint_states.name.index(joint)
  59. joint_positions.append(self.joint_states.position[index])
  60. print("name: " + str(joints))
  61. print("position: " + str(joint_positions))
  62. rospy.signal_shutdown("done")
  63. sys.exit(0)
  64. if __name__ == '__main__':
  65. rospy.init_node('joint_state_printer', anonymous=True)
  66. JSP = JointStatePublisher()
  67. rospy.sleep(.1)
  68. joints = ["joint_lift", "wrist_extension", "joint_wrist_yaw"]
  69. #joints = ["joint_head_pan","joint_head_tilt", joint_gripper_finger_left", "joint_gripper_finger_right"]
  70. JSP.print_states(joints)
  71. rospy.spin()
  72. ```
  73. ### The Code Explained
  74. Now let's break the code down.
  75. ```python
  76. #!/usr/bin/env python
  77. ```
  78. 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.
  79. ```python
  80. import rospy
  81. import sys
  82. from sensor_msgs.msg import JointState
  83. ```
  84. You need to import `rospy` if you are writing a ROS [Node](http://wiki.ros.org/Nodes). Import `sensor_msgs.msg` so that we can subscribe to `JointState` messages.
  85. ```python
  86. self.sub = rospy.Subscriber('joint_states', JointState, self.callback)
  87. ```
  88. Set up a subscriber. We're going to subscribe to the topic "*joint_states*", looking for `JointState` messages. When a message comes in, ROS is going to pass it to the function "callback" automatically
  89. ```python
  90. def callback(self, msg):
  91. self.joint_states = msg
  92. ```
  93. This is the callback function where he `JointState` messages are stored as *self.joint_states*. Further information about the this message type can be found here: [JointState Message](http://docs.ros.org/en/lunar/api/sensor_msgs/html/msg/JointState.html)
  94. ```python
  95. def print_states(self, joints):
  96. joint_positions = []
  97. ```
  98. This is the `print_states()` function which takes in a list of joints of interest as its argument. the is also an empty list set as *joint_positions* and this is where the positions of the requested joints will be appended.
  99. ```python
  100. for joint in joints:
  101. if joint == "wrist_extension":
  102. index = self.joint_states.name.index('joint_arm_l0')
  103. joint_positions.append(4*self.joint_states.position[index])
  104. continue
  105. index = self.joint_states.name.index(joint)
  106. joint_positions.append(self.joint_states.position[index])
  107. ```
  108. In this section of the code, a forloop is used to parse the names of the requested joints from the *self.joint_states* list. The `index()` function returns the index a of the name of the requested joint and appends the respective position to our *joint_positions* list.
  109. ```python
  110. rospy.signal_shutdown("done")
  111. sys.exit(0)
  112. ```
  113. The first line of code initiates a clean shutdown of ROS. The second line of code exits the Python interpreter.
  114. ```python
  115. rospy.init_node('joint_state_printer', anonymous=True)
  116. JSP = JointStatePublisher()
  117. rospy.sleep(.1)
  118. ```
  119. 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 "/".
  120. Declare object, *JSP*, from the `JointStatePublisher` class.
  121. The use of the `rospy.sleep()` function is to allow the *JSP* class to initialize all of its features before requesting to publish joint positions of desired joints (running the `print_states()` method).
  122. ```python
  123. joints = ["joint_lift", "wrist_extension", "joint_wrist_yaw"]
  124. #joints = ["joint_head_pan","joint_head_tilt", joint_gripper_finger_left", "joint_gripper_finger_right"]
  125. JSP.print_states(joints)
  126. ```
  127. Create a list of the desired joints that you want positions to be printed. Then use that list as an argument for the `print_states()` method.
  128. ```python
  129. rospy.spin()
  130. ```
  131. Give control to ROS with `rospy.spin()`. 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.