Classes | Macros | Typedefs | Enumerations | Functions
hebi.h File Reference
#include <math.h>
#include <stddef.h>
#include <stdint.h>
Include dependency graph for hebi.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  _HebiMacAddress
 
struct  _HebiQuaternionf
 
struct  _HebiVector3f
 

Macros

#define M_PI   3.14159265358979323846
 

Typedefs

typedef void(* GroupFeedbackHandlerFunction) (HebiGroupFeedbackPtr fbk, void *user_data)
 Group feedback handling function signature. More...
 
typedef enum HebiCommandBoolField HebiCommandBoolField
 
typedef enum HebiCommandEnumField HebiCommandEnumField
 
typedef enum HebiCommandFlagField HebiCommandFlagField
 
typedef enum HebiCommandFloatField HebiCommandFloatField
 
typedef enum HebiCommandHighResAngleField HebiCommandHighResAngleField
 
typedef enum HebiCommandIoPinBank HebiCommandIoPinBank
 
typedef enum HebiCommandLedField HebiCommandLedField
 
typedef enum HebiCommandNumberedFloatField HebiCommandNumberedFloatField
 
typedef struct _HebiCommand * HebiCommandPtr
 The C-style's API representation of a command. More...
 
typedef enum HebiCommandStringField HebiCommandStringField
 
typedef enum HebiFeedbackEnumField HebiFeedbackEnumField
 
typedef enum HebiFeedbackFloatField HebiFeedbackFloatField
 
typedef enum HebiFeedbackHighResAngleField HebiFeedbackHighResAngleField
 
typedef enum HebiFeedbackIoPinBank HebiFeedbackIoPinBank
 
typedef enum HebiFeedbackLedField HebiFeedbackLedField
 
typedef enum HebiFeedbackNumberedFloatField HebiFeedbackNumberedFloatField
 
typedef struct _HebiFeedback * HebiFeedbackPtr
 The C-style's API representation of feedback. More...
 
typedef enum HebiFeedbackQuaternionfField HebiFeedbackQuaternionfField
 
typedef enum HebiFeedbackUInt64Field HebiFeedbackUInt64Field
 
typedef enum HebiFeedbackVector3fField HebiFeedbackVector3fField
 
typedef enum HebiFrameType HebiFrameType
 
typedef struct _HebiGroupCommand * HebiGroupCommandPtr
 The C-style's API representation of a group command. More...
 
typedef struct _HebiGroupFeedback * HebiGroupFeedbackPtr
 The C-style's API representation of group feedback. More...
 
typedef struct _HebiGroupInfo * HebiGroupInfoPtr
 The C-style's API representation of group info. More...
 
typedef struct _HebiGroup * HebiGroupPtr
 The C-style's API representation of a group. More...
 
typedef struct _HebiIK * HebiIKPtr
 
typedef enum HebiInfoBoolField HebiInfoBoolField
 
typedef enum HebiInfoEnumField HebiInfoEnumField
 
typedef enum HebiInfoFlagField HebiInfoFlagField
 
typedef enum HebiInfoFloatField HebiInfoFloatField
 
typedef enum HebiInfoHighResAngleField HebiInfoHighResAngleField
 
typedef enum HebiInfoLedField HebiInfoLedField
 
typedef struct _HebiInfo * HebiInfoPtr
 The C-style's API representation of a group. More...
 
typedef enum HebiInfoStringField HebiInfoStringField
 
typedef enum HebiJointType HebiJointType
 
typedef struct _HebiLogFile * HebiLogFilePtr
 The C-style's API representation of a log file. More...
 
typedef struct _HebiLookupEntryList * HebiLookupEntryListPtr
 
typedef struct _HebiLookup * HebiLookupPtr
 
typedef struct _HebiMacAddress HebiMacAddress
 
typedef struct _HebiQuaternionf HebiQuaternionf
 
typedef struct _HebiRobotModelElement * HebiRobotModelElementPtr
 
typedef struct _HebiRobotModel * HebiRobotModelPtr
 
typedef enum HebiStatusCode HebiStatusCode
 
typedef struct _HebiString * HebiStringPtr
 The C-style's API representation of a string. More...
 
typedef struct _HebiTrajectory * HebiTrajectoryPtr
 The C-style's API representation of a trajectory. More...
 
typedef struct _HebiVector3f HebiVector3f
 

Enumerations

enum  HebiCommandBoolField { HebiCommandBoolPositionDOnError, HebiCommandBoolVelocityDOnError, HebiCommandBoolEffortDOnError }
 
enum  HebiCommandEnumField { HebiCommandEnumControlStrategy }
 
enum  HebiCommandFlagField { HebiCommandFlagSaveCurrentSettings, HebiCommandFlagReset, HebiCommandFlagBoot, HebiCommandFlagStopBoot }
 
enum  HebiCommandFloatField {
  HebiCommandFloatVelocity, HebiCommandFloatEffort, HebiCommandFloatPositionKp, HebiCommandFloatPositionKi,
  HebiCommandFloatPositionKd, HebiCommandFloatPositionFeedForward, HebiCommandFloatPositionDeadZone, HebiCommandFloatPositionIClamp,
  HebiCommandFloatPositionPunch, HebiCommandFloatPositionMinTarget, HebiCommandFloatPositionMaxTarget, HebiCommandFloatPositionTargetLowpass,
  HebiCommandFloatPositionMinOutput, HebiCommandFloatPositionMaxOutput, HebiCommandFloatPositionOutputLowpass, HebiCommandFloatVelocityKp,
  HebiCommandFloatVelocityKi, HebiCommandFloatVelocityKd, HebiCommandFloatVelocityFeedForward, HebiCommandFloatVelocityDeadZone,
  HebiCommandFloatVelocityIClamp, HebiCommandFloatVelocityPunch, HebiCommandFloatVelocityMinTarget, HebiCommandFloatVelocityMaxTarget,
  HebiCommandFloatVelocityTargetLowpass, HebiCommandFloatVelocityMinOutput, HebiCommandFloatVelocityMaxOutput, HebiCommandFloatVelocityOutputLowpass,
  HebiCommandFloatEffortKp, HebiCommandFloatEffortKi, HebiCommandFloatEffortKd, HebiCommandFloatEffortFeedForward,
  HebiCommandFloatEffortDeadZone, HebiCommandFloatEffortIClamp, HebiCommandFloatEffortPunch, HebiCommandFloatEffortMinTarget,
  HebiCommandFloatEffortMaxTarget, HebiCommandFloatEffortTargetLowpass, HebiCommandFloatEffortMinOutput, HebiCommandFloatEffortMaxOutput,
  HebiCommandFloatEffortOutputLowpass, HebiCommandFloatSpringConstant, HebiCommandFloatReferencePosition, HebiCommandFloatReferenceEffort
}
 
enum  HebiCommandHighResAngleField { HebiCommandHighResAnglePosition, HebiCommandHighResAnglePositionLimitMin, HebiCommandHighResAnglePositionLimitMax }
 
enum  HebiCommandIoPinBank {
  HebiCommandIoBankA, HebiCommandIoBankB, HebiCommandIoBankC, HebiCommandIoBankD,
  HebiCommandIoBankE, HebiCommandIoBankF
}
 
enum  HebiCommandLedField { HebiCommandLedLed }
 
enum  HebiCommandNumberedFloatField { HebiCommandNumberedFloatDebug }
 
enum  HebiCommandStringField { HebiCommandStringName, HebiCommandStringFamily }
 
enum  HebiFeedbackEnumField {
  HebiFeedbackEnumTemperatureState, HebiFeedbackEnumMstopState, HebiFeedbackEnumPositionLimitState, HebiFeedbackEnumVelocityLimitState,
  HebiFeedbackEnumEffortLimitState, HebiFeedbackEnumCommandLifetimeState
}
 
enum  HebiFeedbackFloatField {
  HebiFeedbackFloatBoardTemperature, HebiFeedbackFloatProcessorTemperature, HebiFeedbackFloatVoltage, HebiFeedbackFloatVelocity,
  HebiFeedbackFloatEffort, HebiFeedbackFloatVelocityCommand, HebiFeedbackFloatEffortCommand, HebiFeedbackFloatDeflection,
  HebiFeedbackFloatDeflectionVelocity, HebiFeedbackFloatMotorVelocity, HebiFeedbackFloatMotorCurrent, HebiFeedbackFloatMotorSensorTemperature,
  HebiFeedbackFloatMotorWindingCurrent, HebiFeedbackFloatMotorWindingTemperature, HebiFeedbackFloatMotorHousingTemperature
}
 
enum  HebiFeedbackHighResAngleField { HebiFeedbackHighResAnglePosition, HebiFeedbackHighResAnglePositionCommand }
 
enum  HebiFeedbackIoPinBank {
  HebiFeedbackIoBankA, HebiFeedbackIoBankB, HebiFeedbackIoBankC, HebiFeedbackIoBankD,
  HebiFeedbackIoBankE, HebiFeedbackIoBankF
}
 
enum  HebiFeedbackLedField { HebiFeedbackLedLed }
 
enum  HebiFeedbackNumberedFloatField { HebiFeedbackNumberedFloatDebug }
 
enum  HebiFeedbackQuaternionfField { HebiFeedbackQuaternionfOrientation }
 
enum  HebiFeedbackUInt64Field {
  HebiFeedbackUInt64SequenceNumber, HebiFeedbackUInt64ReceiveTime, HebiFeedbackUInt64TransmitTime, HebiFeedbackUInt64HardwareReceiveTime,
  HebiFeedbackUInt64HardwareTransmitTime, HebiFeedbackUInt64SenderId
}
 
enum  HebiFeedbackVector3fField { HebiFeedbackVector3fAccelerometer, HebiFeedbackVector3fGyro }
 
enum  HebiFrameType { HebiFrameTypeCenterOfMass, HebiFrameTypeOutput, HebiFrameTypeEndEffector }
 
enum  HebiInfoBoolField { HebiInfoBoolPositionDOnError, HebiInfoBoolVelocityDOnError, HebiInfoBoolEffortDOnError }
 
enum  HebiInfoEnumField { HebiInfoEnumControlStrategy, HebiInfoEnumCalibrationState }
 
enum  HebiInfoFlagField { HebiInfoFlagSaveCurrentSettings }
 
enum  HebiInfoFloatField {
  HebiInfoFloatPositionKp, HebiInfoFloatPositionKi, HebiInfoFloatPositionKd, HebiInfoFloatPositionFeedForward,
  HebiInfoFloatPositionDeadZone, HebiInfoFloatPositionIClamp, HebiInfoFloatPositionPunch, HebiInfoFloatPositionMinTarget,
  HebiInfoFloatPositionMaxTarget, HebiInfoFloatPositionTargetLowpass, HebiInfoFloatPositionMinOutput, HebiInfoFloatPositionMaxOutput,
  HebiInfoFloatPositionOutputLowpass, HebiInfoFloatVelocityKp, HebiInfoFloatVelocityKi, HebiInfoFloatVelocityKd,
  HebiInfoFloatVelocityFeedForward, HebiInfoFloatVelocityDeadZone, HebiInfoFloatVelocityIClamp, HebiInfoFloatVelocityPunch,
  HebiInfoFloatVelocityMinTarget, HebiInfoFloatVelocityMaxTarget, HebiInfoFloatVelocityTargetLowpass, HebiInfoFloatVelocityMinOutput,
  HebiInfoFloatVelocityMaxOutput, HebiInfoFloatVelocityOutputLowpass, HebiInfoFloatEffortKp, HebiInfoFloatEffortKi,
  HebiInfoFloatEffortKd, HebiInfoFloatEffortFeedForward, HebiInfoFloatEffortDeadZone, HebiInfoFloatEffortIClamp,
  HebiInfoFloatEffortPunch, HebiInfoFloatEffortMinTarget, HebiInfoFloatEffortMaxTarget, HebiInfoFloatEffortTargetLowpass,
  HebiInfoFloatEffortMinOutput, HebiInfoFloatEffortMaxOutput, HebiInfoFloatEffortOutputLowpass, HebiInfoFloatSpringConstant
}
 
enum  HebiInfoHighResAngleField { HebiInfoHighResAnglePositionLimitMin, HebiInfoHighResAnglePositionLimitMax }
 
enum  HebiInfoLedField { HebiInfoLedLed }
 
enum  HebiInfoStringField { HebiInfoStringName, HebiInfoStringFamily, HebiInfoStringSerial }
 
enum  HebiJointType {
  HebiJointTypeRotationX, HebiJointTypeRotationY, HebiJointTypeRotationZ, HebiJointTypeTranslationX,
  HebiJointTypeTranslationY, HebiJointTypeTranslationZ
}
 
