API Reference

Lookup

class hebi.Lookup

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

DEFAULT_TIMEOUT_MS = 500

The default timeout (in milliseconds)

property 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.

A mac address can be represented by a string or by a 6 element list of bytes:

grp1 = lookup.get_connected_group_from_mac('aa:bb:cc:dd:ee:ff')
grp2 = lookup.get_connected_group_from_mac([0, 0, 42, 42, 42, 42])
Parameters
  • address (str, list) The mac address of the connected device, used to create the Group

  • timeout_ms (int, float) The maximum amount of time to wait, in milliseconds. This is an optional parameter with a default value of Lookup.DEFAULT_TIMEOUT_MS.

Returns

A group on success; None if one or more devices specified could not be found

Return type

hebi._internal.group.Group

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 (str) The family of the connected device, used to create the Group

  • name (str) The name of the connected device, used to create the Group

  • timeout_ms (int, float) The maximum amount of time to wait, in milliseconds. This is an optional parameter with a default value of Lookup.DEFAULT_TIMEOUT_MS.

Returns

A group on success; None if one or more devices specified could not be found

Return type

hebi._internal.group.Group

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 (str) The family of the devices to include in the Group

  • 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

A group on success; None if one or more devices specified could not be found

Return type

hebi._internal.group.Group

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.

A mac address can be represented by a string or by a 6 element list of bytes:

grp1 = lookup.get_group_from_macs(['aa:bb:cc:dd:ee:ff'])
grp2 = lookup.get_group_from_macs([[0, 0, 42, 42, 42, 42]])
Parameters
  • addresses (list) A list of mac addresses specifying the devices to include in the Group

  • 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

A group on success; None if one or more devices specified could not be found

Return type

hebi._internal.group.Group

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 (list) A list of families corresponding to the devices to include in the Group

  • names (list) A list of names corresponding to the devices to include in the Group

  • 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

A group on success; None if one or more devices specified could not be found

Return type

hebi._internal.group.Group

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.

property family
Returns

The family to which this module belongs.

Return type

str

property mac_address
Returns

The immutable MAC address of the module.

Return type

str

property 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.

property command_lifetime

The command lifetime for the modules in this group.

Returns

the command lifetime

Return type

int

property 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

property size

The number of modules in the group.

Returns

size of the group

Return type

int

start_log(directory=None, name=None, mkdirs=False)

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 be gracefully closed.

Note that the directory folder must exist if mkdirs is not True

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.

  • mkdirs (bool) Optional flag denoting if the base path represented by directory should be created, if they do not exist

Returns

The path, including the file, of the log file. Never None.

Return type

str

Raises

IOError If the group could not start logging

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

IPython Issues

Some IDE and development tools such as Jupyter Notebook and Spyder use a Python command shell called IPython. IPython is a very useful tool which unfortunately creates some subtle issues if used with this API.

Currently, the only known issue is when a script is run multiple times while the user assigns a Group object from the script into the running environment repetitively.

For example, assume the following commands are input within a running IPython instance:

In [1]: run ./your_script.py
In [2]: group1  # This is a group instance from your python script run above
Out[2]: <string representation of group1>
In [3]: run ./your_script.py

group1 is saved to a hidden variable in IPython named Out. If the command at In [2] was not executed, there would be no leaking of the group instance referenced by group1 - rerunning the script would reference a different group and allow the original one to be disposed.

However, because group1 is saved to the dict named Out, it will stay alive until it is explicitly deleted. This can become problematic if done repetitively, especially if the groups have a high feedback frequency set.

One way to resolve this issue is to use a function called util.clear_all_groups(). This function explicitly disposes of all current group instances created by the API.

However, it is generally recommended that you ensure to not allow multiple group instances, which refer to the same modules, to be run simultaneously.

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 X or R series HEBI 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_end_effector(end_effector_type)

Add an end effector element to the robot model.

For a “custom” type end effector, indentity transforms and zero mass and inertia parameters are used.

Parameters

end_effector_type (str, unicode) The type of end_effector to add.

Returns

True if the end effector was added, False otherwise

Return type

bool

Raises
  • ValueError If the string from end_effector_type is invalid

  • TypeError If the end_effector_type argument is not a string

add_joint(joint_type)

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.

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)

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).

Deprecation notice: It is deprecated to pass a str in as a parameter to any argument. This functionality will be removed in a future release.

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.

Returns

True if the body could be added, False otherwise.

Return type

bool

Raises

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

property base_frame

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

Returns

The base frame 4x4 matrix

Return type

numpy.ndarray

property 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

property element_count

The number of elements which compose the kinematic tree. This is greater than or equal to 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 method is for kinematic chains that only have a single leaf node frame.

Deprecation notice: It is deprecated to pass a str in as a parameter for positions. This functionality will be removed in a future release.

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.

Deprecation notice: It is deprecated to pass a str in as a parameter for positions. This functionality will be removed in a future release.

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'

  • For input:           'input'

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 method is for kinematic chains that only have a single leaf node frame.

Deprecation notice: It is deprecated to pass a str in as a parameter for positions. This functionality will be removed in a future release.

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.ndarray

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.

Deprecation notice: It is deprecated to pass a str in as a parameter for positions. This functionality will be removed in a future release.

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

property 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

property metadata

Retrieves a list of info about each individual element which composes this robot

Return type

list

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

Deprecation notice: It is deprecated to pass a str in as a parameter for initial_positions. This functionality will be removed in a future release.

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)

HRDF Importing

robot_model.import_from_hrdf(warning_callback=None)

Import a robot description in the HRDF format as a RobotModel instance.

Any warnings generated while importing will be printed to stderr, unless explicitly instructed otherwise by providing a callback.

Parameters
  • hrdf_file The location of the HRDF file to import

  • warning_callback A function, which can accept one argument, to call back if warnings are generated. If None, warnings are printed to stderr

Returns

the RobotModel from the description file

Return type

RobotModel

Raises
  • IOError If the provided file does not exist

  • RuntimeError If the hrdf file could not be imported. The associated error message will be displayed.

robot_model.import_from_hrdf_string(warning_callback=None)

Provides same functionality as import_from_hrdf(), but accepts a string representing the HRDF as opposed to a string to the file representing the HRDF.

Parameters

hrdf_string (str) A string representing HRDF contents

Metadata

A RobotModel contains metadata for each component of the kinematic body. Using the metadata property on an instance, one can retrieve a list of all metadata comprising the body.

All metadata elements are guaranteed to have the following properties:

  • type, which returns an enum value

  • is_dof, which returns a boolean

The type property returns an enum value corresponding to the type of element it represents. All possible values are:

  • hebi.robot_model.enums.RobotModelElementTypeActuator

  • hebi.robot_model.enums.RobotModelElementTypeBracket

  • hebi.robot_model.enums.RobotModelElementTypeJoint

  • hebi.robot_model.enums.RobotModelElementTypeLink

  • hebi.robot_model.enums.RobotModelElementTypeRigidBody

  • hebi.robot_model.enums.RobotModelElementTypeEndEffector

