Skip to content

Stretch Body API Reference

Stretch Body is the Python interface for working with Stretch. This page serves as a reference for the interfaces defined in the stretch_body library. See the Stretch Body Tutorials for additional information on working with this library.

The Robot Class

The most common interface to Stretch is the Robot class. This class encapsulates all devices on the robot. It is typically initialized as:

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
import stretch_body.robot

r = stretch_body.robot.Robot()
if not r.startup():
    exit() # failed to start robot!

# home the joints to find zero, if necessary
if not r.is_calibrated():
    r.home()

# interact with the robot here

The startup() and home() methods start communication with and home each of the robot's devices, respectively. Through the Robot class, users can interact with all devices on the robot. For example, continuing the example above:

12
13
14
15
16
17
18
19
20
21
22
23
# moving joints on the robot
r.arm.pretty_print()
r.lift.pretty_print()
r.base.pretty_print()
r.head.pretty_print()
r.end_of_arm.pretty_print()

# other devices on the robot
r.wacc.pretty_print()
r.pimu.pretty_print()

r.stop()

Each of these devices is defined in separate 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 methods in the Robot class are documented below.

stretch_body.robot.Robot (Device)

API to the Stretch Robot

__init__(self) special

startup(self, start_non_dxl_thread=True, start_dxl_thread=True, start_sys_mon_thread=True)

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_coro(self) async

push_command(self)

Cause all queued up RPC commands to be sent down to Devices

is_trajectory_active(self)

follow_trajectory(self)

stop_trajectory(self)

is_calibrated(self)

Returns true if homing-calibration has been run all joints that require it

get_stow_pos(self, joint)

Return the stow position of a joint. Allow the end_of_arm to override the defaults in order to accomodate stowing different tools

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.

start_event_loop(self)

stop_event_loop(self)

The Device Class

The stretch_body library is modular in design. Each subcomponent of Stretch is defined in its 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 the 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 subclasses of the Device class: the Arm, Lift, Base, Head, EndOfArm, Wacc, and Pimu subcomponents of Stretch.

Using the Arm class

Top down Stretch arm blueprint Top down Stretch arm blueprint

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
import stretch_body.arm

a = stretch_body.arm.Arm()
a.motor.disable_sync_mode()
if not a.startup():
    exit() # failed to start arm!

a.home()

# interact with the arm here

Since both Arm and Robot are subclasses of the Device class, 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
starting_position = a.status['pos']

# move out by 10cm
a.move_to(starting_position + 0.1)
a.push_command()
a.motor.wait_until_at_setpoint()

# move back to starting position quickly
a.move_to(starting_position, v_m=0.2, a_m=0.25)
a.push_command()
a.motor.wait_until_at_setpoint()

a.move_by(0.1) # move out by 10cm
a.push_command()
a.motor.wait_until_at_setpoint()

The move_to() and move_by() methods queue absolute and relative position commands to the arm, respectively, while the nonblocking push_command() method pushes the queued position commands to the hardware for execution.

The attribute motor, an instance of the Stepper class, has the method wait_until_at_setpoint() which blocks program execution until the joint reaches the commanded goal. With firmware P1 or greater 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
starting_position = a.status['pos']

# queue a trajectory consisting of four waypoints
a.trajectory.add(t_s=0, x_m=starting_position)
a.trajectory.add(t_s=3, x_m=0.15)
a.trajectory.add(t_s=6, x_m=0.1)
a.trajectory.add(t_s=9, x_m=0.2)

# trigger trajectory execution
a.follow_trajectory()
import time; time.sleep(9)

The attribute trajectory, an instance of the PrismaticTrajectory class, has the method add() which adds a single waypoint in a linear sliding trajectory. For a well-formed trajectory (see is_valid()), the follow_trajectory() method starts tracking the trajectory for the telescoping arm.

It is also possible to dynamically restrict the arm joint range:

37
38
39
40
41
42
43
44
45
46
47
48
49
50
range_upper_limit = 0.3 # meters

