API Reference

Lookup

class hebi.Lookup

Maintains a registry of network-connected modules and returns Group objects to the user.

DEFAULT_TIMEOUT_MS = 500

The default timeout (in milliseconds)

entrylist

A list of discovered network connected modules.

Returns:The list of modules
Return type:EntryList
get_connected_group_from_mac(address, timeout_ms=None)

Get a group from all modules known to connect to a module with the given mac address.

This is a blocking call which returns a Group with the given parameters. This will time out after Lookup.DEFAULT_TIMEOUT_MS milliseconds, if a matching group cannot be constructed.

Parameters:
  • address
  • timeout_ms – The maximum amount of time to wait, in milliseconds. This is an optional parameter with a default value of Lookup.DEFAULT_TIMEOUT_MS.
Returns:

get_connected_group_from_name(family, name, timeout_ms=None)

Get a group from all modules known to connect to a module with the given name and family.

This is a blocking call which returns a Group with the given parameters. This will time out after Lookup.DEFAULT_TIMEOUT_MS milliseconds, if a matching group cannot be constructed.

Parameters:
  • family
  • name
  • timeout_ms – The maximum amount of time to wait, in milliseconds. This is an optional parameter with a default value of Lookup.DEFAULT_TIMEOUT_MS.
Returns:

get_group_from_family(family, timeout_ms=None)

Get a group from all known modules with the given family.

This is a blocking call which returns a Group with the given parameters. This will time out after Lookup.DEFAULT_TIMEOUT_MS milliseconds, if a matching group cannot be constructed.

Parameters:
  • family
  • timeout_ms – The maximum amount of time to wait, in milliseconds. This is an optional parameter with a default value of Lookup.DEFAULT_TIMEOUT_MS.
Returns:

get_group_from_macs(addresses, timeout_ms=None)

Get a group from modules with the given mac addresses.

This is a blocking call which returns a Group with the given parameters. This will time out after Lookup.DEFAULT_TIMEOUT_MS milliseconds, if a matching group cannot be constructed.

Parameters:
  • addresses
  • timeout_ms – The maximum amount of time to wait, in milliseconds. This is an optional parameter with a default value of Lookup.DEFAULT_TIMEOUT_MS.
Returns:

get_group_from_names(families, names, timeout_ms=None)

Get a group from modules with the given names and families.

If the families or names provided as input is only a single element, then that element is assumed to pair with each item in the other parameter.

This is a blocking call which returns a Group with the given parameters. This will time out after Lookup.DEFAULT_TIMEOUT_MS milliseconds, if a matching group cannot be constructed.

Parameters:
  • families
  • names
  • timeout_ms – The maximum amount of time to wait, in milliseconds. This is an optional parameter with a default value of Lookup.DEFAULT_TIMEOUT_MS.
Returns:

The following classes are used to retrieve information about modules discovered on the network.

Viewing Discovered Modules

class hebi._internal.lookup.EntryList

A list of module entries. This is used by the Lookup class and is returned by entrylist.

This class acts as an iterator for modules discovered on the network. The elements returned from the iterator are of type Entry. To use, iterate in a loop like:

for entry in lookup.entrylist:
  # print data, or gather information
class hebi._internal.lookup.Entry

Represents a HEBI module. This is used by the Lookup class.

family
Returns:The family to which this module belongs.
Return type:str
mac_address
Returns:The immutable MAC address of the module.
Return type:str
name
Returns:The name of the module.
Return type:str

Group

A group is the interface through which you can communicate with the modules by sending commands and receiving data. Group commands are not created directly - they are returned from methods in the Lookup class, as well as from the create_imitation_group() function. An imitation group can be created without any modules, mainly for testing and prototyping purposes. See Imitation Group.

class hebi._internal.group.Group

Represents a group of physical HEBI modules, and allows Command, Feedback, and Info objects to be sent to and recieved from the hardware.

This is created internally. Do not instantiate directly.

DEFAULT_TIMEOUT_MS = 500

The default timeout (in milliseconds)

add_feedback_handler(handler)

Adds a handler function to be called by the internal feedback request thread.

Note that this function must execute very quickly: If a handler takes more time than the reciprocal of the feedback thread frequency, the thread will saturate in feedback events to dispatch. This may cause feedback packets to be dropped from handler dispatch, or delayed invocation of the feedback handlers.

Parameters:handler – A function which is able to accept a single argument
clear_feedback_handlers()

Removes all feedback handlers presently added.

command_lifetime

The command lifetime for the modules in this group.

Returns:the command lifetime
Return type:int
feedback_frequency

The frequency of the internal feedback request + callback thread.

Returns:the frequency
Return type:float
get_next_feedback(timeout_ms=None, reuse_fbk=None)

Returns the most recently stored feedback from a sent feedback request, or the next one received (up to the requested timeout).

Note that a feedback request can be sent either with the send_feedback_request function, or by setting a background feedback frequency with feedback_frequency.

Parameters:
  • timeout_ms (int) – The maximum amount of time to wait, in milliseconds. This is an optional parameter with a default value of Group.DEFAULT_TIMEOUT_MS.
  • reuse_fbk (GroupFeedback) – An optional parameter which can be used to reuse an existing GroupFeedback instance. It is recommended to provide this parameter inside a repetitive loop, as reusing feedback instances results in substantially fewer heap allocations.
Returns:

The most recent feedback, provided one became available before the timeout. None is returned if there was no available feedback.

Return type:

GroupFeedback

request_info(timeout_ms=None, reuse_info=None)

Request info from the group, and store it in the passed-in info object.

Parameters:
  • timeout_ms (int) – The maximum amount of time to wait, in milliseconds. This is an optional parameter with a default value of Group.DEFAULT_TIMEOUT_MS.
  • reuse_info (GroupInfo) – An optional parameter which can be used to reuse an existing GroupInfo instance. It is recommended to provide this parameter inside a repetitive loop, as reusing info instances results in substantially fewer heap allocations.
Returns:

the updated info on success, None otherwise

Return type:

GroupInfo

send_command(group_command)

Send a command to the given group without requesting an acknowledgement. This is appropriate for high-frequency applications.

Parameters:group_command (GroupCommand) – The command to send
Returns:True if succeeded, False otherwise
Return type:bool
send_command_with_acknowledgement(group_command, timeout_ms=None)

Send a command to the given group, requesting an acknowledgement of transmission to be sent back.

Note: A non-true return does not indicate a specific failure, and may result from an error while sending or simply a timeout/dropped response packet after a successful transmission.

Parameters:
  • group_command (GroupCommand) – The command to send
  • timeout_ms (int) – The maximum amount of time to wait, in milliseconds. This is an optional parameter with a default value of Group.DEFAULT_TIMEOUT_MS.
Returns:

True if succeeded, False otherwise

Return type:

bool

send_feedback_request()

Requests feedback from the group.

Sends a background request to the modules in the group; if/when all modules return feedback, any associated handler functions are called. This returned feedback is also stored to be returned by the next call to get_next_feedback() (any previously returned data is discarded).

Returns:True if succeeded, False otherwise
Return type:bool
size

The number of modules in the group.

Returns:size of the group
Return type:int
start_log(directory=None, name=None)

Start logging information and feedback from this group. If a log file was already started before this (and not stopped using stop_log), then that file will automatically be gracefully closed.

Parameters:
  • directory (str) – Optional directory into which the log file will be created. If None, the process’ current working directory is used.
  • name (str) – Optional name of the log file. If None, a name will be generated using the time at which this function was invoked.
Returns:

The path, including the file, of the log file or None on failure

Return type:

str

stop_log()

Stop logging data into the last opened log file. If no log file was opened, None will be returned. If an error occurs while stopping the previously started log file, None will be returned.

Returns:a LogFile object on success, or None
Return type:LogFile

Kinematics

Robot Model

The Robot Model interface is used to create a kinematic body on which one can perform subsequent forward and inverse kinematics computations.

class hebi.robot_model.RobotModel

Represents a chain or tree of robot elements (rigid bodies and joints). Currently, only chains of elements are fully supported.

add_actuator(actuator_type)

Add an element to the robot model with the kinematics/dynamics of an X5 actuator.

Parameters:

actuator_type (str, unicode) – The type of actuator to add.

Returns:

True if the actuator could be added, False otherwise.

Return type:

bool

Raises:
  • ValueError – If the string from actuator_type is invalid
  • TypeError – If the actuator_type argument is not a string
add_bracket(bracket_type, mount)

Add an element to the robot model with the kinematics/dynamics of a bracket between two actuators.

Parameters:
  • bracket_type (str, unicode) – The type of bracket to add.
  • mount (str, unicode) – The mount type of the bracket
Returns:

True if bracket was added, False otherwise

Return type:

bool

Raises:
  • ValueError – If the string from either bracket_type or mount are invalid
  • TypeError – If the either bracket_type or mount arguments are not strings
add_joint(joint_type, combine=False)

Adds a degree of freedom about the specified axis.

This does not represent an element with size or mass, but only a connection between two other elements about a particular axis.

Parameters:
  • joint_type (str) –

    The axis of rotation or translation about which this joint allows motion.

    For a linear joint, use: tx, x, y, ty, tz, or z

    For a rotation joint, use: rx, ry, or rz

    This argument is case insensitive.

  • combine (bool) – Whether or not to combiner with previous element in body
Raises:
  • ValueError – If the string from joint_type is invalid
  • TypeError – If the joint_type argument is not a string

Add an element to the robot model with the kinematics/dynamics of a link between two actuators.

Parameters:
  • link_type (str, unicode) – The type of link between the actuators, e.g. a tube link between two X5 or X8 actuators.
  • extension (int, float) – The center-to-center distance between the actuator rotational axes.
  • twist (int, float) – The rotation (in radians) between the actuator axes of rotation. Note that a 0 radian rotation will result in a z-axis offset between the two actuators, and a pi radian rotation will result in the actuator interfaces to this tube being in the same plane, but the rotational axes being anti-parallel.
Returns:

True if link was added, False otherwise

Return type:

bool

Raises:
  • ValueError – If the string from link_type is invalid
  • TypeError – If the link_type argument is not a string
add_rigid_body(com, inertia, mass, output, combine)

Adds a rigid body with the specified properties to the robot model.

This can be ‘combined’ with the parent element (the element to which this is attaching), which means that the mass, inertia, and output frames of this element will be integrated with the parent. The mass will be combined, and the reported parent output frame that this element attached to will be replaced with the output from this element (so that the number of output frames and masses remains constant).