enum  HebiStatusCode {
  HebiStatusSuccess = 0, HebiStatusInvalidArgument = 1, HebiStatusBufferTooSmall = 2, HebiStatusValueNotSet = 3,
  HebiStatusFailure = 4, HebiStatusArgumentOutOfRange = 5
}
 

Functions

void hebiCleanup (void)
 Frees all resources created by the library. Note: any calls to the HEBI library functions after this will result in undefined behavior! More...
 
void hebiCommandClearLed (HebiCommandPtr cmd, HebiCommandLedField field)
 
HebiStatusCode hebiCommandGetBool (HebiCommandPtr cmd, HebiCommandBoolField field, int32_t *value)
 
HebiStatusCode hebiCommandGetEnum (HebiCommandPtr cmd, HebiCommandEnumField field, int32_t *value)
 
int32_t hebiCommandGetFlag (HebiCommandPtr cmd, HebiCommandFlagField field)
 
HebiStatusCode hebiCommandGetFloat (HebiCommandPtr cmd, HebiCommandFloatField field, float *value)
 
HebiStatusCode hebiCommandGetHighResAngle (HebiCommandPtr cmd, HebiCommandHighResAngleField field, int64_t *int_part, float *dec_part)
 
HebiStatusCode hebiCommandGetIoPinFloat (HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number, float *value)
 
HebiStatusCode hebiCommandGetIoPinInt (HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number, int64_t *value)
 
HebiStatusCode hebiCommandGetLedColor (HebiCommandPtr cmd, HebiCommandLedField field, uint8_t *r, uint8_t *g, uint8_t *b)
 
HebiStatusCode hebiCommandGetNumberedFloat (HebiCommandPtr cmd, HebiCommandNumberedFloatField field, size_t number, float *value)
 
HebiStatusCode hebiCommandGetString (HebiCommandPtr cmd, HebiCommandStringField field, char *buffer, size_t *length)
 
int32_t hebiCommandHasLedModuleControl (HebiCommandPtr cmd, HebiCommandLedField field)
 
void hebiCommandSetBool (HebiCommandPtr cmd, HebiCommandBoolField field, const int32_t *value)
 
void hebiCommandSetEnum (HebiCommandPtr cmd, HebiCommandEnumField field, const int32_t *value)
 
void hebiCommandSetFlag (HebiCommandPtr cmd, HebiCommandFlagField field, int32_t value)
 
void hebiCommandSetFloat (HebiCommandPtr cmd, HebiCommandFloatField field, const float *value)
 
void hebiCommandSetHighResAngle (HebiCommandPtr cmd, HebiCommandHighResAngleField field, const int64_t *int_part, const float *dec_part)
 
void hebiCommandSetIoPinFloat (HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number, const float *value)
 
void hebiCommandSetIoPinInt (HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number, const int64_t *value)
 
void hebiCommandSetLedModuleControl (HebiCommandPtr cmd, HebiCommandLedField field)
 
void hebiCommandSetLedOverrideColor (HebiCommandPtr cmd, HebiCommandLedField field, uint8_t r, uint8_t g, uint8_t b)
 
void hebiCommandSetNumberedFloat (HebiCommandPtr cmd, HebiCommandNumberedFloatField field, size_t number, const float *value)
 
void hebiCommandSetString (HebiCommandPtr cmd, HebiCommandStringField field, const char *buffer, const size_t *length)
 
HebiLookupEntryListPtr hebiCreateLookupEntryList (HebiLookupPtr lookup)
 Return a snapshot of the contents of the module registry – i.e., which modules have been found by the lookup. More...
 
HebiStatusCode hebiFeedbackGetEnum (HebiFeedbackPtr, HebiFeedbackEnumField, int32_t *)
 
HebiStatusCode hebiFeedbackGetFloat (HebiFeedbackPtr fbk, HebiFeedbackFloatField field, float *value)
 
HebiStatusCode hebiFeedbackGetHighResAngle (HebiFeedbackPtr fbk, HebiFeedbackHighResAngleField field, int64_t *int_part, float *dec_part)
 
HebiStatusCode hebiFeedbackGetIoPinFloat (HebiFeedbackPtr fbk, HebiFeedbackIoPinBank field, size_t pin_number, float *value)
 
HebiStatusCode hebiFeedbackGetIoPinInt (HebiFeedbackPtr fbk, HebiFeedbackIoPinBank field, size_t pin_number, int64_t *value)
 
HebiStatusCode hebiFeedbackGetLedColor (HebiFeedbackPtr fbk, HebiFeedbackLedField field, uint8_t *r, uint8_t *g, uint8_t *b)
 
HebiStatusCode hebiFeedbackGetNumberedFloat (HebiFeedbackPtr fbk, HebiFeedbackNumberedFloatField field, size_t number, float *value)
 
HebiStatusCode hebiFeedbackGetQuaternionf (HebiFeedbackPtr fbk, HebiFeedbackQuaternionfField field, HebiQuaternionf *value)
 
HebiStatusCode hebiFeedbackGetUInt64 (HebiFeedbackPtr fbk, HebiFeedbackUInt64Field field, uint64_t *value)
 
HebiStatusCode hebiFeedbackGetVector3f (HebiFeedbackPtr fbk, HebiFeedbackVector3fField field, HebiVector3f *value)
 
HebiStatusCode hebiGetLibraryVersion (int32_t *major, int32_t *minor, int32_t *revision)
 Get the version of the library. More...
 
void hebiGroupClearFeedbackHandlers (HebiGroupPtr group)
 Removes all feedback handling functions from the queue to be called on receipt of group feedback. More...
 
void hebiGroupCommandClear (HebiGroupCommandPtr cmd)
 Clears all data in the GroupCommand object. More...
 
HebiStatusCode hebiGroupCommandCopy (HebiGroupCommandPtr dest, HebiGroupCommandPtr src)
 Clears the dest GroupCommand object, and copies all data from the src GroupCommand object to dest. More...
 
HebiGroupCommandPtr hebiGroupCommandCreate (size_t size)
 Creates a GroupCommand for a group with the specified number of modules. More...
 
HebiCommandPtr hebiGroupCommandGetModuleCommand (HebiGroupCommandPtr cmd, size_t module_index)
 Get an individual command for a particular module at index module_index. More...
 
size_t hebiGroupCommandGetSize (HebiGroupCommandPtr cmd)
 Return the number of modules in this group Command. More...
 
HebiStatusCode hebiGroupCommandReadGains (HebiGroupCommandPtr cmd, const char *file)
 Import gains from a file into a GroupCommand object. More...
 
void hebiGroupCommandRelease (HebiGroupCommandPtr cmd)
 Frees resources created by the GroupCommand object. More...
 
HebiStatusCode hebiGroupCommandWriteGains (HebiGroupCommandPtr cmd, const char *file)
 Export gains from a GroupCommand object into a file. More...
 
HebiGroupPtr hebiGroupCreateConnectedFromMac (HebiLookupPtr lookup, const HebiMacAddress *address, int32_t timeout_ms)
 Create a group with all modules connected to module with the given MAC address. More...
 
HebiGroupPtr hebiGroupCreateConnectedFromName (HebiLookupPtr lookup, const char *family, const char *name, int32_t timeout_ms)
 Create a group with all modules connected to module with the given name and family. More...
 
HebiGroupPtr hebiGroupCreateFromFamily (HebiLookupPtr lookup, const char *family, int32_t timeout_ms)
 Create a group with all modules known to the lookup with the given family. More...
 
HebiGroupPtr hebiGroupCreateFromMacs (HebiLookupPtr lookup, const HebiMacAddress *const *addresses, size_t num_addresses, int32_t timeout_ms)
 Create a group of modules with the given MAC addresses. More...
 
HebiGroupPtr hebiGroupCreateFromNames (HebiLookupPtr lookup, const char *const *families, size_t num_families, const char *const *names, size_t num_names, int32_t timeout_ms)
 Create a group with modules matching the given names and families. More...
 
HebiGroupPtr hebiGroupCreateImitation (size_t size)
 Creates an "imitation" group with the specified number of modules. More...
 
void hebiGroupFeedbackClear (HebiGroupFeedbackPtr fbk)
 Clears all data in the GroupFeedback object. More...
 
HebiStatusCode hebiGroupFeedbackCopy (HebiGroupFeedbackPtr dest, HebiGroupFeedbackPtr src)
 Clears the dest GroupFeedback object, and copies all data from the src GroupFeedback object to dest. More...
 
HebiGroupFeedbackPtr hebiGroupFeedbackCreate (size_t size)
 Creates a GroupFeedback for a group with the specified number of modules. More...
 
HebiFeedbackPtr hebiGroupFeedbackGetModuleFeedback (HebiGroupFeedbackPtr fbk, size_t module_index)
 Get an individual feedback for a particular module at index module_index. More...
 
size_t hebiGroupFeedbackGetSize (HebiGroupFeedbackPtr fbk)
 Return the number of modules in this group Feedback. More...
 
void hebiGroupFeedbackRelease (HebiGroupFeedbackPtr fbk)
 Frees resources created by the GroupFeedback object. More...
 
int32_t hebiGroupGetCommandLifetime (HebiGroupPtr group)
 Returns the current command lifetime, in milliseconds. More...
 
float hebiGroupGetFeedbackFrequencyHz (HebiGroupPtr group)
 Returns the current feedback request loop frequency (in Hz). More...
 
HebiStatusCode hebiGroupGetNextFeedback (HebiGroupPtr group, HebiGroupFeedbackPtr feedback, int32_t timeout_ms)
 Returns the most recently stored feedback from a sent feedback request, or returns the next one received (up to the requested timeout). More...
 
size_t hebiGroupGetSize (HebiGroupPtr group)
 Returns the number of modules in a group. More...
 
void hebiGroupInfoClear (HebiGroupInfoPtr info)
 Clears all data in the GroupInfo object. More...
 
HebiStatusCode hebiGroupInfoCopy (HebiGroupInfoPtr dest, HebiGroupInfoPtr src)
 Clears the dest GroupInfo object, and copies all data from the src GroupInfo object to dest. More...
 
HebiGroupInfoPtr hebiGroupInfoCreate (size_t size)
 Creates a GroupInfo for a group with the specified number of modules. More...
 
HebiInfoPtr hebiGroupInfoGetModuleInfo (HebiGroupInfoPtr info, size_t module_index)
 Get an individual info for a particular module at index module_index. More...
 
size_t hebiGroupInfoGetSize (HebiGroupInfoPtr info)
 Return the number of modules in this group Info. More...
 
void hebiGroupInfoRelease (HebiGroupInfoPtr info)
 Frees resources created by the GroupInfo object. More...
 
HebiStatusCode hebiGroupInfoWriteGains (HebiGroupInfoPtr info, const char *file)
 Export gains from a GroupInfo object into a file. More...
 
HebiStatusCode hebiGroupRegisterFeedbackHandler (HebiGroupPtr group, GroupFeedbackHandlerFunction handler, void *user_data)
 Add a function that is called whenever feedback is returned from the group. More...
 
void hebiGroupRelease (HebiGroupPtr group)
 Release resources for a given group; group should not be used after this call. More...
 
HebiStatusCode hebiGroupRequestInfo (HebiGroupPtr group, HebiGroupInfoPtr info, int32_t timeout_ms)
 Requests info from the group, and writes it to the provided info object. More...
 
HebiStatusCode hebiGroupSendCommand (HebiGroupPtr group, HebiGroupCommandPtr command)
 Sends a command to the given group without requesting an acknowledgement. More...
 
HebiStatusCode hebiGroupSendCommandWithAcknowledgement (HebiGroupPtr group, HebiGroupCommandPtr command, int32_t timeout_ms)
 Sends a command to the given group, requesting an acknowledgement of transmission to be sent back. More...
 
HebiStatusCode hebiGroupSendFeedbackRequest (HebiGroupPtr group)
 Requests feedback from the group. More...
 
HebiStatusCode hebiGroupSetCommandLifetime (HebiGroupPtr group, int32_t lifetime_ms)
 Sets the command lifetime for the group, in milliseconds. More...
 
HebiStatusCode hebiGroupSetFeedbackFrequencyHz (HebiGroupPtr group, float frequency)
 Sets the feedback request loop frequency (in Hz). More...
 
HebiStatusCode hebiGroupStartLog (HebiGroupPtr group, const char *dir, const char *file, HebiStringPtr *ret)
 Starts logging data to a file. More...
 
HebiLogFilePtr hebiGroupStopLog (HebiGroupPtr group)
 Stops logging data to a file. More...
 
HebiStatusCode hebiIKAddConstraintJointAngles (HebiIKPtr ik, double weight, size_t num_joints, const double *min_positions, const double *max_positions)
 Define joint angle constraints. More...
 
HebiStatusCode hebiIKAddObjectiveCustom (HebiIKPtr ik, double weight, size_t num_errors, void(*err_fnc)(void *user_data, size_t num_positions, const double *positions, double *errors), void *user_data)
 Add a custom objective function to be minimized by the IK solver. More...
 
