#include <math.h>
#include <stddef.h>
#include <stdint.h>
Go to the source code of this file.
Classes | |
struct | _HebiMacAddress |
struct | _HebiQuaternionf |
struct | _HebiVector3f |
Macros | |
#define | M_PI 3.14159265358979323846 |
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... | |
typedef void(* GroupFeedbackHandlerFunction) (HebiGroupFeedbackPtr fbk, void *user_data) |
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 struct _HebiCommand* HebiCommandPtr |
typedef enum HebiCommandStringField HebiCommandStringField |
typedef enum HebiFeedbackEnumField HebiFeedbackEnumField |
typedef enum HebiFeedbackFloatField HebiFeedbackFloatField |
typedef enum HebiFeedbackIoPinBank HebiFeedbackIoPinBank |
typedef enum HebiFeedbackLedField HebiFeedbackLedField |
typedef struct _HebiFeedback* HebiFeedbackPtr |
typedef enum HebiFeedbackQuaternionfField HebiFeedbackQuaternionfField |
typedef enum HebiFeedbackUInt64Field HebiFeedbackUInt64Field |
typedef enum HebiFeedbackVector3fField HebiFeedbackVector3fField |
typedef enum HebiFrameType HebiFrameType |
Which frame to report results in (e.g., for getForwardKinematics and other functions.
typedef struct _HebiGroupCommand* HebiGroupCommandPtr |
typedef struct _HebiGroupFeedback* HebiGroupFeedbackPtr |
typedef struct _HebiGroupInfo* HebiGroupInfoPtr |
typedef struct _HebiGroup* HebiGroupPtr |
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 |
typedef enum HebiInfoStringField HebiInfoStringField |
typedef enum HebiJointType HebiJointType |
What the type of motion (axis, rotation, translation, etc) is allowed by a joint.
typedef struct _HebiLogFile* HebiLogFilePtr |
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 |
typedef struct _HebiTrajectory* HebiTrajectoryPtr |
typedef struct _HebiVector3f HebiVector3f |
enum HebiCommandBoolField |
enum HebiCommandEnumField |
enum HebiCommandFlagField |
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. |
enum HebiCommandIoPinBank |
enum HebiCommandLedField |
enum HebiFeedbackLedField |
enum HebiFrameType |
enum HebiInfoBoolField |
enum HebiInfoEnumField |
enum HebiInfoFlagField |
enum HebiInfoFloatField |
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). |
enum HebiInfoLedField |
enum HebiInfoStringField |
enum HebiJointType |
enum HebiStatusCode |
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. |
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.
lookup | A 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.
void hebiGroupClearFeedbackHandlers | ( | HebiGroupPtr | group | ) |
Removes all feedback handling functions from the queue to be called on receipt of group feedback.
group | The 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.
dest | The GroupCommandPtr to copy data into. The previous state of this object will be cleared. |
src | The GroupCommandPtr to copy data from. This object will remain unchanged. |
HebiGroupCommandPtr hebiGroupCommandCreate | ( | size_t | size | ) |
Creates a GroupCommand for a group with the specified number of modules.
size | The number of modules in the group. |
HebiCommandPtr hebiGroupCommandGetModuleCommand | ( | HebiGroupCommandPtr | cmd, |
size_t | module_index | ||
) |
Get an individual command for a particular module at index module_index
.
module_index | The index to retrieve the module command; must be from 0 to the size - 1, inclusive, or results in undefined behavior. |
size_t hebiGroupCommandGetSize | ( | HebiGroupCommandPtr | cmd | ) |
Return the number of modules in this group Command.
HebiStatusCode hebiGroupCommandReadGains | ( | HebiGroupCommandPtr | cmd, |
const char * | file | ||
) |
Import gains from a file into a GroupCommand object.
file | A null-terminated string that gives the path/filename of the gains XML file. Must not be NULL. |
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.
file | A null-terminated string that gives the path/filename to save the gains XML file at. Must not be NULL. |
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.
lookup | A valid HebiLookup object. |
address | Pointer to a HebiMacAddress structure representing the physical mac address of the given module (serves as unique id). Must not be NULL. |
timeout_ms | Timeout 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. |
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.
lookup | A valid HebiLookup object. |
name | The given name of the key module, as viewable in the HEBI GUI. Must be a null-terminated string, and must not be NULL. |
family | The given family of the key module, as viewable in the HEBI GUI. Must be a null-terminated string, and must not be NULL. |
timeout_ms | Timeout 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. |
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.
lookup | A valid HebiLookup object. |
family | The given family of the modules, as viewable in the HEBI GUI. Must be a null-terminated string, and must not be NULL. |
timeout_ms | Timeout 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. |
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.
lookup | A valid HebiLookup object. |
addresses | An 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_addresses | Length of the addresses array of pointers (number of pointers in the array, not cumulative size of objects they point to). |
timeout_ms | Timeout 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. |
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.
lookup | A valid HebiLookup object. |
families | The 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_families | The 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. |
names | The 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_names | The number of pointers to null-terminated strings given by the names parameter. |
timeout_ms | Timeout 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. |
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.
size | The number of modules in the group. |
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.
dest | The GroupFeedbackPtr to copy data into. The previous state of this object will be cleared. |
src | The GroupFeedbackPtr to copy data from. This object will remain unchanged. |
HebiGroupFeedbackPtr hebiGroupFeedbackCreate | ( | size_t | size | ) |
Creates a GroupFeedback for a group with the specified number of modules.
size | The number of modules in the group. |
HebiFeedbackPtr hebiGroupFeedbackGetModuleFeedback | ( | HebiGroupFeedbackPtr | fbk, |
size_t | module_index | ||
) |
Get an individual feedback for a particular module at index module_index
.
module_index | The index to retrieve the module feedback; must be from 0 to the size - 1, inclusive, or results in undefined behavior. |
size_t hebiGroupFeedbackGetSize | ( | HebiGroupFeedbackPtr | fbk | ) |
Return the number of modules 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.
group | Which group is being queried. |
float hebiGroupGetFeedbackFrequencyHz | ( | HebiGroupPtr | group | ) |
Returns the current feedback request loop frequency (in Hz).
group | Which group is being queried. |
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!
group | The group to return feedback from. |
feedback | On success, the feedback read from the group are written into this structure. |
timeout_ms | Indicates 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. |
size_t hebiGroupGetSize | ( | HebiGroupPtr | group | ) |
Returns the number of modules in a group.
group | The group to send this command to. |
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.
dest | The GroupInfoPtr to copy data into. The previous state of this object will be cleared. |
src | The GroupInfoPtr to copy data from. This object will remain unchanged. |
HebiGroupInfoPtr hebiGroupInfoCreate | ( | size_t | size | ) |
Creates a GroupInfo for a group with the specified number of modules.
size | The number of modules in the group. |
HebiInfoPtr hebiGroupInfoGetModuleInfo | ( | HebiGroupInfoPtr | info, |
size_t | module_index | ||
) |
Get an individual info for a particular module at index module_index
.
module_index | The index to retrieve the module info; must be from 0 to the size - 1, inclusive, or results in undefined behavior. |
size_t hebiGroupInfoGetSize | ( | HebiGroupInfoPtr | info | ) |
Return the number of modules 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.
file | A null-terminated string that gives the path/filename to save the gains XML file at. Must not be NULL. |
HebiStatusCode hebiGroupRegisterFeedbackHandler | ( | HebiGroupPtr | group, |
GroupFeedbackHandlerFunction | handler, | ||
void * | user_data | ||
) |
Add a function that is called whenever feedback is returned from the group.
void hebiGroupRelease | ( | HebiGroupPtr | group | ) |
Release resources for a given group; group should not be used after this call.
group | A 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!
group | The group to send this command to. |
info | On success, the info read from the group is written into this structure. |
timeout_ms | Indicates 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. |
HebiStatusCode hebiGroupSendCommand | ( | HebiGroupPtr | group, |
HebiGroupCommandPtr | command | ||
) |
Sends a command to the given group without requesting an acknowledgement.
Appropriate for high-frequency applications.
group | The group to send this command to. |
command | The HebiGroupCommand object containing information to be sent to the group. |
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.
group | The group to send this command to. |
command | The HebiGroupCommand object containing information to be sent to the group. |
timeout_ms | Indicates 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. |
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).
group | The group to return feedback from. |
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.
group | Which group the command lifetime is being set for. |
lifetime_ms | The 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. |
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.
group | Which group this frequency set is for. |
frequency | The feedback request loop frequency (in Hz). A value of '0' is the default, and disables the feedback request thread. |
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)
dir | The relative or absolute path to the directory in which to log. To use the current directory, pass in a null pointer |
file | The optional file name. If this is null, a name will be created using the time at the moment which this function was invoked. |
ret | The 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. |
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)
group | The group that is logging. |
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.
weight | The 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_joints | The number of elements in the min_positions and max_positions arrays. |
min_positions | An 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_positions | An 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. |
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.
weight | The 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_errors | The number of independent error values that this objective returns. |
err_fnc | The 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.
weight | The 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. |
x | The desired x position of the end effector frame. 'NaN' can be passed to ignore this variable. |
y | The desired y position of the end effector frame. 'NaN' can be passed to ignore this variable. |
z | The desired z position of the end effector frame. 'NaN' can be passed to ignore this variable. |
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.
weight | The 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. |
matrix | The desired orientation of the end effector frame, as a 3x3 rotation matrix in row major order. Must not be 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.
weight | The 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. |
x | The desired end effector z axis, projected onto the x axis. |
y | The desired end effector z axis, projected onto the y axis. |
z | The desired end effector z axis, projected onto the z axis. |
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!
ik | A 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.
ik | A valid HEBI IK object. |
model | A valid HEBI RobotModel object. |
initial_positions | The 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_solution | Allocated 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_info | Reserved 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. |
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.
buffer | Pointer 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. |
length | Pointer to the length of the input buffer. This parameter must not be null, or this function will return HebiStatusInvalidArgument |
HebiStatusCode hebiLogFileGetNextFeedback | ( | HebiLogFilePtr | log_file, |
HebiGroupFeedbackPtr | field | ||
) |
Retrieve the next group feedback from the opened log file.
feedback | the feedback object into which the contents will be copied |
size_t hebiLogFileGetNumberOfModules | ( | HebiLogFilePtr | log_file | ) |
Retrieve the number of modules in the group represented by an opened log file.
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.
file | the directory and path of the file to open. Must not be NULL. |
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.
lookup_list | A valid HebiLookupEntryList object. |
index | The entry index that is being queried. |
buffer | An allocated buffer of length 'length'. |
length | the 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. |
HebiStatusCode hebiLookupEntryListGetMacAddress | ( | HebiLookupEntryListPtr | lookup_list, |
size_t | index, | ||
HebiMacAddress * | mac_address | ||
) |
lookup_list | A valid HebiLookupEntryList object. |
index | The entry index that is being queried. |
mac_address | A pointer to an allocated HebiMacAddress structure that the function will update with the mac address of the given entry. |
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.
lookup_list | A valid HebiLookupEntryList object. |
index | The entry index that is being queried. |
buffer | An allocated buffer of length 'length' |
length | the 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. |
size_t hebiLookupEntryListGetSize | ( | HebiLookupEntryListPtr | lookup_list | ) |
Gets the number of entries in the lookup entry list.
lookup_list | A valid HebiLookupEntryList object. |
void hebiLookupEntryListRelease | ( | HebiLookupEntryListPtr | lookup_list | ) |
Release resources for a given lookup entry list; list should not be used after this call.
lookup_list | A 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!
robot_model | A valid HEBI RobotModel object. |
existing_element | The parent element which the element is added to (or NULL to add the initial element to the tree). |
output_index | The index of the requested output on the parent element on which to attach this element. |
new_element | The kinematic element which is added to the tree. Must not be NULL. |
combine | Whether 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. |
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.
joint_type | What the axis of motion for this joint is. The coordinate frame is relative to the previous robot model element this is attached to. |
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.
com | Matrix (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. |
inertia | Vector (6 elements, Ixx, Iyy, Izz, Ixy, Ixz, Iyz) of the inertia tensor, in the frame given by the COM. Must not be NULL. |
mass | Mass (in kg) of the rigid body. |
num_outputs | The number of available outputs. |
outputs | Matrices (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.
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.
A | valid 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.
robot_model | A valid HEBI RobotModel object. |
transform | A 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. |
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.
robot_model | A valid HEBI RobotModel object. |
frame_type | Which type of frame to consider – see HebiFrameType enum. |
positions | A 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. |
frames | An 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. |
HebiStatusCode hebiRobotModelGetJacobians | ( | HebiRobotModelPtr | robot_model, |
HebiFrameType | frame_type, | ||
const double * | positions, | ||
double * | jacobians | ||
) |
Generates the jacobian for each frame in the given kinematic tree.
robot_model | A valid HEBI RobotModel object. |
frame_type | Which type of frame to consider – see HebiFrameType enum. |
positions | A 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. |
jacobians | An 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. |
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.
robot_model | A valid HEBI RobotModel object. |
masses | An allocated array of doubles, with length equal to the return value of hebiRobotModelGetNumberOfFrames with argument HebiFrameTypeCenterOfMass. Must not be 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).
robot_model | A 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.
robot_model | A valid HEBI RobotModel object. |
frame_type | Which 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!
robot_model | A 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.
robot_model | A valid HEBI RobotModel object. |
transform | A 4x4 homogeneous transform, in row major order. Must not be null, and must be a valid transform. |
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.
buffer | Pointer 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. |
length | Pointer to the length of the input buffer. This parameter must not be null, or this function will return HebiStatusInvalidArgument |
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.
num_waypoints | The number of waypoints. |
positions | A 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. |
velocities | An 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. |
accelerations | An 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_vector | A 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. |
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.
trajectory | A HebiTrajectory object |
time | The time within the trajectory (from the beginning to the end of the trajectory's time vector) at which to query. |
position | Filled in with the position at the given time, as defined by this trajectory. Must not be null. |
velocity | Filled in with the velocity at the given time, as defined by this trajectory. Must not be null. |
acceleration | Filled in with the acceleration at the given time, as defined by this trajectory. Must not be null. |
void hebiTrajectoryRelease | ( | HebiTrajectoryPtr | trajectory | ) |
Frees resources created by this trajectory.
Trajectory should no longer be used after this function is called!