Parameters:
  • com (str, list, numpy.ndarray, ctypes.Array) – 3 element vector or 4x4 matrix. If this parameter is a 3 element vector, the elements will be used as the translation vector in a homogeneous transformation matrix. The homogeneous transform is to the center of mass location, relative to the input frame of the element. Note that this frame is also the frame in which the inertia tensor is given.
  • inertia (str, list, numpy.ndarray, ctypes.Array) – The 6 element representation (Ixx, Iyy, Izz, Ixy, Ixz, Iyz) of the inertia tensor, in the frame given by the COM.
  • mass (int, float) – The mass of this element.
  • output (str, list, numpy.ndarray, ctypes.Array) – 4x4 matrix of the homogeneous transform to the output frame, relative to the input frame of the element.
  • combine (bool) – True if the frames and masses of this body should be combined with the parent, False otherwise.
Returns:

True if the body could be added, False otherwise.

Return type:

bool

Raises:

ValueError – if com, inertia, or output are of wrong size

base_frame

The transform from the world coordinate system to the root kinematic body

Returns:The base frame 4x4 matrix
Return type:numpy.matrix
dof_count

The number of settable degrees of freedom in the kinematic tree. This is equal to the number of actuators added.

Returns:the degrees of freedom.
Return type:int
get_end_effector(positions, output=None)

Generates the forward kinematics to the end effector (leaf node)

Note: for center of mass frames, this is one per leaf node; for output frames, this is one per output per leaf node, in depth first order.

This overload is for kinematic chains that only have a single leaf node frame.

Currently, kinematic trees are not fully supported – only kinematic chains – and so there are not other overloads for this function.

Parameters:
  • positions (str, list, numpy.ndarray, ctypes.Array) – A vector of joint positions/angles (in SI units of meters or radians) equal in length to the number of DoFs of the kinematic tree.
  • output (numpy.ndarray) – An optional parameter which allows you to avoid an allocation by copying the results into this parameter. The size of this parameter is not checked, so you must be certain that it is a numpy array of dtype float (np.float64) with 16 elements (e.g., a 4x4 matrix or 16 element array)
Returns:

A 4x4 transform that is resized as necessary in the function and filled in with the homogeneous transform to the end effector frame.

Return type:

numpy.matrix

Raises:
  • RuntimeError – If the RobotModel has no output frames
  • ValueError – If the positions input is not equal to the degrees of freedom of the RobotModel
get_forward_kinematics(frame_type, positions, output=None)

Generates the forward kinematics for the given robot model.

The order of the returned frames is in a depth-first tree.

As an example, assume a body A has one output, to which body B is connected. Body B has two outputs; actuator C is attached to the first output and actuator E is attached to the second output. Body D is attached to the only output of actuator C:

digraph outputs {
  rankdir=LR;
  node [style="filled", shape=circle, size=0.5, fillcolor=orange, fontname="Arial"];
  A;
  B;
  C;
  D;
  E;
  edge [color=black, weight=1, fontname="Arial", fontsize=8, arrowhead=dot];
  A -> B [weight=10];
  B -> C [label="output 1"];
  C -> D;
  B -> E [label="output 2", constraint=false];
  A -> E [style=invis];
}

For center of mass frames, the returned frames would be A-B-C-D-E. For output frames, the returned frames would be A-B(1)-C-D-B(2)-E.

Parameters:
  • frame_type (str) – Which type of frame to consider. See get_frame_count() for valid values.
  • positions (str, list, numpy.ndarray, ctypes.Array) – A vector of joint positions/angles (in SI units of meters or radians) equal in length to the number of DoFs of the kinematic tree.
  • output (list) – An optional parameter, which, if not None, specifies a list into which to put the output frames. If this parameter is not None, it must be large enough to fit all of the frames. No type or size checking is performed, and it is required that you handle error cases yourself.
Returns:

An list of 4x4 transforms; this is resized as necessary in the function and filled in with the 4x4 homogeneous transform of each frame. Note that the number of frames depends on the frame type.

Return type:

list

Raises:
  • TypeError – If frame_type is not a string
  • ValueError – If the positions input is not equal to the degrees of freedom of the RobotModel
get_frame_count(frame_type)

The number of frames in the forward kinematics.

Note that this depends on the type of frame requested:
  • for center of mass frames, there is one per added body.
  • for output frames, there is one per output per body.
Valid strings for valid frame types are:
  • For center of mass: 'CoM' or 'com'
  • For output: 'output'
Parameters:

frame_type (str) – Which type of frame to consider

Returns:

the number of frames of the specified type

Return type:

int

Raises:
  • ValueError – If the string from frame_type is invalid
  • TypeError – If the frame_type argument is not a string
get_jacobian_end_effector(positions, output=None)

Generates the Jacobian for the end effector (leaf node) frames(s).

Note: for center of mass frames, this is one per leaf node; for output frames, this is one per output per leaf node, in depth first order.

This overload is for kinematic chains that only have a single leaf node frame.

Currently, kinematic trees are not fully supported – only kinematic chains – and so there are not other overloads for this function.

Parameters:
  • positions (str, list, numpy.ndarray, ctypes.Array) – A vector of joint positions/angles (in SI units of meters or radians) equal in length to the number of DoFs of the kinematic tree.
  • output (numpy.ndarray) – An optional parameter which allows you to avoid an allocation by copying the results into this parameter. The size of this parameter is not checked, so you must be certain that it is a numpy array or matrix of dtype float (np.float64) with (frames x dofs) elements