Using this property, you can determine what fields are present on a metadata object.

class hebi.robot_model.OtherMetaData

Metadata pertaining to an unknown object

property is_dof
Returns

True if this element corresponds to a degree of freedom; False otherwise

Return type

bool

property type
Returns

The enum value corresponding to this type

class hebi.robot_model.ActuatorMetaData(actuator_type)

Metadata pertaining to an actuator

property actuator_type
Returns

The enum value corresponding to the specific actuator type of this element

property is_dof
Returns

True if this element corresponds to a degree of freedom; False otherwise

Return type

bool

property type
Returns

The enum value corresponding to this type

class hebi.robot_model.BracketMetaData(bracket_type)

Metadata pertaining to a bracket

property bracket_type
Returns

The enum value corresponding to the specific bracket type of this element

property is_dof
Returns

True if this element corresponds to a degree of freedom; False otherwise

Return type

bool

property type
Returns

The enum value corresponding to this type

property type_str
Returns

A string representing the type of this element

Return type

str

class hebi.robot_model.JointMetaData(joint_type)

Metadata pertaining to a joint

property is_dof
Returns

True if this element corresponds to a degree of freedom; False otherwise

Return type

bool

property joint_type
Returns

The enum value corresponding to the specific joint type of this element

property type
Returns

The enum value corresponding to this type

property type_str
Returns

A string representing the type of this element

Return type

str

class hebi.robot_model.LinkMetaData(link_type, extension, twist)

Metadata pertaining to a link

property extension
Returns

The extension of the link [m]

Return type

float

property is_dof
Returns

True if this element corresponds to a degree of freedom; False otherwise

Return type

bool

Returns

The enum value corresponding to the specific link type of this element

property twist
Returns

The twist/rotation of the link [rad]

Return type

float

property type
Returns

The enum value corresponding to this type

property type_str
Returns

A string representing the type of this element

Return type

str

class hebi.robot_model.RigidBodyMetaData

Metadata pertaining to a rigid body

property is_dof
Returns

True if this element corresponds to a degree of freedom; False otherwise

Return type

bool

property type
Returns

The enum value corresponding to this type

property type_str
Returns

A string representing the type of this element

Return type

str

class hebi.robot_model.EndEffectorMetaData(end_effector_type)

Metadata pertaining to an end effector

property end_effector_type
Returns

The enum value corresponding to the specific end effector type of this element

property is_dof
Returns

True if this element corresponds to a degree of freedom; False otherwise

Return type

bool

property type
Returns

The enum value corresponding to this type

property type_str
Returns

A string representing the type of this element

Return type

str

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).

Deprecation notice: It is deprecated to pass a str in as a parameter for any of the waypoint dimensions or time. This functionality will be removed in a future release.

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.

property duration

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

Returns

the duration

Return type

float

property 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

property number_of_joints

The number of joints in this trajectory.

Returns

the number of joints

Return type

int

property number_of_waypoints

The number of waypoints in this trajectory.

Returns

number of waypoints

Return type

int

property start_time

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

Returns

the start time

Return type

float

property waypoint_times
Returns

The input time (in seconds) for each waypoint

Return type

numpy.ndarray

Arm

The arm API is a high level interface intended to be used with robotic chains which have a simple (i.e., non-tree) topology. As the name suggests, this interface is best suited for robotic arms. This API encapsulates the module communication and kinematic description, while also exposing a few tunables and state associated with common kit use cases.

Components

Arm

class hebi.arm.Arm(time_getter, group, robot_model, end_effector=None, plugins=None)
FK(positions, **kwargs)

Retrieves the output frame of the end effector at the provided joint positions.

The keys provided below show the possible retrievable representations of the resulting end effector transform.

Possible keys:
  • xyz_out:          Used to store the 3d translation vector of the end effector

    If this is set, this is also the object returned.

  • tip_axis_out:     Used to store the tip axis of the end effector

  • orientation_out:  Used to store the orientation (SO3 matrix) of the end effector

Parameters

positions The joint space positions

Returns

The 3d translation vector of the end effector

add_plugin(plugin)

Adds the specified plugin to the arm. ArmPlugin.on_associated() callback is invoked on the plugin specified.

Additionally, the plugin is explicitly set to enabled, i.e., plugin.enabled = True.

Parameters

plugin (ArmPlugin) the plugin to add

property at_goal
Return type

bool

cancel_goal()

Removes any currently set goal.

clear_joint_limits()

Removes any currently set joint limits.

property end_effector

The currently set end effector. None if there is no end effector.

get_aux(t)

Retrieve the aux value at the given time point. If there are no aux values, an empty array is returned.

Parameters

t The point in time, intended to be within the interval determined by the current goal.

Return type

np.ndarray

property goal_progress

Progres towards the current goal; in range of [0.0, 1.0].

Return type

float

property group

The underlying group of the arm. Guaranteed to be non-null.

ik_target_xyz(initial_position, target_xyz, out=None)

Solve for the joint space positions such that the end effector is near the target xyz position in space specified.

If there are any joint limits set, the solver will attempt to respect them.

Parameters
  • initial_position The seed angles for the IK solver

  • target_xyz The intended destination coordinate as a 3d vector

  • out The optional output parameter (also always returned)

ik_target_xyz_so3(initial_position, target_xyz, orientation, out=None)

Solve for the joint space positions such that the end effector is near the target xyz position in space with the specified SO3 orientation.

If there are any joint limits set, the solver will attempt to respect them.

Parameters
  • initial_position The seed angles for the IK solver

  • target_xyz The intended destination coordinate as a 3d vector

  • orientation The intended destination orientation as an SO3 matrix

  • out The optional output parameter (also always returned)

ik_target_xyz_tip_axis(initial_position, target_xyz, tip_axis, out=None)

Solve for the joint space positions such that the end effector is near the target xyz position in space and also oriented along the axis specified.

If there are any joint limits set, the solver will attempt to respect them.

Parameters
  • initial_position The seed angles for the IK solver

  • target_xyz The intended destination coordinate as a 3d vector

  • tip_axis The intended destination tip axis as a 3d vector

  • out The optional output parameter (also always returned)

property last_feedback

The most recently received feedback from the arm. This object is guaranteed to not change for the lifetime of the arm.

Return type

hebi.GroupFeedback

load_gains(gains_file, attempts=5)

Load the gains from the provided file and send the gains to the underlying modules in the group.

This method requests acknowledgement from all modules in the group that the gains were received. Consequently, this method may take a few seconds to execute if you are on a network which drops packets (e.g., a suboptimal WiFi network). The attempts parameter is used to re-send the gains to modules, on the event that an ack was not received from each module in the group.

Parameters
  • gains_file The file location of the gains file

  • attempts the number of attempts to send the gains to the group.

Returns

True if gains were successfully sent to the modules; otherwise False

Return type

