12 #define M_PI 3.14159265358979323846 585 size_t num_addresses, int32_t timeout_ms);
621 const char*
const* names,
size_t num_names, int32_t timeout_ms);
1140 void hebiCommandSetFloat(HebiCommandPtr cmd, HebiCommandFloatField field,
const float* value);
1147 int64_t* int_part,
float* dec_part);
1153 const int64_t* int_part,
const float* dec_part);
1160 size_t number,
float* value);
1166 const float* value);
1180 void hebiCommandSetBool(HebiCommandPtr cmd, HebiCommandBoolField field,
const int32_t* value);
1221 void hebiCommandSetString(HebiCommandPtr cmd, HebiCommandStringField field,
const char* buffer,
1222 const size_t* length);
1232 void hebiCommandSetFlag(HebiCommandPtr cmd, HebiCommandFlagField field, int32_t value);
1243 void hebiCommandSetEnum(HebiCommandPtr cmd, HebiCommandEnumField field,
const int32_t* value);
1264 const int64_t* value);
1271 const float* value);
1322 int64_t* int_part,
float* dec_part);
1329 size_t number,
float* value);
1356 HebiFeedbackQuaternionfField field,
1381 uint8_t* g, uint8_t*
b);
1399 int64_t* int_part,
float* dec_part);
1496 double mass,
size_t num_outputs,
1497 const double* outputs);
1607 size_t output_index, HebiRobotModelElementPtr new_element, int32_t combine);
1645 const double* positions,
double* frames);
1664 const double* positions,
double* jacobians);
1722 double x,
double y,
double z);
1742 const double* matrix);
1763 double x,
double y,
double z);
1785 const double* min_positions,
const double* max_positions);
1812 void(*err_fnc)(
void* user_data,
1813 size_t num_positions,
1814 const double* positions,
1846 double* ik_solution,
void* result_info);
1887 const double* velocities,
const double* accelerations,
1888 const double* time_vector);
1918 double* velocity,
double* acceleration);
Ambient temperature inside the module (measured at the IMU chip), in degrees Celsius.
Sets the name for this module. Name must be null-terminated character string for the name; must be <=...
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 ...
HebiFeedbackQuaternionfField
Integral PID gain for position.
HebiStatusCode hebiGroupCommandWriteGains(HebiGroupCommandPtr cmd, const char *file)
Export gains from a GroupCommand object into a file.
void hebiStringRelease(HebiStringPtr str)
Releases a string instance.
Timestamp of when message was received from module (local)
void hebiGroupFeedbackClear(HebiGroupFeedbackPtr fbk)
Clears all data in the GroupFeedback object.
void hebiCommandSetLedOverrideColor(HebiCommandPtr cmd, HebiCommandLedField field, uint8_t r, uint8_t g, uint8_t b)
HebiLogFilePtr hebiLogFileOpen(const char *file)
Opens an existing log file.
HebiStatusCode hebiCommandGetNumberedFloat(HebiCommandPtr cmd, HebiCommandNumberedFloatField field, size_t number, float *value)
Returned when an accessor function attempts to retrieve a field which is not set. ...
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 incomp...
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.
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 ...
HebiLogFilePtr hebiGroupStopLog(HebiGroupPtr group)
Stops logging data to a file.
The spring constant of the module.
void hebiIKRelease(HebiIKPtr ik)
Frees resources created by this inverse kinematics object.
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Derivative PID gain for velocity.
HebiStatusCode hebiLogFileGetFileName(HebiLogFilePtr log_file, char *buffer, size_t *length)
Copy the path and name of the log file into a buffer.
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.
HebiStatusCode hebiGroupSendCommand(HebiGroupPtr group, HebiGroupCommandPtr command)
Sends a command to the given group without requesting an acknowledgement.
struct _HebiLookupEntryList * HebiLookupEntryListPtr
HebiCommandHighResAngleField
void hebiCommandSetBool(HebiCommandPtr cmd, HebiCommandBoolField field, const int32_t *value)
Boot the module from bootloader into application.
HebiStatusCode hebiCommandGetIoPinFloat(HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number, float *value)
void hebiCommandClearLed(HebiCommandPtr cmd, HebiCommandLedField field)
Difference (in radians) between the pre-spring and post-spring output position.
HebiFeedbackVector3fField
HebiStatusCode hebiRobotModelGetJacobians(HebiRobotModelPtr robot_model, HebiFrameType frame_type, const double *positions, double *jacobians)
Generates the jacobian for each frame in the given kinematic tree.
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
Feed forward term for effort (this term is multiplied by the target and added to the output)...
HebiStatusCode hebiInfoGetFloat(HebiInfoPtr info, HebiInfoFloatField field, float *value)
Output from the PID controller is limited to a maximum of this value.
HebiStatusCode hebiGroupInfoCopy(HebiGroupInfoPtr dest, HebiGroupInfoPtr src)
Clears the dest GroupInfo object, and copies all data from the src GroupInfo object to dest...
Set the firmware safety limit for the minimum allowed position.
struct _HebiQuaternionf HebiQuaternionf
int32_t hebiInfoGetFlag(HebiInfoPtr info, HebiInfoFlagField field)
A buffer supplied to the routine was too small (normally determined by a size parameter) ...
HebiStatusCode hebiGroupStartLog(HebiGroupPtr group, const char *dir, const char *file, HebiStringPtr *ret)
Starts logging data to a file.
Software-controlled bounds on the allowable position of the module; user settable.
Output from the PID controller is limited to a minimum of this value.
struct _HebiGroup * HebiGroupPtr
The C-style's API representation of a group.
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
HebiRobotModelElementPtr hebiRobotModelElementCreateJoint(HebiJointType joint_type)
Creates a one-dof joint about the specified axis.
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.
Integral PID gain for position.
Current status of the MStop.
struct _HebiIK * HebiIKPtr
HebiFeedbackHighResAngleField
HebiGroupFeedbackPtr hebiGroupFeedbackCreate(size_t size)
Creates a GroupFeedback for a group with the specified number of modules.
HebiRobotModelPtr hebiRobotModelCreate(void)
Creates an object to hold a robot model (tree topology). This structure has a single output available...
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
struct _HebiGroupFeedback * HebiGroupFeedbackPtr
The C-style's API representation of group feedback.
struct _HebiMacAddress HebiMacAddress
void hebiCommandSetLedModuleControl(HebiCommandPtr cmd, HebiCommandLedField field)
void hebiGroupInfoClear(HebiGroupInfoPtr info)
Clears all data in the GroupInfo object.
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
Software-controlled bounds on the allowable velocity of the module.
Derivative PID gain for effort.
void hebiCommandSetFlag(HebiCommandPtr cmd, HebiCommandFlagField field, int32_t value)
HebiStatusCode hebiInfoGetHighResAngle(HebiInfoPtr, HebiInfoHighResAngleField, int64_t *int_part, float *dec_part)
HebiStatusCode hebiFeedbackGetIoPinInt(HebiFeedbackPtr fbk, HebiFeedbackIoPinBank field, size_t pin_number, int64_t *value)
HebiFeedbackNumberedFloatField
Output from the PID controller is limited to a maximum of this value.
Feed forward term for position (this term is multiplied by the target and added to the output)...
Feed forward term for velocity (this term is multiplied by the target and added to the output)...
HebiStatusCode hebiFeedbackGetLedColor(HebiFeedbackPtr fbk, HebiFeedbackLedField field, uint8_t *r, uint8_t *g, uint8_t *b)
void hebiGroupRelease(HebiGroupPtr group)
Release resources for a given group; group should not be used after this call.
The velocity (in radians/second) of the motor shaft.
void hebiGroupCommandClear(HebiGroupCommandPtr cmd)
Clears all data in the GroupCommand object.
I/O pin bank b (pins 1-8 available)
Constant offset to the effort PID output outside of the deadzone; it is added when the error is posit...
struct _HebiGroupInfo * HebiGroupInfoPtr
The C-style's API representation of group info.
Proportional PID gain for position.
static constexpr size_t size(Tuple< Args... > &)
Provides access to the number of elements in a tuple as a compile-time constant expression.
struct _HebiLookup * HebiLookupPtr
size_t hebiGroupCommandGetSize(HebiGroupCommandPtr cmd)
Return the number of modules in this group Command.
Output from the PID controller is limited to a minimum of this value.
Minimum allowed value for input to the PID controller.
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
size_t hebiGroupInfoGetSize(HebiGroupInfoPtr info)
Return the number of modules in this group Info.
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
HebiStatusCode hebiCommandGetBool(HebiCommandPtr cmd, HebiCommandBoolField field, int32_t *value)
HebiStatusCode hebiGroupCommandCopy(HebiGroupCommandPtr dest, HebiGroupCommandPtr src)
Clears the dest GroupCommand object, and copies all data from the src GroupCommand object to dest...
HebiStatusCode hebiLookupEntryListGetName(HebiLookupEntryListPtr lookup_list, size_t index, char *buffer, size_t *length)
The firmware safety limit for the minimum allowed position.
Output from the PID controller is limited to a maximum of this value.
Output from the PID controller is limited to a maximum of this value.
Sequence number going to module (local)
HebiStatusCode hebiTrajectoryGetState(HebiTrajectoryPtr trajectory, double time, double *position, double *velocity, double *acceleration)
Gets the value of the trajectory at a given time.
HebiStatusCode hebiFeedbackGetUInt64(HebiFeedbackPtr fbk, HebiFeedbackUInt64Field field, uint64_t *value)
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.
Derivative PID gain for velocity.
Generic code for failure; this is generally used for an internal or unknown failure.
Minimum allowed value for input to the PID controller.
Proportional PID gain for velocity.
I/O pin bank e (pins 1-8 available)
Derivative PID gain for position.
Accelerometer data, in m/s^2.
int32_t hebiCommandGetFlag(HebiCommandPtr cmd, HebiCommandFlagField field)
HebiStatusCode hebiGroupSetFeedbackFrequencyHz(HebiGroupPtr group, float frequency)
Sets the feedback request loop frequency (in Hz).
Output from the PID controller is limited to a minimum of this value.
size_t hebiRobotModelGetNumberOfDoFs(HebiRobotModelPtr robot_model)
Returns the number of settable degrees of freedom in the kinematic tree. (This is equal to the number...
float hebiGroupGetFeedbackFrequencyHz(HebiGroupPtr group)
Returns the current feedback request loop frequency (in Hz).
HebiGroupCommandPtr hebiGroupCommandCreate(size_t size)
Creates a GroupCommand for a group with the specified number of modules.
Velocity of the module output (post-spring), in radians/second.
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages)...
HebiStatusCode hebiGroupRequestInfo(HebiGroupPtr group, HebiGroupInfoPtr info, int32_t timeout_ms)
Requests info from the group, and writes it to the provided info object.
Proportional PID gain for effort.
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.
HebiStatusCode hebiFeedbackGetVector3f(HebiFeedbackPtr fbk, HebiFeedbackVector3fField field, HebiVector3f *value)
I/O pin bank b (pins 1-8 available)
size_t hebiLookupEntryListGetSize(HebiLookupEntryListPtr lookup_list)
HebiStatusCode hebiCommandGetIoPinInt(HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number, int64_t *value)
Constant offset to the velocity PID output outside of the deadzone; it is added when the error is pos...
HebiStatusCode hebiCommandGetLedColor(HebiCommandPtr cmd, HebiCommandLedField field, uint8_t *r, uint8_t *g, uint8_t *b)
void hebiRobotModelElementRelease(HebiRobotModelElementPtr element)
Frees resources created by this element.
Integral PID gain for effort.
Derivative PID gain for position.
Bus voltage that the module is running at (in Volts).
Proportional PID gain for velocity.
HebiStatusCode hebiGroupSetCommandLifetime(HebiGroupPtr group, int32_t lifetime_ms)
Sets the command lifetime for the group, in milliseconds.
Gets the family for this module.
HebiInfoHighResAngleField
HebiStatusCode hebiCommandGetString(HebiCommandPtr cmd, HebiCommandStringField field, char *buffer, size_t *length)
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.
double hebiTrajectoryGetDuration(HebiTrajectoryPtr trajectory)
Returns the length of this trajectory (in seconds).
void hebiTrajectoryRelease(HebiTrajectoryPtr trajectory)
Frees resources created by this trajectory.
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.
HebiStatusCode hebiGroupSendFeedbackRequest(HebiGroupPtr group)
Requests feedback from the group.
HebiLookupEntryListPtr hebiCreateLookupEntryList(HebiLookupPtr lookup)
Return a snapshot of the contents of the module registry – i.e., which modules have been found by th...
void hebiCommandSetHighResAngle(HebiCommandPtr cmd, HebiCommandHighResAngleField field, const int64_t *int_part, const float *dec_part)
Constant offset to the effort PID output outside of the deadzone; it is added when the error is posit...
Minimum allowed value for input to the PID controller.
void hebiGroupInfoRelease(HebiGroupInfoPtr info)
Frees resources created by the GroupInfo object.
Minimum allowed value for input to the PID controller.
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...
struct _HebiRobotModel * HebiRobotModelPtr
HebiStatusCode hebiGroupInfoWriteGains(HebiGroupInfoPtr info, const char *file)
Export gains from a GroupInfo object into a file.
HebiGroupInfoPtr hebiGroupInfoCreate(size_t size)
Creates a GroupInfo for a group with the specified number of modules.
HebiCommandPtr hebiGroupCommandGetModuleCommand(HebiGroupCommandPtr cmd, size_t module_index)
Get an individual command for a particular module at index module_index.
An invalid argument was supplied to the routine (e.g. null pointer)
How the position, velocity, and effort PID loops are connected in order to control motor PWM...
HebiStatusCode hebiGetLibraryVersion(int32_t *major, int32_t *minor, int32_t *revision)
Get the version of the library.
HebiFeedbackPtr hebiGroupFeedbackGetModuleFeedback(HebiGroupFeedbackPtr fbk, size_t module_index)
Get an individual feedback for a particular module at index module_index.
Current supplied to the motor.
HebiCommandNumberedFloatField
Set the internal encoder reference offset so that the current position matches the given reference co...
I/O pin bank c (pins 1-8 available)
HebiStatusCode hebiFeedbackGetFloat(HebiFeedbackPtr fbk, HebiFeedbackFloatField field, float *value)
HebiIKPtr hebiIKCreate(void)
Creates an IK (inverse kinematics) object that allows for solving for joint angles/positions given ob...
HebiStatusCode hebiLookupEntryListGetFamily(HebiLookupEntryListPtr lookup_list, size_t index, char *buffer, size_t *length)
The estimated temperature of the motor windings.
Timestamp of when message was transmitted to module (local)
int32_t hebiCommandHasLedModuleControl(HebiCommandPtr cmd, HebiCommandLedField field)
HebiStatusCode hebiCommandGetFloat(HebiCommandPtr cmd, HebiCommandFloatField field, float *value)
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.
Proportional PID gain for effort.
HebiStatusCode hebiGroupCommandReadGains(HebiGroupCommandPtr cmd, const char *file)
Import gains from a file into a GroupCommand object.
Maximum allowed value for input to the PID controller.
HebiStatusCode hebiFeedbackGetEnum(HebiFeedbackPtr, HebiFeedbackEnumField, int32_t *)
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.
struct _HebiRobotModelElement * HebiRobotModelElementPtr
Maximum allowed value for input to the PID controller.
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.
Maximum allowed value for input to the PID controller.
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...
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
void hebiLogFileRelease(HebiLogFilePtr log_file)
Releases a log file instance.
Proportional PID gain for position.
Maximum allowed value for input to the PID controller.
Output from the PID controller is limited to a maximum of this value.
void hebiCommandSetFloat(HebiCommandPtr cmd, HebiCommandFloatField field, const float *value)
void hebiCommandSetNumberedFloat(HebiCommandPtr cmd, HebiCommandNumberedFloatField field, size_t number, const float *value)
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.
HebiLookupPtr hebiLookupCreate(void)
Create a Lookup instance.
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
void hebiGroupCommandRelease(HebiGroupCommandPtr cmd)
Frees resources created by the GroupCommand object.
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
Output from the PID controller is limited to a minimum of this value.
Constant offset to the velocity PID output outside of the deadzone; it is added when the error is pos...
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Feed forward term for position (this term is multiplied by the target and added to the output)...
Maximum allowed value for input to the PID controller.
Success; no failures occurred.
HebiStatusCode hebiRobotModelSetBaseFrame(HebiRobotModelPtr robot_model, const double *transform)
Sets the fixed transform from the origin to the input of the first added model element.
The estimated current in the motor windings.
Timestamp of when message was transmitted from module (remote)
HebiStatusCode hebiFeedbackGetQuaternionf(HebiFeedbackPtr fbk, HebiFeedbackQuaternionfField field, HebiQuaternionf *value)
HebiStatusCode hebiLogFileGetNextFeedback(HebiLogFilePtr log_file, HebiGroupFeedbackPtr field)
Retrieve the next group feedback from the opened log file.
Derivative PID gain for effort.
The temperature from a sensor near the motor housing.
HebiStatusCode hebiStringGetString(HebiStringPtr str, char *buffer, size_t *length)
Copy the string into a buffer.
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.
Integral PID gain for effort.
struct _HebiFeedback * HebiFeedbackPtr
The C-style's API representation of feedback.
HebiStatusCode hebiCommandGetEnum(HebiCommandPtr cmd, HebiCommandEnumField field, int32_t *value)
void hebiCommandSetEnum(HebiCommandPtr cmd, HebiCommandEnumField field, const int32_t *value)
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.
Feed forward term for effort (this term is multiplied by the target and added to the output)...
struct _HebiCommand * HebiCommandPtr
The C-style's API representation of a command.
void hebiCommandSetIoPinInt(HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number, const int64_t *value)
Integral PID gain for velocity.
Integral PID gain for velocity.
HebiStatusCode hebiFeedbackGetHighResAngle(HebiFeedbackPtr fbk, HebiFeedbackHighResAngleField field, int64_t *int_part, float *dec_part)
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Position of the module output (post-spring), in radians.
HebiStatusCode hebiInfoGetString(HebiInfoPtr info, HebiInfoStringField field, char *buffer, size_t *length)
HebiStatusCode hebiInfoGetBool(HebiInfoPtr info, HebiInfoBoolField field, int32_t *value)
Temperature of the processor chip, in degrees Celsius.
Output from the PID controller is limited to a maximum of this value.
struct _HebiTrajectory * HebiTrajectoryPtr
The C-style's API representation of a trajectory.
struct _HebiLogFile * HebiLogFilePtr
The C-style's API representation of a log file.
I/O pin bank d (pins 1-8 available)
Output from the PID controller is limited to a minimum of this value.
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages)...
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 recei...
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
HebiStatusCode hebiLookupEntryListGetMacAddress(HebiLookupEntryListPtr lookup_list, size_t index, HebiMacAddress *mac_address)
void hebiCommandSetIoPinFloat(HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number, const float *value)
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
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.
size_t hebiGroupFeedbackGetSize(HebiGroupFeedbackPtr fbk)
Return the number of modules in this group Feedback.
void hebiRobotModelRelease(HebiRobotModelPtr robot_model)
Frees resources created by this robot model object.
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
Commanded velocity of the module output (post-spring), in radians/second.
void(* GroupFeedbackHandlerFunction)(HebiGroupFeedbackPtr fbk, void *user_data)
Group feedback handling function signature.
size_t hebiLogFileGetNumberOfModules(HebiLogFilePtr log_file)
Retrieve the number of modules in the group represented by an opened log file.
I/O pin bank d (pins 1-8 available)
void hebiCommandSetString(HebiCommandPtr cmd, HebiCommandStringField field, const char *buffer, const size_t *length)
HebiStatusCode hebiFeedbackGetIoPinFloat(HebiFeedbackPtr fbk, HebiFeedbackIoPinBank field, size_t pin_number, float *value)
Minimum allowed value for input to the PID controller.
HebiInfoPtr hebiGroupInfoGetModuleInfo(HebiGroupInfoPtr info, size_t module_index)
Get an individual info for a particular module at index module_index.
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
struct _HebiInfo * HebiInfoPtr
The C-style's API representation of a group.
void hebiGroupFeedbackRelease(HebiGroupFeedbackPtr fbk)
Frees resources created by the GroupFeedback object.
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
HebiStatusCode hebiFeedbackGetNumberedFloat(HebiFeedbackPtr fbk, HebiFeedbackNumberedFloatField field, size_t number, float *value)
int32_t hebiGroupGetCommandLifetime(HebiGroupPtr group)
Returns the current command lifetime, in milliseconds.
struct _HebiVector3f HebiVector3f
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
HebiStatusCode hebiGroupFeedbackCopy(HebiGroupFeedbackPtr dest, HebiGroupFeedbackPtr src)
Clears the dest GroupFeedback object, and copies all data from the src GroupFeedback object to dest...
size_t hebiGroupGetSize(HebiGroupPtr group)
Returns the number of modules in a group.
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement." When the setpoints have step inputs or are noisy, setting this to false can eliminate corresponding spikes or noise in the output.
Velocity (in radians/second) of the difference between the pre-spring and post-spring output position...
HebiStatusCode hebiRobotModelGetBaseFrame(HebiRobotModelPtr robot_model, double *transform)
Retreives the fixed transform from the origin to the input of the first added model element...
HebiStatusCode hebiIKAddConstraintJointAngles(HebiIKPtr ik, double weight, size_t num_joints, const double *min_positions, const double *max_positions)
Define joint angle constraints.
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
HebiGroupPtr hebiGroupCreateImitation(size_t size)
Creates an "imitation" group with the specified number of modules.
Maximum allowed value for input to the PID controller.
HebiStatusCode hebiInfoGetEnum(HebiInfoPtr info, HebiInfoEnumField field, int32_t *value)
size_t hebiRobotModelGetNumberOfFrames(HebiRobotModelPtr robot_model, HebiFrameType frame_type)
Return the number of frames in the forward kinematic tree of the robot model.
HebiStatusCode hebiGroupRegisterFeedbackHandler(HebiGroupPtr group, GroupFeedbackHandlerFunction handler, void *user_data)
Add a function that is called whenever feedback is returned from the group.
Describes how the temperature inside the module is limiting the output of the motor.
void hebiGroupClearFeedbackHandlers(HebiGroupPtr group)
Removes all feedback handling functions from the queue to be called on receipt of group feedback...
EIGEN_DEVICE_FUNC const Scalar & b
Gets the name for this module.
Timestamp of when message was received by module (remote)
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
I/O pin bank a (pins 1-8 available)
struct _HebiString * HebiStringPtr
The C-style's API representation of a string.
Feed forward term for velocity (this term is multiplied by the target and added to the output)...
HebiStatusCode hebiInfoGetLedColor(HebiInfoPtr info, HebiInfoLedField field, uint8_t *r, uint8_t *g, uint8_t *b)
Indicates if the module should save the current values of all of its settings.
struct _HebiGroupCommand * HebiGroupCommandPtr
The C-style's API representation of a group command.
Position of the module output (post-spring), in radians.
Software-controlled bounds on the allowable effort of the module.
void hebiCleanup(void)
Frees all resources created by the library. Note: any calls to the HEBI library functions after this ...
void hebiLookupEntryListRelease(HebiLookupEntryListPtr lookup_list)
Release resources for a given lookup entry list; list should not be used after this call...
Constant offset to the position PID output outside of the deadzone; it is added when the error is pos...
Output from the PID controller is limited to a minimum of this value.
HebiStatusCode hebiCommandGetHighResAngle(HebiCommandPtr cmd, HebiCommandHighResAngleField field, int64_t *int_part, float *dec_part)
void hebiIKClearAll(HebiIKPtr ik)
Clears the objectives and constraints from this IK object, along with any modifications to the defaul...
Constant offset to the position PID output outside of the deadzone; it is added when the error is pos...
I/O pin bank c (pins 1-8 available)
I/O pin bank a (pins 1-8 available)
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
void hebiLookupRelease(HebiLookupPtr lookup)
Frees resources created by the lookup object.
Commanded effort at the module output; units vary (e.g., N * m for rotational joints and N for linear...
Velocity of the module output (post-spring), in radians/second.
I/O pin bank e (pins 1-8 available)
Minimum allowed value for input to the PID controller.