Returns:

A (6 x number of dofs) jacobian matrix for the corresponding end effector frame of reference on the robot. It is resized as necessary inside this function.

Return type:

numpy.matrix

Raises:
  • RuntimeError – If the RobotModel has no output frames
  • ValueError – If the positions input is not equal to the degrees of freedom of the RobotModel
get_jacobians(frame_type, positions, output=None)

Generates the Jacobian for each frame in the given kinematic tree.

Parameters:
  • frame_type – Which type of frame to consider. See get_frame_count() for valid values.
  • frame_type – str
  • positions (str, list, numpy.ndarray, ctypes.Array) – A vector of joint positions/angles (in SI units of meters or radians) equal in length to the number of DoFs of the kinematic tree.
  • output (list) – An optional parameter which allows you to avoid an allocation by copying the results into this parameter. The size of this parameter is not checked, so you must be certain that it is a list of the proper size with all numpy arrays of dtype float (np.float64) with (frames x dofs) elements
Returns:

A vector (length equal to the number of frames) of matrices; each matrix is a (6 x number of dofs) jacobian matrix for the corresponding frame of reference on the robot. It is resized as necessary inside this function.

Return type:

list

masses

The mass of each rigid body (or combination of rigid bodies) in the robot.

Returns:The masses as an array
Return type:numpy.ndarray
solve_inverse_kinematics(initial_positions, *objectives, **kwargs)

Solves for an inverse kinematics solution given a set of objectives.

To avoid unnecessary allocations, provide output as a keyword argument. This argument must be a numpy array or matrix with dtype float (np.float64) with size equal to the initial positions. e.g.,

robot.solve_inverse_kinematics(positions, obj1, obj2, output=calc_pos) # calc_pos.size == positions.size

Parameters:
  • initial_positions (str, list, numpy.ndarray, ctypes.Array) – The seed positions/angles (in SI units of meters or radians) from which to start the IK search; equal in length to the number of DoFs of the kinematic tree.
  • objectives – A variable number of objectives used to define the IK search (e.g., target end effector positions, etc). Each argument must have a base class of Objective.
  • kwargs – An optional keyword arguments map, which currently only allows an output argument
Returns:

A vector equal in length to the number of DoFs of the kinematic tree; this will be filled in with the IK solution (in SI units of meters or radians) and resized as necessary.

Return type:

numpy.ndarray

Raises:
  • HEBI_Exception – If the IK solver failed
  • TypeError – If any of the provided objectives are not an objective type
  • ValueError – If the initial_positions input is not equal to the degrees of freedom of the RobotModel or has non-finite elements (_i.e_, nan, +/-inf)

Objective Functions

These functions are meant to be used with the RobotModel IK solver.

robot_model.endeffector_position_objective(weight=1.0)

Create a position end effector objective with the given parameters. Analogous to EndEffectorPositionObjective in the C++ API.

Parameters:
Returns:

the created objective

Raises:

ValueError – if xyz does not have at least 3 elements

robot_model.endeffector_so3_objective(weight=1.0)

Create an SO3 end effector objective with the given parameters. Analogous to EndEffectorSO3Objective in the C++ API.

Parameters:
Returns:

the created objective

Raises:

ValueError – if rotation matrix is not convertible to a 3x3 matrix, or if the rotation matrix is not in the SO(3) group.

robot_model.endeffector_tipaxis_objective(weight=1.0)

Create a tip axis end effector objective with the given parameters. Analogous to EndEffectorTipAxisObjective in the C++ API.

Parameters:
Returns:

the created objective

Raises:

ValueError – if axis does not have at least 3 elements

robot_model.joint_limit_constraint(maximum, weight=1.0)

Create a joint limit constraint objective. Analogous to JointLimitConstraint in the C++ API.

Parameters:
Returns:

the created objective

Raises:

ValueError – if minimum and maximum are not of the same size

robot_model.custom_objective(func, user_data=None, weight=1.0)

Construct a custom objective using a provided function. The func parameter is a function which accepts 3 parameters: positions, errors and user_data.

The first two parameters are guaranteed to be numpy arrays with dtype=np.float64. The third parameter, user_data, may be None, or set by the user when invoking this function. It is simply used to share application state with the callback function.

The length of errors in the callback will be equal to the num_errors parameter provided to this function. The elements in the errors parameter should be modified by the function to influence the IK solution.

The positions parameter is the joints positions (or angles) at the current point in the optimization. This is a read only array - any attempt to modify its elements will raise an Exception.

Example objective functions include:

def minimize(positions, error, user_data):
  error[0] = 0.0
  for i in range(len(positions)):
    error[0] += (positions[i]*positions[i])

def distance_to_sphere(positions, error, model):
  # model is a hebi.robot_model.RobotModel instance
  frame = model.get_forward_kinematics('endeffector', positions)[0]
  norm = np.linalg.norm(frame[0:3,3]) # translation vector in trasformation matrix
  sphere_radius = 0.25
  error[0] = (sphere_radius-norm)*(sphere_radius-norm)
Parameters:
  • num_errors (int) – The number of independent error values that this objective returns
  • func – The callback function
  • weight (int, float) – The weight of the objective
Returns:

the created objective

Raises:

ValueError – if num_errors is less than 1

Trajectory Planning

Creating Trajectories

To create a trajectory, a simple interface is provided.

hebi.trajectory.create_trajectory(time, position, velocity=None, acceleration=None)