bool

property pending_command

The command which will be send to the modules on Arm.send(). This object is guaranteed to not change for the lifetime of the arm.

Return type

hebi.GroupCommand

property robot_model

The underlying robot description of the arm. Guaranteed to be non-null.

Return type

hebi.robot_model.RobotModel

send()

Send the pending commands to the arm and end effector (if non-null).

Returns

True if command was successfully sent to all components; False otherwise

Return type

bool

set_aux_state(aux_state)

Replace the current aux state with the provided input.

Parameters

aux_state (collections.abc.Sequence) The updated aux state

set_end_effector(end_effector)

Update the currently set end effector for the arm

set_goal(goal)

Sets the current goal of the arm as described by the input waypoints.

Parameters

goal (Goal) Goal object representing waypoints of the goal

set_joint_limits(min_positions, max_positions)

Replace any currently set joint limits with the limits provided

Parameters
property size

The number of modules in the group

Return type

int

property trajectory

The underlying trajectory object used to move the arm through the prescribed waypoints associated with the current goal.

If there is no currently set goal, this will be None.

update()

Receive feedback from the modules, compute pending commands, and update state for the end effector and any associated plugins

Returns

True if feedback was received and all components were able to be updated; False otherwise

Return type

bool

End Effector

An arm can optionally have an end effector associated with it.

class hebi.arm.EndEffector

Abstract base class representing an end effector to be used with an Arm object.

send()

Sends the currently pending command to the end effector.

Returns

True on success; otherwise False

Return type

bool

update(aux_state)

Update the aux state of the end effector.

Parameters

aux_state (int, float, list) a scalar number (int or float) or list of numbers.

Returns

True on success, otherwise False

class hebi.arm.Gripper(group, close_effort, open_effort)

End effector implementation which is intended to be used to provide gripper functionality.

close()

Sets the gripper to be fully closed

property command

The underlying command to be sent to the gripper. Can be modified to extend functionality.

Return type

hebi.GroupCommand

load_gains(gains_file, attempts=5)

Load the gains from the provided file and send the gains to the gripper.

This method requests acknowledgement from the gripper that the gains were received. Consequently, this method may take a few seconds to execute if you are on a network which drops packets (e.g., a suboptimal WiFi network). The attempts parameter is used to re-send the gains, in the event that an ack was not received from the gripper.

Parameters
  • gains_file The file location of the gains file

  • attempts the number of attempts to send the gains to the gripper.

Returns

True if gains were successfully sent to the gripper; otherwise False

Return type

bool

open()

Sets the gripper to be fully open

send()

Send the command to the gripper.

Returns

the result of hebi._internal.group.Group.send_command()

property state

The current state of the gripper. Range of the value is [0.0, 1.0].

Return type

float

toggle()

Toggle the state of the gripper.

If the gripper was fully closed, it will become fully open. If the gripper was fully open, it will become fully closed. Otherwise, this method is a no-op.

update(aux)

Update the state of the gripper

Parameters

aux (int, float, numpy.ndarray) The aux data. Can be a scalar value or a list of values. If a list, it is expected to contain only one element. Values be finite.

Returns

True on success; False otherwise

Plugins

Plugins provide extra functionality for the arm, through an interface which is essentially a collection of callbacks invoked by the arm on certain methods. To add a plugin to an existing arm, one can simply add it via arm.Arm.add_plugin().

class hebi.arm.ArmPlugin

Abstract base class representing a plugin to be used for an Arm object.

property enabled

Determines if the plugin should be invoked by the owning arm. If False, this plugin will not be invoked on Arm.update().

Return type

bool

on_associated(arm)

Override to update any state based on the associated arm.

Invoked when the instance is added to an arm via Arm.add_plugin()

update(arm)

Callback which updates state on the arm. Invoked by Arm.update().

An implementation must return a boolean denoting True on success and False otherwise.

Some plugin implementations are provided:

class hebi.arm.EffortOffset(offset)

Plugin implementation used to offset the effort to be sent to the group.

This offset can be scalar or a vector of length equal to the size of the group.

update(arm)

Callback which updates state on the arm. Invoked by Arm.update().

An implementation must return a boolean denoting True on success and False otherwise.

class hebi.arm.ImpedanceController(gains_in_end_effector_frame=False)

Plugin implementation which provides an impedance controller for the arm.

property gains_in_end_effector_frame

Determines whether the gains are relative to the end effector frame

on_associated(arm)

Override to update any state based on the associated arm.

Invoked when the instance is added to an arm via Arm.add_plugin()

set_kd(x, y, z, roll, pitch, yaw)

Sets the damping gains for the impedance controller. Units are (N/(m/sec)) or (Nm/(rad/sec)).

set_kp(x, y, z, roll, pitch, yaw)

Sets the proportional gains for the impedance controller. Units are (N/m) or (Nm/rad).

update(arm)

Callback which updates state on the arm. Invoked by Arm.update().

An implementation must return a boolean denoting True on success and False otherwise.

class hebi.arm.DoubledJointMirror(index, group)

Plugin implementation meant to be used for an arm that has a joint which is composed of two modules in series.

update(arm)

Callback which updates state on the arm. Invoked by Arm.update().

An implementation must return a boolean denoting True on success and False otherwise.

Creating an Arm Object

arm.create(names=None, command_lifetime=100, control_frequency=100.0, hrdf_file=None, robot_model=None, end_effector=None, time_getter=None, lookup=None)

Create an arm object based off of the provided kinematic representation.

Examples:

import hebi
from hebi import arm as arm_api

# Create based off of a 6-DoF arm with an HRDF file
arm1 = arm_api.create(["Example Arm"],
                      names=['J1_base', 'J2_shoulder', 'J3_elbow', 'J4_wrist1', 'J5_wrist2', 'J6_wrist3'],
                      hrdf_file="hrdf/A-2085-06.hrdf")

# Use some existing objects
lookup = hebi.Lookup()
existing_robot_model = get_robot_model()
families = get_families()
names = get_names()
time_function = get_simulator_time_function()

arm2 = arm_api.create(families=families, names=names,
                      robot_model=existing_robot_model,
                      time_getter=time_function,
                      lookup=lookup)
Parameters
  • families (list, str) Required parameter.

  • names (list) Names of the modules in the group. If None, hebi.Lookup.get_group_from_family() will be used

  • command_lifetime (int) How long a command takes effect for on the robot before expiring.

  • control_frequency (float) Loop rate, in Hz. This is how fast the arm update loop will nominally run.

  • hrdf_file (str) The robot description. Cannot be used in combination with robot_model.

  • robot_model (hebi.robot_model.RobotModel) The robot description. Cannot be used in combination with hrdf_file.

  • end_effector (hebi.arm.EndEffector) Optionally, supply an end effector to be controlled by the “aux” state of provided goals.

  • time_getter (callable) A function pointer which returns a float representing the current time in seconds. Can be overloaded to use, e.g., simulator time

  • lookup (hebi.Lookup) An optional lookup instance to use to find the group. The default instance will be provided if None

