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.

107 lines
3.0 KiB

2 months ago
2 months ago
2 months ago
2 months ago
2 months ago
2 months ago
  1. # Motion Commands in ROS2
  2. ## Quickstart
  3. Sending motion commands is as easy as:
  4. 1. Launch the ROS2 driver in a terminal:
  5. ```{.bash .shell-prompt .copy}
  6. ros2 launch stretch_core stretch_driver.launch.py
  7. ```
  8. 2. Open iPython and type the following code, one line at a time:
  9. ```python
  10. import hello_helpers.hello_misc as hm
  11. node = hm.HelloNode.quick_create('temp')
  12. node.move_to_pose({'joint_lift': 0.4}, blocking=True)
  13. node.move_to_pose({'joint_wrist_yaw': 0.0, 'joint_wrist_roll': 0.0}, blocking=True)
  14. ```
  15. ## Writing a node
  16. You can also write a ROS2 node to send motion commands:
  17. ```python
  18. import hello_helpers.hello_misc as hm
  19. class MyNode(hm.HelloNode):
  20. def __init__(self):
  21. hm.HelloNode.__init__(self)
  22. def main(self):
  23. hm.HelloNode.main(self, 'my_node', 'my_node', wait_for_first_pointcloud=False)
  24. # my_node's main logic goes here
  25. self.move_to_pose({'joint_lift': 0.6}, blocking=True)
  26. self.move_to_pose({'joint_wrist_yaw': -1.0, 'joint_wrist_pitch': -1.0}, blocking=True)
  27. node = MyNode()
  28. node.main()
  29. ```
  30. Copy the above into a file called "example.py" and run it using:
  31. ```{.bash .shell-prompt .copy}
  32. python3 example.py
  33. ```
  34. ## Retrieving joint limits
  35. In a terminal, echo the `/joint_limits` topic:
  36. ```{.bash .shell-prompt .copy}
  37. ros2 topic echo /joint_limits
  38. ```
  39. In a second terminal, request the driver publish the joint limits:
  40. ```{.bash .shell-prompt .copy}
  41. ros2 service call /get_joint_states std_srvs/srv/Trigger {}
  42. ```
  43. In the first terminal, you'll see a single message get published. It'll look like this:
  44. ```yaml
  45. header:
  46. stamp:
  47. sec: 1725388967
  48. nanosec: 818893747
  49. frame_id: ''
  50. name:
  51. - joint_head_tilt
  52. - joint_wrist_pitch
  53. - joint_wrist_roll
  54. - joint_wrist_yaw
  55. - joint_head_pan
  56. - joint_lift
  57. - joint_arm
  58. - gripper_aperture
  59. - joint_gripper_finger_left
  60. - joint_gripper_finger_right
  61. position:
  62. - -2.0171847360696185
  63. - -1.5707963267948966
  64. - -2.9114955354069467
  65. - -1.3933658823294575
  66. - -4.035903452927122
  67. - 0.0
  68. - 0.0
  69. - -0.1285204486235414
  70. - -0.3757907854489514
  71. - -0.3757907854489514
  72. velocity:
  73. - 0.4908738521234052
  74. - 0.45099035163837853
  75. - 2.9176314585584895
  76. - 4.416586351787409
  77. - 1.7303303287350031
  78. - 1.0966833704348709
  79. - 0.5197662863936018
  80. - 0.34289112948906764
  81. - 1.0026056417808995
  82. - 1.0026056417808995
  83. effort: []
  84. ```
  85. We're misusing the [sensor_msgs/JointState](https://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/JointState.html) message to publish the joint limits. The `name` array lists out each ranged joint. The `position` array lists the lower bound for each joint. The `velocity` array lists the upper bound. The length of these 3 arrays will be equal, because the index of the joint in the `name` array determines which index the corresponding limits will be in the other two arrays.
  86. The revolute joints will have their limits published in radians, and the prismatic joints will have them published in meters. See the [Hardware Overview](../../getting_started/stretch_hardware_overview/) to see the ranges represented visually.