Creates a smooth trajectory through a set of waypoints (position velocity and accelerations defined at particular times). This trajectory wrapper object can create multi-dimensional trajectories (i.e., multiple joints moving together using the same time reference).

Parameters:
  • time (list, numpy.ndarray) – A vector of desired times at which to reach each waypoint; this must be defined (and not None or nan for any element).
  • position (str, list, numpy.ndarray, ctypes.Array) – A matrix of waypoint joint positions (in SI units). The number of rows should be equal to the number of joints, and the number of columns equal to the number of waypoints. Any elements that are None or nan will be considered free parameters when solving for a trajectory. Values of +/-inf are not allowed.
  • velocity (NoneType, str, list, numpy.ndarray, ctypes.Array) – An optional matrix of velocity constraints at the corresponding waypoints; should either be None or matching the size of the positions matrix. Any elements that are None or nan will be considered free parameters when solving for a trajectory. Values of +/-inf are not allowed.
  • acceleration (NoneType, str, list, numpy.ndarray, ctypes.Array) – An optional matrix of acceleration constraints at the corresponding waypoints; should either be None or matching the size of the positions matrix. Any elements that are None or nan will be considered free parameters when solving for a trajectory. Values of +/-inf are not allowed.
Returns:

The trajectory. This will never be None.

Return type:

Trajectory

Raises:
  • ValueError – If dimensionality or size of any input parameters are invalid.
  • RuntimeError – If trajectory could not be created.

Trajectory Objects

class hebi._internal.trajectory.Trajectory

Represents a smooth trajectory through a set of waypoints.

duration

The time (in seconds) between the start and end of this trajectory.

Returns:the duration
Return type:float
end_time

The time (in seconds) at which the trajectory ends.

Returns:the end time
Return type:float
get_state(time)

Returns the position, velocity, and acceleration for a given point in time along the trajectory.

Parameters:time (int, float) – the time, in seconds
Returns:a triplet containing the position, velocity, and acceleration at the given point in time.
Return type:numpy.ndarray, numpy.ndarray, numpy.ndarray
number_of_joints

The number of joints in this trajectory.

Returns:the number of joints
Return type:int
number_of_waypoints

The number of waypoints in this trajectory.

Returns:number of waypoints
Return type:int
start_time

The time (in seconds) at which the trajectory starts.

Returns:the start time
Return type:float

Utility Functions and Objects

Miscellaneous functions which don’t fall under any other category appear here.

Logging

Opening a Log File

util.load_log()

Opens an existing log file.

Parameters:

file (str, unicode) – the path to an existing log file

Returns:

The log file. This function will never return None

Return type:

LogFile

Raises:
  • TypeError – If file is an invalid type
  • IOError – If the file does not exist or is not a valid log file

Log File Objects

class hebi._internal.log_file.LogFile

Represents a file which contains previously recorded group messages.

This is created internally. Do not instantiate directly.

filename
Returns:The file name of the log file.
Return type:str
get_next_feedback(reuse_fbk=None)

Retrieves the next group feedback from the log file, if any exists. This function acts as a forward sequential iterator over the data in the file. Each subsequent call to this function moves farther into the file. When the end of the file is reached, all subsequent calls to this function returns None

Warning: any preexisting data in the provided Feedback object is erased.

Parameters:reuse_fbk – An optional parameter which can be used to reuse an existing GroupFeedback instance. It is recommended to provide this parameter inside a repetitive loop, as reusing feedback instances results in substantially fewer heap allocations.
Returns:The most recent feedback, provided one is available. None is returned if there is no available feedback.
Return type:TimedGroupFeedback
number_of_modules
Returns:The number of modules in the group.
Return type:int
class hebi._internal.log_file.TimedGroupFeedback

A feedback object with a time field. Represents feedback returned from a log file. This class inherits all fields and functionality from the GroupFeedback.

time
Returns:The time, relative to the start of the log file (in seconds).
Return type:numpy.ndarray

Imitation Group

An imitation group is an instance of a Group which provides all of the same methods and attributes of a group representing a physically connected collection of HEBI modules on a local network. However, the imitation group differs in implementation due to the fact that it represents a virtual collection of modules.

util.create_imitation_group()

Create an imitation group of the provided size. The imitation group returned from this function provides the exact same interface as a group created from the Lookup class.

However, there are a few subtle differences between the imitation group and group returned from a lookup operation. See Contrasted to Physical Group section for more information.

Parameters:size (int) – The number of modules in the imitation group
Returns:The imitation group. This will never be None
Return type:Group
Raises:ValueError – If size is less than 1

Contrasted to Physical Group

For simplicity, think of the “physical” group returned from a lookup operation as a PhysicalGroup and the imitation group returned from this function as an ImitationGroup.

Commands

While both interfaces allow for commands to be sent, there is no network communication involved in the ImitationGroup implementation. Consequently, any commands sent to an imitation group will be visible immediately.

For example:

group = create_imitation_group(3)
print('Position:')
# Prints [0.0, 0.0, 0.0]
print(group.get_next_feedback().position)
# Move modules in group
cmd = GroupCommand(group.size)
cmd.position = [4.0, 2.0, -2.0]
# Send command, which will be visible immediately
group.send_command(cmd)
# Prints [4.0, 2.0, -2.0]
print(group.get_next_feedback().position)
Info