Return type

hebi.arm.Arm

Utility Functions and Objects

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

Logging

Opening a Log File

util.load_log(load=True)

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.

property feedback_iterate

Retrieves an iterator over feedback from the LogFile, sequentially in order from the beginning of the file.

Note: The object returned from this method is only valid for the duration of the enclosing LogFile (self). If one attempts to use this iterator after the LogFile has been disposed, an exception will be raised.

Returns

A feedback iterator for this LogFile.

property 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

property 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 GroupFeedback.

property time
Returns

The time, relative to the start of the log file (in seconds).

Return type

numpy.ndarray

Mobile IO

Notice: This API is considered experimental and may change in ways which may break backwards compatibility in future versions.

Creating a MobileIO Instance

util.create_mobile_io(family='HEBI', name='mobileIO')

Create a hebi._internal.mobile_io.MobileIO instance with the specified family and name.

Parameters
  • lookup (hebi.Lookup) An existing lookup instance to use to look for the mobile device

  • family (str) The family of the mobile IO device

  • name (str) The name of the mobile IO device

Returns

the mobile IO instance, or None on failure

Return type

hebi._internal.mobile_io.MobileIO

Mobile IO Classes

class hebi._internal.mobile_io.MobileIO(group)

Wrapper around a mobile IO controller

clear_text(blocking=True)

Clear the text display.

Parameters

blocking (bool) If True, block for acknowledgement from the device. Otherwise, return as quickly as possible.

Return type

bool

Returns

True if the device received the command and successfully sent an acknowledgement; False otherwise.

get_axis_state(index)

Retrieve the current state of the specified axis.

Note that this method uses 1-indexing.

Parameters

index (int) The index of the axis (indices starting at 1).

Return type

float

get_button_diff(index)

Retrieve the current diff of the specified button.

Note that this method uses 1-indexing.

Parameters

index (int) The index of the button (indices starting at 1).

Return type

ButtonState

get_button_state(index)

Retrieve the current (pressed/unpressed) state of the specified button.

Note that this method uses 1-indexing.

Parameters

index (int) The index of the button (indices starting at 1).

Return type

bool

get_last_feedback()

Retrieve the last receieved feedback from the mobile IO device.

Return type

hebi._internal.ffi._message_types.Feedback

property orientation

Retrieve the AR orientation of the mobile IO device.

Note that this will only return valid data if the device supports an AR framework.

Return type

numpy.ndarray

property position

Retrieve the AR position of the mobile IO device.

Note that this will only return valid data if the device supports an AR framework.

Return type

numpy.ndarray

send_vibrate(blocking=True)

Send a command to vibrate the device. Note that this feature depends on device support. If the device does not support programmatic vibrating, then this will be a no-op.

Parameters

blocking (bool) If True, block for acknowledgement from the device. Otherwise, return as quickly as possible.

Return type

bool

Returns

True if the device received the command and successfully sent an acknowledgement; False otherwise.

set_axis_value(slider, value)

Set the position on a slider.

Note that this method uses 1-indexing.

Parameters
  • slider (int) The index of the slider to modify (indices starting at 1)

  • value (int, float) The value to set. Note that this will be converted to a float.

Return type

bool

Returns

True if the device received the command and successfully sent an acknowledgement; False otherwise.

set_button_mode(button, value)

Set the mode of the specified button to momentary or toggle.

Note that this method uses 1-indexing.

Parameters
  • button (int) The index of the button to modify (indices starting at 1).

  • value (int, str) The value to set. Momentary corresponds to 0 (default) and toggle corresponds to 1. This parameter allows the strings ‘momentary’ and ‘toggle’

Raises

ValueError If value is an unrecognized string

Return type

bool

Returns

True if the device received the command and successfully sent an acknowledgement; False otherwise.

set_button_output(button, value)

Set the button output behavior (indicator ring on or off).

Note that this method uses 1-indexing.

Parameters
  • button (int) The index of the button to modify (indices starting at 1).

  • value (int) The value to set. To illuminate the indicator ring, use 1. To hide it, use 0.

Return type

bool

Returns

True if the device received the command and successfully sent an acknowledgement; False otherwise.

set_led_color(color, blocking=True)

Set the edge led color

Parameters
  • color (int, str) The color to which the edge color is set. Certain strings are recognized as colors. Reference led for a complete list of allowed colors.

  • blocking (bool) If True, block for acknowledgement from the device. Otherwise, return as quickly as possible.

Return type

bool

Returns

True if the device received the command and successfully sent an acknowledgement; False otherwise.

set_snap(slider, value)

Set the snap position on a slider.

Note that this method uses 1-indexing.

Parameters
  • slider (int) The index of the slider to modify (indices starting at 1)

  • value (int, float) The value to set. Note that this will be converted to a float.

Return type

bool

Returns

True if the device received the command and successfully sent an acknowledgement; False otherwise.

set_text(message, blocking=True)

Append a message to the text display.

Parameters
  • message (str) The string to append to the display

  • blocking (bool) If True, block for acknowledgement from the device. Otherwise, return as quickly as possible.

Return type

bool

Returns

True if the device received the command and successfully sent an acknowledgement; False otherwise.

property state

Retrieve the current state of all buttons and sliders

Return type

MobileIOState

update(timeout_ms=None)

Updates the button and axis values and state. Returns False if feedback could not be received.

Return type

bool

Returns

True on success; False otherwise

class hebi._internal.mobile_io.ButtonState(value=0)

Represents the state of a button.

The defined values for this class are:

  • 0; corresponding to the state Off

  • 1; corresponding to the state On

  • 2; corresponding to the state ToOff

  • 3; corresponding to the state ToOn

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.

Misc Group Utilities

util.clear_all_groups()

Clear all groups currently allocated by the API. This is useful to clear up resources when running in an environment such as IPython.

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.

property accel_includes_gravity
Type: bool
Units: None

Whether to include acceleration due to gravity in acceleration feedback.

Return type

numpy.ndarray

property append_log
Type: string
Units: None

Appends to the current log message on the module.

Return type

list

property boot
Type: flag
Units: None

Boot the module from bootloader into application.

Return type

numpy.ndarray

clear()

Clears all of the fields

property clear_log
Type: flag
Units: None

Clears the log message on the module.

Return type

numpy.ndarray

property control_strategy
Type: enum
Units: None

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

Possible values include:

  • Off (raw value: 0): The motor is not given power (equivalent to a 0 PWM value)

  • DirectPWM (raw value: 1): A direct PWM value (-1 to 1) can be sent to the motor (subject to onboard safety limiting).

  • Strategy2 (raw value: 2): A combination of the position, velocity, and effort loops with P and V feeding to T; documented on docs.hebi.us under “Control Modes”

  • Strategy3 (raw value: 3): A combination of the position, velocity, and effort loops with P, V, and T feeding to PWM; documented on docs.hebi.us under “Control Modes”

  • Strategy4 (raw value: 4): A combination of the position, velocity, and effort loops with P feeding to T and V feeding to PWM; documented on docs.hebi.us under “Control Modes”