# set soft limits on arm's range
a.set_soft_motion_limit_min(0)
a.set_soft_motion_limit_max(range_upper_limit)
a.push_command()

# command the arm outside the valid range
a.move_to(0.4)
a.push_command()
a.motor.wait_until_at_setpoint()
print(a.status['pos']) # we should expect to see ~0.3

a.stop()

The set_soft_motion_limit_min/max() methods form the basis of an experimental self-collision avoidance system built into Stretch Body.

All methods in the Arm class are documented below.

stretch_body.arm.Arm (PrismaticJoint)

API to the Stretch Arm

__init__(self, usb=None) special

motor_rad_to_translate_m(self, ang)

translate_m_to_motor_rad(self, x)

home(self, end_pos=0.1, to_positive_stop=False, measuring=False)

end_pos: position to end on to_positive_stop: -- True: Move to the positive direction stop and mark to range_m[1] -- False: Move to the negative direction stop and mark to range_m[0] measuring: After homing to stop, move to opposite stop and report back measured distance return measured range-of-motion if measuring. Return None if not a valide measurement

Using the Lift class

Stretch lift blueprint Stretch lift blueprint

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
import stretch_body.lift

l = stretch_body.lift.Lift()
l.motor.disable_sync_mode()
if not l.startup():
    exit() # failed to start lift!

l.home()

# interact with the lift here

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 class:

11
12
13
14
15
16
starting_position = l.status['pos']

# move up by 10cm
l.move_to(starting_position + 0.1)
l.push_command()
l.motor.wait_until_at_setpoint()

The 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
starting_position = l.status['pos']

# queue a trajectory consisting of three waypoints
l.trajectory.add(t_s=0, x_m=starting_position, v_m=0.0)
l.trajectory.add(t_s=3, x_m=0.5,               v_m=0.0)
l.trajectory.add(t_s=6, x_m=0.6,               v_m=0.0)

# trigger trajectory execution
l.follow_trajectory()
import time; time.sleep(6)

The 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 can be 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 can be done using:

27
28
29
30
31
32
# cut out 0.2m from the top and bottom of the lift's range
l.set_soft_motion_limit_min(0.2)
l.set_soft_motion_limit_max(0.8)
l.push_command()

l.stop()

The set_soft_motion_limit_min/max() methods perform clipping of the joint's range at the firmware level (can persist across reboots).

All methods in the Lift class are documented below.

stretch_body.lift.Lift (PrismaticJoint)

API to the Stretch Lift

__init__(self, usb=None) special

motor_rad_to_translate_m(self, ang)

translate_m_to_motor_rad(self, x)

home(self, end_pos=0.6, to_positive_stop=True, measuring=False)

end_pos: position to end on to_positive_stop: -- True: Move to the positive direction stop and mark to range_m[1] -- False: Move to the negative direction stop and mark to range_m[0] measuring: After homing to stop, move to opposite stop and report back measured distance return measured range-of-motion if measuring. Return None if not a valide measurement

Using the Base class

Stretch mobile base diagram Stretch mobile base diagram

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
import stretch_body.base

b = stretch_body.base.Base()
b.left_wheel.disable_sync_mode()
b.right_wheel.disable_sync_mode()
if not b.startup():
    exit() # failed to start base!

# interact with the base here

Stretch's mobile base is a differential drive configuration. The left and right wheels are accessible through Base 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. The pretty_print() method prints out mobile base state information in a human-interpretable format. We can read the base's current state and send commands using:

10
11
12
13
14
15
16
17
18
19
20
b.pretty_print()

# translate forward by 10cm
b.translate_by(0.1)
b.push_command()
b.left_wheel.wait_until_at_setpoint()

# rotate counter-clockwise by 90 degrees
b.rotate_by(1.57)
b.push_command()
b.left_wheel.wait_until_at_setpoint()

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
# command the base to translate forward at 5cm / second
b.set_translate_velocity(0.05)
b.push_command()
import time; time.sleep(1)

