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.

217 lines
8.4 KiB

  1. # Commanding Stretch to Move
  2. This tutorial covers sending various kinds of motion commands to Stretch.
  3. ## Introducing Stretch Body
  4. "Stretch Body" is a Python library for Stretch. It's already installed on your robot. The library gives you an interface to command Stretch's body to move. We start by creating an instance of the `stretch_body.robot.Robot` class.
  5. ```python
  6. import stretch_body.robot
  7. r = stretch_body.robot.Robot()
  8. ```
  9. The hardware can only talk to one instance at a time, so if you see an `Another process is already using Stretch. Try running "stretch_free_robot_process.py"` error, you'll need to close the other application or use the `stretch_free_robot_process.py` CLI to free up the hardware.
  10. Next, we'll call the `startup()` method, which opens USB communication with the hardware, loads the parameters that dictate robot behavior, and launches a few helper threads to poll for status in the background.
  11. ```python
  12. did_startup = r.startup()
  13. print(f'Robot connected to hardware: {did_startup}')
  14. ```
  15. To close down the connection to the hardware, use `stop()`. Next, we'll check if the robot is "homed", i.e. the robot knows the zero position for each joint.
  16. ```python
  17. is_homed = r.is_homed()
  18. print(f'Robot is homed: {is_homed}')
  19. ```
  20. To execute the homing procedure, use `home()`. Ensure the robot has space around it.
  21. ## Sending Position Commands
  22. Stretch has the following joints:
  23. <!-- TODO: ![](./images/stretch_joints.png){ width="500" loading=lazy } -->
  24. 1. Left and right wheels, constituting a differential drive
  25. 1. Pristmatic vertical lift
  26. 1. Prismatic telescoping horizontal arm
  27. 1. Up to three revolute joints in the wrist: yaw, pitch, and roll
  28. - Print out `r.end_of_arm.joints` to see which joints your Stretch has
  29. 1. Gripper
  30. 1. Two revolute joints in the head: pan & tilt
  31. Each of these joints are accessible as an attribute of the `Robot` object.
  32. ```python
  33. # The mobile base:
  34. print(r.base)
  35. # The arm/lift:
  36. print(r.arm, r.lift)
  37. # The wrist/gripper
  38. print(r.end_of_arm)
  39. # The head
  40. print(r.head)
  41. ```
  42. Use the `move_to(pos)` method under each joint to queue up a command.
  43. ```python
  44. r.arm.move_to(0.2) # 0.2 meters
  45. r.lift.move_to(0.6) # 0.6 meters
  46. ```
  47. The arm and lift won't move yet. The commands have been queued up, but the hardware will wait to begin moving until we call `push_command()`.
  48. ```python
  49. r.push_command()
  50. ```
  51. The mobile base doesn't have a move method. Instead, its methods are `translate_by(delta)` and `rotate_by(delta)`.
  52. ```python
  53. r.base.translate_by(0.2) # 0.2 meters
  54. r.push_command()
  55. r.base.rotate_by(0.1) # 0.1 radians
  56. r.push_command()
  57. ```
  58. You'll notice the base doesn't translate forward by 0.2m. Instead, it skips to rotating counter-clockwise by 0.1rad. This happens because `push_command()` is asynchronous (i.e. the method returns immediately, and the program flow continues immediately to execute the rotation command). Use the `wait_command()` method to wait for the command to complete execution.
  59. ```python
  60. r.base.translate_by(0.2) # 0.2 meters
  61. r.push_command()
  62. r.wait_command()
  63. r.base.rotate_by(0.1) # 0.1 radians
  64. r.push_command()
  65. r.wait_command()
  66. ```
  67. The wrist and head joints are Dynamixel servos. Their API is `move_to(name, pos)`, and their commands aren't queued. They execute immediately.
  68. ```python
  69. print(f'Wrist joints: {r.end_of_arm.joints}') # ['wrist_yaw', 'wrist_pitch', 'wrist_roll', 'stretch_gripper']
  70. r.end_of_arm.move_to('wrist_yaw', 1.57)
  71. ```
  72. `wait_command()` will still work here. The gripper uses the same `move_to(name, pos)` API, and accepts values between -100 to 100, where the gripper is fully closed at -100 and fully open at 100.
  73. ```python
  74. r.end_of_arm.move_to('stretch_gripper', 100)
  75. ```
  76. ## Querying Stretch's current joint state
  77. The current state of each joint is available in a Python dictionary called `status` under each joint.
  78. ```python
  79. # Wheel odometry
  80. print(r.base.status['x'], r.base.status['y'], r.base.status['theta']) # (x meters, y meters, theta radians)
  81. # Arm/lift positions
  82. print(r.arm.status['pos'], r.lift.status['pos']) # (arm meters, lift meters)
  83. ```
  84. The wrist and head joints are Dynamixel servos. Their `status` dictionary is under the `get_joint(name)` method.
  85. ```python
  86. # Wrist positions
  87. print(f'Wrist joints: {r.end_of_arm.joints}')
  88. print(r.end_of_arm.get_joint('wrist_yaw').status['pos']) # radians
  89. # Head positions
  90. print(f'Head joints: {r.head.joints}')
  91. print(r.head.get_joint('head_pan').status['pos']) # radians
  92. ```
  93. ## Querying Stretch's joint limits
  94. Whereas the mobile base is unbounded (i.e. `translate_by(delta)` can take any value for delta), the rest of the joints have joint limits. They are available as part of the `soft_motion_limits` dictionary.
  95. ### Arm & Lift
  96. ![](./images/stretch_arm_lift_joint_limits.png){ width="500" loading=lazy }
  97. ```python
  98. print(r.lift.soft_motion_limits['hard']) # (lower bound in meters, upper bound in meters)
  99. print(r.arm.soft_motion_limits['hard'])
  100. ```
  101. `soft_motion_limits` is a dictionary with four keys: "collision", "user", "hard", and "current". Each key maps to a `[lower bound, upper bound]` tuple. "collision" is used by Stretch Body's self collision avoidance algorithm to set *soft*ware limits on the joint. "user" is used by you, the user, to set application specific software joint limits. "hard" is the hardware limits of the joint. And "current" is the aggregate of the previous three limits into the final limits enforced by the software.
  102. ### Wrist Joints
  103. | Yaw | Pitch | Roll |
  104. | ----------- | ------ | ------- |
  105. | ![](./images/stretch_yaw_joint_limits.png){ loading=lazy } | ![](./images/stretch_pitch_joint_limits.png){ loading=lazy } | ![](./images/stretch_roll_joint_limits.png){ loading=lazy } |
  106. ```python
  107. print(r.end_of_arm.get_joint('wrist_yaw').soft_motion_limits['hard']) # (lower bound in radians, upper bound in radians)
  108. print(r.end_of_arm.get_joint('wrist_pitch').soft_motion_limits['hard'])
  109. print(r.end_of_arm.get_joint('wrist_roll').soft_motion_limits['hard'])
  110. ```
  111. ### Head Joints
  112. ![](./images/stretch_head_joint_limits.png){ width="500" loading=lazy }
  113. ```python
  114. print(r.head.get_joint('head_pan').soft_motion_limits['hard']) # (lower bound in radians, upper bound in radians)
  115. print(r.head.get_joint('head_tilt').soft_motion_limits['hard'])
  116. ```
  117. ## Sending Velocity Commands
  118. Each joint accepts velocity commands via the `set_velocity(vel)` API.
  119. ```python
  120. r.arm.set_velocity(0.01) # extends 1 cm/s
  121. r.push_command()
  122. ```
  123. Once again, Dynamixel joints push their commands immediately.
  124. ```python
  125. r.end_of_arm.get_joint('wrist_yaw').set_velocity(0.1) # rotate CCW at 0.1 rad/s
  126. ```
  127. The base can execute translational (`v`) and rotational (`ω`) velocity simultaneously via `set_velocity(v, ω)`. You will often see navigation motion planners choose to control mobile bases with `v` and `ω` velocities.
  128. ```python
  129. r.base.set_velocity(0.01, 0.05) # follow a circular path
  130. r.push_command()
  131. ```
  132. ## Following Cubic/quintic Splines
  133. Stretch's joints can follow trajectories defined as splines. You will often see geometric motion planners, graphics software (e.g. Blender, Unity3D), and motion capture systems choose to formulate robot trajectories as splines. Spline trajectories are a series of position waypoints, associated with a time at which the joint should reach the position, and optionally associated with a velocity/acceleration that the joint should be traveling at when it passes the waypoint.
  134. Each joint has a `trajectory` attribute that is an instance of either `stretch_body.trajectories.RevoluteTrajectory` (for the wrist & head joints), `stretch_body.trajectories.PrismaticTrajectory` (for the arm & lift), or `stretch_body.trajectories.DiffDriveTrajectory` (for the base). Adding waypoints looks like:
  135. ```python
  136. r.arm.trajectory.add(t_s=0.0, x_m=0.0, v_m=0.0)
  137. r.arm.trajectory.add(t_s=10.0, x_m=0.5, v_m=0.0)
  138. r.arm.trajectory.add(t_s=20.0, x_m=0.0, v_m=0.0) # 20 second trajectory extending & retracting the arm
  139. ```
  140. Then begin tracking the trajectory using:
  141. ```python
  142. r.follow_trajectory()
  143. ```
  144. Trajectories are preemptive. You can edit the future waypoints in a trajectory while the robot is actively tracking it. For example, geometric planners can use this adapt to changing environments.
  145. You can stop a trajectory early using `stop_trajectory()`.
  146. ### Coordinated Motion through Trajectories
  147. Check out the [Creating smooth motion using trajectories](https://forum.hello-robot.com/t/creating-smooth-motion-using-trajectories/671) tutorial for more info on creating coordinated joint movements.