Return type

numpy.ndarray

copy_from(src)

Copies all fields from the provided message. All fields in the current message are cleared before copied from src.

create_view(mask)

Creates a view into this instance with the indices as specified.

Note that the created view will hold a strong reference to this object. This means that this object will not be destroyed until the created view is also destroyed.

For example:

# group_command has a size of at least 4
indices = [0, 1, 2, 3]
view = group_command.create_view(indices)
# use view like a GroupCommand object
Return type

GroupCommandView

property debug

Values for internal debug functions (channel 1-9 available).

property effort
Type: float
Units: N*m

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

Return type

numpy.ndarray

property effort_d_on_error
Type: bool
Units: None

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 @c false can eliminate corresponding spikes or noise in the output.

Return type

numpy.ndarray

property effort_dead_zone
Type: float
Units: None

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).

Return type

numpy.ndarray

property effort_feed_forward
Type: float
Units: None

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

Return type

numpy.ndarray

property effort_i_clamp
Type: float
Units: None

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.

Return type

numpy.ndarray

property effort_kd
Type: float
Units: None

Derivative PID gain for effort

Return type

numpy.ndarray

property effort_ki
Type: float
Units: None

Integral PID gain for effort

Return type

numpy.ndarray

property effort_kp
Type: float
Units: None

Proportional PID gain for effort

Return type

numpy.ndarray

property effort_limit_max
Type: float
Units: N*m

The firmware safety limit for the maximum allowed effort.

Return type

numpy.ndarray

property effort_limit_min
Type: float
Units: N*m

The firmware safety limit for the minimum allowed effort.

Return type

numpy.ndarray

property effort_max_output
Type: float
Units: None

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

Return type

numpy.ndarray

property effort_max_target
Type: float
Units: None

Maximum allowed value for input to the PID controller

Return type

numpy.ndarray

property effort_min_output
Type: float
Units: None

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

Return type

numpy.ndarray

property effort_min_target
Type: float
Units: None

Minimum allowed value for input to the PID controller

Return type

numpy.ndarray

property effort_output_lowpass
Type: float
Units: None

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).

Return type

numpy.ndarray

property effort_punch
Type: float
Units: None

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.

Return type

numpy.ndarray

property effort_target_lowpass
Type: float
Units: None

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).

Return type

numpy.ndarray

property family
Type: string
Units: None

The family for this module. The string must be null-terminated and less than 21 characters.

Return type

list

property io
Type: ioBank
Units: n/a

Interface to the IO pins of the module.

This field exposes a mutable view of all banks - a, b, c, d, e, f - which all have one or more pins. Each pin has int and float values. The two values are not the same view into a piece of data and thus can both be set to different values.

Examples:

a2 = cmd.io.a.get_int(2)
e4 = cmd.io.e.get_float(4)
cmd.io.a.set_int(1, 42)
cmd.io.e.set_float(4, 13.0)
property led
Type: led
Units: n/a

The module’s LED.

You can retrieve or set the LED color through this interface. The underlying object has a field color which can be set using an integer or string. For example:

cmd.led.color = 'red'
cmd.led.color = 0xFF0000

The available string colors are

  • red

  • green

  • blue

  • black

  • white

  • cyan

  • magenta

  • yellow

  • transparent

property max_position_limit_strategy
Type: enum
Units: None

The position limit strategy (at the maximum position) for the actuator

Possible values include:

  • HoldPosition (raw value: 0): Exceeding the position limit results in the actuator holding the position. Needs to be manually set to ‘disabled’ to recover.

  • DampedSpring (raw value: 1): Exceeding the position limit results in a virtual spring that pushes the actuator back to within the limits.

  • MotorOff (raw value: 2): Exceeding the position limit results in the control strategy being set to ‘off’. Remains ‘off’ until changed by user.

  • Disabled (raw value: 3): Exceeding the position limit has no effect.

Return type

numpy.ndarray

property min_position_limit_strategy
Type: enum
Units: None

The position limit strategy (at the minimum position) for the actuator

Possible values include:

  • HoldPosition (raw value: 0): Exceeding the position limit results in the actuator holding the position. Needs to be manually set to ‘disabled’ to recover.

  • DampedSpring (raw value: 1): Exceeding the position limit results in a virtual spring that pushes the actuator back to within the limits.

  • MotorOff (raw value: 2): Exceeding the position limit results in the control strategy being set to ‘off’. Remains ‘off’ until changed by user.

  • Disabled (raw value: 3): Exceeding the position limit has no effect.

Return type

numpy.ndarray

property mstop_strategy
Type: enum
Units: None

The motion stop strategy for the actuator

Possible values include:

  • Disabled (raw value: 0): Triggering the M-Stop has no effect.

  • MotorOff (raw value: 1): Triggering the M-Stop results in the control strategy being set to ‘off’. Remains ‘off’ until changed by user.

  • HoldPosition (raw value: 2): Triggering the M-Stop results in the motor holding the motor position. Operations resume to normal once trigger is released.

Return type

numpy.ndarray

property name
Type: string
Units: None

The name for this module. The string must be null-terminated and less than 21 characters.

Return type

list

property position
Type: highResAngle
Units: rad

Position of the module output (post-spring).

Return type

numpy.ndarray

property position_d_on_error
Type: bool
Units: None

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 @c false can eliminate corresponding spikes or noise in the output.

Return type

numpy.ndarray

property position_dead_zone
Type: float
Units: None

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).

Return type

numpy.ndarray

property position_feed_forward
Type: float
Units: None

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

Return type

numpy.ndarray

property position_i_clamp
Type: float
Units: None

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.

Return type

numpy.ndarray

property position_kd
Type: float
Units: None

Derivative PID gain for position

Return type

numpy.ndarray

property position_ki
Type: float
Units: None

Integral PID gain for position

Return type

numpy.ndarray

property position_kp
Type: float
Units: None

Proportional PID gain for position

Return type

numpy.ndarray

property position_limit_max
Type: highResAngle
Units: rad

The firmware safety limit for the maximum allowed position.

Return type

numpy.ndarray

property position_limit_min
Type: highResAngle
Units: rad

The firmware safety limit for the minimum allowed position.

Return type

numpy.ndarray

property position_max_output
Type: float
Units: None

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

Return type

numpy.ndarray

property position_max_target
Type: float
Units: None

Maximum allowed value for input to the PID controller

Return type

numpy.ndarray

property position_min_output
Type: float
Units: None

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

Return type

numpy.ndarray

property position_min_target
Type: float
Units: None

Minimum allowed value for input to the PID controller

Return type

numpy.ndarray

property position_output_lowpass
Type: float
Units: None

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).

Return type

numpy.ndarray

property position_punch
Type: float
Units: None

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.

Return type