An ImitationGroup will never return info. In fact, any calls to Group.request_info() will return None. A PhysicalGroup should always return valid info.

Feedback

An ImitationGroup will always have feedback available - i.e., calling Group.get_next_feedback() on an ImitationGroup will always return feedback immediately. In contrast, a PhysicalGroup requires a non-zero feedback frequency, or the Group.send_feedback_request() function to be called. To achieve some level of deterministic behavior, the feedback in an ImitationGroup is always set to an initial state, which is basically a set of sane values for each field in a GroupFeedback object.

Therefore, the following code is valid with the imitation group:

group = create_imitation_group(3)
print('3 Positions:')
# Prints the same position 3 times ([0.0, 0.0, 0.0])
print(group.get_next_feedback().position)
print(group.get_next_feedback().position)
print(group.get_next_feedback().position)

The default feedback frequency for an imitation group is 0. This means that any attached feedback handlers will not be invoked when the object is in its initial state. You must explicitly set the feedback frequency to a positive number if feedback handlers are desired. Remember that unless commands are actively being set, the feedback data will be the same exact value on every feedback handler invocation.

Message Types

These classes are used to communicate with HEBI modules. With the exception of GroupCommand, they are read-only.

Commanding

class hebi.GroupCommand(number_of_modules, shared=None)

Command objects have various fields that can be set; when sent to the module, these fields control internal properties and setpoints.

boot

Boot the module from bootloader into application

clear()

Clears all of the fields

control_strategy

How the position, velocity, and effort PID loops are connected in order to control motor PWM.

effort

Effort at the module output; units vary (e.g., N \cdot m for rotational joints and N for linear stages).

effort_d_on_error

Controls whether the Kd term uses the “derivative of error” or “derivative of measurement.” When the setpoints have step inputs or are noisy, setting this to False can eliminate corresponding spikes or noise in the output.

effort_dead_zone

Error values within +/- this value from zero are treated as zero (in terms of computed proportional output, input to numerical derivative, and accumulated integral error).

effort_feed_forward

Feed forward term for effort (this term is multiplied by the target and added to the output).

effort_i_clamp

Maximum allowed value for the output of the integral component of the PID loop; the integrated error is not allowed to exceed value that will generate this number.

effort_kd

Derivative PID gain for effort

effort_ki

Integral PID gain for effort

effort_kp

Proportional PID gain for effort

effort_max_output

Output from the PID controller is limited to a maximum of this value.

effort_max_target

Maximum allowed value for input to the PID controller

effort_min_output

Output from the PID controller is limited to a minimum of this value.

effort_min_target

Minimum allowed value for input to the PID controller

effort_output_lowpass

A simple lowpass filter applied to the controller output; needs to be between 0 and 1. At each timestep: x_t = x_t * a + x_{t-1} * (1 - a).

effort_punch

Constant offset to the effort PID output outside of the deadzone; it is added when the error is positive and subtracted when it is negative.

effort_target_lowpass

A simple lowpass filter applied to the target set point; needs to be between 0 and 1. At each timestep: x_t = x_t * a + x_{t-1} * (1 - a).

family

Sets the family for this module.

led

The module’s LED.

name

Sets the name for this module.

position

Position of the module output (post-spring), in radians.

position_d_on_error

Controls whether the Kd term uses the “derivative of error” or “derivative of measurement.” When the setpoints have step inputs or are noisy, setting this to False can eliminate corresponding spikes or noise in the output.

position_dead_zone

Error values within +/- this value from zero are treated as zero (in terms of computed proportional output, input to numerical derivative, and accumulated integral error).

position_feed_forward

Feed forward term for position (this term is multiplied by the target and added to the output).

position_i_clamp

Maximum allowed value for the output of the integral component of the PID loop; the integrated error is not allowed to exceed value that will generate this number.

position_kd

Derivative PID gain for position

position_ki

Integral PID gain for position

position_kp

Proportional PID gain for position

position_limit_max

Set the firmware safety limit for the maximum allowed position.

position_limit_min

Set the firmware safety limit for the minimum allowed position.

position_max_output

Output from the PID controller is limited to a maximum of this value.

position_max_target

Maximum allowed value for input to the PID controller

position_min_output

Output from the PID controller is limited to a minimum of this value.

position_min_target

Minimum allowed value for input to the PID controller

position_output_lowpass

A simple lowpass filter applied to the controller output; needs to be between 0 and 1. At each timestep: x_t = x_t * a + x_{t-1} * (1 - a).

position_punch

Constant offset to the position PID output outside of the deadzone; it is added when the error is positive and subtracted when it is negative.

position_target_lowpass

A simple lowpass filter applied to the target set point; needs to be between 0 and 1. At each timestep: x_t = x_t * a + x_{t-1} * (1 - a).

read_gains(file)

Import the gains from a file into this object.

Parameters:file
Raises:IOError is the file could not be opened
reference_effort

Set the internal effort reference offset so that the current effort matches the given reference command

reference_position

Set the internal encoder reference offset so that the current position matches the given reference command

reset

Restarts the module

save_current_settings

Indicates if the module should save the current values of all of its settings.

size

The number of modules in this group message.

spring_constant

The spring constant of the module.

stop_boot

Stop the module from automatically booting into application

velocity

Velocity of the module output (post-spring), in radians/second.

velocity_d_on_error

