hebi.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <math.h>
4 #include <stdbool.h>
5 #include <stddef.h>
6 #include <stdint.h>
7 
8 #ifdef __cplusplus /* Use C linkage when compiling this C library header from C++ */
9 extern "C" {
10 #endif
11 
12 #ifndef M_PI
13 #define M_PI 3.14159265358979323846
14 #endif
15 
19 
23 typedef enum HebiStatusCode {
31 
35 typedef enum HebiArQuality {
44 
46  HebiIoBankPinResidentTypeNone, // Io pin should be interpreted empty
47  HebiIoBankPinResidentTypeInteger, // Io pin should be interpreted as an integer (`int64_t`)
48  HebiIoBankPinResidentTypeFloat // Io pin should be interpreted as a float (`float`)
50 
54 
55 typedef enum HebiCommandFloatField {
105 
111 
115 
116 typedef enum HebiCommandBoolField {
122 
128 
129 typedef enum HebiCommandFlagField {
136 
137 typedef enum HebiCommandEnumField {
143 
144 typedef enum HebiCommandIoPinBank {
152 
153 typedef enum HebiCommandLedField {
156 
160 
180 
186 
190 
199 
205 
210 
211 typedef enum HebiFeedbackEnumField {
220 
221 typedef enum HebiFeedbackIoPinBank {
229 
230 typedef enum HebiFeedbackLedField {
233 
237 
238 typedef enum HebiInfoFloatField {
284 
289 
290 typedef enum HebiInfoBoolField {
296 
297 typedef enum HebiInfoStringField {
302 
303 typedef enum HebiInfoFlagField {
306 
307 typedef enum HebiInfoEnumField {
314 
315 typedef enum HebiInfoLedField {
318 
322 
327 typedef enum HebiFrameType {
332 } HebiFrameType;
333 
347 
352 typedef enum HebiJointType {
359 } HebiJointType;
360 
364 typedef enum HebiActuatorType {
375 
379 typedef enum HebiLinkType {
382 } HebiLinkType;
383 
387 typedef enum HebiLinkInputType {
391 
395 typedef enum HebiLinkOutputType {
399 
403 typedef enum HebiBracketType {
417 
421 typedef enum HebiEndEffectorType {
426 
430 typedef enum HebiMatrixOrdering {
434 
438 
444 typedef struct HebiCommand_* HebiCommandPtr;
445 
451 typedef struct HebiFeedback_* HebiFeedbackPtr;
452 
458 typedef struct HebiInfo_* HebiInfoPtr;
459 
467 typedef struct HebiGroupCommand_* HebiGroupCommandPtr;
468 
476 typedef struct HebiGroupFeedback_* HebiGroupFeedbackPtr;
477 
485 typedef struct HebiGroupInfo_* HebiGroupInfoPtr;
486 
493 typedef struct HebiGroup_* HebiGroupPtr;
494 
500 typedef struct HebiLookup_* HebiLookupPtr;
501 
507 typedef struct HebiLookupEntryList_* HebiLookupEntryListPtr;
508 
514 typedef struct HebiLogFile_* HebiLogFilePtr;
515 
521 typedef struct HebiString_* HebiStringPtr;
522 
527 typedef struct HebiRobotModel_* HebiRobotModelPtr;
528 
533 typedef struct HebiRobotModelElement_* HebiRobotModelElementPtr;
534 
540 typedef struct HebiIK_* HebiIKPtr;
541 
549 typedef struct HebiTrajectory_* HebiTrajectoryPtr;
550 
554 typedef void (*GroupFeedbackHandlerFunction)(HebiGroupFeedbackPtr fbk, void* user_data);
555 
559 
560 typedef struct HebiMacAddress_ {
561  uint8_t bytes_[6];
563 
564 typedef struct HebiVector3f_ {
565  float x;
566  float y;
567  float z;
568 } HebiVector3f;
569 
570 typedef struct HebiQuaternionf_ {
571  float w;
572  float x;
573  float y;
574  float z;
576 
581  uint32_t struct_size_;
583  union {
584  struct /*Actuator Type */ {
586  };
587  struct /*Bracket Type */ {
589  };
590  struct /*Joint Type */ {
592  };
593  struct /*Link Type*/ {
597  float extension_;
598  float twist_;
599  };
600  struct /*End effector Type*/ {
602  };
603  };
605 
607  int32_t element_index_;
608  int32_t parent_index_;
609  int32_t parent_output_;
610  int32_t dof_location_;
611  int32_t com_index_;
612  int32_t output_index_;
615 
616 typedef struct HebiHighResAngleStruct_ {
617  int64_t revolutions_;
618  float offset_;
620 
621 typedef struct HebiIoBankPinStruct_ {
622  union {
623  int64_t int_value_;
624  float float_value_;
625  };
628 
632 typedef struct HebiCommandRef_ {
638  uint64_t* uint64_fields_;
639  int32_t* enum_fields_;
643  uint32_t* led_fields_;
644  void* reserved_;
646 
650 typedef struct HebiCommandMetadata_ {
651  // Total number of fields for each field type
660  uint32_t io_field_count_;
664  // Field offsets into `message_bitfield_`
677  // Corresponds to the relative offset within the relevant block of `HebiCommandRef::message_bitfield_` for individual numbered float fields.
680  // Corresponds to the relative offset within the relevant block of `HebiCommandRef::message_bitfield_` for individual io bank pins.
681  const uint32_t* io_relative_offsets_;
682  const uint32_t* io_field_sizes_;
683  // Total number of bits in `message_bitfield_`
686 
690 typedef struct HebiFeedbackRef_ {
691  const int32_t* message_bitfield_;
692  const float* float_fields_;
696  const uint64_t* uint64_fields_;
697  const int32_t* enum_fields_;
698  const bool* bool_fields_;
701  const uint32_t* led_fields_;
702  void* reserved_;
704 
708 typedef struct HebiFeedbackMetadata_ {
709  // Total number of fields for each field type
718  uint32_t io_field_count_;
722  // Field offsets into `message_bitfield_`
735  // Corresponds to the relative offset within the relevant block of `HebiFeedbackRef::message_bitfield_` for individual numbered float fields.
738  // Corresponds to the relative offset within the relevant block of `HebiFeedbackRef::message_bitfield_` for individual io bank pins.
739  const uint32_t* io_relative_offsets_;
740  const uint32_t* io_field_sizes_;
741  // Total number of bits in `message_bitfield_`
744 
748 typedef struct HebiInfoRef_ {
749  const int32_t* message_bitfield_;
750  const float* float_fields_;
754  const uint64_t* uint64_fields_;
755  const int32_t* enum_fields_;
756  const bool* bool_fields_;
759  const uint32_t* led_fields_;
760  void* reserved_;
761 } HebiInfoRef;
762 
766 typedef struct HebiInfoMetadata_ {
767  // Total number of fields for each field type
776  uint32_t io_field_count_;
780  // Field offsets into `message_bitfield_`
793  // Corresponds to the relative offset within the relevant block of `HebiInfoRef::message_bitfield_` for individual numbered float fields.
796  // Corresponds to the relative offset within the relevant block of `HebiInfoRef::message_bitfield_` for individual io bank pins.
797  const uint32_t* io_relative_offsets_;
798  const uint32_t* io_field_sizes_;
799  // Total number of bits in `message_bitfield_`
802 
806 
826 HebiLookupPtr hebiLookupCreate(const char* const* ifaces, size_t ifaces_length);
827 
834 void hebiLookupRelease(HebiLookupPtr lookup);
835 
842 
847 
855 
862 
883 HebiStatusCode hebiLookupEntryListGetName(HebiLookupEntryListPtr lookup_list, size_t index, char* buffer,
884  size_t* length);
885 
906 HebiStatusCode hebiLookupEntryListGetFamily(HebiLookupEntryListPtr lookup_list, size_t index, char* buffer,
907  size_t* length);
908 
921  HebiMacAddress* mac_address);
922 
930 
934 
950 
972 HebiGroupPtr hebiGroupCreateFromMacs(HebiLookupPtr lookup, const HebiMacAddress* const* addresses, size_t num_addresses,
973  int32_t timeout_ms);
974 
1008 HebiGroupPtr hebiGroupCreateFromNames(HebiLookupPtr lookup, const char* const* families, size_t num_families,
1009  const char* const* names, size_t num_names, int32_t timeout_ms);
1010 
1029 HebiGroupPtr hebiGroupCreateFromFamily(HebiLookupPtr lookup, const char* family, int32_t timeout_ms);
1030 
1052 HebiGroupPtr hebiGroupCreateConnectedFromMac(HebiLookupPtr lookup, const HebiMacAddress* address, int32_t timeout_ms);
1053 
1076 HebiGroupPtr hebiGroupCreateConnectedFromName(HebiLookupPtr lookup, const char* family, const char* name,
1077  int32_t timeout_ms);
1078 
1086 size_t hebiGroupGetSize(HebiGroupPtr group);
1087 
1108  int32_t timeout_ms);
1109 
1123 
1147 HebiStatusCode hebiGroupSetCommandLifetime(HebiGroupPtr group, int32_t lifetime_ms);
1148 
1158 
1173 
1182 
1194  void* user_data);
1195 
1203 
1218 
1240 HebiStatusCode hebiGroupGetNextFeedback(HebiGroupPtr group, HebiGroupFeedbackPtr feedback, int32_t timeout_ms);
1241 
1259 HebiStatusCode hebiGroupRequestInfo(HebiGroupPtr group, HebiGroupInfoPtr info, int32_t timeout_ms);
1260 
1277 HebiStatusCode hebiGroupStartLog(HebiGroupPtr group, const char* dir, const char* file, HebiStringPtr* ret);
1278 
1290 
1297 void hebiGroupRelease(HebiGroupPtr group);
1298 
1309 
1316 
1334 
1345 
1363 
1374 
1385 
1402 
1407 
1414 
1425 
1432 
1443 
1460 
1465 
1472 
1483 
1490 
1501 
1512 
1522 HebiInfoPtr hebiGroupInfoGetModuleInfo(HebiGroupInfoPtr info, size_t module_index);
1523 
1540 
1545 
1552 
1556 
1583 HebiStatusCode hebiCommandGetString(HebiCommandPtr command, HebiCommandStringField field, char* buffer, size_t* length);
1584 
1595 void hebiCommandSetString(HebiCommandPtr command, HebiCommandStringField field, const char* buffer,
1596  const size_t* length);
1597 
1602 
1607 
1611 
1612 
1617 
1622 
1626 
1653 HebiStatusCode hebiInfoGetString(HebiInfoPtr info, HebiInfoStringField field, char* buffer, size_t* length);
1654 
1659 
1663 void hebiInfoGetMetadata(HebiInfoMetadata* metadata);
1664 
1668 
1680 
1701 HebiRobotModelElementPtr hebiRobotModelElementCreateRigidBody(const double* com, const double* inertia, double mass,
1702  size_t num_outputs, const double* outputs,
1703  HebiMatrixOrdering ordering);
1704 
1732  const double* com, const double* inertia,
1733  double mass, const double* output_frame,
1734  HebiMatrixOrdering ordering);
1735 
1747 
1760 
1781  HebiLinkOutputType output_type, double extension,
1782  double twist);
1783 
1796 
1811 HebiRobotModelPtr hebiRobotModelImport(const char* file);
1812 
1829 HebiRobotModelPtr hebiRobotModelImportBuffer(const char* buffer, size_t buffer_size);
1830 
1840 const char* hebiRobotModelGetImportError();
1841 
1851 
1866 const char* hebiRobotModelGetImportWarning(size_t warning_index);
1867 
1876 
1889 HebiStatusCode hebiRobotModelSetBaseFrame(HebiRobotModelPtr robot_model, const double* transform,
1890  HebiMatrixOrdering ordering);
1891 
1904 HebiStatusCode hebiRobotModelGetBaseFrame(HebiRobotModelPtr robot_model, double* transform,
1905  HebiMatrixOrdering ordering);
1906 
1920 size_t hebiRobotModelGetNumberOfFrames(HebiRobotModelPtr robot_model, HebiFrameType frame_type);
1921 
1929 
1937 
1957 
1995  size_t output_index, HebiRobotModelElementPtr new_element);
1996 
2033  const double* positions, double* frames, HebiMatrixOrdering ordering);
2034 
2053  const double* positions, double* jacobians, HebiMatrixOrdering ordering);
2054 
2067 HebiStatusCode hebiRobotModelGetMasses(HebiRobotModelPtr robot_model, double* masses);
2068 
2069 
2083 
2084 
2092 void hebiRobotModelRelease(HebiRobotModelPtr robot_model);
2093 
2097 
2105 HebiIKPtr hebiIKCreate(void);
2106 
2126 HebiStatusCode hebiIKAddObjectiveEndEffectorPosition(HebiIKPtr ik, double weight, size_t end_effector_index, double x,
2127  double y, double z);
2128 
2147 HebiStatusCode hebiIKAddObjectiveEndEffectorSO3(HebiIKPtr ik, double weight, size_t end_effector_index,
2148  const double* matrix, HebiMatrixOrdering ordering);
2149 
2168 HebiStatusCode hebiIKAddObjectiveEndEffectorTipAxis(HebiIKPtr ik, double weight, size_t end_effector_index, double x,
2169  double y, double z);
2170 
2190 HebiStatusCode hebiIKAddConstraintJointAngles(HebiIKPtr ik, double weight, size_t num_joints,
2191  const double* min_positions, const double* max_positions);
2192 
2215 HebiStatusCode hebiIKAddObjectiveCustom(HebiIKPtr ik, double weight, size_t num_errors,
2216  void (*err_fnc)(void* user_data, size_t num_positions, const double* positions,
2217  double* errors),
2218  void* user_data);
2219 
2224 void hebiIKClearAll(HebiIKPtr ik);
2225 
2247 HebiStatusCode hebiIKSolve(HebiIKPtr ik, HebiRobotModelPtr model, const double* initial_positions, double* ik_solution,
2248  void* result_info);
2249 
2257 void hebiIKRelease(HebiIKPtr ik);
2258 
2262 
2288 HebiTrajectoryPtr hebiTrajectoryCreateUnconstrainedQp(size_t num_waypoints, const double* positions,
2289  const double* velocities, const double* accelerations,
2290  const double* time_vector);
2291 
2297 void hebiTrajectoryRelease(HebiTrajectoryPtr trajectory);
2298 
2302 double hebiTrajectoryGetDuration(HebiTrajectoryPtr trajectory);
2303 
2319 HebiStatusCode hebiTrajectoryGetState(HebiTrajectoryPtr trajectory, double time, double* position, double* velocity,
2320  double* acceleration);
2321 
2325 
2329 void hebiLogFileRelease(HebiLogFilePtr log_file);
2330 
2346 HebiStatusCode hebiLogFileGetFileName(HebiLogFilePtr log_file, char* buffer, size_t* length);
2347 
2360 HebiLogFilePtr hebiLogFileOpen(const char* file);
2361 
2368 
2376 
2380 
2395 HebiStatusCode hebiStringGetString(HebiStringPtr str, char* buffer, size_t* length);
2396 
2401 
2405 
2413 const char* hebiSafetyParametersGetLastError(void);
2414 
2423 HebiStatusCode hebiGetLibraryVersion(int32_t* major, int32_t* minor, int32_t* revision);
2424 
2429 void hebiCleanup(void);
2430 
2431 #ifdef __cplusplus
2432 } // extern "C"
2433 #endif
HebiCommandMetadata_::io_field_sizes_
const uint32_t * io_field_sizes_
Definition: hebi.h:682
HebiFeedbackFloatBatteryLevel
@ HebiFeedbackFloatBatteryLevel
The estimated temperature of the motor housing.
Definition: hebi.h:177
HebiArQualityLimitedInsufficientFeatures
@ HebiArQualityLimitedInsufficientFeatures
The device is moving too fast for accurate image-based position tracking.
Definition: hebi.h:41
HebiRobotModelElementTopology_::parent_output_
int32_t parent_output_
Definition: hebi.h:609
hebiIKAddObjectiveEndEffectorPosition
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,...
hebiGroupFeedbackClear
void hebiGroupFeedbackClear(HebiGroupFeedbackPtr feedback)
Clears all data in the GroupFeedback object.
HebiFeedbackMetadata_::uint64_field_count_
uint32_t uint64_field_count_
Definition: hebi.h:714
HebiInfoFloatPositionKd
@ HebiInfoFloatPositionKd
Integral PID gain for position.
Definition: hebi.h:241
hebiRobotModelRelease
void hebiRobotModelRelease(HebiRobotModelPtr robot_model)
Frees resources created by this robot model object.
HebiMatrixOrderingRowMajor
@ HebiMatrixOrderingRowMajor
Definition: hebi.h:431
hebiInfoGetString
HebiStatusCode hebiInfoGetString(HebiInfoPtr info, HebiInfoStringField field, char *buffer, size_t *length)
Info API.
HebiInfoLedLed
@ HebiInfoLedLed
Definition: hebi.h:316
hebiGroupCommandGetModuleCommand
HebiCommandPtr hebiGroupCommandGetModuleCommand(HebiGroupCommandPtr command, size_t module_index)
Get an individual command for a particular module at index module_index.
HebiInfoMetadata_::float_field_count_
uint32_t float_field_count_
Definition: hebi.h:768
HebiLinkTypeX5
@ HebiLinkTypeX5
Definition: hebi.h:380
HebiCommandFloatEffortLimitMin
@ HebiCommandFloatEffortLimitMin
The firmware safety limit for the maximum allowed velocity.
Definition: hebi.h:102
HebiFeedbackHighResAnglePosition
@ HebiFeedbackHighResAnglePosition
Definition: hebi.h:182
HebiFeedbackRef_::numbered_float_fields_
const float * numbered_float_fields_
Definition: hebi.h:699
HebiCommandBoolPositionDOnError
@ HebiCommandBoolPositionDOnError
Definition: hebi.h:117
HebiCommandMetadata
struct HebiCommandMetadata_ HebiCommandMetadata
HebiFeedbackEnumEffortLimitState
@ HebiFeedbackEnumEffortLimitState
Software-controlled bounds on the allowable velocity of the module.
Definition: hebi.h:216
HebiInfoFloatEffortOutputLowpass
@ HebiInfoFloatEffortOutputLowpass
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:277
HebiCommandFlagClearLog
@ HebiCommandFlagClearLog
Stop the module from automatically booting into application.
Definition: hebi.h:134
HebiRobotModelElementPtr
struct HebiRobotModelElement_ * HebiRobotModelElementPtr
Definition: hebi.h:533
hebiRobotModelGetImportWarningCount
size_t hebiRobotModelGetImportWarningCount()
Retrieve the number of warnings corresponding to the last call to hebiRobotModelImport....
HebiActuatorTypeX8_3
@ HebiActuatorTypeX8_3
Definition: hebi.h:368
HebiInfoFloatVelocityDeadZone
@ HebiInfoFloatVelocityDeadZone
Feed forward term for velocity (this term is multiplied by the target and added to the output).
Definition: hebi.h:256
HebiFeedbackMetadata_::io_field_bitfield_offset_
uint32_t io_field_bitfield_offset_
Definition: hebi.h:731
hebiRobotModelImportBuffer
HebiRobotModelPtr hebiRobotModelImportBuffer(const char *buffer, size_t buffer_size)
Import robot model from a buffer into a RobotModel object.
HebiInfoEnumMstopStrategy
@ HebiInfoEnumMstopStrategy
The calibration state of the module.
Definition: hebi.h:310
hebiGroupGetNextFeedback
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
@ HebiCommandFloatPositionDeadZone
Feed forward term for position (this term is multiplied by the target and added to the output).
Definition: hebi.h:62
HebiCommandFloatPositionKp
@ HebiCommandFloatPositionKp
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages).
Definition: hebi.h:58
HebiCommandFloatVelocityKi
@ HebiCommandFloatVelocityKi
Proportional PID gain for velocity.
Definition: hebi.h:72
HebiCommandFloatVelocityOutputLowpass
@ HebiCommandFloatVelocityOutputLowpass
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:83
hebiLookupSetLookupFrequencyHz
HebiStatusCode hebiLookupSetLookupFrequencyHz(HebiLookupPtr lookup, double frequency)
sets the lookup request rate [Hz]
HebiStatusArgumentOutOfRange
@ HebiStatusArgumentOutOfRange
Generic code for failure; this is generally used for an internal or unknown failure.
Definition: hebi.h:29
hebiGroupFeedbackCopy
HebiStatusCode hebiGroupFeedbackCopy(HebiGroupFeedbackPtr dest, HebiGroupFeedbackPtr src)
Clears the dest GroupFeedback object, and copies all data from the src GroupFeedback object to dest.
HebiFeedbackMetadata_::bool_field_count_
uint32_t bool_field_count_
Definition: hebi.h:716
HebiCommandLedField
HebiCommandLedField
Definition: hebi.h:153
HebiFeedbackFloatMotorCurrent
@ HebiFeedbackFloatMotorCurrent
The velocity of the motor shaft.
Definition: hebi.h:172
HebiCommandIoBankC
@ HebiCommandIoBankC
I/O pin bank b (pins 1-8 available)
Definition: hebi.h:147
HebiMatrixOrdering
HebiMatrixOrdering
Definition: hebi.h:430
HebiFeedbackIoBankB
@ HebiFeedbackIoBankB
I/O pin bank a (pins 1-8 available)
Definition: hebi.h:223
HebiInfoMetadata_::io_field_sizes_
const uint32_t * io_field_sizes_
Definition: hebi.h:798
HebiInfoFloatEffortMinTarget
@ HebiInfoFloatEffortMinTarget
Constant offset to the effort PID output outside of the deadzone; it is added when the error is posit...
Definition: hebi.h:272
HebiVector3f_::x
float x
Definition: hebi.h:565
HebiCommandFlagReset
@ HebiCommandFlagReset
Indicates if the module should save the current values of all of its settings.
Definition: hebi.h:131
HebiQuaternionf_::z
float z
Definition: hebi.h:574
HebiCommandMetadata_::io_field_bitfield_offset_
uint32_t io_field_bitfield_offset_
Definition: hebi.h:673
HebiRobotModelElementMetadata_::bracket_type_
HebiBracketType bracket_type_
Definition: hebi.h:588
HebiJointTypeTranslationZ
@ HebiJointTypeTranslationZ
Definition: hebi.h:358
HebiRobotModelElementMetadata_
Definition: hebi.h:580
HebiArQuality
HebiArQuality
Definition: hebi.h:35
HebiInfoFloatPositionMaxTarget
@ HebiInfoFloatPositionMaxTarget
Minimum allowed value for input to the PID controller.
Definition: hebi.h:247
HebiCommandFloatVelocityMaxOutput
@ HebiCommandFloatVelocityMaxOutput
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:82
hebiIKSolve
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.
HebiCommandMetadata_::string_field_count_
uint32_t string_field_count_
Definition: hebi.h:662
HebiCommandFloatPositionMaxTarget
@ HebiCommandFloatPositionMaxTarget
Minimum allowed value for input to the PID controller.
Definition: hebi.h:66
HebiRobotModelElementTopology_::output_index_
int32_t output_index_
Definition: hebi.h:612
HebiInfoFloatVelocityLimitMax
@ HebiInfoFloatVelocityLimitMax
The firmware safety limit for the minimum allowed velocity.
Definition: hebi.h:280
HebiStatusSuccess
@ HebiStatusSuccess
Definition: hebi.h:24
HebiCommandStringAppendLog
@ HebiCommandStringAppendLog
The family for this module. The string must be null-terminated and less than 21 characters.
Definition: hebi.h:126
hebiGroupGetFeedbackFrequencyHz
float hebiGroupGetFeedbackFrequencyHz(HebiGroupPtr group)
Returns the current feedback request loop frequency (in Hz).
HebiBracketTypeX5HeavyLeftInside
@ HebiBracketTypeX5HeavyLeftInside
Definition: hebi.h:406
HebiFeedbackRef
struct HebiFeedbackRef_ HebiFeedbackRef
HebiInfoStringField
HebiInfoStringField
Definition: hebi.h:297
HebiInfoFloatVelocityIClamp
@ HebiInfoFloatVelocityIClamp
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:257
hebiRobotModelGetImportWarning
const char * hebiRobotModelGetImportWarning(size_t warning_index)
Retrieve the 'ith' warning string from the last call to hebiRobotModelImport. This must be called on ...
HebiFeedbackFloatVelocityCommand
@ HebiFeedbackFloatVelocityCommand
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages).
Definition: hebi.h:167
HebiLinkInputTypeRightAngle
@ HebiLinkInputTypeRightAngle
Definition: hebi.h:388
HebiInfoRef_::enum_fields_
const int32_t * enum_fields_
Definition: hebi.h:755
hebiGroupCreateConnectedFromName
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
@ HebiInfoFloatEffortMinOutput
A simple lowpass filter applied to the target set point; needs to be between 0 and 1....
Definition: hebi.h:275
HebiFeedbackIoBankC
@ HebiFeedbackIoBankC
I/O pin bank b (pins 1-8 available)
Definition: hebi.h:224
HebiArQualityNotAvailable
@ HebiArQualityNotAvailable
Definition: hebi.h:36
HebiActuatorTypeX5_4
@ HebiActuatorTypeX5_4
Definition: hebi.h:366
HebiCommandFlagBoot
@ HebiCommandFlagBoot
Restart the module.
Definition: hebi.h:132
HebiCommandIoBankD
@ HebiCommandIoBankD
I/O pin bank c (pins 1-8 available)
Definition: hebi.h:148
HebiStatusCode
HebiStatusCode
Enum Types.
Definition: hebi.h:23
HebiCommandBoolVelocityDOnError
@ HebiCommandBoolVelocityDOnError
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
Definition: hebi.h:118
HebiQuaternionf_
Definition: hebi.h:570
HebiInfoMetadata_::float_field_bitfield_offset_
uint32_t float_field_bitfield_offset_
Definition: hebi.h:781
HebiCommandFloatField
HebiCommandFloatField
Command Enums.
Definition: hebi.h:55
HebiFeedbackEnumTemperatureState
@ HebiFeedbackEnumTemperatureState
Definition: hebi.h:212
HebiFeedbackUInt64ReceiveTime
@ HebiFeedbackUInt64ReceiveTime
Sequence number going to module (local)
Definition: hebi.h:193
HebiCommandIoBankF
@ HebiCommandIoBankF
I/O pin bank e (pins 1-8 available)
Definition: hebi.h:150
HebiBracketTypeX5HeavyRightInside
@ HebiBracketTypeX5HeavyRightInside
Definition: hebi.h:408
HebiInfoRef_::uint64_fields_
const uint64_t * uint64_fields_
Definition: hebi.h:754
HebiCommandFloatEffortMaxTarget
@ HebiCommandFloatEffortMaxTarget
Minimum allowed value for input to the PID controller.
Definition: hebi.h:92
HebiIoBankPinResidentTypeNone
@ HebiIoBankPinResidentTypeNone
Definition: hebi.h:46
hebiCreateLookupEntryList
HebiLookupEntryListPtr hebiCreateLookupEntryList(HebiLookupPtr lookup)
Return a snapshot of the contents of the module registry – i.e., which modules have been found by the...
HebiCommandMetadata_::vector3f_field_count_
uint32_t vector3f_field_count_
Definition: hebi.h:654
HebiGroupFeedbackPtr
struct HebiGroupFeedback_ * HebiGroupFeedbackPtr
The C-style's API representation of a feedback object for a group of modules.
Definition: hebi.h:476
hebiGroupCommandWriteGains
HebiStatusCode hebiGroupCommandWriteGains(HebiGroupCommandPtr command, const char *file)
Export gains from a GroupCommand object into a file.
HebiFeedbackFloatProcessorTemperature
@ HebiFeedbackFloatProcessorTemperature
Ambient temperature inside the module (measured at the IMU chip)
Definition: hebi.h:163
HebiInfoMetadata_::quaternionf_field_count_
uint32_t quaternionf_field_count_
Definition: hebi.h:771
HebiFeedbackRef_::enum_fields_
const int32_t * enum_fields_
Definition: hebi.h:697
HebiCommandMetadata_
Definition: hebi.h:650
HebiCommandRef_::led_fields_
uint32_t * led_fields_
Definition: hebi.h:643
HebiFeedbackQuaternionfField
HebiFeedbackQuaternionfField
Definition: hebi.h:206
HebiCommandStringFamily
@ HebiCommandStringFamily
The name for this module. The string must be null-terminated and less than 21 characters.
Definition: hebi.h:125
HebiIoBankPinStruct_::int_value_
int64_t int_value_
Definition: hebi.h:623
HebiFrameTypeEndEffector
@ HebiFrameTypeEndEffector
Definition: hebi.h:330
HebiVector3f_::z
float z
Definition: hebi.h:567
hebiGroupInfoRelease
void hebiGroupInfoRelease(HebiGroupInfoPtr info)
Frees resources created by the GroupInfo object.
HebiBracketTypeR8HeavyRightOutside
@ HebiBracketTypeR8HeavyRightOutside
Definition: hebi.h:415
HebiFeedbackMetadata_::string_field_bitfield_offset_
uint32_t string_field_bitfield_offset_
Definition: hebi.h:733
HebiMacAddress_::bytes_
uint8_t bytes_[6]
Definition: hebi.h:561
HebiFeedbackHighResAngleMotorPosition
@ HebiFeedbackHighResAngleMotorPosition
Commanded position of the module output (post-spring).
Definition: hebi.h:184
HebiActuatorTypeX5_1
@ HebiActuatorTypeX5_1
Definition: hebi.h:365
hebiTrajectoryRelease
void hebiTrajectoryRelease(HebiTrajectoryPtr trajectory)
Frees resources created by this trajectory.
hebiRobotModelElementCreateLink
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
@ HebiInfoFloatPositionFeedForward
Derivative PID gain for position.
Definition: hebi.h:242
HebiCommandFloatVelocityDeadZone
@ HebiCommandFloatVelocityDeadZone
Feed forward term for velocity (this term is multiplied by the target and added to the output).
Definition: hebi.h:75
HebiFeedbackMetadata_::io_field_sizes_
const uint32_t * io_field_sizes_
Definition: hebi.h:740
HebiCommandFlagSaveCurrentSettings
@ HebiCommandFlagSaveCurrentSettings
Definition: hebi.h:130
HebiQuaternionf_::x
float x
Definition: hebi.h:572
HebiFeedbackMetadata_
Definition: hebi.h:708
HebiCommandMetadata_::led_field_count_
uint32_t led_field_count_
Definition: hebi.h:661
HebiFeedbackHighResAnglePositionCommand
@ HebiFeedbackHighResAnglePositionCommand
Position of the module output (post-spring).
Definition: hebi.h:183
HebiJointTypeRotationZ
@ HebiJointTypeRotationZ
Definition: hebi.h:355
HebiInfoMetadata_::enum_field_bitfield_offset_
uint32_t enum_field_bitfield_offset_
Definition: hebi.h:786
HebiInfoPtr
struct HebiInfo_ * HebiInfoPtr
The C-style's API representation of info.
Definition: hebi.h:458
HebiInfoMetadata_::message_bitfield_count_
uint32_t message_bitfield_count_
Definition: hebi.h:800
HebiGroupPtr
struct HebiGroup_ * HebiGroupPtr
The C-style's API representation of a group.
Definition: hebi.h:493
hebiRobotModelElementRelease
void hebiRobotModelElementRelease(HebiRobotModelElementPtr element)
Frees resources created by this element.
HebiInfoMetadata_::vector3f_field_count_
uint32_t vector3f_field_count_
Definition: hebi.h:770
HebiMatrixOrderingColumnMajor
@ HebiMatrixOrderingColumnMajor
Definition: hebi.h:432
HebiJointType
HebiJointType
Definition: hebi.h:352
hebiGroupClearFeedbackHandlers
void hebiGroupClearFeedbackHandlers(HebiGroupPtr group)
Removes all feedback handling functions from the queue to be called on receipt of group feedback.
hebiGroupStartLog
HebiStatusCode hebiGroupStartLog(HebiGroupPtr group, const char *dir, const char *file, HebiStringPtr *ret)
Starts logging data to a file.
HebiJointTypeRotationY
@ HebiJointTypeRotationY
Definition: hebi.h:354
HebiFeedbackUInt64Field
HebiFeedbackUInt64Field
Definition: hebi.h:191
hebiCleanup
void hebiCleanup(void)
Frees all resources created by the library. Note: any calls to the HEBI library functions after this ...
hebiGroupCreateFromFamily
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.
hebiGroupSendCommandWithAcknowledgement
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
@ HebiInfoFloatPositionMinTarget
Constant offset to the position PID output outside of the deadzone; it is added when the error is pos...
Definition: hebi.h:246
hebiGroupCommandClear
void hebiGroupCommandClear(HebiGroupCommandPtr command)
Clears all data in the GroupCommand object.
HebiInfoMetadata_::vector3f_field_bitfield_offset_
uint32_t vector3f_field_bitfield_offset_
Definition: hebi.h:783
hebiGroupSetCommandLifetime
HebiStatusCode hebiGroupSetCommandLifetime(HebiGroupPtr group, int32_t lifetime_ms)
Sets the command lifetime for the group, in milliseconds.
hebiGroupGetCommandLifetime
int32_t hebiGroupGetCommandLifetime(HebiGroupPtr group)
Returns the current command lifetime, in milliseconds.
HebiCommandFloatEffortKi
@ HebiCommandFloatEffortKi
Proportional PID gain for effort.
Definition: hebi.h:85
hebiGroupInfoWriteGains
HebiStatusCode hebiGroupInfoWriteGains(HebiGroupInfoPtr info, const char *file)
Export gains from a GroupInfo object into a file.
HebiActuatorTypeR8_16
@ HebiActuatorTypeR8_16
Definition: hebi.h:373
HebiFeedbackMetadata_::quaternionf_field_count_
uint32_t quaternionf_field_count_
Definition: hebi.h:713
HebiInfoMetadata_::high_res_angle_field_count_
uint32_t high_res_angle_field_count_
Definition: hebi.h:769
HebiFeedbackHighResAngleField
HebiFeedbackHighResAngleField
Definition: hebi.h:181
HebiStatusBufferTooSmall
@ HebiStatusBufferTooSmall
An invalid argument was supplied to the routine (e.g. null pointer)
Definition: hebi.h:26
HebiInfoFloatVelocityMinTarget
@ HebiInfoFloatVelocityMinTarget
Constant offset to the velocity PID output outside of the deadzone; it is added when the error is pos...
Definition: hebi.h:259
HebiInfoMetadata
struct HebiInfoMetadata_ HebiInfoMetadata
hebiCommandGetReference
void hebiCommandGetReference(HebiCommandPtr command, HebiCommandRef *ref)
HebiFeedbackFloatEffort
@ HebiFeedbackFloatEffort
Velocity of the module output (post-spring).
Definition: hebi.h:166
hebiGroupInfoClear
void hebiGroupInfoClear(HebiGroupInfoPtr info)
Clears all data in the GroupInfo object.
HebiCommandMetadata_::string_field_bitfield_offset_
uint32_t string_field_bitfield_offset_
Definition: hebi.h:675
hebiGroupSendFeedbackRequest
HebiStatusCode hebiGroupSendFeedbackRequest(HebiGroupPtr group)
Requests feedback from the group.
HebiRobotModelElementMetadata_::output_type_
HebiLinkOutputType output_type_
Definition: hebi.h:596
HebiInfoEnumCalibrationState
@ HebiInfoEnumCalibrationState
How the position, velocity, and effort PID loops are connected in order to control motor PWM.
Definition: hebi.h:309
HebiCommandBoolAccelIncludesGravity
@ HebiCommandBoolAccelIncludesGravity
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
Definition: hebi.h:120
hebiIKAddObjectiveCustom
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
@ HebiFeedbackFloatVelocity
Bus voltage at which the module is running.
Definition: hebi.h:165
HebiRobotModelElementMetadata_::actuator_type_
HebiActuatorType actuator_type_
Definition: hebi.h:585
HebiIKPtr
struct HebiIK_ * HebiIKPtr
Definition: hebi.h:540
HebiInfoFloatVelocityKi
@ HebiInfoFloatVelocityKi
Proportional PID gain for velocity.
Definition: hebi.h:253
hebiRobotModelElementCreateEndEffector
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...
HebiCommandRef_::message_bitfield_
int32_t * message_bitfield_
Definition: hebi.h:633
hebiGroupFeedbackGetModuleFeedback
HebiFeedbackPtr hebiGroupFeedbackGetModuleFeedback(HebiGroupFeedbackPtr feedback, size_t module_index)
Get an individual feedback for a particular module at index module_index.
hebiCommandGetMetadata
void hebiCommandGetMetadata(HebiCommandMetadata *metadata)
HebiIoBankPinResidentType
HebiIoBankPinResidentType
Definition: hebi.h:45
HebiCommandRef_::io_fields_
HebiIoBankPinStruct * io_fields_
Definition: hebi.h:642
hebiGroupCreateConnectedFromMac
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
@ HebiIoBankPinResidentTypeFloat
Definition: hebi.h:48
HebiLinkOutputTypeRightAngle
@ HebiLinkOutputTypeRightAngle
Definition: hebi.h:396
HebiRobotModelElementType
HebiRobotModelElementType
Definition: hebi.h:338
HebiInfoBoolField
HebiInfoBoolField
Definition: hebi.h:290
hebiStringRelease
void hebiStringRelease(HebiStringPtr str)
Releases a string instance.
HebiFeedbackUInt64TransmitTime
@ HebiFeedbackUInt64TransmitTime
Timestamp of when message was received from module (local)
Definition: hebi.h:194
hebiGroupRelease
void hebiGroupRelease(HebiGroupPtr group)
Release resources for a given group; group should not be used after this call.
HebiInfoRef_::io_fields_
const HebiIoBankPinStruct * io_fields_
Definition: hebi.h:758
HebiActuatorType
HebiActuatorType
Definition: hebi.h:364
hebiGroupCreateImitation
HebiGroupPtr hebiGroupCreateImitation(size_t size)
Group API.
HebiQuaternionf
struct HebiQuaternionf_ HebiQuaternionf
hebiRobotModelElementCreateBracket
HebiRobotModelElementPtr hebiRobotModelElementCreateBracket(HebiBracketType bracket_type)
Creates a rigid body, including mass and static transforms, corresponding to a standard HEBI bracket.
HebiFeedbackFloatMotorHousingTemperature
@ HebiFeedbackFloatMotorHousingTemperature
The estimated temperature of the motor windings.
Definition: hebi.h:176
HebiFeedbackIoBankA
@ HebiFeedbackIoBankA
Definition: hebi.h:222
HebiStatusFailure
@ HebiStatusFailure
Returned when an accessor function attempts to retrieve a field which is not set.
Definition: hebi.h:28
hebiRobotModelGetTreeTopology
HebiStatusCode hebiRobotModelGetTreeTopology(HebiRobotModelPtr robot_model, HebiFrameType frame_type, HebiRobotModelElementTopology *table)
returns table of information about the shape of kinematic tree
hebiGroupRegisterFeedbackHandler
HebiStatusCode hebiGroupRegisterFeedbackHandler(HebiGroupPtr group, GroupFeedbackHandlerFunction handler, void *user_data)
Add a function that is called whenever feedback is returned from the group.
HebiActuatorTypeX8_9
@ HebiActuatorTypeX8_9
Definition: hebi.h:369
HebiFeedbackMetadata_::float_field_count_
uint32_t float_field_count_
Definition: hebi.h:710
HebiInfoFloatEffortLimitMax
@ HebiInfoFloatEffortLimitMax
The firmware safety limit for the minimum allowed effort.
Definition: hebi.h:282
HebiCommandRef_::high_res_angle_fields_
HebiHighResAngleStruct * high_res_angle_fields_
Definition: hebi.h:635
HebiLinkOutputTypeInline
@ HebiLinkOutputTypeInline
Definition: hebi.h:397
HebiInfoFloatVelocityMaxTarget
@ HebiInfoFloatVelocityMaxTarget
Minimum allowed value for input to the PID controller.
Definition: hebi.h:260
HebiLookupPtr
struct HebiLookup_ * HebiLookupPtr
Definition: hebi.h:500
HebiFeedbackPtr
struct HebiFeedback_ * HebiFeedbackPtr
The C-style's API representation of feedback.
Definition: hebi.h:451
HebiRobotModelElementTypeJoint
@ HebiRobotModelElementTypeJoint
Definition: hebi.h:342
HebiLinkOutputType
HebiLinkOutputType
Definition: hebi.h:395
HebiInfoFloatSpringConstant
@ HebiInfoFloatSpringConstant
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
Definition: hebi.h:278
HebiFeedbackRef_::uint64_fields_
const uint64_t * uint64_fields_
Definition: hebi.h:696
HebiCommandMetadata_::uint64_field_count_
uint32_t uint64_field_count_
Definition: hebi.h:656
HebiInfoFloatPositionKp
@ HebiInfoFloatPositionKp
Definition: hebi.h:239
HebiFeedbackRef_
Definition: hebi.h:690
HebiInfoMetadata_::numbered_float_relative_offsets_
const uint32_t * numbered_float_relative_offsets_
Definition: hebi.h:794
HebiInfoRef_::reserved_
void * reserved_
Definition: hebi.h:760
HebiCommandNumberedFloatField
HebiCommandNumberedFloatField
Definition: hebi.h:112
hebiLogFileGetFileName
HebiStatusCode hebiLogFileGetFileName(HebiLogFilePtr log_file, char *buffer, size_t *length)
Copy the path and name of the log file into a buffer.
hebiGroupInfoCreate
HebiGroupInfoPtr hebiGroupInfoCreate(size_t size)
Creates a GroupInfo for a group with the specified number of modules.
HebiEndEffectorType
HebiEndEffectorType
Definition: hebi.h:421
HebiInfoFloatEffortLimitMin
@ HebiInfoFloatEffortLimitMin
The firmware safety limit for the maximum allowed velocity.
Definition: hebi.h:281
HebiRobotModelElementTopology_::parent_index_
int32_t parent_index_
Definition: hebi.h:608
HebiFeedbackRef_::vector3f_fields_
const HebiVector3f * vector3f_fields_
Definition: hebi.h:694
hebiGroupFeedbackCreate
HebiGroupFeedbackPtr hebiGroupFeedbackCreate(size_t size)
Creates a GroupFeedback for a group with the specified number of modules.
HebiBracketTypeX5LightLeft
@ HebiBracketTypeX5LightLeft
Definition: hebi.h:404
HebiHighResAngleStruct_::revolutions_
int64_t revolutions_
Definition: hebi.h:617
HebiBracketTypeR8HeavyLeftOutside
@ HebiBracketTypeR8HeavyLeftOutside
Definition: hebi.h:413
hebiLookupEntryListGetFamily
HebiStatusCode hebiLookupEntryListGetFamily(HebiLookupEntryListPtr lookup_list, size_t index, char *buffer, size_t *length)
HebiCommandFlagStopBoot
@ HebiCommandFlagStopBoot
Boot the module from bootloader into application.
Definition: hebi.h:133
HebiArQualityLimitedExcessiveMotion
@ HebiArQualityLimitedExcessiveMotion
The AR session is attempting to resume after an interruption.
Definition: hebi.h:40
hebiGroupCommandReadGains
HebiStatusCode hebiGroupCommandReadGains(HebiGroupCommandPtr command, const char *file)
Import gains from a file into a GroupCommand object.
HebiFeedbackMetadata_::flag_field_bitfield_offset_
uint32_t flag_field_bitfield_offset_
Definition: hebi.h:734
HebiInfoMetadata_::led_field_bitfield_offset_
uint32_t led_field_bitfield_offset_
Definition: hebi.h:790
HebiInfoHighResAnglePositionLimitMin
@ HebiInfoHighResAnglePositionLimitMin
Definition: hebi.h:286
HebiQuaternionf_::y
float y
Definition: hebi.h:573
hebiGroupStopLog
HebiLogFilePtr hebiGroupStopLog(HebiGroupPtr group)
Stops logging data to a file.
HebiRobotModelElementTypeLink
@ HebiRobotModelElementTypeLink
Definition: hebi.h:343
HebiInfoMetadata_::io_field_bitfield_offset_
uint32_t io_field_bitfield_offset_
Definition: hebi.h:789
HebiCommandMetadata_::enum_field_count_
uint32_t enum_field_count_
Definition: hebi.h:657
HebiMacAddress
struct HebiMacAddress_ HebiMacAddress
Structures.
hebiRobotModelSetBaseFrame
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.
hebiTrajectoryGetState
HebiStatusCode hebiTrajectoryGetState(HebiTrajectoryPtr trajectory, double time, double *position, double *velocity, double *acceleration)
Gets the value of the trajectory at a given time.
HebiCommandFloatPositionKi
@ HebiCommandFloatPositionKi
Proportional PID gain for position.
Definition: hebi.h:59
HebiCommandMetadata_::vector3f_field_bitfield_offset_
uint32_t vector3f_field_bitfield_offset_
Definition: hebi.h:667
HebiArQualityLimitedUnknown
@ HebiArQualityLimitedUnknown
Camera position tracking is not available.
Definition: hebi.h:37
HebiInfoMetadata_::flag_field_bitfield_offset_
uint32_t flag_field_bitfield_offset_
Definition: hebi.h:792
HebiLookupEntryListPtr
struct HebiLookupEntryList_ * HebiLookupEntryListPtr
Definition: hebi.h:507
HebiInfoMetadata_::numbered_float_field_count_
uint32_t numbered_float_field_count_
Definition: hebi.h:775
HebiFeedbackFloatMotorSensorTemperature
@ HebiFeedbackFloatMotorSensorTemperature
Current supplied to the motor.
Definition: hebi.h:173
HebiCommandFloatPositionOutputLowpass
@ HebiCommandFloatPositionOutputLowpass
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:70
HebiInfoRef_::message_bitfield_
const int32_t * message_bitfield_
Definition: hebi.h:749
HebiInfoRef_::bool_fields_
const bool * bool_fields_
Definition: hebi.h:756
HebiRobotModelElementMetadata_::twist_
float twist_
Definition: hebi.h:598
HebiInfoMetadata_::bool_field_bitfield_offset_
uint32_t bool_field_bitfield_offset_
Definition: hebi.h:787
HebiFeedbackUInt64SequenceNumber
@ HebiFeedbackUInt64SequenceNumber
Definition: hebi.h:192
HebiFeedbackIoBankD
@ HebiFeedbackIoBankD
I/O pin bank c (pins 1-8 available)
Definition: hebi.h:225
hebiRobotModelGetElementMetadata
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...
hebiLogFileOpen
HebiLogFilePtr hebiLogFileOpen(const char *file)
Opens an existing log file.
HebiFeedbackMetadata_::enum_field_count_
uint32_t enum_field_count_
Definition: hebi.h:715
hebiRobotModelGetNumberOfFrames
size_t hebiRobotModelGetNumberOfFrames(HebiRobotModelPtr robot_model, HebiFrameType frame_type)
Return the number of frames in the forward kinematic tree of the robot model.
HebiInfoRef_::vector3f_fields_
const HebiVector3f * vector3f_fields_
Definition: hebi.h:752
HebiRobotModelElementMetadata_::element_type_
HebiRobotModelElementType element_type_
Definition: hebi.h:582
hebiRobotModelGetBaseFrame
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
@ HebiFeedbackFloatPwmCommand
Charge level of the device’s battery (in percent).
Definition: hebi.h:178
HebiCommandHighResAnglePositionLimitMax
@ HebiCommandHighResAnglePositionLimitMax
The firmware safety limit for the minimum allowed position.
Definition: hebi.h:109
hebiLogFileGetNextFeedback
HebiStatusCode hebiLogFileGetNextFeedback(HebiLogFilePtr log_file, HebiGroupFeedbackPtr field)
Retrieve the next group feedback from the opened log file.
HebiCommandEnumControlStrategy
@ HebiCommandEnumControlStrategy
Definition: hebi.h:138
HebiRobotModelElementTypeOther
@ HebiRobotModelElementTypeOther
Definition: hebi.h:339
HebiCommandFloatVelocity
@ HebiCommandFloatVelocity
Definition: hebi.h:56
HebiFeedbackMetadata_::bool_field_bitfield_offset_
uint32_t bool_field_bitfield_offset_
Definition: hebi.h:729
HebiFeedbackMetadata_::vector3f_field_count_
uint32_t vector3f_field_count_
Definition: hebi.h:712
HebiInfoFloatEffortMaxOutput
@ HebiInfoFloatEffortMaxOutput
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:276
HebiStatusValueNotSet
@ HebiStatusValueNotSet
A buffer supplied to the routine was too small (normally determined by a size parameter)
Definition: hebi.h:27
HebiRobotModelElementTypeEndEffector
@ HebiRobotModelElementTypeEndEffector
Definition: hebi.h:345
HebiStatusInvalidArgument
@ HebiStatusInvalidArgument
Success; no failures occurred.
Definition: hebi.h:25
HebiCommandRef_::uint64_fields_
uint64_t * uint64_fields_
Definition: hebi.h:638
HebiCommandFloatVelocityTargetLowpass
@ HebiCommandFloatVelocityTargetLowpass
Maximum allowed value for input to the PID controller.
Definition: hebi.h:80
HebiRobotModelElementTopology_::end_effector_index_
int32_t end_effector_index_
Definition: hebi.h:613
HebiInfoFloatField
HebiInfoFloatField
Info Enums.
Definition: hebi.h:238
HebiGroupInfoPtr
struct HebiGroupInfo_ * HebiGroupInfoPtr
The C-style's API representation of a info object for a group of modules.
Definition: hebi.h:485
HebiBracketTypeX5HeavyRightOutside
@ HebiBracketTypeX5HeavyRightOutside
Definition: hebi.h:409
HebiFeedbackMetadata_::led_field_bitfield_offset_
uint32_t led_field_bitfield_offset_
Definition: hebi.h:732
HebiInfoFloatPositionPunch
@ HebiInfoFloatPositionPunch
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:245
HebiGroupCommandPtr
struct HebiGroupCommand_ * HebiGroupCommandPtr
The C-style's API representation of a command object for a group of modules.
Definition: hebi.h:467
hebiGroupInfoGetSize
size_t hebiGroupInfoGetSize(HebiGroupInfoPtr info)
Return the number of modules in this group Info.
HebiLinkInputType
HebiLinkInputType
Definition: hebi.h:387
HebiIoBankPinStruct_::float_value_
float float_value_
Definition: hebi.h:624
HebiFeedbackEnumVelocityLimitState
@ HebiFeedbackEnumVelocityLimitState
Software-controlled bounds on the allowable position of the module; user settable.
Definition: hebi.h:215
HebiCommandFlagField
HebiCommandFlagField
Definition: hebi.h:129
hebiIKAddObjectiveEndEffectorSO3
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 ...
HebiRobotModelElementTopology_
Definition: hebi.h:606
HebiFeedbackMetadata_::led_field_count_
uint32_t led_field_count_
Definition: hebi.h:719
HebiFeedbackRef_::bool_fields_
const bool * bool_fields_
Definition: hebi.h:698
HebiFeedbackRef_::led_fields_
const uint32_t * led_fields_
Definition: hebi.h:701
HebiFeedbackLedLed
@ HebiFeedbackLedLed
Definition: hebi.h:231
HebiCommandMetadata_::numbered_float_field_sizes_
const uint32_t * numbered_float_field_sizes_
Definition: hebi.h:679
HebiFeedbackEnumPositionLimitState
@ HebiFeedbackEnumPositionLimitState
Current status of the MStop.
Definition: hebi.h:214
HebiFeedbackFloatMotorWindingCurrent
@ HebiFeedbackFloatMotorWindingCurrent
The temperature from a sensor near the motor housing.
Definition: hebi.h:174
HebiLinkType
HebiLinkType
Definition: hebi.h:379
HebiInfoHighResAnglePositionLimitMax
@ HebiInfoHighResAnglePositionLimitMax
The firmware safety limit for the minimum allowed position.
Definition: hebi.h:287
HebiIoBankPinResidentTypeInteger
@ HebiIoBankPinResidentTypeInteger
Definition: hebi.h:47
hebiRobotModelGetImportError
const char * hebiRobotModelGetImportError()
Retrieve any error string from the last call to hebiRobotModelImport. This must be called on the same...
hebiRobotModelImport
HebiRobotModelPtr hebiRobotModelImport(const char *file)
Import robot model from a file into a RobotModel object.
HebiFeedbackQuaternionfArOrientation
@ HebiFeedbackQuaternionfArOrientation
A filtered estimate of the orientation of the module.
Definition: hebi.h:208
HebiFeedbackFloatBoardTemperature
@ HebiFeedbackFloatBoardTemperature
Definition: hebi.h:162
HebiInfoBoolEffortDOnError
@ HebiInfoBoolEffortDOnError
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
Definition: hebi.h:293
hebiTrajectoryCreateUnconstrainedQp
HebiTrajectoryPtr hebiTrajectoryCreateUnconstrainedQp(size_t num_waypoints, const double *positions, const double *velocities, const double *accelerations, const double *time_vector)
Trajectory API.
HebiInfoFloatVelocityOutputLowpass
@ HebiInfoFloatVelocityOutputLowpass
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:264
HebiCommandMetadata_::numbered_float_relative_offsets_
const uint32_t * numbered_float_relative_offsets_
Definition: hebi.h:678
HebiInfoFloatEffortTargetLowpass
@ HebiInfoFloatEffortTargetLowpass
Maximum allowed value for input to the PID controller.
Definition: hebi.h:274
HebiInfoFloatEffortKp
@ HebiInfoFloatEffortKp
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
Definition: hebi.h:265
HebiCommandPtr
struct HebiCommand_ * HebiCommandPtr
Typedefs.
Definition: hebi.h:444
HebiCommandMetadata_::bool_field_bitfield_offset_
uint32_t bool_field_bitfield_offset_
Definition: hebi.h:671
HebiInfoMetadata_::bool_field_count_
uint32_t bool_field_count_
Definition: hebi.h:774
HebiInfoFloatEffortFeedForward
@ HebiInfoFloatEffortFeedForward
Derivative PID gain for effort.
Definition: hebi.h:268
HebiArQualityNormal
@ HebiArQualityNormal
The scene visible to the camera does not contain enough distinguishable features for image-based posi...
Definition: hebi.h:42
HebiFeedbackMetadata_::high_res_angle_field_bitfield_offset_
uint32_t high_res_angle_field_bitfield_offset_
Definition: hebi.h:724
HebiActuatorTypeX8_16
@ HebiActuatorTypeX8_16
Definition: hebi.h:370
hebiGroupSendCommand
HebiStatusCode hebiGroupSendCommand(HebiGroupPtr group, HebiGroupCommandPtr command)
Sends a command to the given group without requesting an acknowledgement.
HebiFrameTypeInput
@ HebiFrameTypeInput
Definition: hebi.h:331
HebiRobotModelElementMetadata_::input_type_
HebiLinkInputType input_type_
Definition: hebi.h:595
HebiFeedbackVector3fArPosition
@ HebiFeedbackVector3fArPosition
Gyro data.
Definition: hebi.h:203
HebiCommandFloatVelocityFeedForward
@ HebiCommandFloatVelocityFeedForward
Derivative PID gain for velocity.
Definition: hebi.h:74
HebiJointTypeTranslationX
@ HebiJointTypeTranslationX
Definition: hebi.h:356
HebiCommandEnumMaxPositionLimitStrategy
@ HebiCommandEnumMaxPositionLimitStrategy
The position limit strategy (at the minimum position) for the actuator.
Definition: hebi.h:141
HebiStringPtr
struct HebiString_ * HebiStringPtr
The C-style's API representation of a string.
Definition: hebi.h:521
HebiInfoFloatPositionTargetLowpass
@ HebiInfoFloatPositionTargetLowpass
Maximum allowed value for input to the PID controller.
Definition: hebi.h:248
HebiVector3f
struct HebiVector3f_ HebiVector3f
hebiLookupRelease
void hebiLookupRelease(HebiLookupPtr lookup)
Frees resources created by the lookup object.
HebiCommandFloatVelocityMaxTarget
@ HebiCommandFloatVelocityMaxTarget
Minimum allowed value for input to the PID controller.
Definition: hebi.h:79
HebiCommandLedLed
@ HebiCommandLedLed
Definition: hebi.h:154
hebiCommandSetString
void hebiCommandSetString(HebiCommandPtr command, HebiCommandStringField field, const char *buffer, const size_t *length)
hebiGroupFeedbackGetSize
size_t hebiGroupFeedbackGetSize(HebiGroupFeedbackPtr feedback)
Return the number of modules in this group Feedback.
HebiRobotModelElementTopology_::dof_location_
int32_t dof_location_
Definition: hebi.h:610
hebiGroupInfoCopy
HebiStatusCode hebiGroupInfoCopy(HebiGroupInfoPtr dest, HebiGroupInfoPtr src)
Clears the dest GroupInfo object, and copies all data from the src GroupInfo object to dest.
HebiFeedbackMetadata_::numbered_float_field_bitfield_offset_
uint32_t numbered_float_field_bitfield_offset_
Definition: hebi.h:730
hebiGroupGetSize
size_t hebiGroupGetSize(HebiGroupPtr group)
Returns the number of modules in a group.
hebiRobotModelElementCreateRigidBody
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
@ HebiCommandNumberedFloatDebug
Definition: hebi.h:113
HebiInfoFloatVelocityKd
@ HebiInfoFloatVelocityKd
Integral PID gain for velocity.
Definition: hebi.h:254
HebiFeedbackRef_::reserved_
void * reserved_
Definition: hebi.h:702
HebiBracketTypeR8LightLeft
@ HebiBracketTypeR8LightLeft
Definition: hebi.h:410
HebiInfoFlagField
HebiInfoFlagField
Definition: hebi.h:303
HebiInfoRef_::quaternionf_fields_
const HebiQuaternionf * quaternionf_fields_
Definition: hebi.h:753
hebiGroupCommandRelease
void hebiGroupCommandRelease(HebiGroupCommandPtr command)
Frees resources created by the GroupCommand object.
HebiInfoFloatPositionDeadZone
@ HebiInfoFloatPositionDeadZone
Feed forward term for position (this term is multiplied by the target and added to the output).
Definition: hebi.h:243
HebiInfoMetadata_::led_field_count_
uint32_t led_field_count_
Definition: hebi.h:777
HebiCommandFloatEffortPunch
@ HebiCommandFloatEffortPunch
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:90
HebiCommandMetadata_::message_bitfield_count_
uint32_t message_bitfield_count_
Definition: hebi.h:684
HebiCommandHighResAnglePositionLimitMin
@ HebiCommandHighResAnglePositionLimitMin
Position of the module output (post-spring).
Definition: hebi.h:108
HebiFrameTypeOutput
@ HebiFrameTypeOutput
Definition: hebi.h:329
hebiLookupEntryListGetMacAddress
HebiStatusCode hebiLookupEntryListGetMacAddress(HebiLookupEntryListPtr lookup_list, size_t index, HebiMacAddress *mac_address)
hebiGroupCommandCreate
HebiGroupCommandPtr hebiGroupCommandCreate(size_t size)
Creates a GroupCommand for a group with the specified number of modules.
HebiCommandEnumField
HebiCommandEnumField
Definition: hebi.h:137
HebiInfoMetadata_::enum_field_count_
uint32_t enum_field_count_
Definition: hebi.h:773
HebiInfoFloatVelocityMinOutput
@ HebiInfoFloatVelocityMinOutput
A simple lowpass filter applied to the target set point; needs to be between 0 and 1....
Definition: hebi.h:262
hebiSafetyParametersGetLastError
const char * hebiSafetyParametersGetLastError(void)
Misc Functions.
hebiIKAddConstraintJointAngles
HebiStatusCode hebiIKAddConstraintJointAngles(HebiIKPtr ik, double weight, size_t num_joints, const double *min_positions, const double *max_positions)
Define joint angle constraints.
HebiIoBankPinStruct
struct HebiIoBankPinStruct_ HebiIoBankPinStruct
HebiEndEffectorTypeR8Parallel
@ HebiEndEffectorTypeR8Parallel
Definition: hebi.h:424
HebiCommandFloatEffortFeedForward
@ HebiCommandFloatEffortFeedForward
Derivative PID gain for effort.
Definition: hebi.h:87
HebiCommandMetadata_::numbered_float_field_bitfield_offset_
uint32_t numbered_float_field_bitfield_offset_
Definition: hebi.h:672
HebiCommandRef_::reserved_
void * reserved_
Definition: hebi.h:644
HebiFeedbackEnumArQuality
@ HebiFeedbackEnumArQuality
The state of the command lifetime safety controller, with respect to the current group.
Definition: hebi.h:218
HebiCommandRef_::quaternionf_fields_
HebiQuaternionf * quaternionf_fields_
Definition: hebi.h:637
HebiInfoRef_::float_fields_
const float * float_fields_
Definition: hebi.h:750
HebiActuatorTypeR8_3
@ HebiActuatorTypeR8_3
Definition: hebi.h:371
HebiInfoFloatPositionMaxOutput
@ HebiInfoFloatPositionMaxOutput
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:250
hebiRobotModelElementCreateActuator
HebiRobotModelElementPtr hebiRobotModelElementCreateActuator(HebiActuatorType actuator_type)
Creates a robot model element corresponding to a standard HEBI actuator.
HebiRobotModelElementMetadata_::struct_size_
uint32_t struct_size_
Definition: hebi.h:581
HebiFeedbackMetadata_::flag_field_count_
uint32_t flag_field_count_
Definition: hebi.h:721
HebiInfoRef_::high_res_angle_fields_
const HebiHighResAngleStruct * high_res_angle_fields_
Definition: hebi.h:751
HebiFeedbackVector3fAccelerometer
@ HebiFeedbackVector3fAccelerometer
Definition: hebi.h:201
HebiCommandFloatPositionFeedForward
@ HebiCommandFloatPositionFeedForward
Derivative PID gain for position.
Definition: hebi.h:61
HebiCommandIoBankA
@ HebiCommandIoBankA
Definition: hebi.h:145
HebiLogFilePtr
struct HebiLogFile_ * HebiLogFilePtr
The C-style's API representation of a log file.
Definition: hebi.h:514
HebiCommandRef_::bool_fields_
bool * bool_fields_
Definition: hebi.h:640
HebiCommandRef_::numbered_float_fields_
float * numbered_float_fields_
Definition: hebi.h:641
HebiCommandMetadata_::flag_field_count_
uint32_t flag_field_count_
Definition: hebi.h:663
HebiFeedbackQuaternionfOrientation
@ HebiFeedbackQuaternionfOrientation
Definition: hebi.h:207
HebiFeedbackMetadata
struct HebiFeedbackMetadata_ HebiFeedbackMetadata
HebiCommandRef_::float_fields_
float * float_fields_
Definition: hebi.h:634
HebiFeedbackMetadata_::float_field_bitfield_offset_
uint32_t float_field_bitfield_offset_
Definition: hebi.h:723
HebiInfoHighResAngleField
HebiInfoHighResAngleField
Definition: hebi.h:285
HebiInfoBoolVelocityDOnError
@ HebiInfoBoolVelocityDOnError
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
Definition: hebi.h:292
hebiInfoGetReference
void hebiInfoGetReference(HebiInfoPtr info, HebiInfoRef *ref)
HebiRobotModelElementMetadata_::link_type_
HebiLinkType link_type_
Definition: hebi.h:594
HebiFeedbackRef_::message_bitfield_
const int32_t * message_bitfield_
Definition: hebi.h:691
HebiFeedbackIoBankF
@ HebiFeedbackIoBankF
I/O pin bank e (pins 1-8 available)
Definition: hebi.h:227
HebiCommandHighResAngleField
HebiCommandHighResAngleField
Definition: hebi.h:106
HebiFeedbackMetadata_::numbered_float_relative_offsets_
const uint32_t * numbered_float_relative_offsets_
Definition: hebi.h:736
HebiVector3f_::y
float y
Definition: hebi.h:566
HebiRobotModelElementTopology
struct HebiRobotModelElementTopology_ HebiRobotModelElementTopology
HebiActuatorTypeX5_9
@ HebiActuatorTypeX5_9
Definition: hebi.h:367
HebiFeedbackRef_::quaternionf_fields_
const HebiQuaternionf * quaternionf_fields_
Definition: hebi.h:695
hebiIKCreate
HebiIKPtr hebiIKCreate(void)
Inverse Kinematics API.
HebiInfoFloatPositionIClamp
@ HebiInfoFloatPositionIClamp
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:244
HebiCommandBoolField
HebiCommandBoolField
Definition: hebi.h:116
HebiCommandFloatVelocityKd
@ HebiCommandFloatVelocityKd
Integral PID gain for velocity.
Definition: hebi.h:73
HebiCommandFloatEffortMinTarget
@ HebiCommandFloatEffortMinTarget
Constant offset to the effort PID output outside of the deadzone; it is added when the error is posit...
Definition: hebi.h:91
HebiFeedbackMetadata_::quaternionf_field_bitfield_offset_
uint32_t quaternionf_field_bitfield_offset_
Definition: hebi.h:726
HebiFeedbackRef_::float_fields_
const float * float_fields_
Definition: hebi.h:692
HebiInfoMetadata_::io_relative_offsets_
const uint32_t * io_relative_offsets_
Definition: hebi.h:797
HebiFeedbackVector3fGyro
@ HebiFeedbackVector3fGyro
Accelerometer data.
Definition: hebi.h:202
hebiIKClearAll
void hebiIKClearAll(HebiIKPtr ik)
Clears the objectives and constraints from this IK object, along with any modifications to the defaul...
hebiRobotModelGetNumberOfElements
size_t hebiRobotModelGetNumberOfElements(HebiRobotModelPtr robot_model)
Returns the number of elements added to the kinematic tree.
hebiGroupCommandReadSafetyParameters
HebiStatusCode hebiGroupCommandReadSafetyParameters(HebiGroupCommandPtr command, const char *file)
Import safety parameters from a file into a GroupCommand object.
HebiBracketTypeR8LightRight
@ HebiBracketTypeR8LightRight
Definition: hebi.h:411
HebiInfoFloatEffortMaxTarget
@ HebiInfoFloatEffortMaxTarget
Minimum allowed value for input to the PID controller.
Definition: hebi.h:273
HebiCommandFloatEffortIClamp
@ HebiCommandFloatEffortIClamp
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:89
HebiInfoFlagSaveCurrentSettings
@ HebiInfoFlagSaveCurrentSettings
Definition: hebi.h:304
hebiRobotModelGetNumberOfDoFs
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
@ HebiCommandFloatEffort
Velocity of the module output (post-spring).
Definition: hebi.h:57
HebiFeedbackNumberedFloatDebug
@ HebiFeedbackNumberedFloatDebug
Definition: hebi.h:188
hebiTrajectoryGetDuration
double hebiTrajectoryGetDuration(HebiTrajectoryPtr trajectory)
Returns the length of this trajectory (in seconds).
HebiEndEffectorTypeCustom
@ HebiEndEffectorTypeCustom
Definition: hebi.h:422
HebiCommandMetadata_::uint64_field_bitfield_offset_
uint32_t uint64_field_bitfield_offset_
Definition: hebi.h:669
HebiInfoMetadata_::high_res_angle_field_bitfield_offset_
uint32_t high_res_angle_field_bitfield_offset_
Definition: hebi.h:782
HebiCommandFloatVelocityMinOutput
@ HebiCommandFloatVelocityMinOutput
A simple lowpass filter applied to the target set point; needs to be between 0 and 1....
Definition: hebi.h:81
HebiRobotModelElementMetadata_::joint_type_
HebiJointType joint_type_
Definition: hebi.h:591
hebiLookupEntryListGetSize
size_t hebiLookupEntryListGetSize(HebiLookupEntryListPtr lookup_list)
hebiGroupCommandWriteSafetyParameters
HebiStatusCode hebiGroupCommandWriteSafetyParameters(HebiGroupCommandPtr command, const char *file)
Export safety parameters from a GroupCommand object into a file.
hebiGroupCommandCopy
HebiStatusCode hebiGroupCommandCopy(HebiGroupCommandPtr dest, HebiGroupCommandPtr src)
Clears the dest GroupCommand object, and copies all data from the src GroupCommand object to dest.
hebiLookupEntryListGetName
HebiStatusCode hebiLookupEntryListGetName(HebiLookupEntryListPtr lookup_list, size_t index, char *buffer, size_t *length)
HebiCommandMetadata_::enum_field_bitfield_offset_
uint32_t enum_field_bitfield_offset_
Definition: hebi.h:670
HebiInfoFloatPositionOutputLowpass
@ HebiInfoFloatPositionOutputLowpass
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:251
HebiInfoMetadata_::uint64_field_count_
uint32_t uint64_field_count_
Definition: hebi.h:772
HebiInfoEnumField
HebiInfoEnumField
Definition: hebi.h:307
HebiInfoMetadata_::string_field_count_
uint32_t string_field_count_
Definition: hebi.h:778
HebiInfoFloatVelocityKp
@ HebiInfoFloatVelocityKp
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
Definition: hebi.h:252
HebiInfoBoolPositionDOnError
@ HebiInfoBoolPositionDOnError
Definition: hebi.h:291
HebiFeedbackEnumMstopState
@ HebiFeedbackEnumMstopState
Describes how the temperature inside the module is limiting the output of the motor.
Definition: hebi.h:213
hebiInfoGetMetadata
void hebiInfoGetMetadata(HebiInfoMetadata *metadata)
HebiInfoMetadata_::numbered_float_field_bitfield_offset_
uint32_t numbered_float_field_bitfield_offset_
Definition: hebi.h:788
HebiJointTypeTranslationY
@ HebiJointTypeTranslationY
Definition: hebi.h:357
HebiInfoStringFamily
@ HebiInfoStringFamily
The name for this module. The string must be null-terminated and less than 21 characters.
Definition: hebi.h:299
HebiBracketType
HebiBracketType
Definition: hebi.h:403
hebiGroupInfoGetModuleInfo
HebiInfoPtr hebiGroupInfoGetModuleInfo(HebiGroupInfoPtr info, size_t module_index)
Get an individual info for a particular module at index module_index.
HebiFeedbackMetadata_::uint64_field_bitfield_offset_
uint32_t uint64_field_bitfield_offset_
Definition: hebi.h:727
HebiCommandRef
struct HebiCommandRef_ HebiCommandRef
HebiCommandStringField
HebiCommandStringField
Definition: hebi.h:123
HebiFeedbackMetadata_::string_field_count_
uint32_t string_field_count_
Definition: hebi.h:720
HebiCommandFloatEffortKd
@ HebiCommandFloatEffortKd
Integral PID gain for effort.
Definition: hebi.h:86
HebiCommandIoPinBank
HebiCommandIoPinBank
Definition: hebi.h:144
hebiLookupEntryListRelease
void hebiLookupEntryListRelease(HebiLookupEntryListPtr lookup_list)
Release resources for a given lookup entry list; list should not be used after this call.
HebiRobotModelElementTypeBracket
@ HebiRobotModelElementTypeBracket
Definition: hebi.h:341
HebiRobotModelElementTopology_::element_index_
int32_t element_index_
Definition: hebi.h:607
HebiInfoStringSerial
@ HebiInfoStringSerial
The family for this module. The string must be null-terminated and less than 21 characters.
Definition: hebi.h:300
HebiBracketTypeX5HeavyLeftOutside
@ HebiBracketTypeX5HeavyLeftOutside
Definition: hebi.h:407
HebiInfoEnumControlStrategy
@ HebiInfoEnumControlStrategy
Definition: hebi.h:308
HebiFeedbackRef_::high_res_angle_fields_
const HebiHighResAngleStruct * high_res_angle_fields_
Definition: hebi.h:693
HebiInfoRef_
Definition: hebi.h:748
HebiInfoFloatVelocityLimitMin
@ HebiInfoFloatVelocityLimitMin
The spring constant of the module.
Definition: hebi.h:279
hebiRobotModelCreate
HebiRobotModelPtr hebiRobotModelCreate(void)
Creates an object to hold a robot model (tree topology). This structure has a single output available...
HebiBracketTypeR8HeavyRightInside
@ HebiBracketTypeR8HeavyRightInside
Definition: hebi.h:414
HebiFeedbackFloatField
HebiFeedbackFloatField
Feedback Enums.
Definition: hebi.h:161
HebiCommandStringName
@ HebiCommandStringName
Definition: hebi.h:124
HebiCommandMetadata_::high_res_angle_field_bitfield_offset_
uint32_t high_res_angle_field_bitfield_offset_
Definition: hebi.h:666
HebiCommandMetadata_::float_field_bitfield_offset_
uint32_t float_field_bitfield_offset_
Definition: hebi.h:665
hebiLogFileGetNumberOfModules
size_t hebiLogFileGetNumberOfModules(HebiLogFilePtr log_file)
Retrieve the number of modules in the group represented by an opened log file.
HebiCommandMetadata_::quaternionf_field_count_
uint32_t quaternionf_field_count_
Definition: hebi.h:655
HebiRobotModelElementMetadata_::extension_
float extension_
Definition: hebi.h:597
hebiFeedbackGetMetadata
void hebiFeedbackGetMetadata(HebiFeedbackMetadata *metadata)
HebiHighResAngleStruct_::offset_
float offset_
Definition: hebi.h:618
HebiFeedbackEnumField
HebiFeedbackEnumField
Definition: hebi.h:211
HebiEndEffectorTypeX5Parallel
@ HebiEndEffectorTypeX5Parallel
Definition: hebi.h:423
hebiIKAddObjectiveEndEffectorTipAxis
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...
HebiQuaternionf_::w
float w
Definition: hebi.h:571
HebiCommandFloatPositionMaxOutput
@ HebiCommandFloatPositionMaxOutput
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:69
HebiFeedbackNumberedFloatField
HebiFeedbackNumberedFloatField
Definition: hebi.h:187
HebiFeedbackMetadata_::numbered_float_field_count_
uint32_t numbered_float_field_count_
Definition: hebi.h:717
HebiFeedbackUInt64HardwareReceiveTime
@ HebiFeedbackUInt64HardwareReceiveTime
Timestamp of when message was transmitted to module (local)
Definition: hebi.h:195
hebiCommandGetString
HebiStatusCode hebiCommandGetString(HebiCommandPtr command, HebiCommandStringField field, char *buffer, size_t *length)
Command API.
HebiCommandMetadata_::io_field_count_
uint32_t io_field_count_
Definition: hebi.h:660
HebiInfoMetadata_::io_field_count_
uint32_t io_field_count_
Definition: hebi.h:776
HebiCommandHighResAnglePosition
@ HebiCommandHighResAnglePosition
Definition: hebi.h:107
HebiFeedbackMetadata_::enum_field_bitfield_offset_
uint32_t enum_field_bitfield_offset_
Definition: hebi.h:728
HebiCommandIoBankB
@ HebiCommandIoBankB
I/O pin bank a (pins 1-8 available)
Definition: hebi.h:146
HebiInfoRef_::numbered_float_fields_
const float * numbered_float_fields_
Definition: hebi.h:757
HebiCommandMetadata_::bool_field_count_
uint32_t bool_field_count_
Definition: hebi.h:658
HebiLinkInputTypeInline
@ HebiLinkInputTypeInline
Definition: hebi.h:389
HebiFeedbackFloatMotorVelocity
@ HebiFeedbackFloatMotorVelocity
Velocity of the difference between the pre-spring and post-spring output position.
Definition: hebi.h:171
HebiInfoMetadata_::uint64_field_bitfield_offset_
uint32_t uint64_field_bitfield_offset_
Definition: hebi.h:785
HebiCommandMetadata_::numbered_float_field_count_
uint32_t numbered_float_field_count_
Definition: hebi.h:659
HebiFeedbackFloatDeflection
@ HebiFeedbackFloatDeflection
Commanded effort at the module output; units vary (e.g., N * m for rotational joints and N for linear...
Definition: hebi.h:169
hebiFeedbackGetReference
void hebiFeedbackGetReference(HebiFeedbackPtr feedback, HebiFeedbackRef *ref)
Feedback API.
HebiCommandFloatEffortTargetLowpass
@ HebiCommandFloatEffortTargetLowpass
Maximum allowed value for input to the PID controller.
Definition: hebi.h:93
HebiFeedbackMetadata_::numbered_float_field_sizes_
const uint32_t * numbered_float_field_sizes_
Definition: hebi.h:737
HebiInfoFloatEffortKi
@ HebiInfoFloatEffortKi
Proportional PID gain for effort.
Definition: hebi.h:266
HebiBracketTypeR8HeavyLeftInside
@ HebiBracketTypeR8HeavyLeftInside
Definition: hebi.h:412
HebiFeedbackMetadata_::high_res_angle_field_count_
uint32_t high_res_angle_field_count_
Definition: hebi.h:711
HebiCommandFloatPositionTargetLowpass
@ HebiCommandFloatPositionTargetLowpass
Maximum allowed value for input to the PID controller.
Definition: hebi.h:67
hebiGroupSetFeedbackFrequencyHz
HebiStatusCode hebiGroupSetFeedbackFrequencyHz(HebiGroupPtr group, float frequency)
Sets the feedback request loop frequency (in Hz).
HebiRobotModelPtr
struct HebiRobotModel_ * HebiRobotModelPtr
Definition: hebi.h:527
HebiFeedbackMetadata_::vector3f_field_bitfield_offset_
uint32_t vector3f_field_bitfield_offset_
Definition: hebi.h:725
HebiInfoEnumMinPositionLimitStrategy
@ HebiInfoEnumMinPositionLimitStrategy
The motion stop strategy for the actuator.
Definition: hebi.h:311
HebiFeedbackUInt64HardwareTransmitTime
@ HebiFeedbackUInt64HardwareTransmitTime
Timestamp of when message was received by module (remote)
Definition: hebi.h:196
HebiCommandFloatVelocityPunch
@ HebiCommandFloatVelocityPunch
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:77
HebiFeedbackRef_::io_fields_
const HebiIoBankPinStruct * io_fields_
Definition: hebi.h:700
HebiCommandRef_::vector3f_fields_
HebiVector3f * vector3f_fields_
Definition: hebi.h:636
HebiInfoFloatEffortPunch
@ HebiInfoFloatEffortPunch
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:271
HebiRobotModelElementTopology_::com_index_
int32_t com_index_
Definition: hebi.h:611
HebiFeedbackIoPinBank
HebiFeedbackIoPinBank
Definition: hebi.h:221
GroupFeedbackHandlerFunction
void(* GroupFeedbackHandlerFunction)(HebiGroupFeedbackPtr fbk, void *user_data)
Group feedback handling function signature.
Definition: hebi.h:554
HebiCommandMetadata_::flag_field_bitfield_offset_
uint32_t flag_field_bitfield_offset_
Definition: hebi.h:676
hebiGroupCreateFromNames
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
@ HebiCommandFloatReferenceEffort
Set the internal encoder reference offset so that the current position matches the given reference co...
Definition: hebi.h:99
HebiFeedbackMetadata_::message_bitfield_count_
uint32_t message_bitfield_count_
Definition: hebi.h:742
HebiBracketTypeX5LightRight
@ HebiBracketTypeX5LightRight
Definition: hebi.h:405
HebiFeedbackEnumCommandLifetimeState
@ HebiFeedbackEnumCommandLifetimeState
Software-controlled bounds on the allowable effort of the module.
Definition: hebi.h:217
HebiCommandFloatPositionMinOutput
@ HebiCommandFloatPositionMinOutput
A simple lowpass filter applied to the target set point; needs to be between 0 and 1....
Definition: hebi.h:68
hebiLookupCreate
HebiLookupPtr hebiLookupCreate(const char *const *ifaces, size_t ifaces_length)
Lookup API.
hebiGroupInfoWriteSafetyParameters
HebiStatusCode hebiGroupInfoWriteSafetyParameters(HebiGroupInfoPtr info, const char *file)
Export safety parameters from a GroupInfo object into a file.
HebiRobotModelElementMetadata
struct HebiRobotModelElementMetadata_ HebiRobotModelElementMetadata
HebiRobotModelElementMetadata_::end_effector_type_
HebiEndEffectorType end_effector_type_
Definition: hebi.h:601
HebiCommandEnumMstopStrategy
@ HebiCommandEnumMstopStrategy
How the position, velocity, and effort PID loops are connected in order to control motor PWM.
Definition: hebi.h:139
HebiInfoBoolAccelIncludesGravity
@ HebiInfoBoolAccelIncludesGravity
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
Definition: hebi.h:294
HebiCommandFloatReferencePosition
@ HebiCommandFloatReferencePosition
The spring constant of the module.
Definition: hebi.h:98
HebiInfoFloatVelocityMaxOutput
@ HebiInfoFloatVelocityMaxOutput
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:263
HebiInfoEnumMaxPositionLimitStrategy
@ HebiInfoEnumMaxPositionLimitStrategy
The position limit strategy (at the minimum position) for the actuator.
Definition: hebi.h:312
hebiGetLibraryVersion
HebiStatusCode hebiGetLibraryVersion(int32_t *major, int32_t *minor, int32_t *revision)
Get the version of the library.
hebiRobotModelGetMasses
HebiStatusCode hebiRobotModelGetMasses(HebiRobotModelPtr robot_model, double *masses)
Fill in the masses vector with the mass of each body with mass in the kinematic tree,...
HebiJointTypeRotationX
@ HebiJointTypeRotationX
Definition: hebi.h:353
HebiCommandEnumMinPositionLimitStrategy
@ HebiCommandEnumMinPositionLimitStrategy
The motion stop strategy for the actuator.
Definition: hebi.h:140
HebiIoBankPinStruct_::stored_type_
HebiIoBankPinResidentType stored_type_
Definition: hebi.h:626
HebiFeedbackMetadata_::io_relative_offsets_
const uint32_t * io_relative_offsets_
Definition: hebi.h:739
HebiCommandFloatPositionMinTarget
@ HebiCommandFloatPositionMinTarget
Constant offset to the position PID output outside of the deadzone; it is added when the error is pos...
Definition: hebi.h:65
HebiInfoMetadata_::flag_field_count_
uint32_t flag_field_count_
Definition: hebi.h:779
HebiMacAddress_
Structures.
Definition: hebi.h:560
HebiCommandFloatSpringConstant
@ HebiCommandFloatSpringConstant
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
Definition: hebi.h:97
HebiInfoRef
struct HebiInfoRef_ HebiInfoRef
HebiInfoLedField
HebiInfoLedField
Definition: hebi.h:315
HebiFeedbackUInt64SenderId
@ HebiFeedbackUInt64SenderId
Timestamp of when message was transmitted from module (remote)
Definition: hebi.h:197
HebiFeedbackFloatDeflectionVelocity
@ HebiFeedbackFloatDeflectionVelocity
Difference between the pre-spring and post-spring output position.
Definition: hebi.h:170
HebiInfoFloatVelocityTargetLowpass
@ HebiInfoFloatVelocityTargetLowpass
Maximum allowed value for input to the PID controller.
Definition: hebi.h:261
hebiGroupFeedbackRelease
void hebiGroupFeedbackRelease(HebiGroupFeedbackPtr feedback)
Frees resources created by the GroupFeedback object.
HebiCommandMetadata_::led_field_bitfield_offset_
uint32_t led_field_bitfield_offset_
Definition: hebi.h:674
HebiFrameTypeCenterOfMass
@ HebiFrameTypeCenterOfMass
Definition: hebi.h:328
hebiRobotModelGetForwardKinematics
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
HebiFeedbackVector3fField
Definition: hebi.h:200
HebiFeedbackLedField
HebiFeedbackLedField
Definition: hebi.h:230
HebiLinkTypeR8
@ HebiLinkTypeR8
Definition: hebi.h:381
HebiRobotModelElementTypeActuator
@ HebiRobotModelElementTypeActuator
Definition: hebi.h:340
HebiCommandRef_
Definition: hebi.h:632
HebiCommandFloatPositionKd
@ HebiCommandFloatPositionKd
Integral PID gain for position.
Definition: hebi.h:60
HebiCommandFloatEffortKp
@ HebiCommandFloatEffortKp
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
Definition: hebi.h:84
hebiGroupRequestInfo
HebiStatusCode hebiGroupRequestInfo(HebiGroupPtr group, HebiGroupInfoPtr info, int32_t timeout_ms)
Requests info from the group, and writes it to the provided info object.
HebiRobotModelElementTypeRigidBody
@ HebiRobotModelElementTypeRigidBody
Definition: hebi.h:344
HebiInfoFloatEffortDeadZone
@ HebiInfoFloatEffortDeadZone
Feed forward term for effort (this term is multiplied by the target and added to the output).
Definition: hebi.h:269
HebiCommandFloatEffortOutputLowpass
@ HebiCommandFloatEffortOutputLowpass
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:96
HebiCommandMetadata_::quaternionf_field_bitfield_offset_
uint32_t quaternionf_field_bitfield_offset_
Definition: hebi.h:668
hebiIKRelease
void hebiIKRelease(HebiIKPtr ik)
Frees resources created by this inverse kinematics object.
HebiFrameType
HebiFrameType
RobotModel Enums.
Definition: hebi.h:327
HebiCommandRef_::enum_fields_
int32_t * enum_fields_
Definition: hebi.h:639
hebiStringGetString
HebiStatusCode hebiStringGetString(HebiStringPtr str, char *buffer, size_t *length)
String Functions.
hebiRobotModelGetJacobians
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.
HebiActuatorTypeR8_9
@ HebiActuatorTypeR8_9
Definition: hebi.h:372
HebiCommandFloatEffortMaxOutput
@ HebiCommandFloatEffortMaxOutput
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:95
HebiInfoFloatEffortIClamp
@ HebiInfoFloatEffortIClamp
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:270
HebiCommandFloatVelocityKp
@ HebiCommandFloatVelocityKp
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
Definition: hebi.h:71
HebiInfoFloatVelocityPunch
@ HebiInfoFloatVelocityPunch
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:258
HebiCommandFloatVelocityMinTarget
@ HebiCommandFloatVelocityMinTarget
Constant offset to the velocity PID output outside of the deadzone; it is added when the error is pos...
Definition: hebi.h:78
HebiCommandMetadata_::io_relative_offsets_
const uint32_t * io_relative_offsets_
Definition: hebi.h:681
HebiInfoRef_::led_fields_
const uint32_t * led_fields_
Definition: hebi.h:759
HebiInfoMetadata_::string_field_bitfield_offset_
uint32_t string_field_bitfield_offset_
Definition: hebi.h:791
HebiCommandMetadata_::float_field_count_
uint32_t float_field_count_
Definition: hebi.h:652
HebiCommandFloatVelocityIClamp
@ HebiCommandFloatVelocityIClamp
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:76
HebiInfoFloatVelocityFeedForward
@ HebiInfoFloatVelocityFeedForward
Derivative PID gain for velocity.
Definition: hebi.h:255
HebiInfoMetadata_::quaternionf_field_bitfield_offset_
uint32_t quaternionf_field_bitfield_offset_
Definition: hebi.h:784
HebiVector3f_
Definition: hebi.h:564
HebiCommandMetadata_::high_res_angle_field_count_
uint32_t high_res_angle_field_count_
Definition: hebi.h:653
HebiFeedbackFloatMotorWindingTemperature
@ HebiFeedbackFloatMotorWindingTemperature
The estimated current in the motor windings.
Definition: hebi.h:175
HebiInfoFloatPositionMinOutput
@ HebiInfoFloatPositionMinOutput
A simple lowpass filter applied to the target set point; needs to be between 0 and 1....
Definition: hebi.h:249
HebiInfoMetadata_
Definition: hebi.h:766
HebiHighResAngleStruct
struct HebiHighResAngleStruct_ HebiHighResAngleStruct
HebiFeedbackFloatVoltage
@ HebiFeedbackFloatVoltage
Temperature of the processor chip.
Definition: hebi.h:164
HebiCommandIoBankE
@ HebiCommandIoBankE
I/O pin bank d (pins 1-8 available)
Definition: hebi.h:149
HebiCommandFloatPositionPunch
@ HebiCommandFloatPositionPunch
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:64
HebiFeedbackMetadata_::io_field_count_
uint32_t io_field_count_
Definition: hebi.h:718
HebiCommandFloatVelocityLimitMax
@ HebiCommandFloatVelocityLimitMax
The firmware safety limit for the minimum allowed velocity.
Definition: hebi.h:101
hebiGroupCommandGetSize
size_t hebiGroupCommandGetSize(HebiGroupCommandPtr command)
Return the number of modules in this group Command.
HebiCommandBoolEffortDOnError
@ HebiCommandBoolEffortDOnError
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
Definition: hebi.h:119
HebiInfoFloatEffortKd
@ HebiInfoFloatEffortKd
Integral PID gain for effort.
Definition: hebi.h:267
HebiArQualityLimitedRelocalizing
@ HebiArQualityLimitedRelocalizing
The AR session has not yet gathered enough camera or motion data to provide tracking information.
Definition: hebi.h:39
HebiCommandFloatVelocityLimitMin
@ HebiCommandFloatVelocityLimitMin
Set the internal effort reference offset so that the current effort matches the given reference comma...
Definition: hebi.h:100
HebiCommandFloatPositionIClamp
@ HebiCommandFloatPositionIClamp
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:63
HebiInfoStringName
@ HebiInfoStringName
Definition: hebi.h:298
hebiLogFileRelease
void hebiLogFileRelease(HebiLogFilePtr log_file)
Logging API.
HebiCommandFloatEffortLimitMax
@ HebiCommandFloatEffortLimitMax
The firmware safety limit for the minimum allowed effort.
Definition: hebi.h:103
hebiRobotModelAdd
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.
hebiRobotModelElementCreateJoint
HebiRobotModelElementPtr hebiRobotModelElementCreateJoint(HebiJointType joint_type)
RobotModel API.
hebiGroupCreateFromMacs
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
@ HebiArQualityLimitedInitializing
Tracking is available albeit suboptimal for an unknown reason.
Definition: hebi.h:38
HebiCommandFloatEffortMinOutput
@ HebiCommandFloatEffortMinOutput
A simple lowpass filter applied to the target set point; needs to be between 0 and 1....
Definition: hebi.h:94
HebiInfoFloatPositionKi
@ HebiInfoFloatPositionKi
Proportional PID gain for position.
Definition: hebi.h:240
HebiHighResAngleStruct_
Definition: hebi.h:616
HebiFeedbackFloatEffortCommand
@ HebiFeedbackFloatEffortCommand
Commanded velocity of the module output (post-spring)
Definition: hebi.h:168
HebiIoBankPinStruct_
Definition: hebi.h:621
HebiFeedbackIoBankE
@ HebiFeedbackIoBankE
I/O pin bank d (pins 1-8 available)
Definition: hebi.h:226
HebiInfoMetadata_::numbered_float_field_sizes_
const uint32_t * numbered_float_field_sizes_
Definition: hebi.h:795
HebiTrajectoryPtr
struct HebiTrajectory_ * HebiTrajectoryPtr
The C-style's API representation of a trajectory.
Definition: hebi.h:549
HebiCommandFloatEffortDeadZone
@ HebiCommandFloatEffortDeadZone
Feed forward term for effort (this term is multiplied by the target and added to the output).
Definition: hebi.h:88
hebiLookupGetLookupFrequencyHz
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