# command the base to rotate counter-clockwise at 0.1rad / second
b.set_rotational_velocity(0.1)
b.push_command()
time.sleep(1)

# command the base with translational and rotational velocities
b.set_velocity(0.05, 0.1)
b.push_command()
time.sleep(1)

# stop base motion
b.enable_freewheel_mode()
b.push_command()

The set_translate_velocity() and set_rotational_velocity() methods give velocity control over the translational and 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, where a desired waypoint is defined as an (x, y) point and a theta orientation:

39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
# reset odometry calculation
b.first_step = True
b.pull_status()

# queue a trajectory consisting of three waypoints
b.trajectory.add(time=0, x=0.0, y=0.0, theta=0.0)
b.trajectory.add(time=3, x=0.1, y=0.0, theta=0.0)
b.trajectory.add(time=6, x=0.0, y=0.0, theta=0.0)

# trigger trajectory execution
b.follow_trajectory()
import time; time.sleep(6)
print(b.status['x'], b.status['y'], b.status['theta']) # we should expect to see around (0.0, 0.0, 0.0 or 6.28)

b.stop()

Warning

The Base waypoint trajectory following has no notion of obstacles in the environment. It will blindly follow the commanded waypoints. For obstacle avoidance, we recommend employing perception and a path planner.

The attribute trajectory is an instance of the DiffDriveTrajectory class. The call to follow_trajectory() begins hardware tracking of the spline.

All methods of the Base class are documented below.

stretch_body.base.Base (Device)

API to the Stretch Mobile Base

__init__(self, usb_left=None, usb_right=None) 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

wait_for_contact(self, timeout=5.0)

wait_until_at_setpoint(self, timeout=15.0)

contact_thresh_to_motor_current(self, is_translate, contact_thresh)

This model converts from a specified percentage effort (-100 to 100) of translate/rotational effort to motor currents