Controls whether the Kd term uses the “derivative of error” or “derivative of measurement.” When the setpoints have step inputs or are noisy, setting this to False can eliminate corresponding spikes or noise in the output.

velocity_dead_zone

Error values within +/- this value from zero are treated as zero (in terms of computed proportional output, input to numerical derivative, and accumulated integral error).

velocity_feed_forward

Feed forward term for velocity (this term is multiplied by the target and added to the output).

velocity_i_clamp

Maximum allowed value for the output of the integral component of the PID loop; the integrated error is not allowed to exceed value that will generate this number.

velocity_kd

Derivative PID gain for velocity

velocity_ki

Integral PID gain for velocity

velocity_kp

Proportional PID gain for velocity

velocity_max_output

Output from the PID controller is limited to a maximum of this value.

velocity_max_target

Maximum allowed value for input to the PID controller

velocity_min_output

Output from the PID controller is limited to a minimum of this value.

velocity_min_target

Minimum allowed value for input to the PID controller

velocity_output_lowpass

A simple lowpass filter applied to the controller output; needs to be between 0 and 1. At each timestep: x_t = x_t * a + x_{t-1} * (1 - a).

velocity_punch

Constant offset to the velocity PID output outside of the deadzone; it is added when the error is positive and subtracted when it is negative.

velocity_target_lowpass

A simple lowpass filter applied to the target set point; needs to be between 0 and 1. At each timestep: x_t = x_t * a + x_{t-1} * (1 - a).

write_gains(file)

Export the gains from this object into a file, creating it if necessary.

Parameters:file

Feedback

class hebi.GroupFeedback(number_of_modules, shared=None)

Feedback objects have various fields representing feedback from modules; which fields are populated depends on the module type and various other settings.

accelerometer

Accelerometer data, in m/s^2.

board_temperature

Ambient temperature inside the module (measured at the IMU chip), in degrees Celsius.

clear()

Clears all of the fields

command_lifetime_state

The state of the command lifetime safety controller, with respect to the current group

deflection

Difference (in radians) between the pre-spring and post-spring output position.

deflection_velocity

Velocity (in radians/second) of the difference between the pre-spring and post-spring output position.

effort

Effort at the module output; units vary (e.g., N \cdot m for rotational joints and N for linear stages).

effort_command

Commanded effort at the module output; units vary (e.g., N \cdot m for rotational joints and N for linear stages).

effort_limit_state

Software-controlled bounds on the allowable effort of the module

get_effort(array)

Convenience method to get efforts into an existing array. The input must be a numpy object with dtype compatible with numpy.float32.

Parameters:array (numpy.ndarray) – a numpy array or matrix with size matching the number of modules in this group message
get_effort_command(array)

Convenience method to get effort commands into an existing array. The input must be a numpy object with dtype compatible with numpy.float32.

Parameters:array (numpy.ndarray) – a numpy array or matrix with size matching the number of modules in this group message
get_position(array)

Convenience method to get positions into an existing array. The input must be a numpy object with dtype compatible with numpy.float64.

Parameters:array (numpy.ndarray) – a numpy array or matrix with size matching the number of modules in this group message
get_position_command(array)

Convenience method to get position commands into an existing array. The input must be a numpy object with dtype compatible with numpy.float64.

Parameters:array (numpy.ndarray) – a numpy array or matrix with size matching the number of modules in this group message
get_velocity(array)

Convenience method to get velocities into an existing array. The input must be a numpy object with dtype compatible with numpy.float32.

Parameters:array (numpy.ndarray) – a numpy array or matrix with size matching the number of modules in this group message
get_velocity_command(array)

Convenience method to get velocity commands into an existing array. The input must be a numpy object with dtype compatible with numpy.float32.

Parameters:array (numpy.ndarray) – a numpy array or matrix with size matching the number of modules in this group message
gyro

Gyro data, in radians/second.

hardware_receive_time

Timestamp of when message was received by module (remote) in seconds

hardware_receive_time_us

Timestamp of when message was received by module (remote) in microseconds

hardware_transmit_time

Timestamp of when message was transmitted from module (remote) in seconds

hardware_transmit_time_us

Timestamp of when message was transmitted from module (remote) in microseconds

io

Interface to the IO pins of the module

led

The module’s LED.

m_stop_state

Current status of the MStop

motor_current

Current supplied to the motor.

motor_housing_temperature

The estimated temperature of the motor housing.

motor_sensor_temperature

The temperature from a sensor near the motor housing.

motor_velocity

The velocity (in radians/second) of the motor shaft.

motor_winding_current

The estimated current in the motor windings.

motor_winding_temperature

The estimated temperature of the motor windings.

orientation

A filtered estimate of the orientation of the module

position

Position of the module output (post-spring), in radians.

position_command

Commanded position of the module output (post-spring), in radians.

position_limit_state

Software-controlled bounds on the allowable position of the module; user settable

processor_temperature

Temperature of the processor chip, in degrees Celsius.

receive_time

Timestamp of when message was received from module (local) in seconds

receive_time_us

Timestamp of when message was received from module (local) in microseconds

sender_id

Unique ID of the module transmitting this feedback

sequence_number

Sequence number going to module (local)

size

The number of modules in this group message.

temperature_state

Describes how the temperature inside the module is limiting the output of the motor

transmit_time

Timestamp of when message was transmitted to module (local) in seconds

transmit_time_us

Timestamp of when message was transmitted to module (local) in microseconds

velocity