numpy.ndarray

property position_target_lowpass
Type: float
Units: None

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).

Return type

numpy.ndarray

read_gains(file)

Import the gains from a file into this object.

Raises

IOError if the file could not be opened for reading

read_safety_params(file)

Import the safety params from a file into this object.

Raises

IOError if the file could not be opened for reading

property reference_effort
Type: float
Units: N*m

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

Return type

numpy.ndarray

property reference_position
Type: float
Units: rad

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

Return type

numpy.ndarray

property reset
Type: flag
Units: None

Restart the module.

Return type

numpy.ndarray

property save_current_settings
Type: flag
Units: None

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

Return type

numpy.ndarray

property size

The number of modules in this group message.

property spring_constant
Type: float
Units: N/m

The spring constant of the module.

Return type

numpy.ndarray

property stop_boot
Type: flag
Units: None

Stop the module from automatically booting into application.

Return type

numpy.ndarray

property velocity
Type: float
Units: rad/s

Velocity of the module output (post-spring).

Return type

numpy.ndarray

property velocity_d_on_error
Type: bool
Units: None

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 @c false can eliminate corresponding spikes or noise in the output.

Return type

numpy.ndarray

property velocity_dead_zone
Type: float
Units: None

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).

Return type

numpy.ndarray

property velocity_feed_forward
Type: float
Units: None

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

Return type

numpy.ndarray

property velocity_i_clamp
Type: float
Units: None

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.

Return type

numpy.ndarray

property velocity_kd
Type: float
Units: None

Derivative PID gain for velocity

Return type

numpy.ndarray

property velocity_ki
Type: float
Units: None

Integral PID gain for velocity

Return type

numpy.ndarray

property velocity_kp
Type: float
Units: None

Proportional PID gain for velocity

Return type

numpy.ndarray

property velocity_limit_max
Type: float
Units: rad/s

The firmware safety limit for the maximum allowed velocity.

Return type

numpy.ndarray

property velocity_limit_min
Type: float
Units: rad/s

The firmware safety limit for the minimum allowed velocity.

Return type

numpy.ndarray

property velocity_max_output
Type: float
Units: None

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

Return type

numpy.ndarray

property velocity_max_target
Type: float
Units: None

Maximum allowed value for input to the PID controller

Return type

numpy.ndarray

property velocity_min_output
Type: float
Units: None

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

Return type

numpy.ndarray

property velocity_min_target
Type: float
Units: None

Minimum allowed value for input to the PID controller

Return type

numpy.ndarray

property velocity_output_lowpass
Type: float
Units: None

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).

Return type

numpy.ndarray

property velocity_punch
Type: float
Units: None

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.

Return type

numpy.ndarray

property velocity_target_lowpass
Type: float
Units: None

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).

Return type

numpy.ndarray

write_gains(file)

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

write_safety_params(file)

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

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.

property accelerometer
Type: vector3f
Units: m/s^2

Accelerometer data

Return type

numpy.ndarray

property ar_orientation
Type: quaternionf
Units: None

A device’s orientation in the world as calculated from an augmented reality framework

Return type

numpy.ndarray

property ar_position
Type: vector3f
Units: m

A device’s position in the world as calculated from an augmented reality framework

Return type

numpy.ndarray

property ar_quality
Type: enum
Units: None

The status of the augmented reality tracking, if using an AR enabled device. See HebiArQuality for values.

Possible values include:

  • ArQualityNotAvailable (raw value: 0): Camera position tracking is not available.

  • ArQualityLimitedUnknown (raw value: 1): Tracking is available albeit suboptimal for an unknown reason.

  • ArQualityLimitedInitializing (raw value: 2): The AR session has not yet gathered enough camera or motion data to provide tracking information.

  • ArQualityLimitedRelocalizing (raw value: 3): The AR session is attempting to resume after an interruption.

  • ArQualityLimitedExcessiveMotion (raw value: 4): The device is moving too fast for accurate image-based position tracking.

  • ArQualityLimitedInsufficientFeatures (raw value: 5): The scene visible to the camera does not contain enough distinguishable features for image-based position tracking.

  • ArQualityNormal (raw value: 6): Camera position tracking is providing optimal results.

Return type

numpy.ndarray

property battery_level
Type: float
Units: None

Charge level of the device’s battery (in percent).

Return type

numpy.ndarray

property board_temperature
Type: float
Units: C

Ambient temperature inside the module (measured at the IMU chip)

Return type

numpy.ndarray

clear()

Clears all of the fields

property command_lifetime_state
Type: enum
Units: None

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

Possible values include:

  • Unlocked (raw value: 0): There is not command lifetime active on this module

  • LockedByOther (raw value: 1): Commands are locked out due to control from other users

  • LockedBySender (raw value: 2): Commands from others are locked out due to control from this group

Return type

numpy.ndarray

copy_from(src)

Copies all fields from the provided message. All fields in the current message are cleared before copied from src.

create_view(mask)

Creates a view into this instance with the indices as specified.

Note that the created view will hold a strong reference to this object. This means that this object will not be destroyed until the created view is also destroyed.

For example:

# group_feedback has a size of at least 4
indices = [0, 1, 2, 3]
view = group_feedback.create_view(indices)
# use view like a GroupFeedback object
Return type

GroupFeedbackView

property debug

Values for internal debug functions (channel 1-9 available).

property deflection
Type: float
Units: rad

Difference between the pre-spring and post-spring output position.

Return type

numpy.ndarray

property deflection_velocity
Type: float
Units: rad/s

Velocity of the difference between the pre-spring and post-spring output position.

Return type

numpy.ndarray

property effort
Type: float
Units: N*m

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

Return type

numpy.ndarray

property effort_command
Type: float
Units: N*m

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

Return type

numpy.ndarray

property effort_limit_state
Type: enum
Units: None

Software-controlled bounds on the allowable effort of the module

Possible values include:

  • Below (raw value: 0): The effort of the module was below the lower safety limit; the motor output is set to return the module to within the limits

  • AtLower (raw value: 1): The effort of the module was near the lower safety limit, and the motor output is being limited or reversed

  • Inside (raw value: 2): The effort of the module was within the safety limits

  • AtUpper (raw value: 3): The effort of the module was near the upper safety limit, and the motor output is being limited or reversed

  • Above (raw value: 4): The effort of the module was above the upper safety limit; the motor output is set to return the module to within the limits

  • Uninitialized (raw value: 5): The module has not been inside the safety limits since it was booted or the safety limits were set

Return type

numpy.ndarray

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

property gyro
Type: vector3f
Units: rad/s

Gyro data

Return type

numpy.ndarray

property hardware_receive_time
Type: UInt64
Units: s

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

Return type

numpy.ndarray

property hardware_receive_time_us
Type: UInt64
Units: μs

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

Return type

numpy.ndarray

property hardware_transmit_time
Type: UInt64
Units: s

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

Return type

numpy.ndarray

