Stretch Body API Reference
Stretch Body is the Python interface to working with the Stretch RE1. This page serves as a reference of the interfaces defined in the stretch_body
library. See the Stretch Body Guide for a tutorial to working with this library.
The Robot Class
Using the Robot class
The most common interface to Stretch is the Robot class. It is typically initialized as:
1 2 3 4 5 6 7 8 9 10 11 |
|
The startup()
and home()
methods starts communication with and homes each of the robot's devices, respectively. Through the Robot class, users can interact with all other devices on the robot. For example, continuing the example above:
12 13 14 15 16 17 18 19 20 21 22 23 |
|
Each of these devices are defined in other modules within stretch_body
. In the following section, we'll look at the API of these classes. The stop()
method shuts down communication with the robot's devices. All of Robot's subroutines are documented below.
stretch_body.robot.Robot (Device)
API to the Stretch RE1 Robot
__init__(self)
special
startup(self)
To be called once after class instantiation. Prepares devices for communications and motion
Returns
bool true if startup of robot succeeded
stop(self)
To be called once before exiting a program Cleanly stops down motion and communication
get_status(self)
Thread safe and atomic read of current Robot status data Returns as a dict.
pretty_print(self)
push_command(self)
Cause all queued up RPC commands to be sent down to Devices
follow_trajectory(self)
stop_trajectory(self)
is_calibrated(self)
Returns true if homing-calibration has been run all joints that require it
stow(self)
Cause the robot to move to its stow position Blocking.
home(self)
Cause the robot to home its joints by moving to hardstops Blocking.
The Device Classes
The stretch_body
library is modular in design. Each subcomponent of Stretch is defined in its own class and the Robot class provides an interface that ties all of these classes together. This modularity allows users to plug in new/modified subcomponents into the Robot interface by extending a device class.
It is possible to interface with a single subcomponent of Stretch by initializing its device class directly. In this section, we'll look at the API of seven device classes: the arm, lift, base, head, end of arm, wacc, and pimu subcomponents of Stretch.
Using the Arm class
The interface to Stretch's telescoping arm is the Arm class. It is typically initialized as:
1 2 3 4 5 6 7 8 9 10 |
|
Since both Arm and Robot subclass Device, the same startup()
and stop()
methods are available here, as well as other Device methods such as home()
. Using the Arm class, we can read the arm's current state and send commands to the joint. For example, continuing the example above:
11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 |
|
The move_to()
and move_by()
methods queue absolute and relative commands to the arm respectively, while the nonblocking push_command()
method pushes the queued command to the hardware for execution. Arm's attribute motor
, an instance of the Stepper class, has wait_until_at_setpoint()
which blocks program execution until the joint reaches the commanded goal. With P1 or greater firmware installed, it is also possible to queue a waypoint trajectory for the arm to follow:
26 27 28 29 30 31 32 33 34 35 36 |
|
Arm's attribute trajectory
, an instance of the PrismaticTrajectory class, has add()
which adds a single waypoint in a linear sliding trajectory. For a well formed trajectory
(see is_valid()
), the follow_trajectory()
method kicks off trajectory following for the telescoping arm. It is also possible to dynamically restrict the arm joint's range:
37 38 39 40 41 42 43 44 45 46 47 48 49 50 |
|
The set_soft_motion_limit_min/max()
methods form the basis of an experimental self-collision avoidance system built into Stretch Body. All of Arm's subroutines are documented below.
stretch_body.arm.Arm (Device)
API to the Stretch RE1 Arm
__init__(self)
special
startup(self, threaded=True)
Starts machinery required to interface with this device
Parameters
threaded : bool whether a thread manages hardware polling/pushing in the background
Returns
bool whether the startup procedure succeeded
stop(self)
Shuts down machinery started in startup()
pull_status(self)
push_command(self)
pretty_print(self)
get_soft_motion_limits(self)
Return the currently applied soft motion limits: [min, max]
The soft motion limit restricts joint motion to be <= its physical limits.
There are three types of limits: Hard: The physical limits Collision: Limits set by RobotCollision to avoid collisions User: Limits set by the user software
The joint is limited to the most restrictive range of the Hard / Collision/ User values. Specifying a value of None for a limit indicates that no constraint exists for that limit type. This allows a User limits and Collision limits to coexist. For example, a user can temporarily restrict the range of motion beyond the current collision limits. Then, by commanding User limits of None, the joint limits will revert back to the collision settings.
set_soft_motion_limit_min(self, x, limit_type='user')
x: value to set a joints limit to limit_type: 'user' or 'collision'
set_soft_motion_limit_max(self, x, limit_type='user')
x: value to set a joints limit to limit_type: 'user' or 'collision'
set_velocity(self, v_m, a_m=None, stiffness=None, contact_thresh_pos_N=None, contact_thresh_neg_N=None, req_calibration=True)
move_to(self, x_m, v_m=None, a_m=None, stiffness=None, contact_thresh_pos_N=None, contact_thresh_neg_N=None, req_calibration=True)
x_m: commanded absolute position (meters). x_m=0 is retracted. x_m=~0.5 is extended v_m: velocity for trapezoidal motion profile (m/s) a_m: acceleration for trapezoidal motion profile (m/s^2) stiffness: stiffness of motion. Range 0.0 (min) to 1.0 (max) contact_thresh_pos_N: force threshold to stop motion (~Newtons, extension direction) contact_thresh_neg_N: force threshold to stop motion (~Newtons, retraction direction) req_calibration: Disallow motion prior to homing
move_by(self, x_m, v_m=None, a_m=None, stiffness=None, contact_thresh_pos_N=None, contact_thresh_neg_N=None, req_calibration=True)
x_m: commanded incremental motion (meters). v_m: velocity for trapezoidal motion profile (m/s) a_m: acceleration for trapezoidal motion profile (m/s^2) stiffness: stiffness of motion. Range 0.0 (min) to 1.0 (max) contact_thresh_pos_N: force threshold to stop motion (~Newtons, extension direction) contact_thresh_neg_N: force threshold to stop motion (~Newtons, retraction direction) req_calibration: Disallow motion prior to homing
follow_trajectory(self, v_m=None, a_m=None, stiffness=None, contact_thresh_pos_N=None, contact_thresh_neg_N=None, req_calibration=True, move_to_start_point=True)
Starts executing a waypoint trajectory
self.trajectory
must be populated with a valid trajectory before calling
this method.
Parameters
v_m : float velocity limit for trajectory in meters per second a_m : float acceleration limit for trajectory in meters per second squared stiffness : float stiffness of motion. Range 0.0 (min) to 1.0 (max) contact_thresh_pos_N : float force threshold to stop motion (~Newtons, extension direction) contact_thresh_neg_N : float force threshold to stop motion (~Newtons, retraction direction) req_calibration : bool whether to allow motion prior to homing move_to_start_point : bool whether to move to the trajectory's start to avoid a jump, this time to move doesn't count against the trajectory's timeline
update_trajectory(self)
Updates hardware with the next segment of self.trajectory
This method must be called frequently to enable complete trajectory execution
and preemption of future segments. If used with stretch_body.robot.Robot
or
with self.startup(threaded=True)
, a background thread is launched for this.
Otherwise, the user must handle calling this method.
stop_trajectory(self)
Stop waypoint trajectory immediately and resets hardware
motor_current_to_translate_force(self, i)
translate_force_to_motor_current(self, f)
motor_rad_to_translate(self, ang)
translate_to_motor_rad(self, arm_m)
home(self, single_stop=True, measuring=False)
Home to hardstops
step_sentry(self, robot)
Using the Lift class
The interface to Stretch's lift is the Lift class. It is typically initialized as:
1 2 3 4 5 6 7 8 9 10 |
|
The startup()
and home()
methods are extended from the Device class. Reading the lift's current state and sending commands to the joint occurs similarly to the Arm:
11 12 13 14 15 16 |
|
Lift's attribute status
is a dictionary of the joint's current status. This state information is updated in the background in real time by default (disable by initializing as startup(threading=False)
). Use the pretty_print()
method to print out this state info in a human interpretable format. Setting up waypoint trajectories for the lift is also similar to the Arm:
17 18 19 20 21 22 23 24 25 26 |
|
Lift's attribute trajectory
is also an instance of the PrismaticTrajectory class, and by providing the instantaneous velocity argument v_m
to the add()
method, a cubic spline has been loaded into the joint's trajectory
. The call to follow_trajectory()
begins hardware tracking of the spline. Finally, setting soft motion limits for the lift's range happens using:
27 28 29 30 31 32 |
|
The set_soft_motion_limit_min/max()
methods perform clipping of the joint's range at the firmware level (can persist across reboots). All of Lift's subroutines are documented below.
stretch_body.lift.Lift (Device)
API to the Stretch RE1 Lift
__init__(self)
special
startup(self, threaded=True)
Starts machinery required to interface with this device
Parameters
threaded : bool whether a thread manages hardware polling/pushing in the background
Returns
bool whether the startup procedure succeeded
stop(self)
Shuts down machinery started in startup()
pull_status(self)
push_command(self)
pretty_print(self)
get_soft_motion_limits(self)
Return the currently applied soft motion limits: [min, max]
The soft motion limit restricts joint motion to be <= its physical limits.
There are three types of limits: Hard: The physical limits Collision: Limits set by RobotCollision to avoid collisions User: Limits set by the user software
The joint is limited to the most restrictive range of the Hard / Collision/ User values. Specifying a value of None for a limit indicates that no constraint exists for that limit type. This allows a User limits and Collision limits to coexist. For example, a user can temporarily restrict the range of motion beyond the current collision limits. Then, by commanding User limits of None, the joint limits will revert back to the collision settings.
set_soft_motion_limit_min(self, x, limit_type='user')
x: value to set a joints limit to limit_type: 'user' or 'collision'
set_soft_motion_limit_max(self, x, limit_type='user')
x: value to set a joints limit to limit_type: 'user' or 'collision'
set_velocity(self, v_m, a_m=None, stiffness=None, contact_thresh_pos_N=None, contact_thresh_neg_N=None, req_calibration=True)
move_to(self, x_m, v_m=None, a_m=None, stiffness=None, contact_thresh_pos_N=None, contact_thresh_neg_N=None, req_calibration=True)
x_m: commanded absolute position (meters). x_m=0 is down. x_m=~1.1 is up v_m: velocity for trapezoidal motion profile (m/s) a_m: acceleration for trapezoidal motion profile (m/s^2) stiffness: stiffness of motion. Range 0.0 (min) to 1.0 (max) contact_thresh_pos_N: force threshold to stop motion (~Newtons, up direction) contact_thresh_neg_N: force threshold to stop motion (~Newtons, down direction) req_calibration: Disallow motion prior to homing
move_by(self, x_m, v_m=None, a_m=None, stiffness=None, contact_thresh_pos_N=None, contact_thresh_neg_N=None, req_calibration=True)
x_m: commanded incremental motion (meters). v_m: velocity for trapezoidal motion profile (m/s) a_m: acceleration for trapezoidal motion profile (m/s^2) stiffness: stiffness of motion. Range 0.0 (min) to 1.0 (max) contact_thresh_pos_N: force threshold to stop motion (~Newtons, up direction) contact_thresh_neg_N: force threshold to stop motion (~Newtons, down direction) req_calibration: Disallow motion prior to homing
follow_trajectory(self, v_m=None, a_m=None, stiffness=None, contact_thresh_pos_N=None, contact_thresh_neg_N=None, req_calibration=True, move_to_start_point=True)
Starts executing a waypoint trajectory
self.trajectory
must be populated with a valid trajectory before calling
this method.
Parameters
v_m : float velocity limit for trajectory in meters per second a_m : float acceleration limit for trajectory in meters per second squared stiffness : float stiffness of motion. Range 0.0 (min) to 1.0 (max) contact_thresh_pos_N : float force threshold to stop motion (~Newtons, up direction) contact_thresh_neg_N : float force threshold to stop motion (~Newtons, down direction) req_calibration : bool whether to allow motion prior to homing move_to_start_point : bool whether to move to the trajectory's start to avoid a jump, this time to move doesn't count against the trajectory's timeline
update_trajectory(self)
Updates hardware with the next segment of self.trajectory
This method must be called frequently to enable complete trajectory execution
and preemption of future segments. If used with stretch_body.robot.Robot
or
with self.startup(threaded=True)
, a background thread is launched for this.
Otherwise, the user must handle calling this method.
stop_trajectory(self)
Stop waypoint trajectory immediately and resets hardware
motor_current_to_translate_force(self, i)
translate_force_to_motor_current(self, f)
motor_rad_to_translate_m(self, ang)
translate_to_motor_rad(self, lift_m)
home(self, measuring=False)
step_sentry(self, robot)
Using the Base class
Item | Notes | |
---|---|---|
A | Drive wheels | 4 inch diameter, urethane rubber shore 60A |
B | Cliff sensors | Sharp GP2Y0A51SK0F, Analog, range 2-15 cm |
C | Mecanum wheel | Diameter 50mm |
The interface to Stretch's mobile base is the Base class. It is typically initialized as:
1 2 3 4 5 6 7 8 9 |
|
Stretch's mobile base is a differential drive configuration. The left and right wheels are accessible through Base's left_wheel
and right_wheel
attributes, both of which are instances of the Stepper class. The startup()
method is extended from the Device class. Since the mobile base is unconstrained, there is no homing method. We can read the base's current state and send commands using:
10 11 12 13 14 15 16 17 18 19 20 |
|
The pretty_print()
method prints out mobile base state info in a human interpretable format. The translate_by()
and rotate_by()
methods send relative commands similar to the way move_by()
behaves for the single degree of freedom joints. The mobile base also supports velocity control:
21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 |
|
The set_translate_velocity()
/set_rotational_velocity()
give velocity control over the translational/rotational components of the mobile base independently. The set_velocity()
method gives control over both of these components simultaneously. To halt motion, you can command zero velocities or command the base into freewheel mode using enable_freewheel_mode()
. The mobile base also supports waypoint trajectory following, but the waypoints are part of the SE2 group (a.k.a. each of the base's desired waypoints is defined as a (x, y) point and a theta orientation):
39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 |
|
Warning
The Base's waypoint trajectory following has no notion of obstacles in the environment. It will blindly follow the commanded waypoints. For obstacle avoidance, perception and a path planner should be employed.
Base's attribute trajectory
is an instance of the DiffDriveTrajectory class. The call to follow_trajectory()
begins hardware tracking of the spline. All of Base's subroutines are documented below.
stretch_body.base.Base (Device)
API to the Stretch RE1 Mobile Base
__init__(self)
special
startup(self, threaded=True)
Starts machinery required to interface with this device
Parameters
threaded : bool whether a thread manages hardware polling/pushing in the background
Returns
bool whether the startup procedure succeeded
stop(self)
Shuts down machinery started in startup()
pretty_print(self)
enable_freewheel_mode(self)
Force motors into freewheel
enable_pos_incr_mode(self)
Force motors into incremental position mode
translate_by(self, x_m, v_m=None, a_m=None, stiffness=None, contact_thresh_N=None)
Incremental translation of the base x_m: desired motion (m) v_m: velocity for trapezoidal motion profile (m/s) a_m: acceleration for trapezoidal motion profile (m/s^2) stiffness: stiffness of motion. Range 0.0 (min) to 1.0 (max) contact_thresh_N: force threshold to stop motion (TODO: Not yet implemented)
rotate_by(self, x_r, v_r=None, a_r=None, stiffness=None, contact_thresh_N=None)
Incremental rotation of the base x_r: desired motion (radians) v_r: velocity for trapezoidal motion profile (rad/s) a_r: acceleration for trapezoidal motion profile (rad/s^2) stiffness: stiffness of motion. Range 0.0 (min) to 1.0 (max) contact_thresh_N: force threshold to stop motion (Not yet implemented)
set_translate_velocity(self, v_m, a_m=None)
Command the bases translational velocity. Use care to prevent collisions / avoid runaways v_m: desired velocity (m/s) a_m: acceleration of motion profile (m/s^2)
set_rotational_velocity(self, v_r, a_r=None)
Command the bases rotational velocity. Use care to prevent collisions / avoid runaways v_r: desired rotational velocity (rad/s) a_r: acceleration of motion profile (rad/s^2)
set_velocity(self, v_m, w_r, a=None)
Command the bases translational and rotational velocities simultaneously. Use care to prevent collisions / avoid runaways v_m: desired velocity (m/s) w_r: desired rotational velocity (rad/s) a: acceleration of motion profile (m/s^2 and rad/s^2)
follow_trajectory(self, v_r=None, a_r=None, stiffness=None, contact_thresh_N=None)
Starts executing a waypoint trajectory
self.trajectory
must be populated with a valid trajectory before calling
this method.
Parameters
v_r : float velocity limit for trajectory in motor space in meters per second a_r : float acceleration limit for trajectory in motor space in meters per second squared stiffness : float stiffness of motion. Range 0.0 (min) to 1.0 (max) contact_thresh_N : float force threshold to stop motion (~Newtons)
update_trajectory(self)
Updates hardware with the next segment of self.trajectory
This method must be called frequently to enable complete trajectory execution
and preemption of future segments. If used with stretch_body.robot.Robot
or
with self.startup(threaded=True)
, a background thread is launched for this.
Otherwise, the user must handle calling this method.
stop_trajectory(self)
Stop waypoint trajectory immediately and resets hardware
step_sentry(self, robot)
Only allow fast mobile base motion if the lift is low, the arm is retracted, and the wrist is stowed. This is intended to keep the center of mass low for increased stability and avoid catching the arm or tool on something.
push_command(self)
pull_status(self)
Computes base odometery based on stepper positions / velocities
motor_current_to_translation_force(self, il, ir)
motor_current_to_rotation_torque(self, il, ir)
translation_force_to_motor_current(self, f_N)
rotation_torque_to_motor_current(self, tq_Nm)
translate_to_motor_rad(self, x_m)
motor_rad_to_translate(self, x_r)
rotate_to_motor_rad(self, x_r)
motor_rad_to_rotate(self, x_r)
translation_to_rotation(self, x_m)
rotation_to_translation(self, x_r)
Using the Head class
The interface to Stretch's head is the Head class. Stretch's head contains a Intel Realsense D435i depth camera, so the pan/tilt joints in the head allows Stretch to swivel and capture depth imagery of its surrounding. The head is typically initialized as:
1 2 3 4 5 6 7 8 9 |
|
Head is a subclass of DynamixelXChain, which in turn subclasses the Device class. Therefore, some of Head's methods, such as startup()
and home()
methods are extended from the Device class, while other come from the DynamixelXChain class. Reading the head's current state and sending commands to its revolute joints (head pan and tilt) happens using:
10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 |
|
Head's attribute status
is a dictionary of dictionaries, where each subdictionary is the status of one of the head's joints. This state information is updated in the background in real time by default (disable by initializing as startup(threading=False)
). Use the pretty_print()
method to print out this state info in a human interpretable format. Commanding the head's revolute joints is done through the move_to()
and move_by()
methods. Notice that unlike the previous joints, no push command call is required here. These joints are Dynamixel servos, which behave differently than the Hello Robot steppers. Their commands are not queued; they're executed as soon as they're received. Head's two joints, the 'head_pan' and 'head_tilt', are instances of the DynamixelHelloXL430 class, and are retreiveable using the get_joint()
method. They have the wait_until_at_setpoint()
method, which blocks program execution until the joint reaches the commanded goal. The pose()
method makes it easy to command the head to common head poses (e.g. looking 'ahead', at the end of arm 'tool', obstacles in front of the 'wheels', or 'up'). The head supports waypoint trajectories as well:
27 28 29 30 31 32 33 34 35 36 37 |
|
The head pan/tilt DynamixelHelloXL430 instances have an attribute trajectory
, which is an instance of the RevoluteTrajectory class. The call to follow_trajectory()
begins software tracking of the spline. Finally, setting soft motion limits for the head's pan/tilt range happens using:
38 39 40 41 42 43 44 45 46 |
|
The set_soft_motion_limit_min/max()
methods perform clipping of the joint's range at the software level (cannot persist across reboots). All of Head's subroutines are documented below.
stretch_body.head.Head (DynamixelXChain)
API to the Stretch RE1 Head
__init__(self)
special
startup(self, threaded=True)
Starts machinery required to interface with this device
Parameters
threaded : bool whether a thread manages hardware polling/pushing in the background
Returns
bool whether the startup procedure succeeded
get_joint(self, joint_name)
Retrieves joint by name.
Parameters
joint_name : str
valid joints defined in joints
Returns
DynamixelHelloXL430 or None Motor object on valid joint name, else None
move_to(self, joint, x_r, v_r=None, a_r=None)
joint: Name of the joint to move ('head_pan' or 'head_tilt') x_r: commanded absolute position (radians). v_r: velocity for trapezoidal motion profile (rad/s). a_r: acceleration for trapezoidal motion profile (rad/s^2)
move_by(self, joint, x_r, v_r=None, a_r=None)
joint: Name of the joint to move ('head_pan' or 'head_tilt') x_r: commanded incremental motion (radians). v_r: velocity for trapezoidal motion profile (rad/s). a_r: acceleration for trapezoidal motion profile (rad/s^2)
home(self)
pose(self, p, v_r=[None, None], a_r=[None, None])
p: Dictionary key to named pose (eg 'ahead') v_r: list, velocities for trapezoidal motion profile (rad/s). a_r: list, accelerations for trapezoidal motion profile (rad/s^2)
Using the EndOfArm class
The interface to Stretch's end of arm is the EndOfArm class. It is typically initialized as:
1 2 3 4 5 6 7 8 9 |
|
EndOfArm's subroutines are documented below.
stretch_body.end_of_arm.EndOfArm (DynamixelXChain)
The EndOfArm class allows for an extensible serial chain of Dynamixel X series devices It allows the specific type of device to be declared at runtime via the Yaml parameters In this way, a user can add their own custom Dynamixel based tools to the robot end-of-arm by simply deriving it from DynamixelHelloXL430 and declaring the class name / Python module name in the User YAML file
__init__(self, name='end_of_arm')
special
startup(self, threaded=True)
Starts machinery required to interface with this device
Parameters
threaded : bool whether a thread manages hardware polling/pushing in the background
Returns
bool whether the startup procedure succeeded
get_joint(self, joint_name)
Retrieves joint by name.
Parameters
joint_name : str valid joints defined as defined in params['devices']
Returns
DynamixelHelloXL430 or None Motor object on valid joint name, else None
move_to(self, joint, x_r, v_r=None, a_r=None)
joint: name of joint (string) x_r: commanded absolute position (radians). v_r: velocity for trapezoidal motion profile (rad/s). a_r: acceleration for trapezoidal motion profile (rad/s^2)
move_by(self, joint, x_r, v_r=None, a_r=None)
joint: name of joint (string) x_r: commanded incremental motion (radians). v_r: velocity for trapezoidal motion profile (rad/s). a_r: acceleration for trapezoidal motion profile (rad/s^2)
pose(self, joint, p, v_r=None, a_r=None)
joint: name of joint (string) p: named pose of joint v_r: velocity for trapezoidal motion profile (rad/s). a_r: acceleration for trapezoidal motion profile (rad/s^2)
stow(self)
home(self, joint=None)
Home to hardstops
is_tool_present(self, class_name)
Return true if the given tool type is present (eg. StretchGripper) Allows for conditional logic when switching end-of-arm tools
Using the Wacc class
The interface to Stretch's wrist board is the Wacc (wrist + accelerometer) class. This board provides an Arduino and accelerometer sensor that is accessible from the Wacc class. It is typically initialized as:
1 2 3 4 5 6 7 8 9 |
|
Wacc's subroutines are documented below.
stretch_body.wacc.Wacc (WaccBase)
API to the Stretch RE1 Power and IMU board (Pimu)
__init__(self)
special
startup(self, threaded=False)
First determine which protocol version the uC firmware is running. Based on that version, replaces PimuBase class inheritance with a inheritance to a child class of PimuBase that supports that protocol
Using the Pimu class
The interface to Stretch's power board is the Pimu (power + IMU) class. This board provides an 9 DOF IMUthat is accessible from the Pimu class. It is typically initialized as:
1 2 3 4 5 6 7 8 9 |
|
Pimu's subroutines are documented below.
stretch_body.pimu.Pimu (PimuBase)
API to the Stretch RE1 Power and IMU board (Pimu)
__init__(self, event_reset=False)
special
startup(self, threaded=False)
First determine which protocol version the uC firmware is running. Based on that version, replaces PimuBase class inheritance with a inheritance to a child class of PimuBase that supports that protocol