HebiStatusCode hebiIKAddObjectiveEndEffectorPosition (HebiIKPtr ik, float weight, size_t end_effector_index, double x, double y, double z)
 Add an objective that optimizes for the end effector output frame origin to be at the given (x, y, z) point. More...
 
HebiStatusCode hebiIKAddObjectiveEndEffectorSO3 (HebiIKPtr ik, double weight, size_t end_effector_index, const double *matrix)
 Add an objective that optimizes for the end effector output frame orientation to be given by the 3x3 (row major) rotation matrix. Note that this is incompatible with the end effector tip axis objective. More...
 
HebiStatusCode hebiIKAddObjectiveEndEffectorTipAxis (HebiIKPtr ik, double weight, size_t end_effector_index, double x, double y, double z)
 Add an objective that points the end effector's z axis in a given direction. Note that this is incompatible with the end effector S03 orientation objective. More...
 
void hebiIKClearAll (HebiIKPtr ik)
 Clears the objectives and constraints from this IK object, along with any modifications to the default algorithm parameters. More...
 
HebiIKPtr hebiIKCreate (void)
 Creates an IK (inverse kinematics) object that allows for solving for joint angles/positions given objectives and constraints. More...
 
void hebiIKRelease (HebiIKPtr ik)
 Frees resources created by this inverse kinematics object. More...
 
HebiStatusCode hebiIKSolve (HebiIKPtr ik, HebiRobotModelPtr model, const double *initial_positions, double *ik_solution, void *result_info)
 Solves for an inverse kinematics solution that moves the end effector to a given point. More...
 
HebiStatusCode hebiInfoGetBool (HebiInfoPtr info, HebiInfoBoolField field, int32_t *value)
 
HebiStatusCode hebiInfoGetEnum (HebiInfoPtr info, HebiInfoEnumField field, int32_t *value)
 
int32_t hebiInfoGetFlag (HebiInfoPtr info, HebiInfoFlagField field)
 
HebiStatusCode hebiInfoGetFloat (HebiInfoPtr info, HebiInfoFloatField field, float *value)
 
HebiStatusCode hebiInfoGetHighResAngle (HebiInfoPtr, HebiInfoHighResAngleField, int64_t *int_part, float *dec_part)
 
HebiStatusCode hebiInfoGetLedColor (HebiInfoPtr info, HebiInfoLedField field, uint8_t *r, uint8_t *g, uint8_t *b)
 
HebiStatusCode hebiInfoGetString (HebiInfoPtr info, HebiInfoStringField field, char *buffer, size_t *length)
 
HebiStatusCode hebiLogFileGetFileName (HebiLogFilePtr log_file, char *buffer, size_t *length)
 Copy the path and name of the log file into a buffer. More...
 
HebiStatusCode hebiLogFileGetNextFeedback (HebiLogFilePtr log_file, HebiGroupFeedbackPtr field)
 Retrieve the next group feedback from the opened log file. More...
 
size_t hebiLogFileGetNumberOfModules (HebiLogFilePtr log_file)
 Retrieve the number of modules in the group represented by an opened log file. More...
 
HebiLogFilePtr hebiLogFileOpen (const char *file)
 Opens an existing log file. More...
 
void hebiLogFileRelease (HebiLogFilePtr log_file)
 Releases a log file instance. More...
 
HebiLookupPtr hebiLookupCreate (void)
 Create a Lookup instance. More...
 
HebiStatusCode hebiLookupEntryListGetFamily (HebiLookupEntryListPtr lookup_list, size_t index, char *buffer, size_t *length)
 
HebiStatusCode hebiLookupEntryListGetMacAddress (HebiLookupEntryListPtr lookup_list, size_t index, HebiMacAddress *mac_address)
 
HebiStatusCode hebiLookupEntryListGetName (HebiLookupEntryListPtr lookup_list, size_t index, char *buffer, size_t *length)
 
size_t hebiLookupEntryListGetSize (HebiLookupEntryListPtr lookup_list)
 
void hebiLookupEntryListRelease (HebiLookupEntryListPtr lookup_list)
 Release resources for a given lookup entry list; list should not be used after this call. More...
 
void hebiLookupRelease (HebiLookupPtr lookup)
 Frees resources created by the lookup object. More...
 
HebiStatusCode hebiRobotModelAdd (HebiRobotModelPtr robot_model, HebiRobotModelElementPtr existing_element, size_t output_index, HebiRobotModelElementPtr new_element, int32_t combine)
 Add an element to a parent element connected to a robot model object. More...
 
HebiRobotModelPtr hebiRobotModelCreate (void)
 Creates an object to hold a robot model (tree topology). This structure has a single output available at the origin. More...
 
HebiRobotModelElementPtr hebiRobotModelElementCreateJoint (HebiJointType joint_type)
 Creates a one-dof joint about the specified axis. More...
 
HebiRobotModelElementPtr hebiRobotModelElementCreateRigidBody (const double *com, const double *inertia, double mass, size_t num_outputs, const double *outputs)
 Creates a rigid body defining static transforms to the given outputs. More...
 
void hebiRobotModelElementRelease (HebiRobotModelElementPtr element)
 Frees resources created by this element. More...
 
HebiStatusCode hebiRobotModelGetBaseFrame (HebiRobotModelPtr robot_model, double *transform)
 Retreives the fixed transform from the origin to the input of the first added model element. More...
 
HebiStatusCode hebiRobotModelGetForwardKinematics (HebiRobotModelPtr robot_model, HebiFrameType frame_type, const double *positions, double *frames)
 Generates the transforms for the forward kinematics of the given robot model. More...
 
HebiStatusCode hebiRobotModelGetJacobians (HebiRobotModelPtr robot_model, HebiFrameType frame_type, const double *positions, double *jacobians)
 Generates the jacobian for each frame in the given kinematic tree. More...
 
HebiStatusCode hebiRobotModelGetMasses (HebiRobotModelPtr robot_model, double *masses)
 Fill in the masses vector with the mass of each body with mass in the kinematic tree, reported in a depth-first ordering. More...
 
size_t hebiRobotModelGetNumberOfDoFs (HebiRobotModelPtr robot_model)
 Returns the number of settable degrees of freedom in the kinematic tree. (This is equal to the number of joints added). More...
 
size_t hebiRobotModelGetNumberOfFrames (HebiRobotModelPtr robot_model, HebiFrameType frame_type)
 Return the number of frames in the forward kinematic tree of the robot model. More...
 
void hebiRobotModelRelease (HebiRobotModelPtr robot_model)
 Frees resources created by this robot model object. More...
 
HebiStatusCode hebiRobotModelSetBaseFrame (HebiRobotModelPtr robot_model, const double *transform)
 Sets the fixed transform from the origin to the input of the first added model element. More...
 
HebiStatusCode hebiStringGetString (HebiStringPtr str, char *buffer, size_t *length)
 Copy the string into a buffer. More...
 
void hebiStringRelease (HebiStringPtr str)
 Releases a string instance. More...
 
HebiTrajectoryPtr hebiTrajectoryCreateUnconstrainedQp (size_t num_waypoints, const double *positions, const double *velocities, const double *accelerations, const double *time_vector)
 Creates a HebiTrajectory object for a single joint using the given parameters; this must be released with hebiTrajectoryRelease after use. More...
 
double hebiTrajectoryGetDuration (HebiTrajectoryPtr trajectory)
 Returns the length of this trajectory (in seconds). More...
 
HebiStatusCode hebiTrajectoryGetState (HebiTrajectoryPtr trajectory, double time, double *position, double *velocity, double *acceleration)
 Gets the value of the trajectory at a given time. More...
 
void hebiTrajectoryRelease (HebiTrajectoryPtr trajectory)
 Frees resources created by this trajectory. More...
 

Macro Definition Documentation

#define M_PI   3.14159265358979323846

Definition at line 12 of file hebi.h.

Typedef Documentation

typedef void(* GroupFeedbackHandlerFunction) (HebiGroupFeedbackPtr fbk, void *user_data)

Group feedback handling function signature.

Definition at line 416 of file hebi.h.

typedef struct _HebiCommand* HebiCommandPtr

The C-style's API representation of a command.

Encapsulates data to be sent to a module

Definition at line 315 of file hebi.h.

typedef struct _HebiFeedback* HebiFeedbackPtr

The C-style's API representation of feedback.

Encapsulates feedback received from a module

Definition at line 322 of file hebi.h.

