Go to the documentation of this file.
75 #ifndef DOXYGEN_OMIT_INTERNAL
77 #endif // DOXYGEN_OMIT_INTERNAL
78 explicit operator bool()
const {
return has(); }
97 void set(
float value);
114 #ifndef DOXYGEN_OMIT_INTERNAL
116 #endif // DOXYGEN_OMIT_INTERNAL
117 explicit operator bool()
const {
return has(); }
149 void get(int64_t* revolutions,
float* radian_offset)
const;
154 void set(
double radians);
161 void set(int64_t revolutions,
float radian_offset);
175 #ifndef DOXYGEN_OMIT_INTERNAL
177 #endif // DOXYGEN_OMIT_INTERNAL
178 bool has(
size_t fieldNumber)
const;
189 float get(
size_t fieldNumber)
const;
195 void set(
size_t fieldNumber,
float value);
201 void clear(
size_t fieldNumber);
212 #ifndef DOXYGEN_OMIT_INTERNAL
214 #endif // DOXYGEN_OMIT_INTERNAL
221 void set(
bool value);
234 #ifndef DOXYGEN_OMIT_INTERNAL
236 #endif // DOXYGEN_OMIT_INTERNAL
237 explicit operator bool()
const {
return has(); }
254 std::string
get()
const;
256 void set(
const std::string& value);
269 #ifndef DOXYGEN_OMIT_INTERNAL
271 #endif // DOXYGEN_OMIT_INTERNAL
272 explicit operator bool()
const {
return has(); }
302 #ifndef DOXYGEN_OMIT_INTERNAL
304 #endif // DOXYGEN_OMIT_INTERNAL
305 explicit operator bool()
const {
return has(); }
327 return static_cast<T
>(ret);
331 int32_t value =
static_cast<int32_t
>(_value);
348 #ifndef DOXYGEN_OMIT_INTERNAL
350 #endif // DOXYGEN_OMIT_INTERNAL
351 bool hasInt(
size_t pinNumber)
const;
362 bool hasFloat(
size_t pinNumber)
const;
368 int64_t
getInt(
size_t pinNumber)
const;
375 float getFloat(
size_t pinNumber)
const;
381 void setInt(
size_t pinNumber, int64_t value);
387 void setFloat(
size_t pinNumber,
float value);
392 void clear(
size_t pinNumber);
402 #ifndef DOXYGEN_OMIT_INTERNAL
404 #endif // DOXYGEN_OMIT_INTERNAL
442 #ifndef DOXYGEN_OMIT_INTERNAL
451 #endif // DOXYGEN_OMIT_INTERNAL
503 #ifndef DOXYGEN_OMIT_INTERNAL
521 #endif // DOXYGEN_OMIT_INTERNAL
622 #ifndef DOXYGEN_OMIT_INTERNAL
625 #endif // DOXYGEN_OMIT_INTERNAL
645 #ifndef DOXYGEN_OMIT_INTERNAL
653 #endif // DOXYGEN_OMIT_INTERNAL
704 #ifndef DOXYGEN_OMIT_INTERNAL
710 #endif // DOXYGEN_OMIT_INTERNAL
748 #ifndef DOXYGEN_OMIT_INTERNAL
754 #endif // DOXYGEN_OMIT_INTERNAL
780 #ifndef DOXYGEN_OMIT_INTERNAL
785 #endif // DOXYGEN_OMIT_INTERNAL
HebiCommandRef & internal_
FloatField & velocity()
Velocity of the module output (post-spring), in radians/second.
Imu(HebiCommandRef &internal)
FloatField & velocityLimitMax()
The firmware safety limit for the maximum allowed velocity.
bool has() const
True if (and only if) the field has a value.
const CommandGains & positionGains() const
Controller gains for the position PID loop.
@ HebiCommandFloatEffortLimitMin
The firmware safety limit for the maximum allowed velocity.
@ HebiCommandBoolPositionDOnError
const StringField & name() const
A message field containing a numbered set of single-precision floating point values.
void clear()
Removes any currently set value for this field.
void set(double radians)
Sets the field to a given double value (in radians). Note that double precision floating point number...
void set(T _value)
Sets the field to a given value.
FloatField & effortLimitMin()
The firmware safety limit for the minimum allowed effort.
const HebiCommandNumberedFloatField field_
@ HebiCommandFloatPositionKp
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages).
StringField(HebiCommandPtr internal, HebiCommandStringField field)
Command & operator=(Command &&other)=delete
const Actuator & actuator() const
Actuator-specific commands.
const FloatField & effortLimitMax() const
The firmware safety limit for the maximum allowed effort.
FloatField effort_limit_min_
HighResAngleField & position()
Position of the module output (post-spring), in radians.
FlagField & stopBoot()
Stop the module from automatically booting into application.
void clear()
Removes any currently set value for this field.
const HighResAngleField & position() const
Position of the module output (post-spring), in radians.
@ HebiCommandIoBankC
I/O pin bank b (pins 1-8 available)
Settings(HebiCommandPtr internal_ptr, HebiCommandRef &internal)
Structure to describe an RGB color.
const HebiCommandHighResAngleField field_
@ DirectPWM
A direct PWM value (-1 to 1) can be sent to the motor (subject to onboard safety limiting).
BoolField accel_includes_gravity_
FloatField & referencePosition()
const FloatField & springConstant() const
The spring constant of the module.
FlagField & boot()
Boot the module from bootloader into application.
const BoolField & accelIncludesGravity() const
Whether to include acceleration due to gravity in acceleration feedback.
@ HebiCommandIoBankD
I/O pin bank c (pins 1-8 available)
@ HebiCommandBoolVelocityDOnError
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
const HebiCommandFlagField field_
const EnumField< ControlStrategy > & controlStrategy() const
How the position, velocity, and effort PID loops are connected in order to control motor PWM.
const FlagField & clearLog() const
Clears the log message on the module.
HebiCommandFloatField
Command Enums.
Actuator-specific settings, such as controller gains.
@ HebiCommandIoBankF
I/O pin bank e (pins 1-8 available)
EnumField< MstopStrategy > mstop_strategy_
FloatField & effortLimitMax()
The firmware safety limit for the maximum allowed effort.
const EnumField< MstopStrategy > & mstopStrategy() const
The motion stop strategy for the actuator.
@ HebiCommandStringFamily
The name for this module. The string must be null-terminated and less than 21 characters.
A message field representable by an enum of a given type.
Actuator(HebiCommandRef &internal)
@ HebiCommandFlagSaveCurrentSettings
A message field representable by a bool value.
T get() const
If the field has a value, returns that value; otherwise, returns a default.
const HebiCommandBoolField field_
const IoBank & f() const
I/O pin bank f (pins 1-8 available)
const CommandGains & velocityGains() const
Controller gains for the velocity PID loop.
HebiCommandRef & internal_
FlagField & saveCurrentSettings()
Indicates if the module should save the current values of all of its settings.
EnumField< PositionLimitStrategy > max_position_limit_strategy_
void set(size_t fieldNumber, float value)
Sets the particular numbered subvalue of this field to a given value.
@ MotorOff
Triggering the M-Stop results in the control strategy being set to 'off'. Remains 'off' until changed...
@ HebiCommandBoolAccelIncludesGravity
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
const FlagField & stopBoot() const
Stop the module from automatically booting into application.
Settings & settings()
Module settings that are typically changed at a slower rate.
void clear()
Removes any currently set value for this field, so that the module maintains its previous state of LE...
#define HEBI_DISABLE_COPY(Class)
std::string get() const
If the field has a value, returns a copy of that value; otherwise, returns a default.
const Settings & settings() const
Module settings that are typically changed at a slower rate.
void clear()
Removes any currently set value for this field.
CommandGains position_gains_
const StringField & appendLog() const
Appends to the current log message on the module.
@ HoldPosition
Exceeding the position limit results in the actuator holding the position. Needs to be manually set t...
EnumField< ControlStrategy > & controlStrategy()
How the position, velocity, and effort PID loops are connected in order to control motor PWM.
const HebiCommandRef & internal_
A message field for an angle measurement which does not lose precision at very high angles.
bool hasInt(size_t pinNumber) const
True if (and only if) the particular numbered pin in this bank has an integer (e.g....
NumberedFloatField(HebiCommandRef &internal, HebiCommandNumberedFloatField field)
Io(HebiCommandRef &internal)
FloatField reference_effort_
Actuator-specific commands.
const HebiCommandStringField field_
EnumField< PositionLimitStrategy > & maxPositionLimitStrategy()
The position limit strategy (at the maximum position) for the actuator.
HebiCommandNumberedFloatField
HebiCommandRef & internal_
void set(bool value)
Sets the field to a given value.
CommandGains & velocityGains()
Controller gains for the velocity PID loop.
const EnumField< PositionLimitStrategy > & minPositionLimitStrategy() const
The position limit strategy (at the minimum position) for the actuator.
HebiCommandRef internal_ref_
const FloatField & effortLimitMin() const
The firmware safety limit for the minimum allowed effort.
const HebiCommandIoPinBank bank_
bool has() const
True if (and only if) the field has a value.
const IoBank & e() const
I/O pin bank e (pins 1-8 available)
HebiCommandRef & internal_
FloatField & effort()
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages).
EnumField< PositionLimitStrategy > & minPositionLimitStrategy()
The position limit strategy (at the minimum position) for the actuator.
const HebiCommandFloatField field_
HebiCommandRef & internal_
const IoBank & b() const
I/O pin bank b (pins 1-8 available)
FloatField & velocityLimitMin()
The firmware safety limit for the minimum allowed velocity.
#define HEBI_DISABLE_COPY_MOVE(Class)
FlagField save_current_settings_
void hebiCommandSetEnum(HebiCommandRef &command, HebiCommandEnumField field, const int32_t *value)
HighResAngleField & positionLimitMin()
The firmware safety limit for the minimum allowed position.
bool has() const
True if (and only if) the field has a value.
@ HebiCommandHighResAnglePositionLimitMax
The firmware safety limit for the minimum allowed position.
EnumField< MstopStrategy > & mstopStrategy()
The motion stop strategy for the actuator.
@ HebiCommandEnumControlStrategy
@ HebiCommandFloatVelocity
@ MotorOff
Exceeding the position limit results in the control strategy being set to 'off'. Remains 'off' until ...
Actuator(HebiCommandRef &internal)
HighResAngleField(HebiCommandRef &internal, HebiCommandHighResAngleField field)
const Io & io() const
Any available digital or analog output pins on the device.
void clear(size_t fieldNumber)
Removes any currently set value for the numbered subvalue of this field.
NumberedFloatField & debug()
Values for internal debug functions (channel 1-9 available).
A message field for interfacing with an LED.
const FloatField & effort() const
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages).
const LedField & led() const
The module's LED.
HighResAngleField position_limit_max_
struct HebiCommand_ * HebiCommandPtr
Typedefs.
const FloatField & velocity() const
Velocity of the module output (post-spring), in radians/second.
const HebiCommandEnumField field_
@ HebiCommandEnumMaxPositionLimitStrategy
The position limit strategy (at the minimum position) for the actuator.
bool has() const
True if (and only if) the field has a value.
bool get() const
If the field has a value, returns that value; otherwise, returns false.
double get() const
If the field has a value, returns that value as a double; otherwise, returns a default.
NumberedFloatField debug_
const NumberedFloatField & debug() const
Values for internal debug functions (channel 1-9 available).
FlagField & reset()
Restart the module.
@ Off
The motor is not given power (equivalent to a 0 PWM value)
IoBank & c()
I/O pin bank c (pins 1-8 available)
@ HebiCommandHighResAnglePositionLimitMin
Position of the module output (post-spring).
void clear()
Clears this flag (e.g., sets it to false/off).
HebiCommandRef & internal_
const FloatField & velocityLimitMax() const
The firmware safety limit for the maximum allowed velocity.
HighResAngleField position_limit_min_
const IoBank & a() const
I/O pin bank a (pins 1-8 available)
Any available digital or analog output pins on the device.
void setFloat(size_t pinNumber, float value)
Sets the particular pin to a floating point value (representing a PWM output).
A message field for interfacing with a bank of I/O pins.
CommandGains velocity_gains_
void set(float value)
Sets the field to a given value.
HighResAngleField & positionLimitMax()
The firmware safety limit for the maximum allowed position.
int64_t getInt(size_t pinNumber) const
If this numbered pin in this bank has an integer (e.g., digital) value, returns that value; otherwise...
const IoBank & c() const
I/O pin bank c (pins 1-8 available)
Color get() const
Returns the current LED command.
@ HoldPosition
Triggering the M-Stop results in the motor holding the motor position. Operations resume to normal on...
const EnumField< PositionLimitStrategy > & maxPositionLimitStrategy() const
The position limit strategy (at the maximum position) for the actuator.
EnumField< PositionLimitStrategy > min_position_limit_strategy_
CommandGains effort_gains_
bool has() const
True if (and only if) the field has a value.
HebiCommandHighResAngleField
FlagField & clearLog()
Clears the log message on the module.
FlagField(HebiCommandRef &internal, HebiCommandFlagField field)
const FlagField & boot() const
Boot the module from bootloader into application.
A two-state message field (either set/true or cleared/false).
@ HebiCommandFloatEffort
Velocity of the module output (post-spring).
Command objects have various fields that can be set; when sent to the module, these fields control in...
const FlagField & reset() const
Restart the module.
IoBank & d()
I/O pin bank d (pins 1-8 available)
const HighResAngleField & positionLimitMax() const
The firmware safety limit for the maximum allowed position.
void clear()
Removes any currently set value for this field.
const FloatField & referenceEffort() const
The internal effort reference offset (setting this matches the current effort to the given reference ...
FloatField spring_constant_
Io & io()
Any available digital or analog output pins on the device.
const FloatField & referencePosition() const
HebiCommandRef & internal_
FloatField(HebiCommandRef &internal, HebiCommandFloatField field)
void clear(size_t pinNumber)
Removes any currently set value for this pin.
FloatField effort_limit_max_
void setInt(size_t pinNumber, int64_t value)
Sets the particular pin to a integer value (representing a digital output).
Imu & imu()
IMU-specific settings.
FloatField velocity_limit_max_
LedField & led()
The module's LED.
@ HebiCommandHighResAnglePosition
bool has(size_t fieldNumber) const
True if (and only if) the particular numbered subvalue of this field has a value.
IoBank & b()
I/O pin bank b (pins 1-8 available)
@ HebiCommandIoBankB
I/O pin bank a (pins 1-8 available)
const Imu & imu() const
IMU-specific settings.
Command(HebiCommandPtr)
Wraps an existing C-style object that is managed by its parent. NOTE: this should not be used except ...
const HebiCommandLedField field_
BoolField(HebiCommandRef &internal, HebiCommandBoolField field)
HebiStatusCode enumGetter(const RefT &ref, MetadataT &metadata, int field, int32_t *value)
float get() const
If the field has a value, returns that value; otherwise, returns a default.
StringField & appendLog()
Appends to the current log message on the module.
HighResAngleField position_
const IoBank & d() const
I/O pin bank d (pins 1-8 available)
IoBank(HebiCommandRef &internal, HebiCommandIoPinBank bank)
FloatField & referenceEffort()
The internal effort reference offset (setting this matches the current effort to the given reference ...
FloatField velocity_limit_min_
float get(size_t fieldNumber) const
If the particular numbered subvalue of this field has a value, returns that value; otherwise returns ...
@ HebiCommandFloatReferenceEffort
Set the internal encoder reference offset so that the current position matches the given reference co...
A message field representable by a std::string.
float getFloat(size_t pinNumber) const
If this numbered pin in this bank has an floating point (e.g., analog or PWM) value,...
bool has() const
Returns true if the LED command has been set, and false otherwise.
IoBank & e()
I/O pin bank e (pins 1-8 available)
IoBank & a()
I/O pin bank a (pins 1-8 available)
EnumField< ControlStrategy > control_strategy_
@ HebiCommandEnumMstopStrategy
How the position, velocity, and effort PID loops are connected in order to control motor PWM.
const FlagField & saveCurrentSettings() const
Indicates if the module should save the current values of all of its settings.
@ HebiCommandFloatReferencePosition
The spring constant of the module.
@ HebiCommandEnumMinPositionLimitStrategy
The motion stop strategy for the actuator.
const CommandGains & effortGains() const
Controller gains for the effort PID loop.
HebiCommandRef & internal_
@ HebiCommandFloatSpringConstant
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
@ Disabled
Triggering the M-Stop has no effect.
void set(const std::string &value)
Sets the field to a given value.
const StringField & family() const
Actuator & actuator()
Actuator-specific commands.
HebiCommandRef & internal_
@ HebiCommandFloatEffortKp
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
Module settings that are typically changed at a slower rate.
EnumField(HebiCommandRef &internal, HebiCommandEnumField field)
bool has() const
Returns true if the flag is set, false if it is cleared.
@ DampedSpring
Exceeding the position limit results in a virtual spring that pushes the actuator back to within the ...
FloatField reference_position_
IoBank & f()
I/O pin bank f (pins 1-8 available)
@ HebiCommandFloatVelocityKp
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
const HighResAngleField & positionLimitMin() const
The firmware safety limit for the minimum allowed position.
void clear()
Removes any currently set value for this field.
FloatField & springConstant()
The spring constant of the module.
@ Disabled
Exceeding the position limit has no effect.
bool hasFloat(size_t pinNumber) const
True if (and only if) the particular numbered pin in this bank has an floating point (e....
Actuator & actuator()
Actuator-specific settings, such as controller gains.
void set()
Sets this flag.
const FloatField & velocityLimitMin() const
The firmware safety limit for the minimum allowed velocity.
CommandGains & positionGains()
Controller gains for the position PID loop.
const HebiCommandPtr internal_
void set(const Color &color)
Commands a color that overrides the module's control of the LED (if the alpha channel is 255),...
A message field representable by a single-precision floating point value.
@ HebiCommandIoBankE
I/O pin bank d (pins 1-8 available)
CommandGains & effortGains()
Controller gains for the effort PID loop.
@ HebiCommandFloatVelocityLimitMax
The firmware safety limit for the minimum allowed velocity.
@ HebiCommandBoolEffortDOnError
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
@ HebiCommandFloatVelocityLimitMin
Set the internal effort reference offset so that the current effort matches the given reference comma...
LedField(HebiCommandRef &internal, HebiCommandLedField field)
@ HebiCommandFloatEffortLimitMax
The firmware safety limit for the minimum allowed effort.
const HebiCommandRef & internal_
HebiCommandRef & internal_
BoolField & accelIncludesGravity()
Whether to include acceleration due to gravity in acceleration feedback.
const Actuator & actuator() const
Actuator-specific settings, such as controller gains.
hebi_cpp_api_ros
Author(s): Chris Bollinger
, Matthew Tesch
autogenerated on Fri Aug 2 2024 08:35:18