property hardware_transmit_time_us
Type: UInt64
Units: μs

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

Return type

numpy.ndarray

property io
Type: ioBank
Units: n/a

Interface to the IO pins of the module.

This field exposes a read-only view of all banks - a, b, c, d, e, f - which all have one or more pins. Each pin has int and float values. The two values are not the same view into a piece of data and thus can both be set to different values.

Examples:

a2 = fbk.io.a.get_int(2)
e4 = fbk.io.e.get_float(4)
property led
Type: led
Units: n/a

The module’s LED.

property motor_current
Type: float
Units: A

Current supplied to the motor.

Return type

numpy.ndarray

property motor_housing_temperature
Type: float
Units: C

The estimated temperature of the motor housing.

Return type

numpy.ndarray

property motor_position
Type: highResAngle
Units: rad

The position of an actuator’s internal motor before the gear reduction.

Return type

numpy.ndarray

property motor_sensor_temperature
Type: float
Units: C

The temperature from a sensor near the motor housing.

Return type

numpy.ndarray

property motor_velocity
Type: float
Units: rad/s

The velocity of the motor shaft.

Return type

numpy.ndarray

property motor_winding_current
Type: float
Units: A

The estimated current in the motor windings.

Return type

numpy.ndarray

property motor_winding_temperature
Type: float
Units: C

The estimated temperature of the motor windings.

Return type

numpy.ndarray

property mstop_state
Type: enum
Units: None

Current status of the MStop

Possible values include:

  • Triggered (raw value: 0): The MStop is pressed

  • NotTriggered (raw value: 1): The MStop is not pressed

Return type

numpy.ndarray

property orientation
Type: quaternionf
Units: None

A filtered estimate of the orientation of the module.

Return type

numpy.ndarray

property position
Type: highResAngle
Units: rad

Position of the module output (post-spring).

Return type

numpy.ndarray

property position_command
Type: highResAngle
Units: rad

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

Return type

numpy.ndarray

property position_limit_state
Type: enum
Units: None

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

Possible values include:

  • Below (raw value: 0): The position of the module was below the lower safety limit; the motor output is set to return the module to within the limits

  • AtLower (raw value: 1): The position of the module was near the lower safety limit, and the motor output is being limited or reversed

  • Inside (raw value: 2): The position of the module was within the safety limits

  • AtUpper (raw value: 3): The position of the module was near the upper safety limit, and the motor output is being limited or reversed

  • Above (raw value: 4): The position of the module was above the upper safety limit; the motor output is set to return the module to within the limits

  • Uninitialized (raw value: 5): The module has not been inside the safety limits since it was booted or the safety limits were set

Return type

numpy.ndarray

property processor_temperature
Type: float
Units: C

Temperature of the processor chip.

Return type

numpy.ndarray

property pwm_command
Type: float
Units: None

Commanded PWM signal sent to the motor; final output of PID controllers.

Return type

numpy.ndarray

property receive_time
Type: UInt64
Units: s

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

Return type

numpy.ndarray

property receive_time_us
Type: UInt64
Units: μs

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

Return type

numpy.ndarray

property sender_id

Unique ID of the module transmitting this feedback

property sequence_number

Sequence number going to module (local)

property size

The number of modules in this group message.

property temperature_state
Type: enum
Units: None

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

Possible values include:

  • Normal (raw value: 0): Temperature within normal range

  • Critical (raw value: 1): Motor output beginning to be limited due to high temperature

  • ExceedMaxMotor (raw value: 2): Temperature exceeds max allowable for motor; motor output disabled

  • ExceedMaxBoard (raw value: 3): Temperature exceeds max allowable for electronics; motor output disabled

Return type

numpy.ndarray

property transmit_time
Type: UInt64
Units: s

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

Return type

numpy.ndarray

property transmit_time_us
Type: UInt64
Units: μs

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

Return type

numpy.ndarray

property velocity
Type: float
Units: rad/s

Velocity of the module output (post-spring).

Return type

numpy.ndarray

property velocity_command
Type: float
Units: rad/s

Commanded velocity of the module output (post-spring)

Return type

numpy.ndarray

property velocity_limit_state
Type: enum
Units: None

Software-controlled bounds on the allowable velocity of the module

Possible values include:

  • Below (raw value: 0): The velocity of the module was below the lower safety limit; the motor output is set to return the module to within the limits

  • AtLower (raw value: 1): The velocity of the module was near the lower safety limit, and the motor output is being limited or reversed

  • Inside (raw value: 2): The velocity of the module was within the safety limits

  • AtUpper (raw value: 3): The velocity of the module was near the upper safety limit, and the motor output is being limited or reversed

  • Above (raw value: 4): The velocity of the module was above the upper safety limit; the motor output is set to return the module to within the limits

  • Uninitialized (raw value: 5): The module has not been inside the safety limits since it was booted or the safety limits were set

Return type

numpy.ndarray

property voltage
Type: float
Units: V

Bus voltage at which the module is running.

Return type

numpy.ndarray

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.

property accel_includes_gravity
Type: bool
Units: None

Whether to include acceleration due to gravity in acceleration feedback.

Return type

numpy.ndarray

property calibration_state
Type: enum
Units: None

The calibration state of the module

Possible values include:

  • Normal (raw value: 0): The module has been calibrated; this is the normal state

  • UncalibratedCurrent (raw value: 1): The current has not been calibrated

  • UncalibratedPosition (raw value: 2): The factory zero position has not been set

  • UncalibratedEffort (raw value: 3): The effort (e.g., spring nonlinearity) has not been calibrated

Return type

numpy.ndarray

property control_strategy
Type: enum
Units: None

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

Possible values include:

  • Off (raw value: 0): The motor is not given power (equivalent to a 0 PWM value)

  • DirectPWM (raw value: 1): A direct PWM value (-1 to 1) can be sent to the motor (subject to onboard safety limiting).

  • Strategy2 (raw value: 2): A combination of the position, velocity, and effort loops with P and V feeding to T; documented on docs.hebi.us under “Control Modes”

  • Strategy3 (raw value: 3): A combination of the position, velocity, and effort loops with P, V, and T feeding to PWM; documented on docs.hebi.us under “Control Modes”

  • Strategy4 (raw value: 4): A combination of the position, velocity, and effort loops with P feeding to T and V feeding to PWM; documented on docs.hebi.us under “Control Modes”

Return type

numpy.ndarray

copy_from(src)

Copies all fields from the provided message. All fields in the current message are cleared before copied from src.

property effort_d_on_error
Type: bool
Units: None

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 @c false can eliminate corresponding spikes or noise in the output.

Return type

numpy.ndarray

property effort_dead_zone
Type: float
Units: None

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).

Return type

numpy.ndarray

property effort_feed_forward
Type: float
Units: None

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

Return type

numpy.ndarray

property effort_i_clamp
Type: float
Units: None

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.

Return type

numpy.ndarray

property effort_kd
Type: float
Units: None

Derivative PID gain for effort