Which frame to report results in (e.g., for getForwardKinematics and other functions.

typedef struct _HebiGroupCommand* HebiGroupCommandPtr

The C-style's API representation of a group command.

This is an iterable list of command structures; commands are sent to modules in a group using the fields within this structure.

Definition at line 338 of file hebi.h.

typedef struct _HebiGroupFeedback* HebiGroupFeedbackPtr

The C-style's API representation of group feedback.

This is an iterable list of feedback structures; feedback from modules in a group are retrieved primarily through this structure.

Definition at line 346 of file hebi.h.

typedef struct _HebiGroupInfo* HebiGroupInfoPtr

The C-style's API representation of group info.

This is an iterable list of info structures; info from modules in a group are retrieved primarily through this structure.

Definition at line 354 of file hebi.h.

typedef struct _HebiGroup* HebiGroupPtr

The C-style's API representation of a group.

Represents a connection to a group of modules. Sends commands to and receives feedback from the group.

Definition at line 330 of file hebi.h.

typedef struct _HebiIK* HebiIKPtr

An inverse kinematics object which uses a kinematics object to search for joint angles that optimize any of several objectives while respecting defined constraints.

Definition at line 369 of file hebi.h.

typedef struct _HebiInfo* HebiInfoPtr

The C-style's API representation of a group.

Represents a connection to a group of modules. Sends commands to and receives feedback from the group.

Definition at line 362 of file hebi.h.

What the type of motion (axis, rotation, translation, etc) is allowed by a joint.

typedef struct _HebiLogFile* HebiLogFilePtr

The C-style's API representation of a log file.

Represents a log file generated by the API.

Definition at line 388 of file hebi.h.

typedef struct _HebiLookupEntryList* HebiLookupEntryListPtr

A list of entries that represent a snapshot of the state of the lookup object at some point in time. These entries include network HEBI devices such as actuators.

Definition at line 402 of file hebi.h.

typedef struct _HebiLookup* HebiLookupPtr

Maintains a registry of network-connected modules and returns Group objects to the user. Only one Lookup object is needed per application.

Definition at line 395 of file hebi.h.

typedef struct _HebiRobotModelElement* HebiRobotModelElementPtr

Contains a robot model element, which has an input and zero or more outputs. This may refer to a rigid body or a massless joint.

Definition at line 381 of file hebi.h.

typedef struct _HebiRobotModel* HebiRobotModelPtr

A robot model object which stores a tree of connected modules, and allows for computation of forward kinematics, jacobians, and more.

Definition at line 375 of file hebi.h.

typedef struct _HebiString* HebiStringPtr

The C-style's API representation of a string.

Represents a null terminated UTF-8 string

Definition at line 308 of file hebi.h.

typedef struct _HebiTrajectory* HebiTrajectoryPtr

The C-style's API representation of a trajectory.

Do not inherit from this; only obtain pointers through the API!

Used to generate position, velocity, and acceleration for different joints.

Definition at line 411 of file hebi.h.

typedef struct _HebiVector3f HebiVector3f

Enumeration Type Documentation

Enumerator
HebiCommandBoolPositionDOnError 
HebiCommandBoolVelocityDOnError 

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

HebiCommandBoolEffortDOnError 

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

Definition at line 89 of file hebi.h.

Enumerator
HebiCommandEnumControlStrategy 

Definition at line 107 of file hebi.h.

Enumerator
HebiCommandFlagSaveCurrentSettings 
HebiCommandFlagReset 

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

HebiCommandFlagBoot 

Restart the module.

HebiCommandFlagStopBoot 

Boot the module from bootloader into application.

Definition at line 100 of file hebi.h.

Enumerator
HebiCommandFloatVelocity 
HebiCommandFloatEffort 

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

HebiCommandFloatPositionKp 

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

HebiCommandFloatPositionKi 

Proportional PID gain for position.

HebiCommandFloatPositionKd 

Integral PID gain for position.

HebiCommandFloatPositionFeedForward 

Derivative PID gain for position.

HebiCommandFloatPositionDeadZone 

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

HebiCommandFloatPositionIClamp 

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

HebiCommandFloatPositionPunch 

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.

HebiCommandFloatPositionMinTarget 

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.

HebiCommandFloatPositionMaxTarget 

Minimum allowed value for input to the PID controller.

HebiCommandFloatPositionTargetLowpass 

Maximum allowed value for input to the PID controller.

HebiCommandFloatPositionMinOutput 

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

HebiCommandFloatPositionMaxOutput 

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

HebiCommandFloatPositionOutputLowpass 

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

HebiCommandFloatVelocityKp 

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

HebiCommandFloatVelocityKi 

Proportional PID gain for velocity.

HebiCommandFloatVelocityKd 

Integral PID gain for velocity.

HebiCommandFloatVelocityFeedForward 

Derivative PID gain for velocity.

HebiCommandFloatVelocityDeadZone 

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

HebiCommandFloatVelocityIClamp 

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

HebiCommandFloatVelocityPunch 

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.

HebiCommandFloatVelocityMinTarget 

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.

HebiCommandFloatVelocityMaxTarget 

Minimum allowed value for input to the PID controller.

HebiCommandFloatVelocityTargetLowpass 

Maximum allowed value for input to the PID controller.

HebiCommandFloatVelocityMinOutput 

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

HebiCommandFloatVelocityMaxOutput 

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

HebiCommandFloatVelocityOutputLowpass 

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

HebiCommandFloatEffortKp 

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

HebiCommandFloatEffortKi 

Proportional PID gain for effort.

HebiCommandFloatEffortKd 

Integral PID gain for effort.

HebiCommandFloatEffortFeedForward 

Derivative PID gain for effort.

HebiCommandFloatEffortDeadZone 

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

HebiCommandFloatEffortIClamp 

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

HebiCommandFloatEffortPunch 

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.

HebiCommandFloatEffortMinTarget 

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.

HebiCommandFloatEffortMaxTarget 

Minimum allowed value for input to the PID controller.

HebiCommandFloatEffortTargetLowpass 

Maximum allowed value for input to the PID controller.

HebiCommandFloatEffortMinOutput 

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

HebiCommandFloatEffortMaxOutput 

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

HebiCommandFloatEffortOutputLowpass 

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

HebiCommandFloatSpringConstant 

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

HebiCommandFloatReferencePosition 

The spring constant of the module.

HebiCommandFloatReferenceEffort 

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

Definition at line 32 of file hebi.h.

Enumerator
HebiCommandHighResAnglePosition 
HebiCommandHighResAnglePositionLimitMin 

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

HebiCommandHighResAnglePositionLimitMax 

Set the firmware safety limit for the minimum allowed position.

Definition at line 79 of file hebi.h.

Enumerator
HebiCommandIoBankA 
HebiCommandIoBankB 

I/O pin bank a (pins 1-8 available)

HebiCommandIoBankC 

I/O pin bank b (pins 1-8 available)

HebiCommandIoBankD 

I/O pin bank c (pins 1-8 available)

HebiCommandIoBankE 

I/O pin bank d (pins 1-8 available)

HebiCommandIoBankF 

I/O pin bank e (pins 1-8 available)

Definition at line 111 of file hebi.h.

Enumerator
HebiCommandLedLed 

Definition at line 120 of file hebi.h.

Enumerator
HebiCommandNumberedFloatDebug 

Definition at line 85 of file hebi.h.

Enumerator
HebiCommandStringName 
HebiCommandStringFamily 

Sets the name for this module. Name must be null-terminated character string for the name; must be <= 20 characters.

Definition at line 95 of file hebi.h.

Enumerator
HebiFeedbackEnumTemperatureState 
HebiFeedbackEnumMstopState 

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

HebiFeedbackEnumPositionLimitState 

Current status of the MStop.

HebiFeedbackEnumVelocityLimitState 

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

HebiFeedbackEnumEffortLimitState 

Software-controlled bounds on the allowable velocity of the module.

HebiFeedbackEnumCommandLifetimeState 

Software-controlled bounds on the allowable effort of the module.

Definition at line 173 of file hebi.h.

Enumerator
HebiFeedbackFloatBoardTemperature 
HebiFeedbackFloatProcessorTemperature 

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

HebiFeedbackFloatVoltage 

Temperature of the processor chip, in degrees Celsius.

HebiFeedbackFloatVelocity 

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

HebiFeedbackFloatEffort 

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

HebiFeedbackFloatVelocityCommand 

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

HebiFeedbackFloatEffortCommand 

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

HebiFeedbackFloatDeflection 

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

HebiFeedbackFloatDeflectionVelocity 

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

HebiFeedbackFloatMotorVelocity 

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

HebiFeedbackFloatMotorCurrent 

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

HebiFeedbackFloatMotorSensorTemperature 

Current supplied to the motor.

HebiFeedbackFloatMotorWindingCurrent 

The temperature from a sensor near the motor housing.

HebiFeedbackFloatMotorWindingTemperature 

The estimated current in the motor windings.

HebiFeedbackFloatMotorHousingTemperature 

The estimated temperature of the motor windings.

Definition at line 128 of file hebi.h.

Enumerator
HebiFeedbackHighResAnglePosition 
HebiFeedbackHighResAnglePositionCommand 

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

Definition at line 146 of file hebi.h.

Enumerator
HebiFeedbackIoBankA 
HebiFeedbackIoBankB 

I/O pin bank a (pins 1-8 available)

HebiFeedbackIoBankC 

I/O pin bank b (pins 1-8 available)

HebiFeedbackIoBankD 

I/O pin bank c (pins 1-8 available)

HebiFeedbackIoBankE 

I/O pin bank d (pins 1-8 available)

HebiFeedbackIoBankF 

I/O pin bank e (pins 1-8 available)

Definition at line 182 of file hebi.h.

Enumerator
HebiFeedbackLedLed 

Definition at line 191 of file hebi.h.

Enumerator
HebiFeedbackNumberedFloatDebug 

Definition at line 151 of file hebi.h.

Enumerator
HebiFeedbackQuaternionfOrientation 

Definition at line 169 of file hebi.h.

Enumerator
HebiFeedbackUInt64SequenceNumber 
HebiFeedbackUInt64ReceiveTime 

Sequence number going to module (local)

HebiFeedbackUInt64TransmitTime 

Timestamp of when message was received from module (local)

HebiFeedbackUInt64HardwareReceiveTime 

Timestamp of when message was transmitted to module (local)

HebiFeedbackUInt64HardwareTransmitTime 

Timestamp of when message was received by module (remote)

HebiFeedbackUInt64SenderId 

Timestamp of when message was transmitted from module (remote)

Definition at line 155 of file hebi.h.

Enumerator
HebiFeedbackVector3fAccelerometer 
HebiFeedbackVector3fGyro 

Accelerometer data, in m/s^2.

Definition at line 164 of file hebi.h.

Which frame to report results in (e.g., for getForwardKinematics and other functions.

Enumerator
HebiFrameTypeCenterOfMass 
HebiFrameTypeOutput 
HebiFrameTypeEndEffector 

Definition at line 280 of file hebi.h.

Enumerator
HebiInfoBoolPositionDOnError 
HebiInfoBoolVelocityDOnError 

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

HebiInfoBoolEffortDOnError 

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

Definition at line 247 of file hebi.h.

Enumerator
HebiInfoEnumControlStrategy 
HebiInfoEnumCalibrationState 

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

Definition at line 263 of file hebi.h.

Enumerator
HebiInfoFlagSaveCurrentSettings 

Definition at line 259 of file hebi.h.

Enumerator
HebiInfoFloatPositionKp 
HebiInfoFloatPositionKi 

Proportional PID gain for position.

HebiInfoFloatPositionKd 

Integral PID gain for position.

HebiInfoFloatPositionFeedForward 

Derivative PID gain for position.

HebiInfoFloatPositionDeadZone 

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

HebiInfoFloatPositionIClamp 

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

HebiInfoFloatPositionPunch 

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.

HebiInfoFloatPositionMinTarget 

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.

HebiInfoFloatPositionMaxTarget 

Minimum allowed value for input to the PID controller.

HebiInfoFloatPositionTargetLowpass 

Maximum allowed value for input to the PID controller.

HebiInfoFloatPositionMinOutput 

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

HebiInfoFloatPositionMaxOutput 

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

HebiInfoFloatPositionOutputLowpass 

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

HebiInfoFloatVelocityKp 

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

HebiInfoFloatVelocityKi 

Proportional PID gain for velocity.

HebiInfoFloatVelocityKd 

Integral PID gain for velocity.

HebiInfoFloatVelocityFeedForward 

Derivative PID gain for velocity.

HebiInfoFloatVelocityDeadZone 

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

HebiInfoFloatVelocityIClamp 

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

HebiInfoFloatVelocityPunch 

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.

HebiInfoFloatVelocityMinTarget 

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.

HebiInfoFloatVelocityMaxTarget 

Minimum allowed value for input to the PID controller.

HebiInfoFloatVelocityTargetLowpass 

Maximum allowed value for input to the PID controller.

HebiInfoFloatVelocityMinOutput 

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

HebiInfoFloatVelocityMaxOutput 

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

HebiInfoFloatVelocityOutputLowpass 

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

HebiInfoFloatEffortKp 

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

HebiInfoFloatEffortKi 

Proportional PID gain for effort.

HebiInfoFloatEffortKd 

Integral PID gain for effort.

HebiInfoFloatEffortFeedForward 

Derivative PID gain for effort.

HebiInfoFloatEffortDeadZone 

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

HebiInfoFloatEffortIClamp 

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

HebiInfoFloatEffortPunch 

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.

HebiInfoFloatEffortMinTarget 

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.

HebiInfoFloatEffortMaxTarget 

Minimum allowed value for input to the PID controller.

HebiInfoFloatEffortTargetLowpass 

Maximum allowed value for input to the PID controller.

HebiInfoFloatEffortMinOutput 

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

HebiInfoFloatEffortMaxOutput 

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

HebiInfoFloatEffortOutputLowpass 

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

HebiInfoFloatSpringConstant 

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

Definition at line 199 of file hebi.h.

Enumerator
HebiInfoHighResAnglePositionLimitMin 
HebiInfoHighResAnglePositionLimitMax 

The firmware safety limit for the minimum allowed position.

Definition at line 242 of file hebi.h.

Enumerator
HebiInfoLedLed 

Definition at line 268 of file hebi.h.

Enumerator
HebiInfoStringName 
HebiInfoStringFamily 

Gets the name for this module.

HebiInfoStringSerial 

Gets the family for this module.

Definition at line 253 of file hebi.h.

What the type of motion (axis, rotation, translation, etc) is allowed by a joint.

Enumerator
HebiJointTypeRotationX 
HebiJointTypeRotationY 
HebiJointTypeRotationZ 
HebiJointTypeTranslationX 
HebiJointTypeTranslationY 
HebiJointTypeTranslationZ 

Definition at line 290 of file hebi.h.

Enumerator
HebiStatusSuccess 
HebiStatusInvalidArgument 

Success; no failures occurred.

HebiStatusBufferTooSmall 

An invalid argument was supplied to the routine (e.g. null pointer)

HebiStatusValueNotSet 

A buffer supplied to the routine was too small (normally determined by a size parameter)

HebiStatusFailure 

Returned when an accessor function attempts to retrieve a field which is not set.

HebiStatusArgumentOutOfRange 

Generic code for failure; this is generally used for an internal or unknown failure.

Definition at line 19 of file hebi.h.

Function Documentation

void hebiCleanup ( void  )

Frees all resources created by the library. Note: any calls to the HEBI library functions after this will result in undefined behavior!

void hebiCommandClearLed ( HebiCommandPtr  cmd,
HebiCommandLedField  field 
)

Clears the given LED field, so that the module maintains its previous state of LED control/color (i.e., does not have an override color command or an explicit 'module control' command).

HebiStatusCode hebiCommandGetBool ( HebiCommandPtr  cmd,
HebiCommandBoolField  field,
int32_t *  value 
)

If the specified value is set, writes the value of the field to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

The value written to the pointer will be 1 for true and 0 for false.

HebiStatusCode hebiCommandGetEnum ( HebiCommandPtr  cmd,
HebiCommandEnumField  field,
int32_t *  value 
)

If the specified value is set, writes the value of the field to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

int32_t hebiCommandGetFlag ( HebiCommandPtr  cmd,
HebiCommandFlagField  field 
)

Checks whether this flag is set. Returns '1' for yes, '0' for no.

HebiStatusCode hebiCommandGetFloat ( HebiCommandPtr  cmd,
HebiCommandFloatField  field,
float *  value 
)

If the specified value is set, writes the value of the field to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiCommandGetHighResAngle ( HebiCommandPtr  cmd,
HebiCommandHighResAngleField  field,
int64_t *  int_part,
float *  dec_part 
)

If the specified value is set, writes the value of the field to the pointers (if both are not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiCommandGetIoPinFloat ( HebiCommandPtr  cmd,
HebiCommandIoPinBank  field,
size_t  pin_number,
float *  value 
)

If the indicated pin has an floating point value, writes it to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiCommandGetIoPinInt ( HebiCommandPtr  cmd,
HebiCommandIoPinBank  field,
size_t  pin_number,
int64_t *  value 
)

If the indicated pin has an integer value, writes it to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiCommandGetLedColor ( HebiCommandPtr  cmd,
HebiCommandLedField  field,
uint8_t *  r,
uint8_t *  g,
uint8_t *  b 
)

If the led color is set, writes it to the three output integer pointers (if all are not NULL), each 0-255, and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

For command-style messages, this refers to the color to override the module's default control of the LED.

HebiStatusCode hebiCommandGetNumberedFloat ( HebiCommandPtr  cmd,
HebiCommandNumberedFloatField  field,
size_t  number,
float *  value 
)

If the specified value is set, writes the value of the field to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiCommandGetString ( HebiCommandPtr  cmd,
HebiCommandStringField  field,
char *  buffer,
size_t *  length 
)

Retrieves the value and/or the length of the string field.

If this string is not set in the Command, HebiStatusValueNotSet is returned (regardless of any other arguments) and any pointer values are unchanged.

If 'length' is NULL, returns HebiStatusValueSuccess if this string value is set (the value of 'buffer' is ignored in this case).

If 'buffer' is not NULL, then 'length' should be non-NULL and set to the number of characters that can be written to 'buffer'. If the specified string is set, and it can fit into the provided buffer (including a null terminating character), then the string is copied to 'buffer' and HebiStatusSuccess is returned. If the buffer is not large enough to contain the string, then HebiStatusBufferTooSmall is returned.

If 'buffer' is NULL, returns HebiStatusValueSuccess if this string value is set.

If 'length' is not NULL (regardless of the state of 'buffer'), it is set to the necessary size to hold the specified string value (including the null terminating character).

Note - assumes ASCII string encoding.

int32_t hebiCommandHasLedModuleControl ( HebiCommandPtr  cmd,
HebiCommandLedField  field 
)

Returns '1' if this message indicates that the module should resume control of the LED. A '0' can indicate either an override command (if and only if HasLedColor() returns '1'), or no information about the LED (i.e., the module should maintain it's current state regarding the LED).

void hebiCommandSetBool ( HebiCommandPtr  cmd,
HebiCommandBoolField  field,
const int32_t *  value 
)

Sets the given field. If the provided pointer is null, the field is cleared.

void hebiCommandSetEnum ( HebiCommandPtr  cmd,
HebiCommandEnumField  field,
const int32_t *  value 
)

Sets the given field. If the provided pointer is null, the field is cleared.

void hebiCommandSetFlag ( HebiCommandPtr  cmd,
HebiCommandFlagField  field,
int32_t  value 
)

Sets or clears a flag value. A nonzero value sets this flag and a value of zero clears this flag.

void hebiCommandSetFloat ( HebiCommandPtr  cmd,
HebiCommandFloatField  field,
const float *  value 
)

Sets the given field. If the provided pointer is null, the field is cleared.

void hebiCommandSetHighResAngle ( HebiCommandPtr  cmd,
HebiCommandHighResAngleField  field,
const int64_t *  int_part,
const float *  dec_part 
)

Sets the given field. If any of the provided pointers are null, the field is cleared.

void hebiCommandSetIoPinFloat ( HebiCommandPtr  cmd,
HebiCommandIoPinBank  field,
size_t  pin_number,
const float *  value 
)

Sets the indicated pin to this floating point value. If the provided pointer is NULL the field is cleared (of values of any type).

void hebiCommandSetIoPinInt ( HebiCommandPtr  cmd,
HebiCommandIoPinBank  field,
size_t  pin_number,
const int64_t *  value 
)

Sets the indicated pin to this integer value. If the provided pointer is NULL the field is cleared (of values of any type).

void hebiCommandSetLedModuleControl ( HebiCommandPtr  cmd,
HebiCommandLedField  field 
)

Sets the module to regain control of the LED.

void hebiCommandSetLedOverrideColor ( HebiCommandPtr  cmd,
HebiCommandLedField  field,
uint8_t  r,
uint8_t  g,
uint8_t  b 
)

Commands a color that overrides the module's control of the LED.

void hebiCommandSetNumberedFloat ( HebiCommandPtr  cmd,
HebiCommandNumberedFloatField  field,
size_t  number,
const float *  value 
)

Sets the given field. If the provided pointer is null, the field is cleared.

void hebiCommandSetString ( HebiCommandPtr  cmd,
HebiCommandStringField  field,
const char *  buffer,
const size_t *  length 
)

Sets the given string to the value given in the buffer (if given). If any of the provided pointers are null, the field is cleared.

If not null, 'length' should be set to the length of the c-style string in 'buffer', without including the terminating null character. The data in 'buffer' does not need to be null terminated.

Note - assumes ASCII string encoding.

HebiLookupEntryListPtr hebiCreateLookupEntryList ( HebiLookupPtr  lookup)

Return a snapshot of the contents of the module registry – i.e., which modules have been found by the lookup.

Parameters
lookupA valid HebiLookup object.
HebiStatusCode hebiFeedbackGetEnum ( HebiFeedbackPtr  ,
HebiFeedbackEnumField  ,
int32_t *   
)

If the specified value is set, writes the value of the field to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiFeedbackGetFloat ( HebiFeedbackPtr  fbk,
HebiFeedbackFloatField  field,
float *  value 
)

If the specified value is set, writes the value of the field to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiFeedbackGetHighResAngle ( HebiFeedbackPtr  fbk,
HebiFeedbackHighResAngleField  field,
int64_t *  int_part,
float *  dec_part 
)

If the specified value is set, writes the value of the field to the pointers (if both are not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiFeedbackGetIoPinFloat ( HebiFeedbackPtr  fbk,
HebiFeedbackIoPinBank  field,
size_t  pin_number,
float *  value 
)

If the indicated pin has an floating point value, writes it to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiFeedbackGetIoPinInt ( HebiFeedbackPtr  fbk,
HebiFeedbackIoPinBank  field,
size_t  pin_number,
int64_t *  value 
)

If the indicated pin has an integer value, writes it to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiFeedbackGetLedColor ( HebiFeedbackPtr  fbk,
HebiFeedbackLedField  field,
uint8_t *  r,
uint8_t *  g,
uint8_t *  b 
)

If the led color is set, writes it to the three output integer pointers (if all are not NULL), each 0-255, and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

For command-style messages, this refers to the color to override the module's default control of the LED.

HebiStatusCode hebiFeedbackGetNumberedFloat ( HebiFeedbackPtr  fbk,
HebiFeedbackNumberedFloatField  field,
size_t  number,
float *  value 
)

If the specified value is set, writes the value of the field to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiFeedbackGetQuaternionf ( HebiFeedbackPtr  fbk,
HebiFeedbackQuaternionfField  field,
HebiQuaternionf value 
)

If the specified value is set, writes the value of the field to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiFeedbackGetUInt64 ( HebiFeedbackPtr  fbk,
HebiFeedbackUInt64Field  field,
uint64_t *  value 
)

If the specified value is set, writes the value of the field to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiFeedbackGetVector3f ( HebiFeedbackPtr  fbk,
HebiFeedbackVector3fField  field,
HebiVector3f value 
)

If the specified value is set, writes the value of the field to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiGetLibraryVersion ( int32_t *  major,
int32_t *  minor,
int32_t *  revision 
)

Get the version of the library.

All parameters must not be NULL.

Returns
HebiStatusSuccess on success, otherwise HebiStatusInvalidArgument if a parameter is NULL.
void hebiGroupClearFeedbackHandlers ( HebiGroupPtr  group)

Removes all feedback handling functions from the queue to be called on receipt of group feedback.

Parameters
groupThe group to which the handlers are attached.
void hebiGroupCommandClear ( HebiGroupCommandPtr  cmd)

Clears all data in the GroupCommand object.

HebiStatusCode hebiGroupCommandCopy ( HebiGroupCommandPtr  dest,
HebiGroupCommandPtr  src 
)

Clears the dest GroupCommand object, and copies all data from the src GroupCommand object to dest.

The GroupCommand objects should have identical state after this.

Parameters
destThe GroupCommandPtr to copy data into. The previous state of this object will be cleared.
srcThe GroupCommandPtr to copy data from. This object will remain unchanged.
Returns
HebiStatusSuccess if the operation succeeds; HebiStatusInvalidArgument if the sizes of the two messages do not match; HebiStatusError for any other error.
HebiGroupCommandPtr hebiGroupCommandCreate ( size_t  size)

Creates a GroupCommand for a group with the specified number of modules.

Parameters
sizeThe number of modules in the group.
Returns
A pointer to a new GroupCommand object. This must be released with hebiGroupCommandRelease(HebiGroupCommandPtr).
HebiCommandPtr hebiGroupCommandGetModuleCommand ( HebiGroupCommandPtr  cmd,
size_t  module_index 
)

Get an individual command for a particular module at index module_index.

Parameters
module_indexThe index to retrieve the module command; must be from 0 to the size - 1, inclusive, or results in undefined behavior.
Returns
The command corresponding to the module at the specified index
size_t hebiGroupCommandGetSize ( HebiGroupCommandPtr  cmd)

Return the number of modules in this group Command.

Returns
The number of module commands in this group command.
HebiStatusCode hebiGroupCommandReadGains ( HebiGroupCommandPtr  cmd,
const char *  file 
)

Import gains from a file into a GroupCommand object.

Parameters
fileA null-terminated string that gives the path/filename of the gains XML file. Must not be NULL.
Returns
HebiStatusSuccess on success, or a failure code if the file could note be opened or read. In particular:
  • if the file was successfully read, but the number of modules in the file is not equal to '1' or the size of the group, returns HebiStatusInvalidArgument.
  • if file is NULL, returns HebiStatusInvalidArgument.
  • for other parsing errors, may return HebiStatusFailure or HebiStatusInvalidArgument.
void hebiGroupCommandRelease ( HebiGroupCommandPtr  cmd)

Frees resources created by the GroupCommand object.

The GroupCommandPtr must not be used after this function is called.

HebiStatusCode hebiGroupCommandWriteGains ( HebiGroupCommandPtr  cmd,
const char *  file 
)

Export gains from a GroupCommand object into a file.

Parameters
fileA null-terminated string that gives the path/filename to save the gains XML file at. Must not be NULL.
Returns
HebiStatusSuccess on success, or a failure code if the file could not be written to or an internal error occurs.
HebiGroupPtr hebiGroupCreateConnectedFromMac ( HebiLookupPtr  lookup,
const HebiMacAddress address,
int32_t  timeout_ms 
)

Create a group with all modules connected to module with the given MAC address.

Modules in group will be ordered depth-first, starting with the most proximal module.

Blocking call which waits to get a pointer to a Group object with the given parameters. Times out after timeout_msec milliseconds. Must be released when use is complete via the hebiGroupRelease function.

Parameters
lookupA valid HebiLookup object.
addressPointer to a HebiMacAddress structure representing the physical mac address of the given module (serves as unique id). Must not be NULL.
timeout_msTimeout in milliseconds. A value of -1 blocks until a module is found, and a value of 0 returns immediately if no module with that address is currently known by the Lookup class.
Returns
NULL if matching group not found in allotted time; pointer to newly allocated group object otherwise.
HebiGroupPtr hebiGroupCreateConnectedFromName ( HebiLookupPtr  lookup,
const char *  family,
const char *  name,
int32_t  timeout_ms 
)

Create a group with all modules connected to module with the given name and family.

Modules in group will be ordered depth-first, starting with the most proximal module.

Blocking call which waits to get a pointer to a Group object with the given parameters. Times out after timeout_msec milliseconds. Must be released when use is complete via the hebiGroupRelease function.

Parameters
lookupA valid HebiLookup object.
nameThe given name of the key module, as viewable in the HEBI GUI. Must be a null-terminated string, and must not be NULL.
familyThe given family of the key module, as viewable in the HEBI GUI. Must be a null-terminated string, and must not be NULL.
timeout_msTimeout in milliseconds. A value of -1 blocks until a module is found, and a value of 0 returns immediately if no module with that address is currently known by the Lookup class.
Returns
NULL if matching group not found in allotted time; pointer to newly allocated group object otherwise.
HebiGroupPtr hebiGroupCreateFromFamily ( HebiLookupPtr  lookup,
const char *  family,
int32_t  timeout_ms 
)

Create a group with all modules known to the lookup with the given family.

Group contains all modules with the given family, regardless of name.

Blocking call which waits to get a pointer to a Group object with the given parameters. Times out after timeout_msec milliseconds. Must be released when use is complete via the hebiGroupRelease function.

Parameters
lookupA valid HebiLookup object.
familyThe given family of the modules, as viewable in the HEBI GUI. Must be a null-terminated string, and must not be NULL.
timeout_msTimeout in milliseconds. A value of -1 blocks until a module is found, and a value of 0 returns immediately if no module with that address is currently known by the Lookup class.
Returns
NULL if matching group not found in allotted time; pointer to newly allocated group object otherwise.
HebiGroupPtr hebiGroupCreateFromMacs ( HebiLookupPtr  lookup,
const HebiMacAddress *const *  addresses,
size_t  num_addresses,
int32_t  timeout_ms 
)

Create a group of modules with the given MAC addresses.

If any given modules are not found, no group is created.

Blocking call which waits to get a pointer to a Group object with the given parameters. Times out after timeout_msec milliseconds. Must be released when use is complete via the hebiGroupRelease function.

Parameters
lookupA valid HebiLookup object.
addressesAn array of pointers to physical mac addresses of the given modules. Length of the array must equal num_addresses. This param must not be NULL, and each element of this list must not be NULL.
num_addressesLength of the addresses array of pointers (number of pointers in the array, not cumulative size of objects they point to).
timeout_msTimeout in milliseconds. A value of -1 blocks until a module is found, and a value of 0 returns immediately if no module with that address is currently known by the Lookup class.
Returns
NULL if matching group not found in allotted time; pointer to newly allocated group object otherwise.
HebiGroupPtr hebiGroupCreateFromNames ( HebiLookupPtr  lookup,
const char *const *  families,
size_t  num_families,
const char *const *  names,
size_t  num_names,
int32_t  timeout_ms 
)

Create a group with modules matching the given names and families.

If only one family is given, it is used for all modules. Otherwise, number of names and families must match. If any given modules are not found, no group is created.

Blocking call which waits to get a pointer to a Group object with the given parameters. Times out after timeout_msec milliseconds. Must be released when use is complete via the hebiGroupRelease function.

Parameters
lookupA valid HebiLookup object.
familiesThe given families of the modules, as viewable in the HEBI GUI. Must be a list of pointers to null-terminated strings. The number of pointers must match the num_families parameter. Note that a single string (with corresponding value of num_families == 1) will be used with each name in the names list. This param must not be NULL, and each element of this list must not be NULL.
num_familiesThe number of pointers to null-terminated strings given by the families parameter. Note that this must either be 1, or be equal to num_names.
namesThe given names of the modules, as viewable in the HEBI GUI. Must be a list of pointers to null-terminated strings. The number of pointers must match the num_names parameter. This param must not be NULL, and each element of this list must not be NULL.
num_namesThe number of pointers to null-terminated strings given by the names parameter.
timeout_msTimeout in milliseconds. A value of -1 blocks until a module is found, and a value of 0 returns immediately if no module with that address is currently known by the Lookup class.
Returns
NULL if matching group not found in allotted time; pointer to newly allocated group object otherwise.
HebiGroupPtr hebiGroupCreateImitation ( size_t  size)

Creates an "imitation" group with the specified number of modules.

The imitation group is useful for testing the API, as it acts like a Group would in most cases, but is not backed by hardware. Commands that are sent to the imitation group are returned as feedback, using the standard feedback request methods.

Note that standard groups are created through the HebiLookup objects.

Parameters
sizeThe number of modules in the group.
Returns
An imitation group that returns commanded values as feedback.
void hebiGroupFeedbackClear ( HebiGroupFeedbackPtr  fbk)

Clears all data in the GroupFeedback object.

HebiStatusCode hebiGroupFeedbackCopy ( HebiGroupFeedbackPtr  dest,
HebiGroupFeedbackPtr  src 
)

Clears the dest GroupFeedback object, and copies all data from the src GroupFeedback object to dest.

The GroupFeedback objects should have identical state after this.

Parameters
destThe GroupFeedbackPtr to copy data into. The previous state of this object will be cleared.
srcThe GroupFeedbackPtr to copy data from. This object will remain unchanged.
Returns
HebiStatusSuccess if the operation succeeds; HebiStatusInvalidArgument if the sizes of the two messages do not match; HebiStatusError for any other error.
HebiGroupFeedbackPtr hebiGroupFeedbackCreate ( size_t  size)

Creates a GroupFeedback for a group with the specified number of modules.

Parameters
sizeThe number of modules in the group.
Returns
A pointer to a new GroupFeedback object. This must be released with hebiGroupFeedbackRelease(HebiGroupFeedbackPtr).
HebiFeedbackPtr hebiGroupFeedbackGetModuleFeedback ( HebiGroupFeedbackPtr  fbk,
size_t  module_index 
)

Get an individual feedback for a particular module at index module_index.

Parameters
module_indexThe index to retrieve the module feedback; must be from 0 to the size - 1, inclusive, or results in undefined behavior.
Returns
The feedback corresponding to the module at the specified index.
size_t hebiGroupFeedbackGetSize ( HebiGroupFeedbackPtr  fbk)

Return the number of modules in this group Feedback.

Returns
The number of module feedbacks in this group feedback.
void hebiGroupFeedbackRelease ( HebiGroupFeedbackPtr  fbk)

Frees resources created by the GroupFeedback object.

The GroupFeedbackPtr should must not be used after this function is called.

int32_t hebiGroupGetCommandLifetime ( HebiGroupPtr  group)

Returns the current command lifetime, in milliseconds.

Parameters
groupWhich group is being queried.
Returns
The current command lifetime, in milliseconds. A value of '0' indicates that commands remain active until the next command is received.
float hebiGroupGetFeedbackFrequencyHz ( HebiGroupPtr  group)

Returns the current feedback request loop frequency (in Hz).

Parameters
groupWhich group is being queried.
Returns
The current feedback request loop frequency (in Hz).
HebiStatusCode hebiGroupGetNextFeedback ( HebiGroupPtr  group,
HebiGroupFeedbackPtr  feedback,
int32_t  timeout_ms 
)

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

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

Warning: other data in the provided 'Feedback' object is erased!

Parameters
groupThe group to return feedback from.
feedbackOn success, the feedback read from the group are written into this structure.
timeout_msIndicates how many milliseconds to wait for feedback. For typical networks, '15' ms is a value that can be reasonably expected to allow for a round trip transmission after the last 'send feedback request' call.
Returns
HebiStatusSuccess if feedback was returned, or a failure code if not (i.e., connection error or timeout waiting for response).
size_t hebiGroupGetSize ( HebiGroupPtr  group)

Returns the number of modules in a group.

Parameters
groupThe group to send this command to.
Returns
the number of modules in the group.
void hebiGroupInfoClear ( HebiGroupInfoPtr  info)

Clears all data in the GroupInfo object.

HebiStatusCode hebiGroupInfoCopy ( HebiGroupInfoPtr  dest,
HebiGroupInfoPtr  src 
)

Clears the dest GroupInfo object, and copies all data from the src GroupInfo object to dest.

The GroupInfo objects should have identical state after this.

Parameters
destThe GroupInfoPtr to copy data into. The previous state of this object will be cleared.
srcThe GroupInfoPtr to copy data from. This object will remain unchanged.
Returns
HebiStatusSuccess if the operation succeeds; HebiStatusInvalidArgument if the sizes of the two messages do not match; HebiStatusError for any other error.
HebiGroupInfoPtr hebiGroupInfoCreate ( size_t  size)

Creates a GroupInfo for a group with the specified number of modules.

Parameters
sizeThe number of modules in the group.
Returns
A pointer to a new GroupInfo object. This must be released with hebiGroupInfoRelease(HebiGroupInfoPtr).
HebiInfoPtr hebiGroupInfoGetModuleInfo ( HebiGroupInfoPtr  info,
size_t  module_index 
)

Get an individual info for a particular module at index module_index.

Parameters
module_indexThe index to retrieve the module info; must be from 0 to the size - 1, inclusive, or results in undefined behavior.
Returns
The info corresponding to the module at the specified index.
size_t hebiGroupInfoGetSize ( HebiGroupInfoPtr  info)

Return the number of modules in this group Info.

Returns
The number of module infos in this group info.
void hebiGroupInfoRelease ( HebiGroupInfoPtr  info)

Frees resources created by the GroupInfo object.

The GroupInfoPtr must not be used after this function is called.

HebiStatusCode hebiGroupInfoWriteGains ( HebiGroupInfoPtr  info,
const char *  file 
)

Export gains from a GroupInfo object into a file.

Parameters
fileA null-terminated string that gives the path/filename to save the gains XML file at. Must not be NULL.
Returns
HebiStatusSuccess on success, or a failure code if the file could not be written to or an internal error occurs.
HebiStatusCode hebiGroupRegisterFeedbackHandler ( HebiGroupPtr  group,
GroupFeedbackHandlerFunction  handler,
void *  user_data 
)

Add a function that is called whenever feedback is returned from the group.

Parameters
groupThe group to attach this handler to.
handlerA feedback handling function called whenever feedback is received from the group.
user_dataA pointer to user data which will be returned as the second callback argument. This pointer can be NULL if desired.
void hebiGroupRelease ( HebiGroupPtr  group)

Release resources for a given group; group should not be used after this call.

Parameters
groupA valid HebiGroup object.
HebiStatusCode hebiGroupRequestInfo ( HebiGroupPtr  group,
HebiGroupInfoPtr  info,
int32_t  timeout_ms 
)

Requests info from the group, and writes it to the provided info object.

Warning: other data in the provided 'Info' object is erased!

Parameters
groupThe group to send this command to.
infoOn success, the info read from the group is written into this structure.
timeout_msIndicates how many milliseconds to wait for a response after sending a packet. For typical networks, '15' ms is a value that can be reasonably expected to encompass the time required for a round-trip transmission.
Returns
HebiStatusSuccess if info was received, or a failure code if not (i.e., connection error or timeout waiting for response).
HebiStatusCode hebiGroupSendCommand ( HebiGroupPtr  group,
HebiGroupCommandPtr  command 
)

Sends a command to the given group without requesting an acknowledgement.

Appropriate for high-frequency applications.

Parameters
groupThe group to send this command to.
commandThe HebiGroupCommand object containing information to be sent to the group.
Returns
HebiStatusSuccess if the command was successfully sent, otherwise a failure code.
HebiStatusCode hebiGroupSendCommandWithAcknowledgement ( HebiGroupPtr  group,
HebiGroupCommandPtr  command,
int32_t  timeout_ms 
)

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

Note: A non-HebiStatusSuccess 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
groupThe group to send this command to.
commandThe HebiGroupCommand object containing information to be sent to the group.
timeout_msIndicates how many milliseconds to wait for a response after sending a packet. For typical networks, '15' ms is a value that can be reasonably expected to encompass the time required for a round-trip transmission.
Returns
HebiStatusSuccess if an acknowledgement was successfully received (guaranteeing the group received this command), or a failure code for an error otherwise.
HebiStatusCode hebiGroupSendFeedbackRequest ( HebiGroupPtr  group)

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 hebiGroupGetNextFeedback (any previously returned data is discarded).

Parameters
groupThe group to return feedback from.
Returns
HebiStatusSuccess if request was successfully sent, or a failure code if not (i.e., connection error).
HebiStatusCode hebiGroupSetCommandLifetime ( HebiGroupPtr  group,
int32_t  lifetime_ms 
)

Sets the command lifetime for the group, in milliseconds.

The command lifetime is the duration for which a sent command remains active. If the hardware does not receive further commands within the specified time frame, all local controllers get deactivated. This is a safety feature to mitigate the risk of accidents in case programs get interrupted in an unsafe state, e.g., on program exceptions or during a network fault.

Additionally, supporting hardware does not accept commands from any other sources during the lifetime of a command. This mitigates the risk of other users accidentally sending conflicting targets from, e.g., the GUI.

Parameters
groupWhich group the command lifetime is being set for.
lifetime_msThe number of milliseconds which the command 'lives' for. Setting a value less than or equal to '0' disables command lifetime. When disabled, the hardware will continue to execute the last sent command. Setting a value above the accepted maximum will set the lockout to the maximum value.
Returns
HebiStatusSuccess if command lifetime successfully set, or a failure code if value was outside of accepted range (higher than supported maximum or negative).
HebiStatusCode hebiGroupSetFeedbackFrequencyHz ( HebiGroupPtr  group,
float  frequency 
)

Sets the feedback request loop frequency (in Hz).

The group is queried for feedback in a background thread at this frequency, and any added callbacks are called from this background thread.

Parameters
groupWhich group this frequency set is for.
frequencyThe feedback request loop frequency (in Hz). A value of '0' is the default, and disables the feedback request thread.
Returns
HebiStatusSuccess if feedback frequency successfully set, or a failure code if value was outside of accepted range (higher than supported maximum, NaN or negative).
HebiStatusCode hebiGroupStartLog ( HebiGroupPtr  group,
const char *  dir,
const char *  file,
HebiStringPtr ret 
)

Starts logging data to a file.

Note: If a non null parameter is used for the returned string, and it is populated with a non null reference to a string, it must be explicitly freed using hebiStringRelease(HebiStringPtr str)

Parameters
dirThe relative or absolute path to the directory in which to log. To use the current directory, pass in a null pointer
fileThe optional file name. If this is null, a name will be created using the time at the moment which this function was invoked.
retThe optional pointer to a string reference. If this is null, this is ignored. Otherwise, a reference to a string is populated with the path and name of the log file created. If this function does not return HebiStatusSuccess and this parameter is not null, the value at this pointer is set to null.
Returns
HebiStatusSuccess if successfully started a log, a failure code otherwise.
HebiLogFilePtr hebiGroupStopLog ( HebiGroupPtr  group)

Stops logging data to a file.

Note: This function allocates a log file structure on the heap, so make sure to release the pointer returned by this function by calling hebiLogFileRelease(HebiLogFilePtr ptr)

Parameters
groupThe group that is logging.
Returns
a log file instance on success, otherwise a null pointer.
HebiStatusCode hebiIKAddConstraintJointAngles ( HebiIKPtr  ik,
double  weight,
size_t  num_joints,
const double *  min_positions,
const double *  max_positions 
)

Define joint angle constraints.

NaN or +/- infinity can be set on particular joints to ignore joint limits. Currently, the joint limit constraints are two-sided, which means that any joint must either have both min/max set to NaN/inf, or have neither.

Parameters
weightThe weight of this constraint relative to any other objective functions (this constraint is multiplied by this weight before passing to the optimizer). Defaults to 1.0.
num_jointsThe number of elements in the min_positions and max_positions arrays.
min_positionsAn array with the minimum joint limit for each joint, or NaN or inf if unlimited. Must have num_joints elements, and must not be NULL.
max_positionsAn array with the maximum joint limit for each joint, or NaN or inf if unlimited. Must have num_joints elements, and must not be NULL.
Returns
HebiStatusSuccess on success; otherwise a failure code.
HebiStatusCode hebiIKAddObjectiveCustom ( HebiIKPtr  ik,
double  weight,
size_t  num_errors,
void(*)(void *user_data, size_t num_positions, const double *positions, double *errors)  err_fnc,
void *  user_data 
)

Add a custom objective function to be minimized by the IK solver.

The given callback is called at each iteration of the local optimization, and is expected to fill in each entry of the "errors" vector.

Parameters
weightThe weight of this constraint relative to any other objective functions (this constraint is multiplied by this weight before passing to the optimizer). Defaults to 1.0.
num_errorsThe number of independent error values that this objective returns.
err_fncThe callback function which is used to compute the errors. The arguments are: user_data - The pointer passed in when adding a custom objective; this can be anything (even NULL), and is designed to allow the user to easily access information in the callback. num_positions - the number of elements in the 'positions' array positions - an array of the joint positions at this point in the optimization; of length 'num_positions' errors - an array of error values which must be filled in by the callback; of length 'num_errors'.
HebiStatusCode hebiIKAddObjectiveEndEffectorPosition ( HebiIKPtr  ik,
float  weight,
size_t  end_effector_index,
double  x,
double  y,
double  z 
)

Add an objective that optimizes for the end effector output frame origin to be at the given (x, y, z) point.

If an end effector position objective already exists, this will replace it.

Parameters
weightThe weight of this objective relative to any other objective functions (this objective is multiplied by this weight before passing to the optimizer). Defaults to 1.0.
xThe desired x position of the end effector frame. 'NaN' can be passed to ignore this variable.
yThe desired y position of the end effector frame. 'NaN' can be passed to ignore this variable.
zThe desired z position of the end effector frame. 'NaN' can be passed to ignore this variable.
Returns
HebiStatusSuccess on success, otherwise a failure code (e.g. incompatible with existing objectives, or all components are set to 'NaN')
HebiStatusCode hebiIKAddObjectiveEndEffectorSO3 ( HebiIKPtr  ik,
double  weight,
size_t  end_effector_index,
const double *  matrix 
)

Add an objective that optimizes for the end effector output frame orientation to be given by the 3x3 (row major) rotation matrix. Note that this is incompatible with the end effector tip axis objective.

If an end effector orientation objective already exists, this will replace it.

Parameters
weightThe weight of this objective relative to any other objective functions (this objective is multiplied by this weight before passing to the optimizer). Defaults to 1.0.
matrixThe desired orientation of the end effector frame, as a 3x3 rotation matrix in row major order. Must not be NULL.
Returns
HebiStatusSuccess on success, otherwise a failure code (e.g. incompatible with existing objectives, or rotation matrix is invalid or null.)
HebiStatusCode hebiIKAddObjectiveEndEffectorTipAxis ( HebiIKPtr  ik,
double  weight,
size_t  end_effector_index,
double  x,
double  y,
double  z 
)

Add an objective that points the end effector's z axis in a given direction. Note that this is incompatible with the end effector S03 orientation objective.

If an end effector orientation objective already exists, this will replace it.

Parameters
weightThe weight of this objective relative to any other objective functions (this objective is multiplied by this weight before passing to the optimizer). Defaults to 1.0.
xThe desired end effector z axis, projected onto the x axis.
yThe desired end effector z axis, projected onto the y axis.
zThe desired end effector z axis, projected onto the z axis.
Returns
HebiStatusSuccess on success, otherwise a failure code (e.g. incompatible with existing objectives, or rotation matrix is invalid.)
void hebiIKClearAll ( HebiIKPtr  ik)

Clears the objectives and constraints from this IK object, along with any modifications to the default algorithm parameters.

HebiIKPtr hebiIKCreate ( void  )

Creates an IK (inverse kinematics) object that allows for solving for joint angles/positions given objectives and constraints.

This optimization is completed using a specified forward kinematics object. The objectives and constraints are stored with this object.

void hebiIKRelease ( HebiIKPtr  ik)

Frees resources created by this inverse kinematics object.

IK object should no longer be used after this function is called!

Parameters
ikA valid HEBI inverse kinematics object.
HebiStatusCode hebiIKSolve ( HebiIKPtr  ik,
HebiRobotModelPtr  model,
const double *  initial_positions,
double *  ik_solution,
void *  result_info 
)

Solves for an inverse kinematics solution that moves the end effector to a given point.

Note: multiple "hebiIKSolve" calls can be made using the same IK object.

Parameters
ikA valid HEBI IK object.
modelA valid HEBI RobotModel object.
initial_positionsThe seed positions/angles (in SI units of meters or radians) to start the IK search from; equal in length to the number of DoFs of the kinematic tree. Must not be NULL.
ik_solutionAllocated array of doubles equal in length to the number of DoFs of the kinematic tree; the function will fill in this array with the IK solution (in SI units of meters or radians). Must not be NULL.
result_infoReserved for future use (will enable more information about output of optimization such as success/failure, function error, etc). This should currently be set to NULL.
Returns
HebiStatusSuccess on success, other values on failure (e.g., no objectives given or dimension mismatch between kinematics object and stored objectives).
HebiStatusCode hebiInfoGetBool ( HebiInfoPtr  info,
HebiInfoBoolField  field,
int32_t *  value 
)

If the specified value is set, writes the value of the field to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

The value written to the pointer will be 1 for true and 0 for false.

HebiStatusCode hebiInfoGetEnum ( HebiInfoPtr  info,
HebiInfoEnumField  field,
int32_t *  value 
)

If the specified value is set, writes the value of the field to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

int32_t hebiInfoGetFlag ( HebiInfoPtr  info,
HebiInfoFlagField  field 
)

Checks whether this flag is set. Returns '1' for yes, '0' for no.

HebiStatusCode hebiInfoGetFloat ( HebiInfoPtr  info,
HebiInfoFloatField  field,
float *  value 
)

If the specified value is set, writes the value of the field to the pointer (if not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiInfoGetHighResAngle ( HebiInfoPtr  ,
HebiInfoHighResAngleField  ,
int64_t *  int_part,
float *  dec_part 
)

If the specified value is set, writes the value of the field to the pointers (if both are not NULL), and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

HebiStatusCode hebiInfoGetLedColor ( HebiInfoPtr  info,
HebiInfoLedField  field,
uint8_t *  r,
uint8_t *  g,
uint8_t *  b 
)

If the led color is set, writes it to the three output integer pointers (if all are not NULL), each 0-255, and returns HebiStatusSuccess. Otherwise, returns HebiStatusValueNotSet.

For command-style messages, this refers to the color to override the module's default control of the LED.

HebiStatusCode hebiInfoGetString ( HebiInfoPtr  info,
HebiInfoStringField  field,
char *  buffer,
size_t *  length 
)

Retrieves the value and/or the length of the string field.

If this string is not set in the Info, HebiStatusValueNotSet is returned (regardless of any other arguments) and any pointer values are unchanged.

If 'length' is NULL, returns HebiStatusValueSuccess if this string value is set (the value of 'buffer' is ignored in this case).

If 'buffer' is not NULL, then 'length' should be non-NULL and set to the number of characters that can be written to 'buffer'. If the specified string is set, and it can fit into the provided buffer (including a null terminating character), then the string is copied to 'buffer' and HebiStatusSuccess is returned. If the buffer is not large enough to contain the string, then HebiStatusBufferTooSmall is returned.

If 'buffer' is NULL, returns HebiStatusValueSuccess if this string value is set.

If 'length' is not NULL (regardless of the state of 'buffer'), it is set to the necessary size to hold the specified string value (including the null terminating character).

Note - assumes ASCII string encoding.

HebiStatusCode hebiLogFileGetFileName ( HebiLogFilePtr  log_file,
char *  buffer,
size_t *  length 
)

Copy the path and name of the log file into a buffer.

To only query the length of the string, provide a null pointer for the buffer parameter. If the provided buffer is not large enough to hold the string (the length determined by the length parameter), the call will fail. Note that the size of this buffer includes the null terminating character.

Parameters
bufferPointer to a buffer into which the string will be written. This can be null, in which case this function will write the size of the string (including null character) into length.
lengthPointer to the length of the input buffer. This parameter must not be null, or this function will return HebiStatusInvalidArgument
Returns
HebiStatusSuccess on success, HebiStatusBufferTooSmall if the value referenced by length is smaller than the string (including the character), or HebiStatusInvalidArgument if length pointer is null
HebiStatusCode hebiLogFileGetNextFeedback ( HebiLogFilePtr  log_file,
HebiGroupFeedbackPtr  field 
)

Retrieve the next group feedback from the opened log file.

Parameters
feedbackthe feedback object into which the contents will be copied
Returns
HebiStatusSuccess on success, otherwise HebiStatusFailure
size_t hebiLogFileGetNumberOfModules ( HebiLogFilePtr  log_file)

Retrieve the number of modules in the group represented by an opened log file.

Returns
The number of modules in the group
HebiLogFilePtr hebiLogFileOpen ( const char *  file)

Opens an existing log file.

Note: It is up to the user to check if the returned pointer is null. If the file does not exist, or if the file is not a valid log file, this function returns null.

If this function returns a pointer, you must call hebiLogFileRelease(HebiLogFilePtr) to release the allocated memory.

Parameters
filethe directory and path of the file to open. Must not be NULL.
Returns
a pointer to the file; null if the file could not be opened
void hebiLogFileRelease ( HebiLogFilePtr  log_file)

Releases a log file instance.

HebiLookupPtr hebiLookupCreate ( void  )

Create a Lookup instance.

Lookup created by this function must be released with 'hebiLookupRelease' when no longer needed.

Note that this call invokes a background thread to query the network for modules at regular intervals.

HebiStatusCode hebiLookupEntryListGetFamily ( HebiLookupEntryListPtr  lookup_list,
size_t  index,
char *  buffer,
size_t *  length 
)

Gets the family of the given entry in the lookup entry list. Must be a valid index.

To only query the length of the string, provide a null pointer for the buffer parameter. If the provided buffer is not large enough to hold the string (the length determined by the length parameter), the call will fail. Note that the size of this buffer includes the null terminating character.

Note - assumes ASCII string encoding.

Parameters
lookup_listA valid HebiLookupEntryList object.
indexThe entry index that is being queried.
bufferAn allocated buffer of length 'length'.
lengththe length of the provided buffer. After calling this function, the value dereferenced will be updated with the length of the string plus the null character. This argument must not be NULL.
Returns
HebiStatusSuccess on success, HebiStatusBufferTooSmall if the provided buffer is too small, or HebiStatusInvalidArgument if the length parameter is null
HebiStatusCode hebiLookupEntryListGetMacAddress ( HebiLookupEntryListPtr  lookup_list,
size_t  index,
HebiMacAddress mac_address 
)
Parameters
lookup_listA valid HebiLookupEntryList object.
indexThe entry index that is being queried.
mac_addressA pointer to an allocated HebiMacAddress structure that the function will update with the mac address of the given entry.
Returns
HebiStatusSuccess on success, HebiStatusInvalidArgument if the mac_address parameter is null, or HebiStatusArgumentOutOfRange if there is no entry with the given index.
HebiStatusCode hebiLookupEntryListGetName ( HebiLookupEntryListPtr  lookup_list,
size_t  index,
char *  buffer,
size_t *  length 
)

Gets the name of the given entry in the lookup entry list. Must be a valid index.

To only query the length of the string, provide a null pointer for the buffer parameter. If the provided buffer is not large enough to hold the string (the length determined by the length parameter), the call will fail. Note that the size of this buffer includes the null terminating character.

Note - assumes ASCII string encoding.

Parameters
lookup_listA valid HebiLookupEntryList object.
indexThe entry index that is being queried.
bufferAn allocated buffer of length 'length'
lengththe length of the provided buffer. After calling this function, the value dereferenced will be updated with the length of the string plus the null character. This argument must not be NULL.
Returns
HebiStatusSuccess on success, HebiStatusBufferTooSmall if the provided buffer is too small, or HebiStatusInvalidArgument if the length parameter is null
size_t hebiLookupEntryListGetSize ( HebiLookupEntryListPtr  lookup_list)

Gets the number of entries in the lookup entry list.

Parameters
lookup_listA valid HebiLookupEntryList object.
void hebiLookupEntryListRelease ( HebiLookupEntryListPtr  lookup_list)

Release resources for a given lookup entry list; list should not be used after this call.

Parameters
lookup_listA valid HebiLookupEntryList object.
void hebiLookupRelease ( HebiLookupPtr  lookup)

Frees resources created by the lookup object.

Lookup object should no longer be used after this function is called! Note that background query thread is stopped by this function.

HebiStatusCode hebiRobotModelAdd ( HebiRobotModelPtr  robot_model,
HebiRobotModelElementPtr  existing_element,
size_t  output_index,
HebiRobotModelElementPtr  new_element,
int32_t  combine 
)

Add an element to a parent element connected to a robot model object.

After the addition, the robot model object manages the resources of the added element.

The added element is assumed to connect to an available output on a element that has already been attached to the kinematic tree. That element should be passed in as 'existing_element', and the index of the requested output on that element should be given as 'output_index'.

To attach the initial element to the robot model object, use NULL for the 'existing_element' argument.

NOTE: currently, only a single output is supported for each element (e.g., a kinematic chain), and so the 'existing_element' and 'output_index' parameters are not checked; this will be changed in an upcoming minor release so do not rely on this behavior!

Parameters
robot_modelA valid HEBI RobotModel object.
existing_elementThe parent element which the element is added to (or NULL to add the initial element to the tree).
output_indexThe index of the requested output on the parent element on which to attach this element.
new_elementThe kinematic element which is added to the tree. Must not be NULL.
combineWhether or not to combine this with the output frame where this is being attached to, essentially "hiding" this existing output frame from returned frames and replacing it with the output from this. Body masses and inertias are also combined. '1' means combine; '0' means do not combine.
Returns
HebiStatusSuccess on success, otherwise HebiStatusFailure (e.g., the parent body's requested output is invalid or already occupied) or HebiStatusInvalidArgument (e.g., 'new_element' is NULL).
HebiRobotModelPtr hebiRobotModelCreate ( void  )

Creates an object to hold a robot model (tree topology). This structure has a single output available at the origin.

RobotModel object created by this function must be released with 'hebiRobotModelRelease' when no longer needed.

HebiRobotModelElementPtr hebiRobotModelElementCreateJoint ( HebiJointType  joint_type)

Creates a one-dof joint about the specified axis.

Parameters
joint_typeWhat the axis of motion for this joint is. The coordinate frame is relative to the previous robot model element this is attached to.
Returns
NULL if the joint could not be created; otherwise, pointer to newly allocated joint. Must either be added to a robot model object or released via hebiRobotModelElementRelease(HebiRobotModelElementPtr).
HebiRobotModelElementPtr hebiRobotModelElementCreateRigidBody ( const double *  com,
const double *  inertia,
double  mass,
size_t  num_outputs,
const double *  outputs 
)

Creates a rigid body defining static transforms to the given outputs.

Parameters
comMatrix (4x4 tranform, row major order) for the center of mass location, including the frame which the inertia tensor is given in. Must not be NULL.
inertiaVector (6 elements, Ixx, Iyy, Izz, Ixy, Ixz, Iyz) of the inertia tensor, in the frame given by the COM. Must not be NULL.
massMass (in kg) of the rigid body.
num_outputsThe number of available outputs.
outputsMatrices (list of n 4x4 transforms, row major order) of the transforms from input to the available outputs of the body. Must not be NULL unless num_outputs is 0.

NOTE: currently, num_outputs must be 1.

Returns
NULL if the rigid body could not be created; otherwise, pointer to newly allocated body. Must either be added to a robot model object or released via 'hebiRobotModelElementRelease'.
void hebiRobotModelElementRelease ( HebiRobotModelElementPtr  element)

Frees resources created by this element.

Note: Only do this if element has not been added to a robot model object! Once added, the robot model object manages the element's resources.

The element should no longer be used after this function is called.

Parameters
Avalid robot model element object which has not been added to a robot_model object.
HebiStatusCode hebiRobotModelGetBaseFrame ( HebiRobotModelPtr  robot_model,
double *  transform 
)

Retreives the fixed transform from the origin to the input of the first added model element.

Parameters
robot_modelA valid HEBI RobotModel object.
transformA allocated 16 element array of doubles; this is filled in by the function with the 4x4 homogeneous transform in row major order. Must not be NULL.
Returns
HebiStatusSuccess on success, or HebiStatusInvalidArgument if transform is null.
HebiStatusCode hebiRobotModelGetForwardKinematics ( HebiRobotModelPtr  robot_model,
HebiFrameType  frame_type,
const double *  positions,
double *  frames 
)

Generates the transforms for the forward kinematics of the given robot model.

The order of the returned frames is in a depth-first tree. As an example, assume an element A has one output, to which element B is connected to. Element B has two outputs; C is attached to the first output and E is attached to the second output. Element D is attached to the only output of element C:

(BASE) A - B(1) - C - D (2) | E

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.

For end effector frames, the returned frames are the outputs of the leaf nodes; here the output of D and E.

Parameters
robot_modelA valid HEBI RobotModel object.
frame_typeWhich type of frame to consider – see HebiFrameType enum.
positionsA vector of joint positions/angles (in SI units of meters or radians) equal in length to the number of DoFs of the robot model. Must not be NULL.
framesAn allocated (16 x number of frames) array of doubles; this is filled in by the function with the 4x4 homogeneous transform of each frame, each given in row major order. Note that the number of frames depends on the frame type! Must not be NULL.
Returns
HebiStatusSuccess on success, or HebiStatusInvalidArgument if positions or frames are NULL.
HebiStatusCode hebiRobotModelGetJacobians ( HebiRobotModelPtr  robot_model,
HebiFrameType  frame_type,
const double *  positions,
double *  jacobians 
)

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

Parameters
robot_modelA valid HEBI RobotModel object.
frame_typeWhich type of frame to consider – see HebiFrameType enum.
positionsA vector of joint positions/angles (in SI units of meters or radians) equal in length to the number of DoFs of the robot model. Must not be NULL.
jacobiansAn allocated (6 x number of dofs x number of frames) array of doubles; this is filled in by the function with the 6 x number of dofs jacobian for each frame, each given in row major order. Note that the number of frames depends on the frame type! Must not be NULL.
Returns
HebiStatusSuccess on success, or HebiStatusInvalidArgument if positions or jacobians are NULL.
HebiStatusCode hebiRobotModelGetMasses ( HebiRobotModelPtr  robot_model,
double *  masses 
)

Fill in the masses vector with the mass of each body with mass in the kinematic tree, reported in a depth-first ordering.

Parameters
robot_modelA valid HEBI RobotModel object.
massesAn allocated array of doubles, with length equal to the return value of hebiRobotModelGetNumberOfFrames with argument HebiFrameTypeCenterOfMass. Must not be NULL.
Returns
HebiStatusSuccess on success, or HebiStatusInvalidArgument if masses is NULL.
size_t hebiRobotModelGetNumberOfDoFs ( HebiRobotModelPtr  robot_model)

Returns the number of settable degrees of freedom in the kinematic tree. (This is equal to the number of joints added).

Parameters
robot_modelA valid HEBI RobotModel object.
size_t hebiRobotModelGetNumberOfFrames ( HebiRobotModelPtr  robot_model,
HebiFrameType  frame_type 
)

Return the number of frames in the forward kinematic tree of the robot model.

Note that this depends on the type of frame requested – for center of mass frames, there is one per added rigid body (that was not combined with another); for output frames, there is one per output per element. For end effectors, this is the total number of outputs on the leaves of the kinematic tree.

Parameters
robot_modelA valid HEBI RobotModel object.
frame_typeWhich type of frame to consider – see HebiFrameType enum.
void hebiRobotModelRelease ( HebiRobotModelPtr  robot_model)

Frees resources created by this robot model object.

RobotModel object should no longer be used after this function is called!

Parameters
robot_modelA valid HEBI RobotModel object.
HebiStatusCode hebiRobotModelSetBaseFrame ( HebiRobotModelPtr  robot_model,
const double *  transform 
)

Sets the fixed transform from the origin to the input of the first added model element.

Parameters
robot_modelA valid HEBI RobotModel object.
transformA 4x4 homogeneous transform, in row major order. Must not be null, and must be a valid transform.
Returns
HebiStatusSuccess on success, or HebiStatusInvalidArgument if transform is null or invalid.
HebiStatusCode hebiStringGetString ( HebiStringPtr  str,
char *  buffer,
size_t *  length 
)

Copy the string into a buffer.

To only query the length of the string, provide a null pointer for the buffer parameter. If the provided buffer is not large enough to hold the string (the length determined by the length parameter), the call will fail. Note that the size of this buffer includes the null terminating character.

Parameters
bufferPointer to a buffer into which the string will be written. This can be null, in which case this function will write the size of the string (including null character) into length.
lengthPointer to the length of the input buffer. This parameter must not be null, or this function will return HebiStatusInvalidArgument
Returns
HebiStatusSuccess on success, HebiStatusBufferTooSmall if the value referenced by length is smaller than the string (including the character), or HebiStatusInvalidArgument if length pointer is null
void hebiStringRelease ( HebiStringPtr  str)

Releases a string instance.

HebiTrajectoryPtr hebiTrajectoryCreateUnconstrainedQp ( size_t  num_waypoints,
const double *  positions,
const double *  velocities,
const double *  accelerations,
const double *  time_vector 
)

Creates a HebiTrajectory object for a single joint using the given parameters; this must be released with hebiTrajectoryRelease after use.

Parameters
num_waypointsThe number of waypoints.
positionsA vector of waypoints for this joint; should be num_waypoints in length. Any elements that are NAN will be considered free parameters, and will be set by the function. Values of +/-infinity are not allowed. Must not be NULL.
velocitiesAn optional vector of velocity constraints at the corresponding waypoints; should either be NULL or num_waypoints in length. Any elements that are NAN will be considered free parameters, and will be set by the function. Values of +/-infinity are not allowed.
accelerationsAn optional vector of acceleration constraints at the corresponding waypoints; should either be NULL or num_waypoints in length. Any elements that are NAN will be considered free parameters, and will be set by the function. Values of +/-infinity are not allowed.
time_vectorA vector of times to reach each waypoint; this must be defined (not NULL, and not NAN for any element). The first element must be zero.
Returns
A HebiTrajectory object if there were no errors, and the trajectory has been created. A NULL value indicates that there was an error, but does not specify any details about the error at this time.
double hebiTrajectoryGetDuration ( HebiTrajectoryPtr  trajectory)

Returns the length of this trajectory (in seconds).

HebiStatusCode hebiTrajectoryGetState ( HebiTrajectoryPtr  trajectory,
double  time,
double *  position,
double *  velocity,
double *  acceleration 
)

Gets the value of the trajectory at a given time.

Parameters
trajectoryA HebiTrajectory object
timeThe time within the trajectory (from the beginning to the end of the trajectory's time vector) at which to query.
positionFilled in with the position at the given time, as defined by this trajectory. Must not be null.
velocityFilled in with the velocity at the given time, as defined by this trajectory. Must not be null.
accelerationFilled in with the acceleration at the given time, as defined by this trajectory. Must not be null.
Returns
HebiStatusSuccess on success, otherwise an error status.
void hebiTrajectoryRelease ( HebiTrajectoryPtr  trajectory)

Frees resources created by this trajectory.

Trajectory should no longer be used after this function is called!



hebiros
Author(s): Xavier Artache , Matthew Tesch
autogenerated on Thu Sep 3 2020 04:09:49