Go to the documentation of this file.
13 #define M_PI 3.14159265358979323846
1009 const char*
const* names,
size_t num_names, int32_t timeout_ms);
1077 int32_t timeout_ms);
1108 int32_t timeout_ms);
1596 const size_t* length);
1702 size_t num_outputs,
const double* outputs,
1732 const double* com,
const double* inertia,
1733 double mass,
const double* output_frame,
2127 double y,
double z);
2169 double y,
double z);
2191 const double* min_positions,
const double* max_positions);
2216 void (*err_fnc)(
void* user_data,
size_t num_positions,
const double* positions,
2289 const double* velocities,
const double* accelerations,
2290 const double* time_vector);
2320 double* acceleration);
@ HebiFeedbackFloatBatteryLevel
The estimated temperature of the motor housing.
@ HebiArQualityLimitedInsufficientFeatures
The device is moving too fast for accurate image-based position tracking.
HebiStatusCode hebiIKAddObjectiveEndEffectorPosition(HebiIKPtr ik, double 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,...
void hebiGroupFeedbackClear(HebiGroupFeedbackPtr feedback)
Clears all data in the GroupFeedback object.
@ HebiInfoFloatPositionKd
Integral PID gain for position.
void hebiRobotModelRelease(HebiRobotModelPtr robot_model)
Frees resources created by this robot model object.
@ HebiMatrixOrderingRowMajor
HebiStatusCode hebiInfoGetString(HebiInfoPtr info, HebiInfoStringField field, char *buffer, size_t *length)
Info API.
HebiCommandPtr hebiGroupCommandGetModuleCommand(HebiGroupCommandPtr command, size_t module_index)
Get an individual command for a particular module at index module_index.
@ HebiCommandFloatEffortLimitMin
The firmware safety limit for the maximum allowed velocity.
@ HebiFeedbackHighResAnglePosition
const float * numbered_float_fields_
@ HebiCommandBoolPositionDOnError
struct HebiCommandMetadata_ HebiCommandMetadata
@ HebiFeedbackEnumEffortLimitState
Software-controlled bounds on the allowable velocity of the module.
@ HebiInfoFloatEffortOutputLowpass
Output from the PID controller is limited to a maximum of this value.
@ HebiCommandFlagClearLog
Stop the module from automatically booting into application.
struct HebiRobotModelElement_ * HebiRobotModelElementPtr
size_t hebiRobotModelGetImportWarningCount()
Retrieve the number of warnings corresponding to the last call to hebiRobotModelImport....
@ HebiInfoFloatVelocityDeadZone
Feed forward term for velocity (this term is multiplied by the target and added to the output).
HebiRobotModelPtr hebiRobotModelImportBuffer(const char *buffer, size_t buffer_size)
Import robot model from a buffer into a RobotModel object.
@ HebiInfoEnumMstopStrategy
The calibration state of the module.
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...
@ HebiCommandFloatPositionDeadZone
Feed forward term for position (this term is multiplied by the target and added to the output).
@ HebiCommandFloatPositionKp
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages).
@ HebiCommandFloatVelocityKi
Proportional PID gain for velocity.
@ HebiCommandFloatVelocityOutputLowpass
Output from the PID controller is limited to a maximum of this value.
HebiStatusCode hebiLookupSetLookupFrequencyHz(HebiLookupPtr lookup, double frequency)
sets the lookup request rate [Hz]
@ HebiStatusArgumentOutOfRange
Generic code for failure; this is generally used for an internal or unknown failure.
HebiStatusCode hebiGroupFeedbackCopy(HebiGroupFeedbackPtr dest, HebiGroupFeedbackPtr src)
Clears the dest GroupFeedback object, and copies all data from the src GroupFeedback object to dest.
@ HebiFeedbackFloatMotorCurrent
The velocity of the motor shaft.
@ HebiCommandIoBankC
I/O pin bank b (pins 1-8 available)
@ HebiFeedbackIoBankB
I/O pin bank a (pins 1-8 available)
@ HebiInfoFloatEffortMinTarget
Constant offset to the effort PID output outside of the deadzone; it is added when the error is posit...
@ HebiCommandFlagReset
Indicates if the module should save the current values of all of its settings.
@ HebiJointTypeTranslationZ
@ HebiInfoFloatPositionMaxTarget
Minimum allowed value for input to the PID controller.
@ HebiCommandFloatVelocityMaxOutput
Output from the PID controller is limited to a minimum of this value.
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.
@ HebiCommandFloatPositionMaxTarget
Minimum allowed value for input to the PID controller.
@ HebiInfoFloatVelocityLimitMax
The firmware safety limit for the minimum allowed velocity.
@ HebiCommandStringAppendLog
The family for this module. The string must be null-terminated and less than 21 characters.
float hebiGroupGetFeedbackFrequencyHz(HebiGroupPtr group)
Returns the current feedback request loop frequency (in Hz).
@ HebiBracketTypeX5HeavyLeftInside
struct HebiFeedbackRef_ HebiFeedbackRef
@ HebiInfoFloatVelocityIClamp
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
const char * hebiRobotModelGetImportWarning(size_t warning_index)
Retrieve the 'ith' warning string from the last call to hebiRobotModelImport. This must be called on ...
@ HebiFeedbackFloatVelocityCommand
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages).
@ HebiLinkInputTypeRightAngle
const int32_t * enum_fields_
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.
@ HebiInfoFloatEffortMinOutput
A simple lowpass filter applied to the target set point; needs to be between 0 and 1....
@ HebiFeedbackIoBankC
I/O pin bank b (pins 1-8 available)
@ HebiArQualityNotAvailable
@ HebiCommandFlagBoot
Restart the module.
@ HebiCommandIoBankD
I/O pin bank c (pins 1-8 available)
HebiStatusCode
Enum Types.
@ HebiCommandBoolVelocityDOnError
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
HebiCommandFloatField
Command Enums.
@ HebiFeedbackEnumTemperatureState
@ HebiFeedbackUInt64ReceiveTime
Sequence number going to module (local)
@ HebiCommandIoBankF
I/O pin bank e (pins 1-8 available)
@ HebiBracketTypeX5HeavyRightInside
const uint64_t * uint64_fields_
@ HebiCommandFloatEffortMaxTarget
Minimum allowed value for input to the PID controller.
@ HebiIoBankPinResidentTypeNone
HebiLookupEntryListPtr hebiCreateLookupEntryList(HebiLookupPtr lookup)
Return a snapshot of the contents of the module registry – i.e., which modules have been found by the...
struct HebiGroupFeedback_ * HebiGroupFeedbackPtr
The C-style's API representation of a feedback object for a group of modules.
HebiStatusCode hebiGroupCommandWriteGains(HebiGroupCommandPtr command, const char *file)
Export gains from a GroupCommand object into a file.
@ HebiFeedbackFloatProcessorTemperature
Ambient temperature inside the module (measured at the IMU chip)
const int32_t * enum_fields_
HebiFeedbackQuaternionfField
@ HebiCommandStringFamily
The name for this module. The string must be null-terminated and less than 21 characters.
@ HebiFrameTypeEndEffector
void hebiGroupInfoRelease(HebiGroupInfoPtr info)
Frees resources created by the GroupInfo object.
@ HebiBracketTypeR8HeavyRightOutside
@ HebiFeedbackHighResAngleMotorPosition
Commanded position of the module output (post-spring).
void hebiTrajectoryRelease(HebiTrajectoryPtr trajectory)
Frees resources created by this trajectory.
HebiRobotModelElementPtr hebiRobotModelElementCreateLink(HebiLinkType link_type, HebiLinkInputType input_type, HebiLinkOutputType output_type, double extension, double twist)
Creates a rigid body, including mass and static transforms, corresponding to a standard HEBI link.
@ HebiInfoFloatPositionFeedForward
Derivative PID gain for position.
@ HebiCommandFloatVelocityDeadZone
Feed forward term for velocity (this term is multiplied by the target and added to the output).
@ HebiCommandFlagSaveCurrentSettings
@ HebiFeedbackHighResAnglePositionCommand
Position of the module output (post-spring).
struct HebiInfo_ * HebiInfoPtr
The C-style's API representation of info.
struct HebiGroup_ * HebiGroupPtr
The C-style's API representation of a group.
void hebiRobotModelElementRelease(HebiRobotModelElementPtr element)
Frees resources created by this element.
@ HebiMatrixOrderingColumnMajor
void hebiGroupClearFeedbackHandlers(HebiGroupPtr group)
Removes all feedback handling functions from the queue to be called on receipt of group feedback.
HebiStatusCode hebiGroupStartLog(HebiGroupPtr group, const char *dir, const char *file, HebiStringPtr *ret)
Starts logging data to a file.
void hebiCleanup(void)
Frees all resources created by the library. Note: any calls to the HEBI library functions after this ...
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.
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.
@ HebiInfoFloatPositionMinTarget
Constant offset to the position PID output outside of the deadzone; it is added when the error is pos...
void hebiGroupCommandClear(HebiGroupCommandPtr command)
Clears all data in the GroupCommand object.
HebiStatusCode hebiGroupSetCommandLifetime(HebiGroupPtr group, int32_t lifetime_ms)
Sets the command lifetime for the group, in milliseconds.
int32_t hebiGroupGetCommandLifetime(HebiGroupPtr group)
Returns the current command lifetime, in milliseconds.
@ HebiCommandFloatEffortKi
Proportional PID gain for effort.
HebiStatusCode hebiGroupInfoWriteGains(HebiGroupInfoPtr info, const char *file)
Export gains from a GroupInfo object into a file.
HebiFeedbackHighResAngleField
@ HebiStatusBufferTooSmall
An invalid argument was supplied to the routine (e.g. null pointer)
@ HebiInfoFloatVelocityMinTarget
Constant offset to the velocity PID output outside of the deadzone; it is added when the error is pos...
struct HebiInfoMetadata_ HebiInfoMetadata
void hebiCommandGetReference(HebiCommandPtr command, HebiCommandRef *ref)
@ HebiFeedbackFloatEffort
Velocity of the module output (post-spring).
void hebiGroupInfoClear(HebiGroupInfoPtr info)
Clears all data in the GroupInfo object.
HebiStatusCode hebiGroupSendFeedbackRequest(HebiGroupPtr group)
Requests feedback from the group.
@ HebiInfoEnumCalibrationState
How the position, velocity, and effort PID loops are connected in order to control motor PWM.
@ HebiCommandBoolAccelIncludesGravity
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
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.
@ HebiFeedbackFloatVelocity
Bus voltage at which the module is running.
struct HebiIK_ * HebiIKPtr
@ HebiInfoFloatVelocityKi
Proportional PID gain for velocity.
HebiRobotModelElementPtr hebiRobotModelElementCreateEndEffector(HebiEndEffectorType end_effector_type, const double *com, const double *inertia, double mass, const double *output_frame, HebiMatrixOrdering ordering)
Creates a robot model element corresponding to a standard HEBI end effector, or a custom end effector...
int32_t * message_bitfield_
HebiFeedbackPtr hebiGroupFeedbackGetModuleFeedback(HebiGroupFeedbackPtr feedback, size_t module_index)
Get an individual feedback for a particular module at index module_index.
void hebiCommandGetMetadata(HebiCommandMetadata *metadata)
HebiIoBankPinResidentType
HebiIoBankPinStruct * io_fields_
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.
@ HebiIoBankPinResidentTypeFloat
@ HebiLinkOutputTypeRightAngle
HebiRobotModelElementType
void hebiStringRelease(HebiStringPtr str)
Releases a string instance.
@ HebiFeedbackUInt64TransmitTime
Timestamp of when message was received from module (local)
void hebiGroupRelease(HebiGroupPtr group)
Release resources for a given group; group should not be used after this call.
const HebiIoBankPinStruct * io_fields_
HebiGroupPtr hebiGroupCreateImitation(size_t size)
Group API.
struct HebiQuaternionf_ HebiQuaternionf
HebiRobotModelElementPtr hebiRobotModelElementCreateBracket(HebiBracketType bracket_type)
Creates a rigid body, including mass and static transforms, corresponding to a standard HEBI bracket.
@ HebiFeedbackFloatMotorHousingTemperature
The estimated temperature of the motor windings.
@ HebiStatusFailure
Returned when an accessor function attempts to retrieve a field which is not set.
HebiStatusCode hebiRobotModelGetTreeTopology(HebiRobotModelPtr robot_model, HebiFrameType frame_type, HebiRobotModelElementTopology *table)
returns table of information about the shape of kinematic tree
HebiStatusCode hebiGroupRegisterFeedbackHandler(HebiGroupPtr group, GroupFeedbackHandlerFunction handler, void *user_data)
Add a function that is called whenever feedback is returned from the group.
@ HebiInfoFloatEffortLimitMax
The firmware safety limit for the minimum allowed effort.
HebiHighResAngleStruct * high_res_angle_fields_
@ HebiLinkOutputTypeInline
@ HebiInfoFloatVelocityMaxTarget
Minimum allowed value for input to the PID controller.
struct HebiLookup_ * HebiLookupPtr
struct HebiFeedback_ * HebiFeedbackPtr
The C-style's API representation of feedback.
@ HebiRobotModelElementTypeJoint
@ HebiInfoFloatSpringConstant
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
const uint64_t * uint64_fields_
@ HebiInfoFloatPositionKp
HebiCommandNumberedFloatField
HebiStatusCode hebiLogFileGetFileName(HebiLogFilePtr log_file, char *buffer, size_t *length)
Copy the path and name of the log file into a buffer.
HebiGroupInfoPtr hebiGroupInfoCreate(size_t size)
Creates a GroupInfo for a group with the specified number of modules.
@ HebiInfoFloatEffortLimitMin
The firmware safety limit for the maximum allowed velocity.
const HebiVector3f * vector3f_fields_
HebiGroupFeedbackPtr hebiGroupFeedbackCreate(size_t size)
Creates a GroupFeedback for a group with the specified number of modules.
@ HebiBracketTypeX5LightLeft
@ HebiBracketTypeR8HeavyLeftOutside
HebiStatusCode hebiLookupEntryListGetFamily(HebiLookupEntryListPtr lookup_list, size_t index, char *buffer, size_t *length)
@ HebiCommandFlagStopBoot
Boot the module from bootloader into application.
@ HebiArQualityLimitedExcessiveMotion
The AR session is attempting to resume after an interruption.
HebiStatusCode hebiGroupCommandReadGains(HebiGroupCommandPtr command, const char *file)
Import gains from a file into a GroupCommand object.
@ HebiInfoHighResAnglePositionLimitMin
HebiLogFilePtr hebiGroupStopLog(HebiGroupPtr group)
Stops logging data to a file.
@ HebiRobotModelElementTypeLink
struct HebiMacAddress_ HebiMacAddress
Structures.
HebiStatusCode hebiRobotModelSetBaseFrame(HebiRobotModelPtr robot_model, const double *transform, HebiMatrixOrdering ordering)
Sets the fixed transform from the origin to the input of the first added model element.
HebiStatusCode hebiTrajectoryGetState(HebiTrajectoryPtr trajectory, double time, double *position, double *velocity, double *acceleration)
Gets the value of the trajectory at a given time.
@ HebiCommandFloatPositionKi
Proportional PID gain for position.
@ HebiArQualityLimitedUnknown
Camera position tracking is not available.
struct HebiLookupEntryList_ * HebiLookupEntryListPtr
@ HebiFeedbackFloatMotorSensorTemperature
Current supplied to the motor.
@ HebiCommandFloatPositionOutputLowpass
Output from the PID controller is limited to a maximum of this value.
const int32_t * message_bitfield_
const bool * bool_fields_
@ HebiFeedbackUInt64SequenceNumber
@ HebiFeedbackIoBankD
I/O pin bank c (pins 1-8 available)
HebiStatusCode hebiRobotModelGetElementMetadata(HebiRobotModelPtr model, size_t index, HebiRobotModelElementMetadata *output)
Retrieves metadata about an element in the robot model. This metadata includes what type of element t...
HebiLogFilePtr hebiLogFileOpen(const char *file)
Opens an existing log file.
size_t hebiRobotModelGetNumberOfFrames(HebiRobotModelPtr robot_model, HebiFrameType frame_type)
Return the number of frames in the forward kinematic tree of the robot model.
const HebiVector3f * vector3f_fields_
HebiStatusCode hebiRobotModelGetBaseFrame(HebiRobotModelPtr robot_model, double *transform, HebiMatrixOrdering ordering)
Retreives the fixed transform from the origin to the input of the first added model element.
@ HebiFeedbackFloatPwmCommand
Charge level of the device’s battery (in percent).
@ HebiCommandHighResAnglePositionLimitMax
The firmware safety limit for the minimum allowed position.
HebiStatusCode hebiLogFileGetNextFeedback(HebiLogFilePtr log_file, HebiGroupFeedbackPtr field)
Retrieve the next group feedback from the opened log file.
@ HebiCommandEnumControlStrategy
@ HebiRobotModelElementTypeOther
@ HebiCommandFloatVelocity
@ HebiInfoFloatEffortMaxOutput
Output from the PID controller is limited to a minimum of this value.
@ HebiStatusValueNotSet
A buffer supplied to the routine was too small (normally determined by a size parameter)
@ HebiRobotModelElementTypeEndEffector
@ HebiStatusInvalidArgument
Success; no failures occurred.
uint64_t * uint64_fields_
@ HebiCommandFloatVelocityTargetLowpass
Maximum allowed value for input to the PID controller.
int32_t end_effector_index_
HebiInfoFloatField
Info Enums.
struct HebiGroupInfo_ * HebiGroupInfoPtr
The C-style's API representation of a info object for a group of modules.
@ HebiBracketTypeX5HeavyRightOutside
@ HebiInfoFloatPositionPunch
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
struct HebiGroupCommand_ * HebiGroupCommandPtr
The C-style's API representation of a command object for a group of modules.
size_t hebiGroupInfoGetSize(HebiGroupInfoPtr info)
Return the number of modules in this group Info.
@ HebiFeedbackEnumVelocityLimitState
Software-controlled bounds on the allowable position of the module; user settable.
HebiStatusCode hebiIKAddObjectiveEndEffectorSO3(HebiIKPtr ik, double weight, size_t end_effector_index, const double *matrix, HebiMatrixOrdering ordering)
Add an objective that optimizes for the end effector output frame orientation to be given by the 3x3 ...
const bool * bool_fields_
const uint32_t * led_fields_
@ HebiFeedbackEnumPositionLimitState
Current status of the MStop.
@ HebiFeedbackFloatMotorWindingCurrent
The temperature from a sensor near the motor housing.
@ HebiInfoHighResAnglePositionLimitMax
The firmware safety limit for the minimum allowed position.
@ HebiIoBankPinResidentTypeInteger
const char * hebiRobotModelGetImportError()
Retrieve any error string from the last call to hebiRobotModelImport. This must be called on the same...
HebiRobotModelPtr hebiRobotModelImport(const char *file)
Import robot model from a file into a RobotModel object.
@ HebiFeedbackQuaternionfArOrientation
A filtered estimate of the orientation of the module.
@ HebiFeedbackFloatBoardTemperature
@ HebiInfoBoolEffortDOnError
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
HebiTrajectoryPtr hebiTrajectoryCreateUnconstrainedQp(size_t num_waypoints, const double *positions, const double *velocities, const double *accelerations, const double *time_vector)
Trajectory API.
@ HebiInfoFloatVelocityOutputLowpass
Output from the PID controller is limited to a maximum of this value.
@ HebiInfoFloatEffortTargetLowpass
Maximum allowed value for input to the PID controller.
@ HebiInfoFloatEffortKp
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
struct HebiCommand_ * HebiCommandPtr
Typedefs.
@ HebiInfoFloatEffortFeedForward
Derivative PID gain for effort.
@ HebiArQualityNormal
The scene visible to the camera does not contain enough distinguishable features for image-based posi...
HebiStatusCode hebiGroupSendCommand(HebiGroupPtr group, HebiGroupCommandPtr command)
Sends a command to the given group without requesting an acknowledgement.
@ HebiFeedbackVector3fArPosition
Gyro data.
@ HebiCommandFloatVelocityFeedForward
Derivative PID gain for velocity.
@ HebiJointTypeTranslationX
@ HebiCommandEnumMaxPositionLimitStrategy
The position limit strategy (at the minimum position) for the actuator.
struct HebiString_ * HebiStringPtr
The C-style's API representation of a string.
@ HebiInfoFloatPositionTargetLowpass
Maximum allowed value for input to the PID controller.
struct HebiVector3f_ HebiVector3f
void hebiLookupRelease(HebiLookupPtr lookup)
Frees resources created by the lookup object.
@ HebiCommandFloatVelocityMaxTarget
Minimum allowed value for input to the PID controller.
void hebiCommandSetString(HebiCommandPtr command, HebiCommandStringField field, const char *buffer, const size_t *length)
size_t hebiGroupFeedbackGetSize(HebiGroupFeedbackPtr feedback)
Return the number of modules in this group Feedback.
HebiStatusCode hebiGroupInfoCopy(HebiGroupInfoPtr dest, HebiGroupInfoPtr src)
Clears the dest GroupInfo object, and copies all data from the src GroupInfo object to dest.
size_t hebiGroupGetSize(HebiGroupPtr group)
Returns the number of modules in a group.
HebiRobotModelElementPtr hebiRobotModelElementCreateRigidBody(const double *com, const double *inertia, double mass, size_t num_outputs, const double *outputs, HebiMatrixOrdering ordering)
Creates a rigid body defining static transforms to the given outputs.
@ HebiCommandNumberedFloatDebug
@ HebiInfoFloatVelocityKd
Integral PID gain for velocity.
@ HebiBracketTypeR8LightLeft
const HebiQuaternionf * quaternionf_fields_
void hebiGroupCommandRelease(HebiGroupCommandPtr command)
Frees resources created by the GroupCommand object.
@ HebiInfoFloatPositionDeadZone
Feed forward term for position (this term is multiplied by the target and added to the output).
@ HebiCommandFloatEffortPunch
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
@ HebiCommandHighResAnglePositionLimitMin
Position of the module output (post-spring).
HebiStatusCode hebiLookupEntryListGetMacAddress(HebiLookupEntryListPtr lookup_list, size_t index, HebiMacAddress *mac_address)
HebiGroupCommandPtr hebiGroupCommandCreate(size_t size)
Creates a GroupCommand for a group with the specified number of modules.
@ HebiInfoFloatVelocityMinOutput
A simple lowpass filter applied to the target set point; needs to be between 0 and 1....
const char * hebiSafetyParametersGetLastError(void)
Misc Functions.
HebiStatusCode hebiIKAddConstraintJointAngles(HebiIKPtr ik, double weight, size_t num_joints, const double *min_positions, const double *max_positions)
Define joint angle constraints.
struct HebiIoBankPinStruct_ HebiIoBankPinStruct
@ HebiEndEffectorTypeR8Parallel
@ HebiCommandFloatEffortFeedForward
Derivative PID gain for effort.
@ HebiFeedbackEnumArQuality
The state of the command lifetime safety controller, with respect to the current group.
HebiQuaternionf * quaternionf_fields_
const float * float_fields_
@ HebiInfoFloatPositionMaxOutput
Output from the PID controller is limited to a minimum of this value.
HebiRobotModelElementPtr hebiRobotModelElementCreateActuator(HebiActuatorType actuator_type)
Creates a robot model element corresponding to a standard HEBI actuator.
const HebiHighResAngleStruct * high_res_angle_fields_
@ HebiFeedbackVector3fAccelerometer
@ HebiCommandFloatPositionFeedForward
Derivative PID gain for position.
struct HebiLogFile_ * HebiLogFilePtr
The C-style's API representation of a log file.
float * numbered_float_fields_
@ HebiFeedbackQuaternionfOrientation
struct HebiFeedbackMetadata_ HebiFeedbackMetadata
HebiInfoHighResAngleField
@ HebiInfoBoolVelocityDOnError
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
void hebiInfoGetReference(HebiInfoPtr info, HebiInfoRef *ref)
const int32_t * message_bitfield_
@ HebiFeedbackIoBankF
I/O pin bank e (pins 1-8 available)
HebiCommandHighResAngleField
struct HebiRobotModelElementTopology_ HebiRobotModelElementTopology
const HebiQuaternionf * quaternionf_fields_
HebiIKPtr hebiIKCreate(void)
Inverse Kinematics API.
@ HebiInfoFloatPositionIClamp
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
@ HebiCommandFloatVelocityKd
Integral PID gain for velocity.
@ HebiCommandFloatEffortMinTarget
Constant offset to the effort PID output outside of the deadzone; it is added when the error is posit...
const float * float_fields_
@ HebiFeedbackVector3fGyro
Accelerometer data.
void hebiIKClearAll(HebiIKPtr ik)
Clears the objectives and constraints from this IK object, along with any modifications to the defaul...
size_t hebiRobotModelGetNumberOfElements(HebiRobotModelPtr robot_model)
Returns the number of elements added to the kinematic tree.
HebiStatusCode hebiGroupCommandReadSafetyParameters(HebiGroupCommandPtr command, const char *file)
Import safety parameters from a file into a GroupCommand object.
@ HebiBracketTypeR8LightRight
@ HebiInfoFloatEffortMaxTarget
Minimum allowed value for input to the PID controller.
@ HebiCommandFloatEffortIClamp
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
@ HebiInfoFlagSaveCurrentSettings
size_t hebiRobotModelGetNumberOfDoFs(HebiRobotModelPtr robot_model)
Returns the number of settable degrees of freedom in the kinematic tree. (This is equal to the number...
@ HebiCommandFloatEffort
Velocity of the module output (post-spring).
@ HebiFeedbackNumberedFloatDebug
double hebiTrajectoryGetDuration(HebiTrajectoryPtr trajectory)
Returns the length of this trajectory (in seconds).
@ HebiEndEffectorTypeCustom
@ HebiCommandFloatVelocityMinOutput
A simple lowpass filter applied to the target set point; needs to be between 0 and 1....
size_t hebiLookupEntryListGetSize(HebiLookupEntryListPtr lookup_list)
HebiStatusCode hebiGroupCommandWriteSafetyParameters(HebiGroupCommandPtr command, const char *file)
Export safety parameters from a GroupCommand object into a file.
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)
@ 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....
@ HebiInfoBoolPositionDOnError
@ HebiFeedbackEnumMstopState
Describes how the temperature inside the module is limiting the output of the motor.
void hebiInfoGetMetadata(HebiInfoMetadata *metadata)
@ HebiJointTypeTranslationY
@ HebiInfoStringFamily
The name for this module. The string must be null-terminated and less than 21 characters.
HebiInfoPtr hebiGroupInfoGetModuleInfo(HebiGroupInfoPtr info, size_t module_index)
Get an individual info for a particular module at index module_index.
struct HebiCommandRef_ HebiCommandRef
@ HebiCommandFloatEffortKd
Integral PID gain for effort.
void hebiLookupEntryListRelease(HebiLookupEntryListPtr lookup_list)
Release resources for a given lookup entry list; list should not be used after this call.
@ HebiRobotModelElementTypeBracket
@ HebiInfoStringSerial
The family for this module. The string must be null-terminated and less than 21 characters.
@ HebiBracketTypeX5HeavyLeftOutside
@ HebiInfoEnumControlStrategy
const HebiHighResAngleStruct * high_res_angle_fields_
@ HebiInfoFloatVelocityLimitMin
The spring constant of the module.
HebiRobotModelPtr hebiRobotModelCreate(void)
Creates an object to hold a robot model (tree topology). This structure has a single output available...
@ HebiBracketTypeR8HeavyRightInside
HebiFeedbackFloatField
Feedback Enums.
size_t hebiLogFileGetNumberOfModules(HebiLogFilePtr log_file)
Retrieve the number of modules in the group represented by an opened log file.
void hebiFeedbackGetMetadata(HebiFeedbackMetadata *metadata)
@ HebiEndEffectorTypeX5Parallel
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...
@ HebiCommandFloatPositionMaxOutput
Output from the PID controller is limited to a minimum of this value.
HebiFeedbackNumberedFloatField
@ HebiFeedbackUInt64HardwareReceiveTime
Timestamp of when message was transmitted to module (local)
HebiStatusCode hebiCommandGetString(HebiCommandPtr command, HebiCommandStringField field, char *buffer, size_t *length)
Command API.
@ HebiCommandHighResAnglePosition
@ HebiCommandIoBankB
I/O pin bank a (pins 1-8 available)
const float * numbered_float_fields_
@ HebiLinkInputTypeInline
@ HebiFeedbackFloatMotorVelocity
Velocity of the difference between the pre-spring and post-spring output position.
@ HebiFeedbackFloatDeflection
Commanded effort at the module output; units vary (e.g., N * m for rotational joints and N for linear...
void hebiFeedbackGetReference(HebiFeedbackPtr feedback, HebiFeedbackRef *ref)
Feedback API.
@ HebiCommandFloatEffortTargetLowpass
Maximum allowed value for input to the PID controller.
@ HebiInfoFloatEffortKi
Proportional PID gain for effort.
@ HebiBracketTypeR8HeavyLeftInside
@ HebiCommandFloatPositionTargetLowpass
Maximum allowed value for input to the PID controller.
HebiStatusCode hebiGroupSetFeedbackFrequencyHz(HebiGroupPtr group, float frequency)
Sets the feedback request loop frequency (in Hz).
struct HebiRobotModel_ * HebiRobotModelPtr
@ HebiInfoEnumMinPositionLimitStrategy
The motion stop strategy for the actuator.
@ HebiFeedbackUInt64HardwareTransmitTime
Timestamp of when message was received by module (remote)
@ HebiCommandFloatVelocityPunch
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
const HebiIoBankPinStruct * io_fields_
HebiVector3f * vector3f_fields_
@ HebiInfoFloatEffortPunch
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
void(* GroupFeedbackHandlerFunction)(HebiGroupFeedbackPtr fbk, void *user_data)
Group feedback handling function signature.
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.
@ HebiCommandFloatReferenceEffort
Set the internal encoder reference offset so that the current position matches the given reference co...
@ HebiBracketTypeX5LightRight
@ HebiFeedbackEnumCommandLifetimeState
Software-controlled bounds on the allowable effort of the module.
@ HebiCommandFloatPositionMinOutput
A simple lowpass filter applied to the target set point; needs to be between 0 and 1....
HebiLookupPtr hebiLookupCreate(const char *const *ifaces, size_t ifaces_length)
Lookup API.
HebiStatusCode hebiGroupInfoWriteSafetyParameters(HebiGroupInfoPtr info, const char *file)
Export safety parameters from a GroupInfo object into a file.
struct HebiRobotModelElementMetadata_ HebiRobotModelElementMetadata
@ HebiCommandEnumMstopStrategy
How the position, velocity, and effort PID loops are connected in order to control motor PWM.
@ HebiInfoBoolAccelIncludesGravity
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
@ HebiCommandFloatReferencePosition
The spring constant of the module.
@ HebiInfoFloatVelocityMaxOutput
Output from the PID controller is limited to a minimum of this value.
@ HebiInfoEnumMaxPositionLimitStrategy
The position limit strategy (at the minimum position) for the actuator.
HebiStatusCode hebiGetLibraryVersion(int32_t *major, int32_t *minor, int32_t *revision)
Get the version of the library.
HebiStatusCode hebiRobotModelGetMasses(HebiRobotModelPtr robot_model, double *masses)
Fill in the masses vector with the mass of each body with mass in the kinematic tree,...
@ HebiCommandEnumMinPositionLimitStrategy
The motion stop strategy for the actuator.
HebiIoBankPinResidentType stored_type_
@ HebiCommandFloatPositionMinTarget
Constant offset to the position PID output outside of the deadzone; it is added when the error is pos...
@ HebiCommandFloatSpringConstant
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
struct HebiInfoRef_ HebiInfoRef
@ HebiFeedbackUInt64SenderId
Timestamp of when message was transmitted from module (remote)
@ HebiFeedbackFloatDeflectionVelocity
Difference between the pre-spring and post-spring output position.
@ HebiInfoFloatVelocityTargetLowpass
Maximum allowed value for input to the PID controller.
void hebiGroupFeedbackRelease(HebiGroupFeedbackPtr feedback)
Frees resources created by the GroupFeedback object.
@ HebiFrameTypeCenterOfMass
HebiStatusCode hebiRobotModelGetForwardKinematics(HebiRobotModelPtr robot_model, HebiFrameType frame_type, const double *positions, double *frames, HebiMatrixOrdering ordering)
Generates the transforms for the forward kinematics of the given robot model.
HebiFeedbackVector3fField
@ HebiRobotModelElementTypeActuator
@ HebiCommandFloatPositionKd
Integral PID gain for position.
@ HebiCommandFloatEffortKp
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
HebiStatusCode hebiGroupRequestInfo(HebiGroupPtr group, HebiGroupInfoPtr info, int32_t timeout_ms)
Requests info from the group, and writes it to the provided info object.
@ HebiRobotModelElementTypeRigidBody
@ HebiInfoFloatEffortDeadZone
Feed forward term for effort (this term is multiplied by the target and added to the output).
@ HebiCommandFloatEffortOutputLowpass
Output from the PID controller is limited to a maximum of this value.
void hebiIKRelease(HebiIKPtr ik)
Frees resources created by this inverse kinematics object.
HebiFrameType
RobotModel Enums.
HebiStatusCode hebiStringGetString(HebiStringPtr str, char *buffer, size_t *length)
String Functions.
HebiStatusCode hebiRobotModelGetJacobians(HebiRobotModelPtr robot_model, HebiFrameType frame_type, const double *positions, double *jacobians, HebiMatrixOrdering ordering)
Generates the jacobian for each frame in the given kinematic tree.
@ HebiCommandFloatEffortMaxOutput
Output from the PID controller is limited to a minimum of this value.
@ HebiInfoFloatEffortIClamp
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
@ HebiCommandFloatVelocityKp
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
@ HebiInfoFloatVelocityPunch
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
@ HebiCommandFloatVelocityMinTarget
Constant offset to the velocity PID output outside of the deadzone; it is added when the error is pos...
const uint32_t * led_fields_
@ HebiCommandFloatVelocityIClamp
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
@ HebiInfoFloatVelocityFeedForward
Derivative PID gain for velocity.
@ HebiFeedbackFloatMotorWindingTemperature
The estimated current in the motor windings.
@ HebiInfoFloatPositionMinOutput
A simple lowpass filter applied to the target set point; needs to be between 0 and 1....
struct HebiHighResAngleStruct_ HebiHighResAngleStruct
@ HebiFeedbackFloatVoltage
Temperature of the processor chip.
@ HebiCommandIoBankE
I/O pin bank d (pins 1-8 available)
@ HebiCommandFloatPositionPunch
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
@ HebiCommandFloatVelocityLimitMax
The firmware safety limit for the minimum allowed velocity.
size_t hebiGroupCommandGetSize(HebiGroupCommandPtr command)
Return the number of modules in this group Command.
@ HebiCommandBoolEffortDOnError
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
@ HebiInfoFloatEffortKd
Integral PID gain for effort.
@ HebiArQualityLimitedRelocalizing
The AR session has not yet gathered enough camera or motion data to provide tracking information.
@ HebiCommandFloatVelocityLimitMin
Set the internal effort reference offset so that the current effort matches the given reference comma...
@ HebiCommandFloatPositionIClamp
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
void hebiLogFileRelease(HebiLogFilePtr log_file)
Logging API.
@ HebiCommandFloatEffortLimitMax
The firmware safety limit for the minimum allowed effort.
HebiStatusCode hebiRobotModelAdd(HebiRobotModelPtr robot_model, HebiRobotModelElementPtr existing_element, size_t output_index, HebiRobotModelElementPtr new_element)
Add an element to a parent element connected to a robot model object.
HebiRobotModelElementPtr hebiRobotModelElementCreateJoint(HebiJointType joint_type)
RobotModel API.
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.
@ HebiArQualityLimitedInitializing
Tracking is available albeit suboptimal for an unknown reason.
@ HebiCommandFloatEffortMinOutput
A simple lowpass filter applied to the target set point; needs to be between 0 and 1....
@ HebiInfoFloatPositionKi
Proportional PID gain for position.
@ HebiFeedbackFloatEffortCommand
Commanded velocity of the module output (post-spring)
@ HebiFeedbackIoBankE
I/O pin bank d (pins 1-8 available)
struct HebiTrajectory_ * HebiTrajectoryPtr
The C-style's API representation of a trajectory.
@ HebiCommandFloatEffortDeadZone
Feed forward term for effort (this term is multiplied by the target and added to the output).
double hebiLookupGetLookupFrequencyHz(HebiLookupPtr lookup)
gets the lookup request rate [Hz]
hebi_cpp_api_ros
Author(s): Chris Bollinger
, Matthew Tesch
autogenerated on Fri Aug 2 2024 08:35:18