Return type

numpy.ndarray

property effort_ki
Type: float
Units: None

Integral PID gain for effort

Return type

numpy.ndarray

property effort_kp
Type: float
Units: None

Proportional PID gain for effort

Return type

numpy.ndarray

property effort_limit_max
Type: float
Units: N*m

The firmware safety limit for the maximum allowed effort.

Return type

numpy.ndarray

property effort_limit_min
Type: float
Units: N*m

The firmware safety limit for the minimum allowed effort.

Return type

numpy.ndarray

property effort_max_output
Type: float
Units: None

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

Return type

numpy.ndarray

property effort_max_target
Type: float
Units: None

Maximum allowed value for input to the PID controller

Return type

numpy.ndarray

property effort_min_output
Type: float
Units: None

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

Return type

numpy.ndarray

property effort_min_target
Type: float
Units: None

Minimum allowed value for input to the PID controller

Return type

numpy.ndarray

property effort_output_lowpass
Type: float
Units: None

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).

Return type

numpy.ndarray

property effort_punch
Type: float
Units: None

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.

Return type

numpy.ndarray

property effort_target_lowpass
Type: float
Units: None

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).

Return type

numpy.ndarray

property family
Type: string
Units: None

The family for this module. The string must be null-terminated and less than 21 characters.

Return type

list

property led
Type: led
Units: n/a

The module’s LED.

property max_position_limit_strategy
Type: enum
Units: None

The position limit strategy (at the maximum position) for the actuator

Possible values include:

  • HoldPosition (raw value: 0): Exceeding the position limit results in the actuator holding the position. Needs to be manually set to ‘disabled’ to recover.

  • DampedSpring (raw value: 1): Exceeding the position limit results in a virtual spring that pushes the actuator back to within the limits.

  • MotorOff (raw value: 2): Exceeding the position limit results in the control strategy being set to ‘off’. Remains ‘off’ until changed by user.

  • Disabled (raw value: 3): Exceeding the position limit has no effect.

Return type

numpy.ndarray

property min_position_limit_strategy
Type: enum
Units: None

The position limit strategy (at the minimum position) for the actuator

Possible values include:

  • HoldPosition (raw value: 0): Exceeding the position limit results in the actuator holding the position. Needs to be manually set to ‘disabled’ to recover.

  • DampedSpring (raw value: 1): Exceeding the position limit results in a virtual spring that pushes the actuator back to within the limits.

  • MotorOff (raw value: 2): Exceeding the position limit results in the control strategy being set to ‘off’. Remains ‘off’ until changed by user.

  • Disabled (raw value: 3): Exceeding the position limit has no effect.

Return type

numpy.ndarray

property mstop_strategy
Type: enum
Units: None

The motion stop strategy for the actuator

Possible values include:

  • Disabled (raw value: 0): Triggering the M-Stop has no effect.

  • MotorOff (raw value: 1): Triggering the M-Stop results in the control strategy being set to ‘off’. Remains ‘off’ until changed by user.

  • HoldPosition (raw value: 2): Triggering the M-Stop results in the motor holding the motor position. Operations resume to normal once trigger is released.

Return type

numpy.ndarray

property name
Type: string
Units: None

The name for this module. The string must be null-terminated and less than 21 characters.

Return type

list

property position_d_on_error
Type: bool
Units: None

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 @c false can eliminate corresponding spikes or noise in the output.

Return type

numpy.ndarray

property position_dead_zone
Type: float
Units: None

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).

Return type

numpy.ndarray

property position_feed_forward
Type: float
Units: None

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

Return type

numpy.ndarray

property position_i_clamp
Type: float
Units: None

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.

Return type

numpy.ndarray

property position_kd
Type: float
Units: None

Derivative PID gain for position

Return type

numpy.ndarray

property position_ki
Type: float
Units: None

Integral PID gain for position

Return type

numpy.ndarray

property position_kp
Type: float
Units: None

Proportional PID gain for position

Return type

numpy.ndarray

property position_limit_max
Type: highResAngle
Units: rad

The firmware safety limit for the maximum allowed position.

Return type

numpy.ndarray

property position_limit_min
Type: highResAngle
Units: rad

The firmware safety limit for the minimum allowed position.

Return type

numpy.ndarray

property position_max_output
Type: float
Units: None

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

Return type

numpy.ndarray

property position_max_target
Type: float
Units: None

Maximum allowed value for input to the PID controller

Return type

numpy.ndarray

property position_min_output
Type: float
Units: None

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

Return type

numpy.ndarray

property position_min_target
Type: float
Units: None

Minimum allowed value for input to the PID controller

Return type

numpy.ndarray

property position_output_lowpass
Type: float
Units: None

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).

Return type

numpy.ndarray

property position_punch
Type: float
Units: None

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.

Return type

numpy.ndarray

property position_target_lowpass
Type: float
Units: None

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).

Return type

numpy.ndarray

property save_current_settings
Type: flag
Units: None

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

Return type

numpy.ndarray

property serial
Type: string
Units: None

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

Return type

list

property size

The number of modules in this group message.

property spring_constant
Type: float
Units: N/m

The spring constant of the module.

Return type

numpy.ndarray

property velocity_d_on_error
Type: bool
Units: None

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 @c false can eliminate corresponding spikes or noise in the output.

Return type

numpy.ndarray

property velocity_dead_zone
Type: float
Units: None

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).

Return type

numpy.ndarray

property velocity_feed_forward
Type: float
Units: None

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

Return type

numpy.ndarray

property velocity_i_clamp
Type: float
Units: None

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.

Return type

numpy.ndarray

property velocity_kd
Type: float
Units: None

Derivative PID gain for velocity

Return type

numpy.ndarray

property velocity_ki
Type: float
Units: None

Integral PID gain for velocity

Return type

numpy.ndarray

property velocity_kp
Type: float
Units: None

Proportional PID gain for velocity

Return type

numpy.ndarray

property velocity_limit_max
Type: float
Units: rad/s

The firmware safety limit for the maximum allowed velocity.

Return type

numpy.ndarray

property velocity_limit_min
Type: float
Units: rad/s

The firmware safety limit for the minimum allowed velocity.

Return type

numpy.ndarray

property velocity_max_output
Type: float
Units: None

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

Return type

numpy.ndarray

property velocity_max_target
Type: float
Units: None

Maximum allowed value for input to the PID controller

Return type

numpy.ndarray

property velocity_min_output
Type: float
Units: None

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

Return type

numpy.ndarray

property velocity_min_target
Type: float
Units: None

Minimum allowed value for input to the PID controller

Return type

numpy.ndarray

property velocity_output_lowpass
Type: float
Units: None

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).

Return type

numpy.ndarray

property velocity_punch
Type: float
Units: None

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.

Return type

numpy.ndarray

property velocity_target_lowpass
Type: float
Units: None

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).

Return type

numpy.ndarray

write_gains(file)

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

write_safety_params(file)

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