Velocity of the module output (post-spring), in radians/second.

velocity_command

Commanded velocity of the module output (post-spring), in radians/second.

velocity_limit_state

Software-controlled bounds on the allowable velocity of the module

voltage

Bus voltage that the module is running at (in Volts).

Info

class hebi.GroupInfo(number_of_modules, shared=None)

Info objects have various fields representing the module state; which fields are populated depends on the module type and various other settings.

calibration_state

The calibration state of the module

control_strategy

How the position, velocity, and effort PID loops are connected in order to control motor PWM.

effort_d_on_error

Controls whether the Kd term uses the “derivative of error” or “derivative of measurement.” When the setpoints have step inputs or are noisy, setting this to False can eliminate corresponding spikes or noise in the output.

effort_dead_zone

Error values within +/- this value from zero are treated as zero (in terms of computed proportional output, input to numerical derivative, and accumulated integral error).

effort_feed_forward

Feed forward term for effort (this term is multiplied by the target and added to the output).

effort_i_clamp

Maximum allowed value for the output of the integral component of the PID loop; the integrated error is not allowed to exceed value that will generate this number.

effort_kd

Derivative PID gain for effort

effort_ki

Integral PID gain for effort

effort_kp

Proportional PID gain for effort

effort_max_output

Output from the PID controller is limited to a maximum of this value.

effort_max_target

Maximum allowed value for input to the PID controller

effort_min_output

Output from the PID controller is limited to a minimum of this value.

effort_min_target

Minimum allowed value for input to the PID controller

effort_output_lowpass

A simple lowpass filter applied to the controller output; needs to be between 0 and 1. At each timestep: x_t = x_t * a + x_{t-1} * (1 - a).

effort_punch

Constant offset to the effort PID output outside of the deadzone; it is added when the error is positive and subtracted when it is negative.

effort_target_lowpass

A simple lowpass filter applied to the target set point; needs to be between 0 and 1. At each timestep: x_t = x_t * a + x_{t-1} * (1 - a).

family

Sets the family for this module.

led

The module’s LED.

name

Sets the name for this module.

position_d_on_error

Controls whether the Kd term uses the “derivative of error” or “derivative of measurement.” When the setpoints have step inputs or are noisy, setting this to False can eliminate corresponding spikes or noise in the output.

position_dead_zone

Error values within +/- this value from zero are treated as zero (in terms of computed proportional output, input to numerical derivative, and accumulated integral error).

position_feed_forward

Feed forward term for position (this term is multiplied by the target and added to the output).

position_i_clamp

Maximum allowed value for the output of the integral component of the PID loop; the integrated error is not allowed to exceed value that will generate this number.

position_kd

Derivative PID gain for position

position_ki

Integral PID gain for position

position_kp

Proportional PID gain for position

position_limit_max

The firmware safety limit for the maximum allowed position.

position_limit_min

The firmware safety limit for the minimum allowed position.

position_max_output

Output from the PID controller is limited to a maximum of this value.

position_max_target

Maximum allowed value for input to the PID controller

position_min_output

Output from the PID controller is limited to a minimum of this value.

position_min_target

Minimum allowed value for input to the PID controller

position_output_lowpass

A simple lowpass filter applied to the controller output; needs to be between 0 and 1. At each timestep: x_t = x_t * a + x_{t-1} * (1 - a).

position_punch

Constant offset to the position PID output outside of the deadzone; it is added when the error is positive and subtracted when it is negative.

position_target_lowpass

A simple lowpass filter applied to the target set point; needs to be between 0 and 1. At each timestep: x_t = x_t * a + x_{t-1} * (1 - a).

save_current_settings

Indicates if the module should save the current values of all of its settings.

serial

Gets the serial number for this module (e.g., X5-0001).

size

The number of modules in this group message.

spring_constant

The spring constant of the module.

velocity_d_on_error

Controls whether the Kd term uses the “derivative of error” or “derivative of measurement.” When the setpoints have step inputs or are noisy, setting this to False can eliminate corresponding spikes or noise in the output.

velocity_dead_zone

Error values within +/- this value from zero are treated as zero (in terms of computed proportional output, input to numerical derivative, and accumulated integral error).

velocity_feed_forward

Feed forward term for velocity (this term is multiplied by the target and added to the output).

velocity_i_clamp

Maximum allowed value for the output of the integral component of the PID loop; the integrated error is not allowed to exceed value that will generate this number.

velocity_kd

Derivative PID gain for velocity

velocity_ki

Integral PID gain for velocity

velocity_kp

Proportional PID gain for velocity

velocity_max_output

Output from the PID controller is limited to a maximum of this value.

velocity_max_target

Maximum allowed value for input to the PID controller

velocity_min_output

Output from the PID controller is limited to a minimum of this value.

velocity_min_target

Minimum allowed value for input to the PID controller

velocity_output_lowpass

A simple lowpass filter applied to the controller output; needs to be between 0 and 1. At each timestep: x_t = x_t * a + x_{t-1} * (1 - a).

velocity_punch

Constant offset to the velocity PID output outside of the deadzone; it is added when the error is positive and subtracted when it is negative.

velocity_target_lowpass

A simple lowpass filter applied to the target set point; needs to be between 0 and 1. At each timestep: x_t = x_t * a + x_{t-1} * (1 - a).

write_gains(file)

Export the gains from this object into a file, creating it if necessary.

Parameters:file