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_;
582  HebiRobotModelElementType element_type_;
583  union {
584  struct /*Actuator Type */ {
585  HebiActuatorType actuator_type_;
586  };
587  struct /*Bracket Type */ {
588  HebiBracketType bracket_type_;
589  };
590  struct /*Joint Type */ {
591  HebiJointType joint_type_;
592  };
593  struct /*Link Type*/ {
594  HebiLinkType link_type_;
595  HebiLinkInputType input_type_;
596  HebiLinkOutputType output_type_;
597  float extension_;
598  float twist_;
599  };
600  struct /*End effector Type*/ {
601  HebiEndEffectorType 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  };
626  HebiIoBankPinResidentType stored_type_;
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 
841 HebiStatusCode hebiLookupSetLookupFrequencyHz(HebiLookupPtr lookup, double frequency);
842 
846 double hebiLookupGetLookupFrequencyHz(HebiLookupPtr lookup);
847 
854 HebiLookupEntryListPtr hebiCreateLookupEntryList(HebiLookupPtr lookup);
855 
861 size_t hebiLookupEntryListGetSize(HebiLookupEntryListPtr lookup_list);
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 
920 HebiStatusCode hebiLookupEntryListGetMacAddress(HebiLookupEntryListPtr lookup_list, size_t index,
921  HebiMacAddress* mac_address);
922 
929 void hebiLookupEntryListRelease(HebiLookupEntryListPtr lookup_list);
930 
934 
949 HebiGroupPtr hebiGroupCreateImitation(size_t size);
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 
1107 HebiStatusCode hebiGroupSendCommandWithAcknowledgement(HebiGroupPtr group, HebiGroupCommandPtr command,
1108  int32_t timeout_ms);
1109 
1122 HebiStatusCode hebiGroupSendCommand(HebiGroupPtr group, HebiGroupCommandPtr command);
1123 
1147 HebiStatusCode hebiGroupSetCommandLifetime(HebiGroupPtr group, int32_t lifetime_ms);
1148 
1157 int32_t hebiGroupGetCommandLifetime(HebiGroupPtr group);
1158 
1172 HebiStatusCode hebiGroupSetFeedbackFrequencyHz(HebiGroupPtr group, float frequency);
1173 
1181 float hebiGroupGetFeedbackFrequencyHz(HebiGroupPtr group);
1182 
1194  void* user_data);
1195 
1202 void hebiGroupClearFeedbackHandlers(HebiGroupPtr group);
1203 
1217 HebiStatusCode hebiGroupSendFeedbackRequest(HebiGroupPtr group);
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 
1289 HebiLogFilePtr hebiGroupStopLog(HebiGroupPtr group);
1290 
1297 void hebiGroupRelease(HebiGroupPtr group);
1298 
1308 HebiGroupCommandPtr hebiGroupCommandCreate(size_t size);
1309 
1315 size_t hebiGroupCommandGetSize(HebiGroupCommandPtr command);
1316 
1333 HebiStatusCode hebiGroupCommandReadGains(HebiGroupCommandPtr command, const char* file);
1334 
1344 HebiStatusCode hebiGroupCommandWriteGains(HebiGroupCommandPtr command, const char* file);
1345 
1362 HebiStatusCode hebiGroupCommandReadSafetyParameters(HebiGroupCommandPtr command, const char* file);
1363 
1373 HebiStatusCode hebiGroupCommandWriteSafetyParameters(HebiGroupCommandPtr command, const char* file);
1374 
1384 HebiCommandPtr hebiGroupCommandGetModuleCommand(HebiGroupCommandPtr command, size_t module_index);
1385 
1401 HebiStatusCode hebiGroupCommandCopy(HebiGroupCommandPtr dest, HebiGroupCommandPtr src);
1402 
1406 void hebiGroupCommandClear(HebiGroupCommandPtr command);
1407 
1413 void hebiGroupCommandRelease(HebiGroupCommandPtr command);
1414 
1424 HebiGroupFeedbackPtr hebiGroupFeedbackCreate(size_t size);
1425 
1431 size_t hebiGroupFeedbackGetSize(HebiGroupFeedbackPtr feedback);
1432 
1442 HebiFeedbackPtr hebiGroupFeedbackGetModuleFeedback(HebiGroupFeedbackPtr feedback, size_t module_index);
1443 
1459 HebiStatusCode hebiGroupFeedbackCopy(HebiGroupFeedbackPtr dest, HebiGroupFeedbackPtr src);
1460 
1464 void hebiGroupFeedbackClear(HebiGroupFeedbackPtr feedback);
1465 
1471 void hebiGroupFeedbackRelease(HebiGroupFeedbackPtr feedback);
1472 
1482 HebiGroupInfoPtr hebiGroupInfoCreate(size_t size);
1483 
1489 size_t hebiGroupInfoGetSize(HebiGroupInfoPtr info);
1490 
1500 HebiStatusCode hebiGroupInfoWriteGains(HebiGroupInfoPtr info, const char* file);
1501 
1511 HebiStatusCode hebiGroupInfoWriteSafetyParameters(HebiGroupInfoPtr info, const char* file);
1512 
1522 HebiInfoPtr hebiGroupInfoGetModuleInfo(HebiGroupInfoPtr info, size_t module_index);
1523 
1539 HebiStatusCode hebiGroupInfoCopy(HebiGroupInfoPtr dest, HebiGroupInfoPtr src);
1540 
1544 void hebiGroupInfoClear(HebiGroupInfoPtr info);
1545 
1551 void hebiGroupInfoRelease(HebiGroupInfoPtr info);
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 
1601 void hebiCommandGetReference(HebiCommandPtr command, HebiCommandRef* ref);
1602 
1607 
1611 
1612 
1616 void hebiFeedbackGetReference(HebiFeedbackPtr feedback, HebiFeedbackRef* ref);
1617 
1622 
1626 
1653 HebiStatusCode hebiInfoGetString(HebiInfoPtr info, HebiInfoStringField field, char* buffer, size_t* length);
1654 
1658 void hebiInfoGetReference(HebiInfoPtr info, HebiInfoRef* ref);
1659 
1663 void hebiInfoGetMetadata(HebiInfoMetadata* metadata);
1664 
1668 
1679 HebiRobotModelElementPtr hebiRobotModelElementCreateJoint(HebiJointType joint_type);
1680 
1701 HebiRobotModelElementPtr hebiRobotModelElementCreateRigidBody(const double* com, const double* inertia, double mass,
1702  size_t num_outputs, const double* outputs,
1703  HebiMatrixOrdering ordering);
1704 
1731 HebiRobotModelElementPtr hebiRobotModelElementCreateEndEffector(HebiEndEffectorType end_effector_type,
1732  const double* com, const double* inertia,
1733  double mass, const double* output_frame,
1734  HebiMatrixOrdering ordering);
1735 
1746 HebiRobotModelElementPtr hebiRobotModelElementCreateActuator(HebiActuatorType actuator_type);
1747 
1759 HebiRobotModelElementPtr hebiRobotModelElementCreateBracket(HebiBracketType bracket_type);
1760 
1780 HebiRobotModelElementPtr hebiRobotModelElementCreateLink(HebiLinkType link_type, HebiLinkInputType input_type,
1781  HebiLinkOutputType output_type, double extension,
1782  double twist);
1783 
1795 void hebiRobotModelElementRelease(HebiRobotModelElementPtr element);
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 
1875 HebiRobotModelPtr hebiRobotModelCreate(void);
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 
1928 size_t hebiRobotModelGetNumberOfDoFs(HebiRobotModelPtr robot_model);
1929 
1936 size_t hebiRobotModelGetNumberOfElements(HebiRobotModelPtr robot_model);
1937 
1956 HebiStatusCode hebiRobotModelGetElementMetadata(HebiRobotModelPtr model, size_t index, HebiRobotModelElementMetadata* output);
1957 
1994 HebiStatusCode hebiRobotModelAdd(HebiRobotModelPtr robot_model, HebiRobotModelElementPtr existing_element,
1995  size_t output_index, HebiRobotModelElementPtr new_element);
1996 
2032 HebiStatusCode hebiRobotModelGetForwardKinematics(HebiRobotModelPtr robot_model, HebiFrameType frame_type,
2033  const double* positions, double* frames, HebiMatrixOrdering ordering);
2034 
2052 HebiStatusCode hebiRobotModelGetJacobians(HebiRobotModelPtr robot_model, HebiFrameType frame_type,
2053  const double* positions, double* jacobians, HebiMatrixOrdering ordering);
2054 
2067 HebiStatusCode hebiRobotModelGetMasses(HebiRobotModelPtr robot_model, double* masses);
2068 
2069 
2082 HebiStatusCode hebiRobotModelGetTreeTopology(HebiRobotModelPtr robot_model, HebiFrameType frame_type, HebiRobotModelElementTopology* table);
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 
2367 size_t hebiLogFileGetNumberOfModules(HebiLogFilePtr log_file);
2368 
2375 HebiStatusCode hebiLogFileGetNextFeedback(HebiLogFilePtr log_file, HebiGroupFeedbackPtr field);
2376 
2380 
2395 HebiStatusCode hebiStringGetString(HebiStringPtr str, char* buffer, size_t* length);
2396 
2400 void hebiStringRelease(HebiStringPtr str);
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
Ambient temperature inside the module (measured at the IMU chip)
Definition: hebi.h:163
The name for this module. The string must be null-terminated and less than 21 characters.
Definition: hebi.h:125
uint32_t bool_field_count_
Definition: hebi.h:716
HebiFeedbackQuaternionfField
Definition: hebi.h:206
Integral PID gain for position.
Definition: hebi.h:60
uint32_t led_field_count_
Definition: hebi.h:777
struct HebiFeedback_ * HebiFeedbackPtr
The C-style&#39;s API representation of feedback.
Definition: hebi.h:451
uint32_t io_field_count_
Definition: hebi.h:776
const uint32_t * io_field_sizes_
Definition: hebi.h:740
uint32_t enum_field_count_
Definition: hebi.h:773
void hebiStringRelease(HebiStringPtr str)
Releases a string instance.
Timestamp of when message was received from module (local)
Definition: hebi.h:194
uint32_t string_field_bitfield_offset_
Definition: hebi.h:733
HebiLogFilePtr hebiLogFileOpen(const char *file)
Opens an existing log file.
uint32_t float_field_bitfield_offset_
Definition: hebi.h:665
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.
void hebiFeedbackGetMetadata(HebiFeedbackMetadata *metadata)
uint32_t led_field_bitfield_offset_
Definition: hebi.h:790
Returned when an accessor function attempts to retrieve a field which is not set. ...
Definition: hebi.h:28
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&#39;s z axis in a given direction. Note that this is incomp...
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.
HebiStatusCode hebiCommandGetString(HebiCommandPtr command, HebiCommandStringField field, char *buffer, size_t *length)
Command API.
HebiTrajectoryPtr hebiTrajectoryCreateUnconstrainedQp(size_t num_waypoints, const double *positions, const double *velocities, const double *accelerations, const double *time_vector)
Trajectory API.
HebiLogFilePtr hebiGroupStopLog(HebiGroupPtr group)
Stops logging data to a file.
The spring constant of the module.
Definition: hebi.h:98
struct HebiFeedbackMetadata_ HebiFeedbackMetadata
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 ...
uint32_t bool_field_bitfield_offset_
Definition: hebi.h:787
void hebiIKRelease(HebiIKPtr ik)
Frees resources created by this inverse kinematics object.
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:76
HebiIoBankPinResidentType
Definition: hebi.h:45
Derivative PID gain for velocity.
Definition: hebi.h:255
HebiStatusCode hebiLogFileGetFileName(HebiLogFilePtr log_file, char *buffer, size_t *length)
Copy the path and name of the log file into a buffer.
void hebiInfoGetReference(HebiInfoPtr info, HebiInfoRef *ref)
HebiGroupPtr hebiGroupCreateConnectedFromMac(HebiLookupPtr lookup, const HebiMacAddress *address, int32_t timeout_ms)
Create a group with all modules connected to module with the given MAC address.
HebiStatusCode hebiGroupSendCommand(HebiGroupPtr group, HebiGroupCommandPtr command)
Sends a command to the given group without requesting an acknowledgement.
HebiCommandHighResAngleField
Definition: hebi.h:106
const float * numbered_float_fields_
Definition: hebi.h:699
Boot the module from bootloader into application.
Definition: hebi.h:133
size_t hebiGroupFeedbackGetSize(HebiGroupFeedbackPtr feedback)
Return the number of modules in this group Feedback.
const int32_t * enum_fields_
Definition: hebi.h:755
int64_t int_value_
Definition: hebi.h:623
Difference between the pre-spring and post-spring output position.
Definition: hebi.h:170
HebiFeedbackVector3fField
Definition: hebi.h:200
uint32_t * led_fields_
Definition: hebi.h:643
The AR session has not yet gathered enough camera or motion data to provide tracking information...
Definition: hebi.h:39
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
Definition: hebi.h:84
HebiLinkType link_type_
Definition: hebi.h:594
struct HebiGroupInfo_ * HebiGroupInfoPtr
The C-style&#39;s API representation of a info object for a group of modules.
Definition: hebi.h:485
Feed forward term for effort (this term is multiplied by the target and added to the output)...
Definition: hebi.h:269
uint32_t io_field_bitfield_offset_
Definition: hebi.h:731
struct HebiCommandRef_ HebiCommandRef
uint32_t high_res_angle_field_bitfield_offset_
Definition: hebi.h:782
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:96
HebiStatusCode hebiGroupInfoCopy(HebiGroupInfoPtr dest, HebiGroupInfoPtr src)
Clears the dest GroupInfo object, and copies all data from the src GroupInfo object to dest...
The firmware safety limit for the minimum allowed position.
Definition: hebi.h:109
uint32_t uint64_field_count_
Definition: hebi.h:772
uint32_t float_field_count_
Definition: hebi.h:710
uint32_t quaternionf_field_count_
Definition: hebi.h:655
Charge level of the device’s battery (in percent).
Definition: hebi.h:178
A buffer supplied to the routine was too small (normally determined by a size parameter) ...
Definition: hebi.h:27
The firmware safety limit for the minimum allowed effort.
Definition: hebi.h:282
HebiStatusCode hebiGroupStartLog(HebiGroupPtr group, const char *dir, const char *file, HebiStringPtr *ret)
Starts logging data to a file.
HebiBracketType
Definition: hebi.h:403
uint32_t numbered_float_field_bitfield_offset_
Definition: hebi.h:788
uint32_t string_field_count_
Definition: hebi.h:778
float float_value_
Definition: hebi.h:624
HebiStatusCode hebiGroupCommandReadGains(HebiGroupCommandPtr command, const char *file)
Import gains from a file into a GroupCommand object.
Software-controlled bounds on the allowable position of the module; user settable.
Definition: hebi.h:215
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:95
struct HebiCommand_ * HebiCommandPtr
Typedefs.
Definition: hebi.h:444
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
Definition: hebi.h:278
HebiRobotModelElementPtr hebiRobotModelElementCreateJoint(HebiJointType joint_type)
RobotModel API.
HebiStatusCode hebiRobotModelGetMasses(HebiRobotModelPtr robot_model, double *masses)
Fill in the masses vector with the mass of each body with mass in the kinematic tree, reported in a depth-first ordering.
Integral PID gain for position.
Definition: hebi.h:241
const uint32_t * numbered_float_field_sizes_
Definition: hebi.h:679
Current status of the MStop.
Definition: hebi.h:214
HebiFeedbackHighResAngleField
Definition: hebi.h:181
HebiGroupFeedbackPtr hebiGroupFeedbackCreate(size_t size)
Creates a GroupFeedback for a group with the specified number of modules.
HebiRobotModelPtr hebiRobotModelCreate(void)
Creates an object to hold a robot model (tree topology). This structure has a single output available...
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
Definition: hebi.h:249
void hebiCommandSetString(HebiCommandPtr command, HebiCommandStringField field, const char *buffer, const size_t *length)
void hebiGroupInfoClear(HebiGroupInfoPtr info)
Clears all data in the GroupInfo object.
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...
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
Definition: hebi.h:265
void * reserved_
Definition: hebi.h:760
HebiLinkInputType input_type_
Definition: hebi.h:595
Software-controlled bounds on the allowable velocity of the module.
Definition: hebi.h:216
HebiFeedbackEnumField
Definition: hebi.h:211
HebiRobotModelElementPtr hebiRobotModelElementCreateActuator(HebiActuatorType actuator_type)
Creates a robot model element corresponding to a standard HEBI actuator.
Derivative PID gain for effort.
Definition: hebi.h:268
void hebiCommandGetMetadata(HebiCommandMetadata *metadata)
const bool * bool_fields_
Definition: hebi.h:756
The firmware safety limit for the minimum allowed velocity.
Definition: hebi.h:101
HebiFeedbackNumberedFloatField
Definition: hebi.h:187
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:83
Feed forward term for position (this term is multiplied by the target and added to the output)...
Definition: hebi.h:62
Feed forward term for velocity (this term is multiplied by the target and added to the output)...
Definition: hebi.h:256
uint8_t bytes_[6]
Definition: hebi.h:561
uint32_t vector3f_field_count_
Definition: hebi.h:654
struct HebiInfoMetadata_ HebiInfoMetadata
void hebiGroupRelease(HebiGroupPtr group)
Release resources for a given group; group should not be used after this call.
uint32_t high_res_angle_field_bitfield_offset_
Definition: hebi.h:666
The velocity of the motor shaft.
Definition: hebi.h:172
uint32_t uint64_field_bitfield_offset_
Definition: hebi.h:785
I/O pin bank b (pins 1-8 available)
Definition: hebi.h:147
HebiFrameType
RobotModel Enums.
Definition: hebi.h:327
const float * float_fields_
Definition: hebi.h:692
Constant offset to the effort PID output outside of the deadzone; it is added when the error is posit...
Definition: hebi.h:272
HebiFeedbackLedField
Definition: hebi.h:230
Proportional PID gain for position.
Definition: hebi.h:240
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:276
const char * hebiRobotModelGetImportError()
Retrieve any error string from the last call to hebiRobotModelImport. This must be called on the same...
size_t hebiGroupCommandGetSize(HebiGroupCommandPtr command)
Return the number of modules in this group Command.
Minimum allowed value for input to the PID controller.
Definition: hebi.h:247
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:245
The family for this module. The string must be null-terminated and less than 21 characters.
Definition: hebi.h:126
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:90
uint32_t vector3f_field_count_
Definition: hebi.h:712
size_t hebiGroupInfoGetSize(HebiGroupInfoPtr info)
Return the number of modules in this group Info.
const HebiQuaternionf * quaternionf_fields_
Definition: hebi.h:695
uint32_t quaternionf_field_count_
Definition: hebi.h:713
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
Definition: hebi.h:262
int64_t revolutions_
Definition: hebi.h:617
struct HebiMacAddress_ HebiMacAddress
Structures.
HebiFeedbackFloatField
Feedback Enums.
Definition: hebi.h:161
The firmware safety limit for the maximum allowed velocity.
Definition: hebi.h:102
Restart the module.
Definition: hebi.h:132
HebiLookupPtr hebiLookupCreate(const char *const *ifaces, size_t ifaces_length)
Lookup API.
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)
uint32_t flag_field_bitfield_offset_
Definition: hebi.h:734
struct HebiFeedbackRef_ HebiFeedbackRef
The firmware safety limit for the minimum allowed position.
Definition: hebi.h:287
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:264
Stop the module from automatically booting into application.
Definition: hebi.h:134
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:277
Sequence number going to module (local)
Definition: hebi.h:193
struct HebiVector3f_ HebiVector3f
HebiStatusCode hebiTrajectoryGetState(HebiTrajectoryPtr trajectory, double time, double *position, double *velocity, double *acceleration)
Gets the value of the trajectory at a given time.
HebiCommandIoPinBank
Definition: hebi.h:144
The calibration state of the module.
Definition: hebi.h:310
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.
The position limit strategy (at the minimum position) for the actuator.
Definition: hebi.h:141
struct HebiString_ * HebiStringPtr
The C-style&#39;s API representation of a string.
Definition: hebi.h:521
uint32_t string_field_bitfield_offset_
Definition: hebi.h:675
Derivative PID gain for velocity.
Definition: hebi.h:74
HebiStatusCode hebiGroupCommandReadSafetyParameters(HebiGroupCommandPtr command, const char *file)
Import safety parameters from a file into a GroupCommand object.
Generic code for failure; this is generally used for an internal or unknown failure.
Definition: hebi.h:29
int32_t * message_bitfield_
Definition: hebi.h:633
Minimum allowed value for input to the PID controller.
Definition: hebi.h:79
Proportional PID gain for velocity.
Definition: hebi.h:72
float x
Definition: hebi.h:565
const uint32_t * numbered_float_relative_offsets_
Definition: hebi.h:678
uint32_t flag_field_count_
Definition: hebi.h:779
uint64_t * uint64_fields_
Definition: hebi.h:638
I/O pin bank e (pins 1-8 available)
Definition: hebi.h:227
HebiIoBankPinStruct * io_fields_
Definition: hebi.h:642
Derivative PID gain for position.
Definition: hebi.h:242
void hebiFeedbackGetReference(HebiFeedbackPtr feedback, HebiFeedbackRef *ref)
Feedback API.
HebiLinkOutputType output_type_
Definition: hebi.h:596
uint32_t io_field_bitfield_offset_
Definition: hebi.h:673
void hebiGroupFeedbackRelease(HebiGroupFeedbackPtr feedback)
Frees resources created by the GroupFeedback object.
struct HebiInfo_ * HebiInfoPtr
The C-style&#39;s API representation of info.
Definition: hebi.h:458
Accelerometer data.
Definition: hebi.h:202
uint32_t led_field_count_
Definition: hebi.h:719
struct HebiGroupCommand_ * HebiGroupCommandPtr
The C-style&#39;s API representation of a command object for a group of modules.
Definition: hebi.h:467
uint32_t bool_field_bitfield_offset_
Definition: hebi.h:729
HebiStatusCode hebiGroupSetFeedbackFrequencyHz(HebiGroupPtr group, float frequency)
Sets the feedback request loop frequency (in Hz).
HebiHighResAngleStruct * high_res_angle_fields_
Definition: hebi.h:635
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:82
size_t hebiRobotModelGetNumberOfDoFs(HebiRobotModelPtr robot_model)
Returns the number of settable degrees of freedom in the kinematic tree. (This is equal to the number...
float hebiGroupGetFeedbackFrequencyHz(HebiGroupPtr group)
Returns the current feedback request loop frequency (in Hz).
HebiGroupCommandPtr hebiGroupCommandCreate(size_t size)
Creates a GroupCommand for a group with the specified number of modules.
void hebiInfoGetMetadata(HebiInfoMetadata *metadata)
Velocity of the module output (post-spring).
Definition: hebi.h:57
struct HebiHighResAngleStruct_ HebiHighResAngleStruct
struct HebiRobotModel_ * HebiRobotModelPtr
Definition: hebi.h:527
uint32_t uint64_field_bitfield_offset_
Definition: hebi.h:669
void * reserved_
Definition: hebi.h:702
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages)...
Definition: hebi.h:167
uint32_t led_field_bitfield_offset_
Definition: hebi.h:732
void hebiGroupCommandClear(HebiGroupCommandPtr command)
Clears all data in the GroupCommand object.
HebiStatusCode hebiGroupRequestInfo(HebiGroupPtr group, HebiGroupInfoPtr info, int32_t timeout_ms)
Requests info from the group, and writes it to the provided info object.
Proportional PID gain for effort.
Definition: hebi.h:85
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.
uint32_t enum_field_bitfield_offset_
Definition: hebi.h:670
I/O pin bank b (pins 1-8 available)
Definition: hebi.h:224
size_t hebiLookupEntryListGetSize(HebiLookupEntryListPtr lookup_list)
const int32_t * message_bitfield_
Definition: hebi.h:749
Constant offset to the velocity PID output outside of the deadzone; it is added when the error is pos...
Definition: hebi.h:259
The state of the command lifetime safety controller, with respect to the current group.
Definition: hebi.h:218
const int32_t * message_bitfield_
Definition: hebi.h:691
void hebiRobotModelElementRelease(HebiRobotModelElementPtr element)
Frees resources created by this element.
uint32_t high_res_angle_field_bitfield_offset_
Definition: hebi.h:724
HebiJointType
Definition: hebi.h:352
HebiInfoStringField
Definition: hebi.h:297
Integral PID gain for effort.
Definition: hebi.h:86
Derivative PID gain for position.
Definition: hebi.h:61
uint32_t string_field_bitfield_offset_
Definition: hebi.h:791
Bus voltage at which the module is running.
Definition: hebi.h:165
Proportional PID gain for velocity.
Definition: hebi.h:253
HebiStatusCode hebiGroupSetCommandLifetime(HebiGroupPtr group, int32_t lifetime_ms)
Sets the command lifetime for the group, in milliseconds.
The family for this module. The string must be null-terminated and less than 21 characters.
Definition: hebi.h:300
HebiCommandPtr hebiGroupCommandGetModuleCommand(HebiGroupCommandPtr command, size_t module_index)
Get an individual command for a particular module at index module_index.
HebiInfoHighResAngleField
Definition: hebi.h:285
const float * float_fields_
Definition: hebi.h:750
HebiGroupPtr hebiGroupCreateFromNames(HebiLookupPtr lookup, const char *const *families, size_t num_families, const char *const *names, size_t num_names, int32_t timeout_ms)
Create a group with modules matching the given names and families.
double hebiTrajectoryGetDuration(HebiTrajectoryPtr trajectory)
Returns the length of this trajectory (in seconds).
Commanded position of the module output (post-spring).
Definition: hebi.h:184
void hebiTrajectoryRelease(HebiTrajectoryPtr trajectory)
Frees resources created by this trajectory.
struct HebiInfoRef_ HebiInfoRef
float z
Definition: hebi.h:567
HebiStatusCode hebiGroupSendFeedbackRequest(HebiGroupPtr group)
Requests feedback from the group.
const int32_t * enum_fields_
Definition: hebi.h:697
HebiInfoFlagField
Definition: hebi.h:303
HebiLookupEntryListPtr hebiCreateLookupEntryList(HebiLookupPtr lookup)
Return a snapshot of the contents of the module registry – i.e., which modules have been found by th...
uint32_t float_field_bitfield_offset_
Definition: hebi.h:781
Constant offset to the effort PID output outside of the deadzone; it is added when the error is posit...
Definition: hebi.h:91
Minimum allowed value for input to the PID controller.
Definition: hebi.h:273
void hebiGroupInfoRelease(HebiGroupInfoPtr info)
Frees resources created by the GroupInfo object.
Minimum allowed value for input to the PID controller.
Definition: hebi.h:260
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...
HebiMatrixOrdering
Definition: hebi.h:430
HebiInfoBoolField
Definition: hebi.h:290
void * reserved_
Definition: hebi.h:644
HebiLinkOutputType
Definition: hebi.h:395
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...
HebiInfoLedField
Definition: hebi.h:315
HebiStatusCode hebiGroupInfoWriteGains(HebiGroupInfoPtr info, const char *file)
Export gains from a GroupInfo object into a file.
HebiJointType joint_type_
Definition: hebi.h:591
struct HebiRobotModelElementTopology_ HebiRobotModelElementTopology
HebiGroupInfoPtr hebiGroupInfoCreate(size_t size)
Creates a GroupInfo for a group with the specified number of modules.
uint32_t message_bitfield_count_
Definition: hebi.h:684
struct HebiTrajectory_ * HebiTrajectoryPtr
The C-style&#39;s API representation of a trajectory.
Definition: hebi.h:549
The firmware safety limit for the maximum allowed velocity.
Definition: hebi.h:281
An invalid argument was supplied to the routine (e.g. null pointer)
Definition: hebi.h:26
The AR session is attempting to resume after an interruption.
Definition: hebi.h:40
HebiCommandFloatField
Command Enums.
Definition: hebi.h:55
HebiFeedbackUInt64Field
Definition: hebi.h:191
float * float_fields_
Definition: hebi.h:634
uint32_t enum_field_bitfield_offset_
Definition: hebi.h:786
HebiCommandStringField
Definition: hebi.h:123
void hebiGroupFeedbackClear(HebiGroupFeedbackPtr feedback)
Clears all data in the GroupFeedback object.
How the position, velocity, and effort PID loops are connected in order to control motor PWM...
Definition: hebi.h:309
Camera position tracking is not available.
Definition: hebi.h:37
The spring constant of the module.
Definition: hebi.h:279
HebiStatusCode hebiGetLibraryVersion(int32_t *major, int32_t *minor, int32_t *revision)
Get the version of the library.
uint32_t uint64_field_bitfield_offset_
Definition: hebi.h:727
Current supplied to the motor.
Definition: hebi.h:173
uint32_t quaternionf_field_bitfield_offset_
Definition: hebi.h:668
uint32_t float_field_count_
Definition: hebi.h:768
HebiCommandNumberedFloatField
Definition: hebi.h:112
Set the internal encoder reference offset so that the current position matches the given reference co...
Definition: hebi.h:99
uint32_t numbered_float_field_bitfield_offset_
Definition: hebi.h:730
struct HebiCommandMetadata_ HebiCommandMetadata
uint32_t enum_field_count_
Definition: hebi.h:715
I/O pin bank c (pins 1-8 available)
Definition: hebi.h:225
float * numbered_float_fields_
Definition: hebi.h:641
uint32_t numbered_float_field_count_
Definition: hebi.h:717
HebiIKPtr hebiIKCreate(void)
Inverse Kinematics API.
void hebiCommandGetReference(HebiCommandPtr command, HebiCommandRef *ref)
HebiStatusCode hebiLookupEntryListGetFamily(HebiLookupEntryListPtr lookup_list, size_t index, char *buffer, size_t *length)
size_t hebiRobotModelGetImportWarningCount()
Retrieve the number of warnings corresponding to the last call to hebiRobotModelImport. This must be called on the same thread as the call to hebiRobotModelImport.
How the position, velocity, and effort PID loops are connected in order to control motor PWM...
Definition: hebi.h:139
The estimated temperature of the motor windings.
Definition: hebi.h:176
const HebiHighResAngleStruct * high_res_angle_fields_
Definition: hebi.h:751
Timestamp of when message was transmitted to module (local)
Definition: hebi.h:195
HebiActuatorType actuator_type_
Definition: hebi.h:585
const uint32_t * numbered_float_relative_offsets_
Definition: hebi.h:736
const uint64_t * uint64_fields_
Definition: hebi.h:696
uint32_t string_field_count_
Definition: hebi.h:662
void hebiGroupCommandRelease(HebiGroupCommandPtr command)
Frees resources created by the GroupCommand object.
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.
const uint32_t * io_field_sizes_
Definition: hebi.h:798
HebiCommandFlagField
Definition: hebi.h:129
float y
Definition: hebi.h:566
uint32_t io_field_count_
Definition: hebi.h:660
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.
Proportional PID gain for effort.
Definition: hebi.h:266
Maximum allowed value for input to the PID controller.
Definition: hebi.h:261
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.
Maximum allowed value for input to the PID controller.
Definition: hebi.h:67
uint32_t flag_field_count_
Definition: hebi.h:663
A filtered estimate of the orientation of the module.
Definition: hebi.h:208
const uint32_t * numbered_float_field_sizes_
Definition: hebi.h:737
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement." When the setpoints have step inputs or are noisy, setting this to false can eliminate corresponding spikes or noise in the output.
Definition: hebi.h:293
HebiInfoFloatField
Info Enums.
Definition: hebi.h:238
Maximum allowed value for input to the PID controller.
Definition: hebi.h:274
HebiLinkInputType
Definition: hebi.h:387
uint32_t quaternionf_field_bitfield_offset_
Definition: hebi.h:784
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:77
void hebiLogFileRelease(HebiLogFilePtr log_file)
Logging API.
HebiQuaternionf * quaternionf_fields_
Definition: hebi.h:637
bool * bool_fields_
Definition: hebi.h:640
Proportional PID gain for position.
Definition: hebi.h:59
Maximum allowed value for input to the PID controller.
Definition: hebi.h:248
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:70
uint32_t string_field_count_
Definition: hebi.h:720
const uint32_t * numbered_float_relative_offsets_
Definition: hebi.h:794
uint32_t float_field_bitfield_offset_
Definition: hebi.h:723
const uint32_t * led_fields_
Definition: hebi.h:701
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
Definition: hebi.h:68
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement." When the setpoints have step inputs or are noisy, setting this to false can eliminate corresponding spikes or noise in the output.
Definition: hebi.h:294
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
Definition: hebi.h:71
HebiIoBankPinResidentType stored_type_
Definition: hebi.h:626
const float * numbered_float_fields_
Definition: hebi.h:757
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:263
Constant offset to the velocity PID output outside of the deadzone; it is added when the error is pos...
Definition: hebi.h:78
uint32_t quaternionf_field_count_
Definition: hebi.h:771
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:270
HebiFeedbackPtr hebiGroupFeedbackGetModuleFeedback(HebiGroupFeedbackPtr feedback, size_t module_index)
Get an individual feedback for a particular module at index module_index.
The position limit strategy (at the minimum position) for the actuator.
Definition: hebi.h:312
struct HebiLookup_ * HebiLookupPtr
Definition: hebi.h:500
Feed forward term for position (this term is multiplied by the target and added to the output)...
Definition: hebi.h:243
Maximum allowed value for input to the PID controller.
Definition: hebi.h:80
const uint64_t * uint64_fields_
Definition: hebi.h:754
Success; no failures occurred.
Definition: hebi.h:25
HebiRobotModelElementType element_type_
Definition: hebi.h:582
The estimated current in the motor windings.
Definition: hebi.h:175
uint32_t quaternionf_field_bitfield_offset_
Definition: hebi.h:726
size_t hebiRobotModelGetNumberOfElements(HebiRobotModelPtr robot_model)
Returns the number of elements added to the kinematic tree.
uint32_t numbered_float_field_bitfield_offset_
Definition: hebi.h:672
uint32_t flag_field_bitfield_offset_
Definition: hebi.h:792
Timestamp of when message was transmitted from module (remote)
Definition: hebi.h:197
HebiRobotModelElementPtr hebiRobotModelElementCreateBracket(HebiBracketType bracket_type)
Creates a rigid body, including mass and static transforms, corresponding to a standard HEBI bracket...
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.
HebiStatusCode hebiLogFileGetNextFeedback(HebiLogFilePtr log_file, HebiGroupFeedbackPtr field)
Retrieve the next group feedback from the opened log file.
Derivative PID gain for effort.
Definition: hebi.h:87
const uint32_t * numbered_float_field_sizes_
Definition: hebi.h:795
uint32_t message_bitfield_count_
Definition: hebi.h:800
The temperature from a sensor near the motor housing.
Definition: hebi.h:174
HebiStatusCode hebiStringGetString(HebiStringPtr str, char *buffer, size_t *length)
String Functions.
HebiInfoEnumField
Definition: hebi.h:307
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement." When the setpoints have step inputs or are noisy, setting this to false can eliminate corresponding spikes or noise in the output.
Definition: hebi.h:119
uint32_t numbered_float_field_count_
Definition: hebi.h:659
uint32_t enum_field_count_
Definition: hebi.h:657
uint32_t high_res_angle_field_count_
Definition: hebi.h:711
Integral PID gain for effort.
Definition: hebi.h:267
The firmware safety limit for the minimum allowed effort.
Definition: hebi.h:103
HebiStatusCode hebiLookupSetLookupFrequencyHz(HebiLookupPtr lookup, double frequency)
sets the lookup request rate [Hz]
uint32_t bool_field_bitfield_offset_
Definition: hebi.h:671
struct HebiLogFile_ * HebiLogFilePtr
The C-style&#39;s API representation of a log file.
Definition: hebi.h:514
The scene visible to the camera does not contain enough distinguishable features for image-based posi...
Definition: hebi.h:42
HebiVector3f * vector3f_fields_
Definition: hebi.h:636
HebiEndEffectorType
Definition: hebi.h:421
uint32_t flag_field_count_
Definition: hebi.h:721
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement." When the setpoints have step inputs or are noisy, setting this to false can eliminate corresponding spikes or noise in the output.
Definition: hebi.h:292
const HebiQuaternionf * quaternionf_fields_
Definition: hebi.h:753
uint32_t high_res_angle_field_count_
Definition: hebi.h:769
Feed forward term for effort (this term is multiplied by the target and added to the output)...
Definition: hebi.h:88
HebiArQuality
Definition: hebi.h:35
Integral PID gain for velocity.
Definition: hebi.h:254
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.
struct HebiLookupEntryList_ * HebiLookupEntryListPtr
Definition: hebi.h:507
Integral PID gain for velocity.
Definition: hebi.h:73
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:258
const HebiIoBankPinStruct * io_fields_
Definition: hebi.h:758
Position of the module output (post-spring).
Definition: hebi.h:108
HebiStatusCode hebiInfoGetString(HebiInfoPtr info, HebiInfoStringField field, char *buffer, size_t *length)
Info API.
const uint32_t * io_field_sizes_
Definition: hebi.h:682
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...
HebiStatusCode hebiRobotModelGetTreeTopology(HebiRobotModelPtr robot_model, HebiFrameType frame_type, HebiRobotModelElementTopology *table)
returns table of information about the shape of kinematic tree
const HebiVector3f * vector3f_fields_
Definition: hebi.h:752
const uint32_t * io_relative_offsets_
Definition: hebi.h:681
uint32_t io_field_count_
Definition: hebi.h:718
uint32_t float_field_count_
Definition: hebi.h:652
Structures.
Definition: hebi.h:560
Temperature of the processor chip.
Definition: hebi.h:164
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:251
HebiLinkType
Definition: hebi.h:379
const HebiHighResAngleStruct * high_res_angle_fields_
Definition: hebi.h:693
I/O pin bank d (pins 1-8 available)
Definition: hebi.h:149
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:250
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:64
struct HebiGroupFeedback_ * HebiGroupFeedbackPtr
The C-style&#39;s API representation of a feedback object for a group of modules.
Definition: hebi.h:476
HebiStatusCode hebiGroupCommandWriteGains(HebiGroupCommandPtr command, const char *file)
Export gains from a GroupCommand object into a file.
Set the internal effort reference offset so that the current effort matches the given reference comma...
Definition: hebi.h:100
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages)...
Definition: hebi.h:58
HebiStatusCode hebiGroupGetNextFeedback(HebiGroupPtr group, HebiGroupFeedbackPtr feedback, int32_t timeout_ms)
Returns the most recently stored feedback from a sent feedback request, or returns the next one recei...
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
Definition: hebi.h:252
HebiStatusCode hebiLookupEntryListGetMacAddress(HebiLookupEntryListPtr lookup_list, size_t index, HebiMacAddress *mac_address)
HebiCommandEnumField
Definition: hebi.h:137
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:63
uint32_t vector3f_field_bitfield_offset_
Definition: hebi.h:667
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.
HebiBracketType bracket_type_
Definition: hebi.h:588
void hebiRobotModelRelease(HebiRobotModelPtr robot_model)
Frees resources created by this robot model object.
Tracking is available albeit suboptimal for an unknown reason.
Definition: hebi.h:38
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
Definition: hebi.h:94
Commanded velocity of the module output (post-spring)
Definition: hebi.h:168
void(* GroupFeedbackHandlerFunction)(HebiGroupFeedbackPtr fbk, void *user_data)
Group feedback handling function signature.
Definition: hebi.h:554
size_t hebiLogFileGetNumberOfModules(HebiLogFilePtr log_file)
Retrieve the number of modules in the group represented by an opened log file.
I/O pin bank d (pins 1-8 available)
Definition: hebi.h:226
double hebiLookupGetLookupFrequencyHz(HebiLookupPtr lookup)
gets the lookup request rate [Hz]
uint32_t io_field_bitfield_offset_
Definition: hebi.h:789
uint32_t message_bitfield_count_
Definition: hebi.h:742
The estimated temperature of the motor housing.
Definition: hebi.h:177
Minimum allowed value for input to the PID controller.
Definition: hebi.h:66
uint32_t high_res_angle_field_count_
Definition: hebi.h:653
HebiInfoPtr hebiGroupInfoGetModuleInfo(HebiGroupInfoPtr info, size_t module_index)
Get an individual info for a particular module at index module_index.
The device is moving too fast for accurate image-based position tracking.
Definition: hebi.h:41
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:244
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...
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:257
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
Definition: hebi.h:275
struct HebiRobotModelElementMetadata_ HebiRobotModelElementMetadata
int32_t hebiGroupGetCommandLifetime(HebiGroupPtr group)
Returns the current command lifetime, in milliseconds.
uint32_t uint64_field_count_
Definition: hebi.h:656
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...
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:89
uint32_t numbered_float_field_count_
Definition: hebi.h:775
uint32_t led_field_bitfield_offset_
Definition: hebi.h:674
HebiStatusCode hebiGroupFeedbackCopy(HebiGroupFeedbackPtr dest, HebiGroupFeedbackPtr src)
Clears the dest GroupFeedback object, and copies all data from the src GroupFeedback object to dest...
HebiCommandLedField
Definition: hebi.h:153
struct HebiQuaternionf_ HebiQuaternionf
size_t hebiGroupGetSize(HebiGroupPtr group)
Returns the number of modules in a group.
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement." When the setpoints have step inputs or are noisy, setting this to false can eliminate corresponding spikes or noise in the output.
Definition: hebi.h:118
Velocity of the difference between the pre-spring and post-spring output position.
Definition: hebi.h:171
uint32_t enum_field_bitfield_offset_
Definition: hebi.h:728
const uint32_t * io_relative_offsets_
Definition: hebi.h:739
uint32_t bool_field_count_
Definition: hebi.h:658
HebiStatusCode hebiIKAddConstraintJointAngles(HebiIKPtr ik, double weight, size_t num_joints, const double *min_positions, const double *max_positions)
Define joint angle constraints.
uint32_t vector3f_field_count_
Definition: hebi.h:770
struct HebiRobotModelElement_ * HebiRobotModelElementPtr
Definition: hebi.h:533
HebiCommandBoolField
Definition: hebi.h:116
HebiStatusCode hebiGroupCommandWriteSafetyParameters(HebiGroupCommandPtr command, const char *file)
Export safety parameters from a GroupCommand object into a file.
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
Definition: hebi.h:81
HebiGroupPtr hebiGroupCreateImitation(size_t size)
Group API.
Maximum allowed value for input to the PID controller.
Definition: hebi.h:93
uint32_t vector3f_field_bitfield_offset_
Definition: hebi.h:725
size_t hebiRobotModelGetNumberOfFrames(HebiRobotModelPtr robot_model, HebiFrameType frame_type)
Return the number of frames in the forward kinematic tree of the robot model.
HebiStatusCode hebiGroupRegisterFeedbackHandler(HebiGroupPtr group, GroupFeedbackHandlerFunction handler, void *user_data)
Add a function that is called whenever feedback is returned from the group.
uint32_t vector3f_field_bitfield_offset_
Definition: hebi.h:783
struct HebiIK_ * HebiIKPtr
Definition: hebi.h:540
Describes how the temperature inside the module is limiting the output of the motor.
Definition: hebi.h:213
void hebiGroupClearFeedbackHandlers(HebiGroupPtr group)
Removes all feedback handling functions from the queue to be called on receipt of group feedback...
const uint32_t * io_relative_offsets_
Definition: hebi.h:797
The name for this module. The string must be null-terminated and less than 21 characters.
Definition: hebi.h:299
Timestamp of when message was received by module (remote)
Definition: hebi.h:196
The motion stop strategy for the actuator.
Definition: hebi.h:311
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:271
I/O pin bank a (pins 1-8 available)
Definition: hebi.h:223
const char * hebiSafetyParametersGetLastError(void)
Misc Functions.
HebiRobotModelElementType
Definition: hebi.h:338
const char * hebiRobotModelGetImportWarning(size_t warning_index)
Retrieve the &#39;ith&#39; warning string from the last call to hebiRobotModelImport. This must be called on ...
const HebiIoBankPinStruct * io_fields_
Definition: hebi.h:700
Feed forward term for velocity (this term is multiplied by the target and added to the output)...
Definition: hebi.h:75
int32_t * enum_fields_
Definition: hebi.h:639
HebiFeedbackIoPinBank
Definition: hebi.h:221
Indicates if the module should save the current values of all of its settings.
Definition: hebi.h:131
uint32_t flag_field_bitfield_offset_
Definition: hebi.h:676
HebiRobotModelPtr hebiRobotModelImport(const char *file)
Import robot model from a file into a RobotModel object.
Position of the module output (post-spring).
Definition: hebi.h:183
struct HebiGroup_ * HebiGroupPtr
The C-style&#39;s API representation of a group.
Definition: hebi.h:493
Software-controlled bounds on the allowable effort of the module.
Definition: hebi.h:217
The firmware safety limit for the minimum allowed velocity.
Definition: hebi.h:280
void hebiCleanup(void)
Frees all resources created by the library. Note: any calls to the HEBI library functions after this ...
uint32_t uint64_field_count_
Definition: hebi.h:714
HebiStatusCode hebiGroupInfoWriteSafetyParameters(HebiGroupInfoPtr info, const char *file)
Export safety parameters from a GroupInfo object into a file.
uint32_t bool_field_count_
Definition: hebi.h:774
void hebiLookupEntryListRelease(HebiLookupEntryListPtr lookup_list)
Release resources for a given lookup entry list; list should not be used after this call...
Constant offset to the position PID output outside of the deadzone; it is added when the error is pos...
Definition: hebi.h:246
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:69
void hebiIKClearAll(HebiIKPtr ik)
Clears the objectives and constraints from this IK object, along with any modifications to the defaul...
uint32_t led_field_count_
Definition: hebi.h:661
const HebiVector3f * vector3f_fields_
Definition: hebi.h:694
Constant offset to the position PID output outside of the deadzone; it is added when the error is pos...
Definition: hebi.h:65
The motion stop strategy for the actuator.
Definition: hebi.h:140
HebiEndEffectorType end_effector_type_
Definition: hebi.h:601
I/O pin bank c (pins 1-8 available)
Definition: hebi.h:148
HebiStatusCode
Enum Types.
Definition: hebi.h:23
I/O pin bank a (pins 1-8 available)
Definition: hebi.h:146
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
Definition: hebi.h:97
void hebiLookupRelease(HebiLookupPtr lookup)
Frees resources created by the lookup object.
struct HebiIoBankPinStruct_ HebiIoBankPinStruct
const bool * bool_fields_
Definition: hebi.h:698
HebiActuatorType
Definition: hebi.h:364
Commanded effort at the module output; units vary (e.g., N * m for rotational joints and N for linear...
Definition: hebi.h:169
Velocity of the module output (post-spring).
Definition: hebi.h:166
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement." When the setpoints have step inputs or are noisy, setting this to false can eliminate corresponding spikes or noise in the output.
Definition: hebi.h:120
I/O pin bank e (pins 1-8 available)
Definition: hebi.h:150
Minimum allowed value for input to the PID controller.
Definition: hebi.h:92
HebiRobotModelPtr hebiRobotModelImportBuffer(const char *buffer, size_t buffer_size)
Import robot model from a buffer into a RobotModel object.
const uint32_t * led_fields_
Definition: hebi.h:759


hebi_cpp_api_ros
Author(s): Chris Bollinger , Matthew Tesch
autogenerated on Thu May 28 2020 03:14:45