translate_by(self, x_m, v_m=None, a_m=None, stiffness=None, contact_thresh_N=None, contact_thresh=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: (deprecated) effort to stop at (units of pseudo_N) contact_thresh: effort to stop at (units of effort_pct (-100, 100))

rotate_by(self, x_r, v_r=None, a_r=None, stiffness=None, contact_thresh_N=None, contact_thresh=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: (deprecated) effort to stop at (units of pseudo_N) contact_thresh: effort to stop at (units of effort_pct (-100, 100))

set_translate_velocity(self, v_m, a_m=None, stiffness=None, contact_thresh_N=None, contact_thresh=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) contact_thresh_N: (deprecated) effort to stop at (units of pseudo_N) contact_thresh: effort to stop at (units of effort_pct (-100, 100))

set_rotational_velocity(self, v_r, a_r=None, stiffness=None, contact_thresh_N=None, contact_thresh=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) contact_thresh_N: (deprecated) effort to stop at (units of pseudo_N) contact_thresh: effort to stop at (units of effort_pct (-100, 100))

set_velocity(self, v_m, w_r, a=None, stiffness=None, contact_thresh_N=None, contact_thresh=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) contact_thresh_N: (deprecated) effort to stop at (units of pseudo_N) contact_thresh: effort to stop at (units of effort_pct (-100, 100))

follow_trajectory(self, v_r=None, a_r=None, stiffness=None, contact_thresh_N=None, contact_thresh=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: (deprecated) effort to stop at (units of pseudo_N) contact_thresh: effort to stop at (units of effort_pct (-100, 100))

reset_odometry(self)

Reset X/Y/Theta to report 0

is_trajectory_active(self)

get_trajectory_ts(self)

get_trajectory_time_remaining(self)

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

pull_status_async(self) async

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)

rotation_effort_pct_to_motor_current(self, e_pct)

translation_effort_pct_to_motor_current(self, e_pct)

motor_current_to_translate_effort_pct(self, il, ir)

motor_current_to_rotation_effort_pct(self, il, ir)

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

Stretch head blueprint Stretch head blueprint

The interface to Stretch's head is the Head class. The head contains an Intel Realsense D435i depth camera. The pan and tilt joints in the head allow 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
import stretch_body.head

h = stretch_body.head.Head()
if not h.startup():
    exit() # failed to start head!

h.home()

# interact with the head here

Head is a subclass of the DynamixelXChain class, which in turn is a subclass of the Device class. Therefore, some of Head's methods, such as startup() and home() are extended from the Device class, while others come from the DynamixelXChain class. Reading the head's current state and sending commands to its revolute joints (head pan and tilt) can be achieved using:

10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
starting_position = h.status['head_pan']['pos']

# look right by 90 degrees
h.move_to('head_pan', starting_position + 1.57)
h.get_joint('head_pan').wait_until_at_setpoint()

# tilt up by 30 degrees
h.move_by('head_tilt', -1.57 / 3)
h.get_joint('head_tilt').wait_until_at_setpoint()

# look down towards the wheels
h.pose('wheels')
import time; time.sleep(3)

# look ahead
h.pose('ahead')
time.sleep(3)

The 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 information 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 and are 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 retrievable 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
# queue a trajectory consisting of three waypoints
h.get_joint('head_tilt').trajectory.add(t_s=0, x_r=0.0)
h.get_joint('head_tilt').trajectory.add(t_s=3, x_r=-1.0)
h.get_joint('head_tilt').trajectory.add(t_s=6, x_r=0.0)
h.get_joint('head_pan').trajectory.add(t_s=0, x_r=0.1)
h.get_joint('head_pan').trajectory.add(t_s=3, x_r=-0.9)
h.get_joint('head_pan').trajectory.add(t_s=6, x_r=0.1)

# trigger trajectory execution
h.follow_trajectory()
import time; time.sleep(6)

The head pan and 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 and tilt range can be achieved using:

38
39
40
41
42
43
44
45
46
# clip the head_pan's range
h.get_joint('head_pan').set_soft_motion_limit_min(-1.0)
h.get_joint('head_pan').set_soft_motion_limit_max(1.0)

# clip the head_tilt's range
h.get_joint('head_tilt').set_soft_motion_limit_min(-1.0)
h.get_joint('head_tilt').set_soft_motion_limit_max(0.1)

h.stop()

The set_soft_motion_limit_min/max() methods perform clipping of the joint's range at the software level (cannot persist across reboots).

All methods of the Head class are documented below.

stretch_body.head.Head (DynamixelXChain)

API to the Stretch RE1 Head

__init__(self, usb=None) 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
import stretch_body.end_of_arm

e = stretch_body.end_of_arm.EndOfArm()
if not e.startup(threaded=True):
    exit() # failed to start end of arm!

# interact with the end of arm here

e.stop()

All methods of the EndOfArm class 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', usb=None) 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
import stretch_body.wacc

w = stretch_body.wacc.Wacc()
if not w.startup(threaded=True):
    exit() # failed to start wacc!

# interact with the wacc here

w.stop()

All methods of the Wacc class are documented below.

stretch_body.wacc.Wacc (WaccBase)

API to the Stretch Wrist Accelerometer (Wacc) Board

__init__(self, usb=None) 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 a 9-DOF IMU that is accessible from the Pimu class. It is typically initialized as:

1
2
3
4
5
6
7
8
9
import stretch_body.pimu

p = stretch_body.pimu.Pimu()
if not p.startup(threaded=True):
    exit() # failed to start pimu!

# interact with the pimu here

p.stop()

All methods of the Pimu class are documented below.

stretch_body.pimu.Pimu (PimuBase)

API to the Stretch Power and IMU board (Pimu)

__init__(self, event_reset=False, usb=None) 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


All materials are Copyright 2022 by Hello Robot Inc. Hello Robot and Stretch are registered trademarks.