hebi.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <math.h>
4 #include <stddef.h>
5 #include <stdint.h>
6 
7 #ifdef __cplusplus /* Use C linkage when compiling this C library header from C++ */
8 extern "C" {
9 #endif
10 
11 #ifndef M_PI
12 #define M_PI 3.14159265358979323846
13 #endif
14 
16 // Enum Types
18 
19 typedef enum HebiStatusCode {
27 
29 // Command Enums
31 
32 typedef enum HebiCommandFloatField {
78 
84 
88 
89 typedef enum HebiCommandBoolField {
94 
95 typedef enum HebiCommandStringField {
99 
100 typedef enum HebiCommandFlagField {
106 
107 typedef enum HebiCommandEnumField {
110 
111 typedef enum HebiCommandIoPinBank {
119 
120 typedef enum HebiCommandLedField {
123 
125 // Feedback Enums
127 
145 
150 
154 
163 
168 
172 
173 typedef enum HebiFeedbackEnumField {
181 
182 typedef enum HebiFeedbackIoPinBank {
190 
191 typedef enum HebiFeedbackLedField {
194 
196 // Info Enums
198 
199 typedef enum HebiInfoFloatField {
241 
246 
247 typedef enum HebiInfoBoolField {
252 
253 typedef enum HebiInfoStringField {
258 
259 typedef enum HebiInfoFlagField {
262 
263 typedef enum HebiInfoEnumField {
267 
268 typedef enum HebiInfoLedField {
271 
273 // RobotModel Enums
275 
280 typedef enum HebiFrameType {
284 } HebiFrameType;
285 
290 typedef enum HebiJointType {
297 } HebiJointType;
298 
300 // Typedefs
302 
308 typedef struct _HebiString* HebiStringPtr;
309 
315 typedef struct _HebiCommand* HebiCommandPtr;
316 
322 typedef struct _HebiFeedback* HebiFeedbackPtr;
323 
330 typedef struct _HebiGroup* HebiGroupPtr;
331 
338 typedef struct _HebiGroupCommand* HebiGroupCommandPtr;
339 
346 typedef struct _HebiGroupFeedback* HebiGroupFeedbackPtr;
347 
354 typedef struct _HebiGroupInfo* HebiGroupInfoPtr;
355 
362 typedef struct _HebiInfo* HebiInfoPtr;
363 
369 typedef struct _HebiIK* HebiIKPtr;
370 
375 typedef struct _HebiRobotModel* HebiRobotModelPtr;
376 
381 typedef struct _HebiRobotModelElement* HebiRobotModelElementPtr;
382 
388 typedef struct _HebiLogFile* HebiLogFilePtr;
389 
395 typedef struct _HebiLookup* HebiLookupPtr;
396 
402 typedef struct _HebiLookupEntryList* HebiLookupEntryListPtr;
403 
411 typedef struct _HebiTrajectory* HebiTrajectoryPtr;
412 
416 typedef void (*GroupFeedbackHandlerFunction)(HebiGroupFeedbackPtr fbk, void* user_data);
417 
419 // Structures
421 
422 typedef struct _HebiMacAddress { uint8_t bytes_[6]; } HebiMacAddress;
423 
424 typedef struct _HebiVector3f {
425  float x;
426  float y;
427  float z;
428 } HebiVector3f;
429 
430 typedef struct _HebiQuaternionf {
431  float w;
432  float x;
433  float y;
434  float z;
436 
438 // Lookup API
440 
450 HebiLookupPtr hebiLookupCreate(void);
451 
458 void hebiLookupRelease(HebiLookupPtr lookup);
459 
466 HebiLookupEntryListPtr hebiCreateLookupEntryList(HebiLookupPtr lookup);
467 
473 size_t hebiLookupEntryListGetSize(HebiLookupEntryListPtr lookup_list);
474 
495 HebiStatusCode hebiLookupEntryListGetName(HebiLookupEntryListPtr lookup_list, size_t index, char* buffer,
496  size_t* length);
497 
518 HebiStatusCode hebiLookupEntryListGetFamily(HebiLookupEntryListPtr lookup_list, size_t index, char* buffer,
519  size_t* length);
520 
532 HebiStatusCode hebiLookupEntryListGetMacAddress(HebiLookupEntryListPtr lookup_list, size_t index,
533  HebiMacAddress* mac_address);
534 
541 void hebiLookupEntryListRelease(HebiLookupEntryListPtr lookup_list);
542 
544 // Group API
546 
561 HebiGroupPtr hebiGroupCreateImitation(size_t size);
562 
584 HebiGroupPtr hebiGroupCreateFromMacs(HebiLookupPtr lookup, const HebiMacAddress* const* addresses,
585  size_t num_addresses, int32_t timeout_ms);
586 
620 HebiGroupPtr hebiGroupCreateFromNames(HebiLookupPtr lookup, const char* const* families, size_t num_families,
621  const char* const* names, size_t num_names, int32_t timeout_ms);
622 
641 HebiGroupPtr hebiGroupCreateFromFamily(HebiLookupPtr lookup, const char* family, int32_t timeout_ms);
642 
664 HebiGroupPtr hebiGroupCreateConnectedFromMac(HebiLookupPtr lookup, const HebiMacAddress* address,
665  int32_t timeout_ms);
666 
689 HebiGroupPtr hebiGroupCreateConnectedFromName(HebiLookupPtr lookup, const char* family, const char* name,
690  int32_t timeout_ms);
691 
699 size_t hebiGroupGetSize(HebiGroupPtr group);
700 
720 HebiStatusCode hebiGroupSendCommandWithAcknowledgement(HebiGroupPtr group, HebiGroupCommandPtr command,
721  int32_t timeout_ms);
722 
735 HebiStatusCode hebiGroupSendCommand(HebiGroupPtr group, HebiGroupCommandPtr command);
736 
760 HebiStatusCode hebiGroupSetCommandLifetime(HebiGroupPtr group, int32_t lifetime_ms);
761 
770 int32_t hebiGroupGetCommandLifetime(HebiGroupPtr group);
771 
785 HebiStatusCode hebiGroupSetFeedbackFrequencyHz(HebiGroupPtr group, float frequency);
786 
794 float hebiGroupGetFeedbackFrequencyHz(HebiGroupPtr group);
795 
807  void* user_data);
808 
815 void hebiGroupClearFeedbackHandlers(HebiGroupPtr group);
816 
830 HebiStatusCode hebiGroupSendFeedbackRequest(HebiGroupPtr group);
831 
853 HebiStatusCode hebiGroupGetNextFeedback(HebiGroupPtr group, HebiGroupFeedbackPtr feedback,
854  int32_t timeout_ms);
855 
873 HebiStatusCode hebiGroupRequestInfo(HebiGroupPtr group, HebiGroupInfoPtr info, int32_t timeout_ms);
874 
891 HebiStatusCode hebiGroupStartLog(HebiGroupPtr group, const char* dir, const char* file, HebiStringPtr* ret);
892 
903 HebiLogFilePtr hebiGroupStopLog(HebiGroupPtr group);
904 
911 void hebiGroupRelease(HebiGroupPtr group);
912 
922 HebiGroupCommandPtr hebiGroupCommandCreate(size_t size);
923 
929 size_t hebiGroupCommandGetSize(HebiGroupCommandPtr cmd);
930 
947 HebiStatusCode hebiGroupCommandReadGains(HebiGroupCommandPtr cmd, const char* file);
948 
958 HebiStatusCode hebiGroupCommandWriteGains(HebiGroupCommandPtr cmd, const char* file);
959 
969 HebiCommandPtr hebiGroupCommandGetModuleCommand(HebiGroupCommandPtr cmd, size_t module_index);
970 
986 HebiStatusCode hebiGroupCommandCopy(HebiGroupCommandPtr dest, HebiGroupCommandPtr src);
987 
991 void hebiGroupCommandClear(HebiGroupCommandPtr cmd);
992 
998 void hebiGroupCommandRelease(HebiGroupCommandPtr cmd);
999 
1009 HebiGroupFeedbackPtr hebiGroupFeedbackCreate(size_t size);
1010 
1016 size_t hebiGroupFeedbackGetSize(HebiGroupFeedbackPtr fbk);
1017 
1027 HebiFeedbackPtr hebiGroupFeedbackGetModuleFeedback(HebiGroupFeedbackPtr fbk, size_t module_index);
1028 
1044 HebiStatusCode hebiGroupFeedbackCopy(HebiGroupFeedbackPtr dest, HebiGroupFeedbackPtr src);
1045 
1049 void hebiGroupFeedbackClear(HebiGroupFeedbackPtr fbk);
1050 
1056 void hebiGroupFeedbackRelease(HebiGroupFeedbackPtr fbk);
1057 
1067 HebiGroupInfoPtr hebiGroupInfoCreate(size_t size);
1068 
1074 size_t hebiGroupInfoGetSize(HebiGroupInfoPtr info);
1075 
1085 HebiStatusCode hebiGroupInfoWriteGains(HebiGroupInfoPtr info, const char* file);
1086 
1096 HebiInfoPtr hebiGroupInfoGetModuleInfo(HebiGroupInfoPtr info, size_t module_index);
1097 
1113 HebiStatusCode hebiGroupInfoCopy(HebiGroupInfoPtr dest, HebiGroupInfoPtr src);
1114 
1118 void hebiGroupInfoClear(HebiGroupInfoPtr info);
1119 
1125 void hebiGroupInfoRelease(HebiGroupInfoPtr info);
1126 
1128 // Command API
1130 
1135 HebiStatusCode hebiCommandGetFloat(HebiCommandPtr cmd, HebiCommandFloatField field, float* value);
1136 
1140 void hebiCommandSetFloat(HebiCommandPtr cmd, HebiCommandFloatField field, const float* value);
1141 
1146 HebiStatusCode hebiCommandGetHighResAngle(HebiCommandPtr cmd, HebiCommandHighResAngleField field,
1147  int64_t* int_part, float* dec_part);
1148 
1152 void hebiCommandSetHighResAngle(HebiCommandPtr cmd, HebiCommandHighResAngleField field,
1153  const int64_t* int_part, const float* dec_part);
1154 
1159 HebiStatusCode hebiCommandGetNumberedFloat(HebiCommandPtr cmd, HebiCommandNumberedFloatField field,
1160  size_t number, float* value);
1161 
1165 void hebiCommandSetNumberedFloat(HebiCommandPtr cmd, HebiCommandNumberedFloatField field, size_t number,
1166  const float* value);
1167 
1175 HebiStatusCode hebiCommandGetBool(HebiCommandPtr cmd, HebiCommandBoolField field, int32_t* value);
1176 
1180 void hebiCommandSetBool(HebiCommandPtr cmd, HebiCommandBoolField field, const int32_t* value);
1181 
1208 HebiStatusCode hebiCommandGetString(HebiCommandPtr cmd, HebiCommandStringField field, char* buffer,
1209  size_t* length);
1210 
1221 void hebiCommandSetString(HebiCommandPtr cmd, HebiCommandStringField field, const char* buffer,
1222  const size_t* length);
1223 
1227 int32_t hebiCommandGetFlag(HebiCommandPtr cmd, HebiCommandFlagField field);
1228 
1232 void hebiCommandSetFlag(HebiCommandPtr cmd, HebiCommandFlagField field, int32_t value);
1233 
1238 HebiStatusCode hebiCommandGetEnum(HebiCommandPtr cmd, HebiCommandEnumField field, int32_t* value);
1239 
1243 void hebiCommandSetEnum(HebiCommandPtr cmd, HebiCommandEnumField field, const int32_t* value);
1244 
1249 HebiStatusCode hebiCommandGetIoPinInt(HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number,
1250  int64_t* value);
1251 
1256 HebiStatusCode hebiCommandGetIoPinFloat(HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number,
1257  float* value);
1258 
1263 void hebiCommandSetIoPinInt(HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number,
1264  const int64_t* value);
1265 
1270 void hebiCommandSetIoPinFloat(HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number,
1271  const float* value);
1272 
1280 HebiStatusCode hebiCommandGetLedColor(HebiCommandPtr cmd, HebiCommandLedField field, uint8_t* r, uint8_t* g,
1281  uint8_t* b);
1282 
1288 int32_t hebiCommandHasLedModuleControl(HebiCommandPtr cmd, HebiCommandLedField field);
1289 
1293 void hebiCommandSetLedOverrideColor(HebiCommandPtr cmd, HebiCommandLedField field, uint8_t r, uint8_t g,
1294  uint8_t b);
1295 
1299 void hebiCommandSetLedModuleControl(HebiCommandPtr cmd, HebiCommandLedField field);
1300 
1305 void hebiCommandClearLed(HebiCommandPtr cmd, HebiCommandLedField field);
1306 
1308 // Feedback API
1310 
1315 HebiStatusCode hebiFeedbackGetFloat(HebiFeedbackPtr fbk, HebiFeedbackFloatField field, float* value);
1316 
1321 HebiStatusCode hebiFeedbackGetHighResAngle(HebiFeedbackPtr fbk, HebiFeedbackHighResAngleField field,
1322  int64_t* int_part, float* dec_part);
1323 
1328 HebiStatusCode hebiFeedbackGetNumberedFloat(HebiFeedbackPtr fbk, HebiFeedbackNumberedFloatField field,
1329  size_t number, float* value);
1330 
1335 HebiStatusCode hebiFeedbackGetUInt64(HebiFeedbackPtr fbk, HebiFeedbackUInt64Field field, uint64_t* value);
1336 
1342 HebiStatusCode hebiFeedbackGetEnum(HebiFeedbackPtr, HebiFeedbackEnumField, int32_t*);
1343 
1348 HebiStatusCode hebiFeedbackGetVector3f(HebiFeedbackPtr fbk, HebiFeedbackVector3fField field,
1349  HebiVector3f* value);
1350 
1355 HebiStatusCode hebiFeedbackGetQuaternionf(HebiFeedbackPtr fbk,
1356  HebiFeedbackQuaternionfField field,
1357  HebiQuaternionf* value);
1358 
1363 HebiStatusCode hebiFeedbackGetIoPinInt(HebiFeedbackPtr fbk, HebiFeedbackIoPinBank field, size_t pin_number,
1364  int64_t* value);
1365 
1370 HebiStatusCode hebiFeedbackGetIoPinFloat(HebiFeedbackPtr fbk, HebiFeedbackIoPinBank field, size_t pin_number,
1371  float* value);
1372 
1380 HebiStatusCode hebiFeedbackGetLedColor(HebiFeedbackPtr fbk, HebiFeedbackLedField field, uint8_t* r,
1381  uint8_t* g, uint8_t* b);
1382 
1384 // Info API
1386 
1391 HebiStatusCode hebiInfoGetFloat(HebiInfoPtr info, HebiInfoFloatField field, float* value);
1392 
1398 HebiStatusCode hebiInfoGetHighResAngle(HebiInfoPtr, HebiInfoHighResAngleField,
1399  int64_t* int_part, float* dec_part);
1400 
1408 HebiStatusCode hebiInfoGetBool(HebiInfoPtr info, HebiInfoBoolField field, int32_t* value);
1409 
1436 HebiStatusCode hebiInfoGetString(HebiInfoPtr info, HebiInfoStringField field, char* buffer, size_t* length);
1437 
1441 int32_t hebiInfoGetFlag(HebiInfoPtr info, HebiInfoFlagField field);
1442 
1447 HebiStatusCode hebiInfoGetEnum(HebiInfoPtr info, HebiInfoEnumField field, int32_t* value);
1448 
1456 HebiStatusCode hebiInfoGetLedColor(HebiInfoPtr info, HebiInfoLedField field, uint8_t* r, uint8_t* g,
1457  uint8_t* b);
1458 
1460 // RobotModel API
1462 
1473 HebiRobotModelElementPtr hebiRobotModelElementCreateJoint(HebiJointType joint_type);
1474 
1495 HebiRobotModelElementPtr hebiRobotModelElementCreateRigidBody(const double* com, const double* inertia,
1496  double mass, size_t num_outputs,
1497  const double* outputs);
1498 
1510 void hebiRobotModelElementRelease(HebiRobotModelElementPtr element);
1511 
1519 HebiRobotModelPtr hebiRobotModelCreate(void);
1520 
1532 HebiStatusCode hebiRobotModelSetBaseFrame(HebiRobotModelPtr robot_model, const double* transform);
1533 
1546 HebiStatusCode hebiRobotModelGetBaseFrame(HebiRobotModelPtr robot_model, double* transform);
1547 
1561 size_t hebiRobotModelGetNumberOfFrames(HebiRobotModelPtr robot_model, HebiFrameType frame_type);
1562 
1569 size_t hebiRobotModelGetNumberOfDoFs(HebiRobotModelPtr robot_model);
1570 
1606 HebiStatusCode hebiRobotModelAdd(HebiRobotModelPtr robot_model, HebiRobotModelElementPtr existing_element,
1607  size_t output_index, HebiRobotModelElementPtr new_element, int32_t combine);
1608 
1644 HebiStatusCode hebiRobotModelGetForwardKinematics(HebiRobotModelPtr robot_model, HebiFrameType frame_type,
1645  const double* positions, double* frames);
1646 
1663 HebiStatusCode hebiRobotModelGetJacobians(HebiRobotModelPtr robot_model, HebiFrameType frame_type,
1664  const double* positions, double* jacobians);
1665 
1678 HebiStatusCode hebiRobotModelGetMasses(HebiRobotModelPtr robot_model, double* masses);
1679 
1687 void hebiRobotModelRelease(HebiRobotModelPtr robot_model);
1688 
1690 // Inverse Kinematics API
1692 
1700 HebiIKPtr hebiIKCreate(void);
1701 
1721 HebiStatusCode hebiIKAddObjectiveEndEffectorPosition(HebiIKPtr ik, float weight, size_t end_effector_index,
1722  double x, double y, double z);
1723 
1741 HebiStatusCode hebiIKAddObjectiveEndEffectorSO3(HebiIKPtr ik, double weight, size_t end_effector_index,
1742  const double* matrix);
1743 
1762 HebiStatusCode hebiIKAddObjectiveEndEffectorTipAxis(HebiIKPtr ik, double weight, size_t end_effector_index,
1763  double x, double y, double z);
1764 
1784 HebiStatusCode hebiIKAddConstraintJointAngles(HebiIKPtr ik, double weight, size_t num_joints,
1785  const double* min_positions, const double* max_positions);
1786 
1787 
1810 HebiStatusCode hebiIKAddObjectiveCustom(HebiIKPtr ik, double weight,
1811  size_t num_errors,
1812  void(*err_fnc)(void* user_data,
1813  size_t num_positions,
1814  const double* positions,
1815  double* errors),
1816  void* user_data);
1817 
1822 void hebiIKClearAll(HebiIKPtr ik);
1823 
1845 HebiStatusCode hebiIKSolve(HebiIKPtr ik, HebiRobotModelPtr model, const double* initial_positions,
1846  double* ik_solution, void* result_info);
1847 
1855 void hebiIKRelease(HebiIKPtr ik);
1856 
1858 // Trajectory API
1860 
1886 HebiTrajectoryPtr hebiTrajectoryCreateUnconstrainedQp(size_t num_waypoints, const double* positions,
1887  const double* velocities, const double* accelerations,
1888  const double* time_vector);
1889 
1895 void hebiTrajectoryRelease(HebiTrajectoryPtr trajectory);
1896 
1900 double hebiTrajectoryGetDuration(HebiTrajectoryPtr trajectory);
1901 
1917 HebiStatusCode hebiTrajectoryGetState(HebiTrajectoryPtr trajectory, double time, double* position,
1918  double* velocity, double* acceleration);
1919 
1921 // Logging API
1923 
1927 void hebiLogFileRelease(HebiLogFilePtr log_file);
1928 
1944 HebiStatusCode hebiLogFileGetFileName(HebiLogFilePtr log_file, char* buffer, size_t* length);
1945 
1958 HebiLogFilePtr hebiLogFileOpen(const char* file);
1959 
1965 size_t hebiLogFileGetNumberOfModules(HebiLogFilePtr log_file);
1966 
1973 HebiStatusCode hebiLogFileGetNextFeedback(HebiLogFilePtr log_file, HebiGroupFeedbackPtr field);
1974 
1976 // String Functions
1978 
1993 HebiStatusCode hebiStringGetString(HebiStringPtr str, char* buffer, size_t* length);
1994 
1998 void hebiStringRelease(HebiStringPtr str);
1999 
2001 // Misc Functions
2003 
2012 HebiStatusCode hebiGetLibraryVersion(int32_t* major, int32_t* minor, int32_t* revision);
2013 
2018 void hebiCleanup(void);
2019 
2020 #ifdef __cplusplus
2021 } // extern "C"
2022 #endif
Ambient temperature inside the module (measured at the IMU chip), in degrees Celsius.
Definition: hebi.h:130
Sets the name for this module. Name must be null-terminated character string for the name; must be <=...
Definition: hebi.h:97
HebiStatusCode hebiIKAddObjectiveEndEffectorSO3(HebiIKPtr ik, double weight, size_t end_effector_index, const double *matrix)
Add an objective that optimizes for the end effector output frame orientation to be given by the 3x3 ...
HebiFeedbackQuaternionfField
Definition: hebi.h:169
Integral PID gain for position.
Definition: hebi.h:37
HebiStatusCode hebiGroupCommandWriteGains(HebiGroupCommandPtr cmd, const char *file)
Export gains from a GroupCommand object into a file.
void hebiStringRelease(HebiStringPtr str)
Releases a string instance.
Timestamp of when message was received from module (local)
Definition: hebi.h:158
void hebiGroupFeedbackClear(HebiGroupFeedbackPtr fbk)
Clears all data in the GroupFeedback object.
void hebiCommandSetLedOverrideColor(HebiCommandPtr cmd, HebiCommandLedField field, uint8_t r, uint8_t g, uint8_t b)
HebiLogFilePtr hebiLogFileOpen(const char *file)
Opens an existing log file.
float x
Definition: hebi.h:425
HebiStatusCode hebiCommandGetNumberedFloat(HebiCommandPtr cmd, HebiCommandNumberedFloatField field, size_t number, float *value)
Returned when an accessor function attempts to retrieve a field which is not set. ...
Definition: hebi.h:24
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 hebiRobotModelGetForwardKinematics(HebiRobotModelPtr robot_model, HebiFrameType frame_type, const double *positions, double *frames)
Generates the transforms for the forward kinematics of the given robot model.
HebiTrajectoryPtr hebiTrajectoryCreateUnconstrainedQp(size_t num_waypoints, const double *positions, const double *velocities, const double *accelerations, const double *time_vector)
Creates a HebiTrajectory object for a single joint using the given parameters; this must be released ...
HebiLogFilePtr hebiGroupStopLog(HebiGroupPtr group)
Stops logging data to a file.
The spring constant of the module.
Definition: hebi.h:75
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:53
Derivative PID gain for velocity.
Definition: hebi.h:216
HebiStatusCode hebiLogFileGetFileName(HebiLogFilePtr log_file, char *buffer, size_t *length)
Copy the path and name of the log file into a buffer.
HebiGroupPtr hebiGroupCreateConnectedFromMac(HebiLookupPtr lookup, const HebiMacAddress *address, int32_t timeout_ms)
Create a group with all modules connected to module with the given MAC address.
HebiStatusCode hebiGroupSendCommand(HebiGroupPtr group, HebiGroupCommandPtr command)
Sends a command to the given group without requesting an acknowledgement.
struct _HebiLookupEntryList * HebiLookupEntryListPtr
Definition: hebi.h:402
HebiCommandHighResAngleField
Definition: hebi.h:79
void hebiCommandSetBool(HebiCommandPtr cmd, HebiCommandBoolField field, const int32_t *value)
Boot the module from bootloader into application.
Definition: hebi.h:104
HebiStatusCode hebiCommandGetIoPinFloat(HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number, float *value)
void hebiCommandClearLed(HebiCommandPtr cmd, HebiCommandLedField field)
Difference (in radians) between the pre-spring and post-spring output position.
Definition: hebi.h:137
HebiFeedbackVector3fField
Definition: hebi.h:164
HebiStatusCode hebiRobotModelGetJacobians(HebiRobotModelPtr robot_model, HebiFrameType frame_type, const double *positions, double *jacobians)
Generates the jacobian for each frame in the given kinematic tree.
uint8_t bytes_[6]
Definition: hebi.h:422
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
Definition: hebi.h:61
Feed forward term for effort (this term is multiplied by the target and added to the output)...
Definition: hebi.h:230
HebiStatusCode hebiInfoGetFloat(HebiInfoPtr info, HebiInfoFloatField field, float *value)
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:73
HebiStatusCode hebiGroupInfoCopy(HebiGroupInfoPtr dest, HebiGroupInfoPtr src)
Clears the dest GroupInfo object, and copies all data from the src GroupInfo object to dest...
Set the firmware safety limit for the minimum allowed position.
Definition: hebi.h:82
struct _HebiQuaternionf HebiQuaternionf
int32_t hebiInfoGetFlag(HebiInfoPtr info, HebiInfoFlagField field)
A buffer supplied to the routine was too small (normally determined by a size parameter) ...
Definition: hebi.h:23
HebiStatusCode hebiGroupStartLog(HebiGroupPtr group, const char *dir, const char *file, HebiStringPtr *ret)
Starts logging data to a file.
Software-controlled bounds on the allowable position of the module; user settable.
Definition: hebi.h:177
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:72
struct _HebiGroup * HebiGroupPtr
The C-style&#39;s API representation of a group.
Definition: hebi.h:330
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
Definition: hebi.h:239
HebiRobotModelElementPtr hebiRobotModelElementCreateJoint(HebiJointType joint_type)
Creates a one-dof joint about the specified axis.
HebiStatusCode hebiRobotModelGetMasses(HebiRobotModelPtr robot_model, double *masses)
Fill in the masses vector with the mass of each body with mass in the kinematic tree, reported in a depth-first ordering.
Integral PID gain for position.
Definition: hebi.h:202
Current status of the MStop.
Definition: hebi.h:176
struct _HebiIK * HebiIKPtr
Definition: hebi.h:369
HebiFeedbackHighResAngleField
Definition: hebi.h:146
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:210
struct _HebiGroupFeedback * HebiGroupFeedbackPtr
The C-style&#39;s API representation of group feedback.
Definition: hebi.h:346
struct _HebiMacAddress HebiMacAddress
void hebiCommandSetLedModuleControl(HebiCommandPtr cmd, HebiCommandLedField field)
void hebiGroupInfoClear(HebiGroupInfoPtr info)
Clears all data in the GroupInfo object.
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
Definition: hebi.h:226
Software-controlled bounds on the allowable velocity of the module.
Definition: hebi.h:178
HebiFeedbackEnumField
Definition: hebi.h:173
Derivative PID gain for effort.
Definition: hebi.h:229
void hebiCommandSetFlag(HebiCommandPtr cmd, HebiCommandFlagField field, int32_t value)
HebiStatusCode hebiInfoGetHighResAngle(HebiInfoPtr, HebiInfoHighResAngleField, int64_t *int_part, float *dec_part)
HebiStatusCode hebiFeedbackGetIoPinInt(HebiFeedbackPtr fbk, HebiFeedbackIoPinBank field, size_t pin_number, int64_t *value)
HebiFeedbackNumberedFloatField
Definition: hebi.h:151
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:60
Feed forward term for position (this term is multiplied by the target and added to the output)...
Definition: hebi.h:39
Feed forward term for velocity (this term is multiplied by the target and added to the output)...
Definition: hebi.h:217
HebiStatusCode hebiFeedbackGetLedColor(HebiFeedbackPtr fbk, HebiFeedbackLedField field, uint8_t *r, uint8_t *g, uint8_t *b)
void hebiGroupRelease(HebiGroupPtr group)
Release resources for a given group; group should not be used after this call.
The velocity (in radians/second) of the motor shaft.
Definition: hebi.h:139
void hebiGroupCommandClear(HebiGroupCommandPtr cmd)
Clears all data in the GroupCommand object.
I/O pin bank b (pins 1-8 available)
Definition: hebi.h:114
HebiFrameType
Definition: hebi.h:280
Constant offset to the effort PID output outside of the deadzone; it is added when the error is posit...
Definition: hebi.h:233
HebiFeedbackLedField
Definition: hebi.h:191
struct _HebiGroupInfo * HebiGroupInfoPtr
The C-style&#39;s API representation of group info.
Definition: hebi.h:354
Proportional PID gain for position.
Definition: hebi.h:201
static constexpr size_t size(Tuple< Args... > &)
Provides access to the number of elements in a tuple as a compile-time constant expression.
struct _HebiLookup * HebiLookupPtr
Definition: hebi.h:395
size_t hebiGroupCommandGetSize(HebiGroupCommandPtr cmd)
Return the number of modules in this group Command.
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:237
Minimum allowed value for input to the PID controller.
Definition: hebi.h:208
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:206
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:67
size_t hebiGroupInfoGetSize(HebiGroupInfoPtr info)
Return the number of modules in this group Info.
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
Definition: hebi.h:223
HebiStatusCode hebiCommandGetBool(HebiCommandPtr cmd, HebiCommandBoolField field, int32_t *value)
HebiFeedbackFloatField
Definition: hebi.h:128
Restart the module.
Definition: hebi.h:103
HebiStatusCode hebiGroupCommandCopy(HebiGroupCommandPtr dest, HebiGroupCommandPtr src)
Clears the dest GroupCommand object, and copies all data from the src GroupCommand object to dest...
HebiStatusCode hebiLookupEntryListGetName(HebiLookupEntryListPtr lookup_list, size_t index, char *buffer, size_t *length)
The firmware safety limit for the minimum allowed position.
Definition: hebi.h:244
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:225
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:238
Sequence number going to module (local)
Definition: hebi.h:157
HebiStatusCode hebiTrajectoryGetState(HebiTrajectoryPtr trajectory, double time, double *position, double *velocity, double *acceleration)
Gets the value of the trajectory at a given time.
float z
Definition: hebi.h:427
HebiCommandIoPinBank
Definition: hebi.h:111
HebiStatusCode hebiFeedbackGetUInt64(HebiFeedbackPtr fbk, HebiFeedbackUInt64Field field, uint64_t *value)
HebiStatusCode hebiIKAddObjectiveCustom(HebiIKPtr ik, double weight, size_t num_errors, void(*err_fnc)(void *user_data, size_t num_positions, const double *positions, double *errors), void *user_data)
Add a custom objective function to be minimized by the IK solver.
Derivative PID gain for velocity.
Definition: hebi.h:51
Generic code for failure; this is generally used for an internal or unknown failure.
Definition: hebi.h:25
float y
Definition: hebi.h:426
Minimum allowed value for input to the PID controller.
Definition: hebi.h:56
Proportional PID gain for velocity.
Definition: hebi.h:49
I/O pin bank e (pins 1-8 available)
Definition: hebi.h:188
Derivative PID gain for position.
Definition: hebi.h:203
Accelerometer data, in m/s^2.
Definition: hebi.h:166
int32_t hebiCommandGetFlag(HebiCommandPtr cmd, HebiCommandFlagField field)
HebiStatusCode hebiGroupSetFeedbackFrequencyHz(HebiGroupPtr group, float frequency)
Sets the feedback request loop frequency (in Hz).
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:59
size_t hebiRobotModelGetNumberOfDoFs(HebiRobotModelPtr robot_model)
Returns the number of settable degrees of freedom in the kinematic tree. (This is equal to the number...
float hebiGroupGetFeedbackFrequencyHz(HebiGroupPtr group)
Returns the current feedback request loop frequency (in Hz).
HebiGroupCommandPtr hebiGroupCommandCreate(size_t size)
Creates a GroupCommand for a group with the specified number of modules.
Velocity of the module output (post-spring), in radians/second.
Definition: hebi.h:34
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages)...
Definition: hebi.h:134
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:62
HebiGroupPtr hebiGroupCreateConnectedFromName(HebiLookupPtr lookup, const char *family, const char *name, int32_t timeout_ms)
Create a group with all modules connected to module with the given name and family.
HebiStatusCode hebiFeedbackGetVector3f(HebiFeedbackPtr fbk, HebiFeedbackVector3fField field, HebiVector3f *value)
I/O pin bank b (pins 1-8 available)
Definition: hebi.h:185
size_t hebiLookupEntryListGetSize(HebiLookupEntryListPtr lookup_list)
HebiStatusCode hebiCommandGetIoPinInt(HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number, int64_t *value)
Constant offset to the velocity PID output outside of the deadzone; it is added when the error is pos...
Definition: hebi.h:220
HebiStatusCode hebiCommandGetLedColor(HebiCommandPtr cmd, HebiCommandLedField field, uint8_t *r, uint8_t *g, uint8_t *b)
void hebiRobotModelElementRelease(HebiRobotModelElementPtr element)
Frees resources created by this element.
HebiJointType
Definition: hebi.h:290
HebiInfoStringField
Definition: hebi.h:253
Integral PID gain for effort.
Definition: hebi.h:63
Derivative PID gain for position.
Definition: hebi.h:38
Bus voltage that the module is running at (in Volts).
Definition: hebi.h:132
Proportional PID gain for velocity.
Definition: hebi.h:214
HebiStatusCode hebiGroupSetCommandLifetime(HebiGroupPtr group, int32_t lifetime_ms)
Sets the command lifetime for the group, in milliseconds.
Gets the family for this module.
Definition: hebi.h:256
HebiInfoHighResAngleField
Definition: hebi.h:242
HebiStatusCode hebiCommandGetString(HebiCommandPtr cmd, HebiCommandStringField field, char *buffer, size_t *length)
HebiGroupPtr hebiGroupCreateFromNames(HebiLookupPtr lookup, const char *const *families, size_t num_families, const char *const *names, size_t num_names, int32_t timeout_ms)
Create a group with modules matching the given names and families.
double hebiTrajectoryGetDuration(HebiTrajectoryPtr trajectory)
Returns the length of this trajectory (in seconds).
void hebiTrajectoryRelease(HebiTrajectoryPtr trajectory)
Frees resources created by this trajectory.
HebiRobotModelElementPtr hebiRobotModelElementCreateRigidBody(const double *com, const double *inertia, double mass, size_t num_outputs, const double *outputs)
Creates a rigid body defining static transforms to the given outputs.
HebiStatusCode hebiGroupSendFeedbackRequest(HebiGroupPtr group)
Requests feedback from the group.
HebiInfoFlagField
Definition: hebi.h:259
HebiLookupEntryListPtr hebiCreateLookupEntryList(HebiLookupPtr lookup)
Return a snapshot of the contents of the module registry – i.e., which modules have been found by th...
void hebiCommandSetHighResAngle(HebiCommandPtr cmd, HebiCommandHighResAngleField field, const int64_t *int_part, const float *dec_part)
Constant offset to the effort PID output outside of the deadzone; it is added when the error is posit...
Definition: hebi.h:68
Minimum allowed value for input to the PID controller.
Definition: hebi.h:234
void hebiGroupInfoRelease(HebiGroupInfoPtr info)
Frees resources created by the GroupInfo object.
Minimum allowed value for input to the PID controller.
Definition: hebi.h:221
HebiStatusCode hebiGroupSendCommandWithAcknowledgement(HebiGroupPtr group, HebiGroupCommandPtr command, int32_t timeout_ms)
Sends a command to the given group, requesting an acknowledgement of transmission to be sent back...
struct _HebiRobotModel * HebiRobotModelPtr
Definition: hebi.h:375
HebiInfoBoolField
Definition: hebi.h:247
HebiInfoLedField
Definition: hebi.h:268
HebiStatusCode hebiGroupInfoWriteGains(HebiGroupInfoPtr info, const char *file)
Export gains from a GroupInfo object into a file.
HebiGroupInfoPtr hebiGroupInfoCreate(size_t size)
Creates a GroupInfo for a group with the specified number of modules.
HebiCommandPtr hebiGroupCommandGetModuleCommand(HebiGroupCommandPtr cmd, size_t module_index)
Get an individual command for a particular module at index module_index.
An invalid argument was supplied to the routine (e.g. null pointer)
Definition: hebi.h:22
HebiCommandFloatField
Definition: hebi.h:32
HebiFeedbackUInt64Field
Definition: hebi.h:155
HebiCommandStringField
Definition: hebi.h:95
How the position, velocity, and effort PID loops are connected in order to control motor PWM...
Definition: hebi.h:265
HebiStatusCode hebiGetLibraryVersion(int32_t *major, int32_t *minor, int32_t *revision)
Get the version of the library.
HebiFeedbackPtr hebiGroupFeedbackGetModuleFeedback(HebiGroupFeedbackPtr fbk, size_t module_index)
Get an individual feedback for a particular module at index module_index.
Current supplied to the motor.
Definition: hebi.h:140
HebiCommandNumberedFloatField
Definition: hebi.h:85
Set the internal encoder reference offset so that the current position matches the given reference co...
Definition: hebi.h:76
I/O pin bank c (pins 1-8 available)
Definition: hebi.h:186
HebiStatusCode hebiFeedbackGetFloat(HebiFeedbackPtr fbk, HebiFeedbackFloatField field, float *value)
HebiIKPtr hebiIKCreate(void)
Creates an IK (inverse kinematics) object that allows for solving for joint angles/positions given ob...
HebiStatusCode hebiLookupEntryListGetFamily(HebiLookupEntryListPtr lookup_list, size_t index, char *buffer, size_t *length)
The estimated temperature of the motor windings.
Definition: hebi.h:143
Timestamp of when message was transmitted to module (local)
Definition: hebi.h:159
int32_t hebiCommandHasLedModuleControl(HebiCommandPtr cmd, HebiCommandLedField field)
HebiStatusCode hebiCommandGetFloat(HebiCommandPtr cmd, HebiCommandFloatField field, float *value)
HebiGroupPtr hebiGroupCreateFromFamily(HebiLookupPtr lookup, const char *family, int32_t timeout_ms)
Create a group with all modules known to the lookup with the given family.
HebiCommandFlagField
Definition: hebi.h:100
Proportional PID gain for effort.
Definition: hebi.h:227
HebiStatusCode hebiGroupCommandReadGains(HebiGroupCommandPtr cmd, const char *file)
Import gains from a file into a GroupCommand object.
Maximum allowed value for input to the PID controller.
Definition: hebi.h:222
HebiStatusCode hebiFeedbackGetEnum(HebiFeedbackPtr, HebiFeedbackEnumField, int32_t *)
HebiStatusCode hebiIKSolve(HebiIKPtr ik, HebiRobotModelPtr model, const double *initial_positions, double *ik_solution, void *result_info)
Solves for an inverse kinematics solution that moves the end effector to a given point.
struct _HebiRobotModelElement * HebiRobotModelElementPtr
Definition: hebi.h:381
Maximum allowed value for input to the PID controller.
Definition: hebi.h:44
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:250
HebiInfoFloatField
Definition: hebi.h:199
Maximum allowed value for input to the PID controller.
Definition: hebi.h:235
HebiStatusCode hebiIKAddObjectiveEndEffectorPosition(HebiIKPtr ik, float weight, size_t end_effector_index, double x, double y, double z)
Add an objective that optimizes for the end effector output frame origin to be at the given (x...
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:54
void hebiLogFileRelease(HebiLogFilePtr log_file)
Releases a log file instance.
Proportional PID gain for position.
Definition: hebi.h:36
Maximum allowed value for input to the PID controller.
Definition: hebi.h:209
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:47
void hebiCommandSetFloat(HebiCommandPtr cmd, HebiCommandFloatField field, const float *value)
void hebiCommandSetNumberedFloat(HebiCommandPtr cmd, HebiCommandNumberedFloatField field, size_t number, const float *value)
HebiStatusCode hebiRobotModelAdd(HebiRobotModelPtr robot_model, HebiRobotModelElementPtr existing_element, size_t output_index, HebiRobotModelElementPtr new_element, int32_t combine)
Add an element to a parent element connected to a robot model object.
HebiLookupPtr hebiLookupCreate(void)
Create a Lookup instance.
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
Definition: hebi.h:45
void hebiGroupCommandRelease(HebiGroupCommandPtr cmd)
Frees resources created by the GroupCommand object.
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
Definition: hebi.h:48
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:224
Constant offset to the velocity PID output outside of the deadzone; it is added when the error is pos...
Definition: hebi.h:55
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:231
Feed forward term for position (this term is multiplied by the target and added to the output)...
Definition: hebi.h:204
Maximum allowed value for input to the PID controller.
Definition: hebi.h:57
Success; no failures occurred.
Definition: hebi.h:21
HebiStatusCode hebiRobotModelSetBaseFrame(HebiRobotModelPtr robot_model, const double *transform)
Sets the fixed transform from the origin to the input of the first added model element.
The estimated current in the motor windings.
Definition: hebi.h:142
Timestamp of when message was transmitted from module (remote)
Definition: hebi.h:161
HebiStatusCode hebiFeedbackGetQuaternionf(HebiFeedbackPtr fbk, HebiFeedbackQuaternionfField field, HebiQuaternionf *value)
HebiStatusCode hebiLogFileGetNextFeedback(HebiLogFilePtr log_file, HebiGroupFeedbackPtr field)
Retrieve the next group feedback from the opened log file.
Derivative PID gain for effort.
Definition: hebi.h:64
The temperature from a sensor near the motor housing.
Definition: hebi.h:141
HebiStatusCode hebiStringGetString(HebiStringPtr str, char *buffer, size_t *length)
Copy the string into a buffer.
HebiInfoEnumField
Definition: hebi.h:263
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:92
Integral PID gain for effort.
Definition: hebi.h:228
struct _HebiFeedback * HebiFeedbackPtr
The C-style&#39;s API representation of feedback.
Definition: hebi.h:322
HebiStatusCode hebiCommandGetEnum(HebiCommandPtr cmd, HebiCommandEnumField field, int32_t *value)
void hebiCommandSetEnum(HebiCommandPtr cmd, HebiCommandEnumField field, const int32_t *value)
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement." When the setpoints have step inputs or are noisy, setting this to false can eliminate corresponding spikes or noise in the output.
Definition: hebi.h:249
Feed forward term for effort (this term is multiplied by the target and added to the output)...
Definition: hebi.h:65
struct _HebiCommand * HebiCommandPtr
The C-style&#39;s API representation of a command.
Definition: hebi.h:315
void hebiCommandSetIoPinInt(HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number, const int64_t *value)
Integral PID gain for velocity.
Definition: hebi.h:215
Integral PID gain for velocity.
Definition: hebi.h:50
HebiStatusCode hebiFeedbackGetHighResAngle(HebiFeedbackPtr fbk, HebiFeedbackHighResAngleField field, int64_t *int_part, float *dec_part)
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:219
Position of the module output (post-spring), in radians.
Definition: hebi.h:81
HebiStatusCode hebiInfoGetString(HebiInfoPtr info, HebiInfoStringField field, char *buffer, size_t *length)
HebiStatusCode hebiInfoGetBool(HebiInfoPtr info, HebiInfoBoolField field, int32_t *value)
Temperature of the processor chip, in degrees Celsius.
Definition: hebi.h:131
Output from the PID controller is limited to a maximum of this value.
Definition: hebi.h:212
struct _HebiTrajectory * HebiTrajectoryPtr
The C-style&#39;s API representation of a trajectory.
Definition: hebi.h:411
struct _HebiLogFile * HebiLogFilePtr
The C-style&#39;s API representation of a log file.
Definition: hebi.h:388
I/O pin bank d (pins 1-8 available)
Definition: hebi.h:116
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:211
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:41
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages)...
Definition: hebi.h:35
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:213
HebiStatusCode hebiLookupEntryListGetMacAddress(HebiLookupEntryListPtr lookup_list, size_t index, HebiMacAddress *mac_address)
void hebiCommandSetIoPinFloat(HebiCommandPtr cmd, HebiCommandIoPinBank field, size_t pin_number, const float *value)
HebiCommandEnumField
Definition: hebi.h:107
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:40
HebiGroupPtr hebiGroupCreateFromMacs(HebiLookupPtr lookup, const HebiMacAddress *const *addresses, size_t num_addresses, int32_t timeout_ms)
Create a group of modules with the given MAC addresses.
size_t hebiGroupFeedbackGetSize(HebiGroupFeedbackPtr fbk)
Return the number of modules in this group Feedback.
void hebiRobotModelRelease(HebiRobotModelPtr robot_model)
Frees resources created by this robot model object.
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
Definition: hebi.h:71
Commanded velocity of the module output (post-spring), in radians/second.
Definition: hebi.h:135
void(* GroupFeedbackHandlerFunction)(HebiGroupFeedbackPtr fbk, void *user_data)
Group feedback handling function signature.
Definition: hebi.h:416
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:187
void hebiCommandSetString(HebiCommandPtr cmd, HebiCommandStringField field, const char *buffer, const size_t *length)
HebiStatusCode hebiFeedbackGetIoPinFloat(HebiFeedbackPtr fbk, HebiFeedbackIoPinBank field, size_t pin_number, float *value)
Minimum allowed value for input to the PID controller.
Definition: hebi.h:43
HebiInfoPtr hebiGroupInfoGetModuleInfo(HebiGroupInfoPtr info, size_t module_index)
Get an individual info for a particular module at index module_index.
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:205
struct _HebiInfo * HebiInfoPtr
The C-style&#39;s API representation of a group.
Definition: hebi.h:362
void hebiGroupFeedbackRelease(HebiGroupFeedbackPtr fbk)
Frees resources created by the GroupFeedback object.
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:218
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
Definition: hebi.h:236
HebiStatusCode hebiFeedbackGetNumberedFloat(HebiFeedbackPtr fbk, HebiFeedbackNumberedFloatField field, size_t number, float *value)
int32_t hebiGroupGetCommandLifetime(HebiGroupPtr group)
Returns the current command lifetime, in milliseconds.
struct _HebiVector3f HebiVector3f
Error values within +/- this value from zero are treated as zero (in terms of computed proportional o...
Definition: hebi.h:66
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:120
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:91
Velocity (in radians/second) of the difference between the pre-spring and post-spring output position...
Definition: hebi.h:138
HebiStatusCode hebiRobotModelGetBaseFrame(HebiRobotModelPtr robot_model, double *transform)
Retreives the fixed transform from the origin to the input of the first added model element...
HebiStatusCode hebiIKAddConstraintJointAngles(HebiIKPtr ik, double weight, size_t num_joints, const double *min_positions, const double *max_positions)
Define joint angle constraints.
HebiCommandBoolField
Definition: hebi.h:89
A simple lowpass filter applied to the target set point; needs to be between 0 and 1...
Definition: hebi.h:58
HebiGroupPtr hebiGroupCreateImitation(size_t size)
Creates an "imitation" group with the specified number of modules.
Maximum allowed value for input to the PID controller.
Definition: hebi.h:70
HebiStatusCode hebiInfoGetEnum(HebiInfoPtr info, HebiInfoEnumField field, int32_t *value)
size_t hebiRobotModelGetNumberOfFrames(HebiRobotModelPtr robot_model, HebiFrameType frame_type)
Return the number of frames in the forward kinematic tree of the robot model.
HebiStatusCode hebiGroupRegisterFeedbackHandler(HebiGroupPtr group, GroupFeedbackHandlerFunction handler, void *user_data)
Add a function that is called whenever feedback is returned from the group.
Describes how the temperature inside the module is limiting the output of the motor.
Definition: hebi.h:175
void hebiGroupClearFeedbackHandlers(HebiGroupPtr group)
Removes all feedback handling functions from the queue to be called on receipt of group feedback...
EIGEN_DEVICE_FUNC const Scalar & b
Gets the name for this module.
Definition: hebi.h:255
Timestamp of when message was received by module (remote)
Definition: hebi.h:160
Maximum allowed value for the output of the integral component of the PID loop; the integrated error ...
Definition: hebi.h:232
I/O pin bank a (pins 1-8 available)
Definition: hebi.h:184
struct _HebiString * HebiStringPtr
The C-style&#39;s API representation of a string.
Definition: hebi.h:308
Feed forward term for velocity (this term is multiplied by the target and added to the output)...
Definition: hebi.h:52
HebiStatusCode hebiInfoGetLedColor(HebiInfoPtr info, HebiInfoLedField field, uint8_t *r, uint8_t *g, uint8_t *b)
HebiFeedbackIoPinBank
Definition: hebi.h:182
Indicates if the module should save the current values of all of its settings.
Definition: hebi.h:102
struct _HebiGroupCommand * HebiGroupCommandPtr
The C-style&#39;s API representation of a group command.
Definition: hebi.h:338
Position of the module output (post-spring), in radians.
Definition: hebi.h:148
Software-controlled bounds on the allowable effort of the module.
Definition: hebi.h:179
void hebiCleanup(void)
Frees all resources created by the library. Note: any calls to the HEBI library functions after this ...
void hebiLookupEntryListRelease(HebiLookupEntryListPtr lookup_list)
Release resources for a given lookup entry list; list should not be used after this call...
Constant offset to the position PID output outside of the deadzone; it is added when the error is pos...
Definition: hebi.h:207
Output from the PID controller is limited to a minimum of this value.
Definition: hebi.h:46
HebiStatusCode hebiCommandGetHighResAngle(HebiCommandPtr cmd, HebiCommandHighResAngleField field, int64_t *int_part, float *dec_part)
void hebiIKClearAll(HebiIKPtr ik)
Clears the objectives and constraints from this IK object, along with any modifications to the defaul...
Constant offset to the position PID output outside of the deadzone; it is added when the error is pos...
Definition: hebi.h:42
I/O pin bank c (pins 1-8 available)
Definition: hebi.h:115
HebiStatusCode
Definition: hebi.h:19
I/O pin bank a (pins 1-8 available)
Definition: hebi.h:113
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
Definition: hebi.h:74
void hebiLookupRelease(HebiLookupPtr lookup)
Frees resources created by the lookup object.
Commanded effort at the module output; units vary (e.g., N * m for rotational joints and N for linear...
Definition: hebi.h:136
Velocity of the module output (post-spring), in radians/second.
Definition: hebi.h:133
I/O pin bank e (pins 1-8 available)
Definition: hebi.h:117
Minimum allowed value for input to the PID controller.
Definition: hebi.h:69


hebiros
Author(s): Xavier Artache , Matthew Tesch
autogenerated on Thu Sep 3 2020 04:08:14