52 #ifndef DOXYGEN_OMIT_INTERNAL 54 #endif // DOXYGEN_OMIT_INTERNAL 55 explicit operator bool()
const;
74 void set(
float value);
92 #ifndef DOXYGEN_OMIT_INTERNAL 94 #endif // DOXYGEN_OMIT_INTERNAL 95 explicit operator bool()
const;
127 void get(int64_t* revolutions,
float* radian_offset)
const;
132 void set(
double radians);
139 void set(int64_t revolutions,
float radian_offset);
155 #ifndef DOXYGEN_OMIT_INTERNAL 157 #endif // DOXYGEN_OMIT_INTERNAL 158 bool has(
size_t fieldNumber)
const;
169 float get(
size_t fieldNumber)
const;
175 void set(
size_t fieldNumber,
float value);
181 void clear(
size_t fieldNumber);
194 #ifndef DOXYGEN_OMIT_INTERNAL 196 #endif // DOXYGEN_OMIT_INTERNAL 203 void set(
bool value);
218 #ifndef DOXYGEN_OMIT_INTERNAL 220 #endif // DOXYGEN_OMIT_INTERNAL 221 explicit operator bool()
const;
238 std::string
get()
const;
240 void set(
const std::string& value);
255 #ifndef DOXYGEN_OMIT_INTERNAL 257 #endif // DOXYGEN_OMIT_INTERNAL 258 explicit operator bool()
const;
286 template <
typename T>
290 #ifndef DOXYGEN_OMIT_INTERNAL 293 #endif // DOXYGEN_OMIT_INTERNAL 294 explicit operator bool()
const {
return has(); }
328 #ifndef DOXYGEN_OMIT_INTERNAL 330 #endif // DOXYGEN_OMIT_INTERNAL 331 bool hasInt(
size_t pinNumber)
const;
342 bool hasFloat(
size_t pinNumber)
const;
348 int64_t getInt(
size_t pinNumber)
const;
355 float getFloat(
size_t pinNumber)
const;
361 void setInt(
size_t pinNumber, int64_t value);
367 void setFloat(
size_t pinNumber,
float value);
372 void clear(
size_t pinNumber);
384 #ifndef DOXYGEN_OMIT_INTERNAL 386 #endif // DOXYGEN_OMIT_INTERNAL 408 void set(
const Color& color);
426 #ifndef DOXYGEN_OMIT_INTERNAL 437 #endif // DOXYGEN_OMIT_INTERNAL 493 #ifndef DOXYGEN_OMIT_INTERNAL 507 #endif // DOXYGEN_OMIT_INTERNAL 572 #ifndef DOXYGEN_OMIT_INTERNAL 581 #endif // DOXYGEN_OMIT_INTERNAL 624 #ifndef DOXYGEN_OMIT_INTERNAL 632 #endif // DOXYGEN_OMIT_INTERNAL 670 #ifndef DOXYGEN_OMIT_INTERNAL 676 #endif // DOXYGEN_OMIT_INTERNAL 706 #ifndef DOXYGEN_OMIT_INTERNAL 711 #endif // DOXYGEN_OMIT_INTERNAL Sets the name for this module. Name must be null-terminated character string for the name; must be <=...
HebiCommandPtr const internal_
FloatField spring_constant_
IoBank & f()
I/O pin bank f (pins 1-8 available)
const CommandGains & velocityGains() const
Controller gains for the velocity PID loop.
FlagField & saveCurrentSettings()
Indicates if the module should save the current values of all of its settings.
HebiCommandBoolField const field_
The spring constant of the module.
IoBank & d()
I/O pin bank d (pins 1-8 available)
const FloatField & velocity() const
Velocity of the module output (post-spring), in radians/second.
HebiCommandPtr const internal_
HebiCommandPtr const internal_
HebiCommandHighResAngleField
const FloatField & effort() const
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages)...
HighResAngleField & positionLimitMax()
The firmware safety limit for the maximum allowed position.
#define HEBI_DISABLE_COPY(Class)
const FloatField & springConstant() const
The spring constant of the module.
CommandGains effort_gains_
HebiCommandIoPinBank const bank_
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
A message field representable by a bool value.
Actuator & actuator()
Actuator-specific commands.
Actuator-specific commands.
HebiCommandPtr const internal_
Io & io()
Any available digital or analog output pins on the device.
Settings & settings()
Module settings that are typically changed at a slower rate.
const StringField & name() const
Sets the name for this module. Name must be null-terminated character string for the name; must be <=...
HebiCommandPtr const internal_
Set the firmware safety limit for the minimum allowed position.
FloatField & springConstant()
The spring constant of the module.
HebiCommandPtr const internal_
FlagField save_current_settings_
A message field for interfacing with a bank of I/O pins.
const Actuator & actuator() const
Actuator-specific commands.
FlagField & stopBoot()
Stop the module from automatically booting into application.
Actuator & actuator()
Actuator-specific settings, such as controller gains.
StringField & family()
Sets the family for this module. Name must be null-terminated character string for the family; must b...
Command objects have various fields that can be set; when sent to the module, these fields control in...
~Command() noexcept
Cleans up command object as necessary.
IoBank & a()
I/O pin bank a (pins 1-8 available)
A message field representable by a std::string.
Command(HebiCommandPtr)
Wraps an existing C-style object that is managed by its parent. NOTE: this should not be used except ...
I/O pin bank b (pins 1-8 available)
const HighResAngleField & positionLimitMin() const
The firmware safety limit for the minimum allowed position.
A combination of the position, velocity, and effort loops with P feeding to T and V feeding to PWM; d...
A message field for interfacing with an LED.
HebiCommandNumberedFloatField const field_
HebiCommandPtr const internal_
Actuator(HebiCommandPtr internal)
FloatField reference_effort_
CommandGains position_gains_
The motor is not given power (equivalent to a 0 PWM value)
HebiCommandHighResAngleField const field_
bool has() const
True if (and only if) the field has a value.
CommandGains & effortGains()
Controller gains for the effort PID loop.
#define HEBI_DISABLE_COPY_MOVE(Class)
CommandGains velocity_gains_
HebiCommandPtr const internal_
IoBank & c()
I/O pin bank c (pins 1-8 available)
HebiCommandFloatField const field_
HighResAngleField & position()
Position of the module output (post-spring), in radians.
CommandGains & velocityGains()
Controller gains for the velocity PID loop.
HebiCommandPtr const internal_
Velocity of the module output (post-spring), in radians/second.
Actuator-specific settings, such as controller gains.
const Io & io() const
Any available digital or analog output pins on the device.
FlagField & reset()
Restart the module.
Module settings that are typically changed at a slower rate.
FloatField & referencePosition()
The internal encoder reference offset (setting this matches the current position to the given referen...
A combination of the position, velocity, and effort loops with P and V feeding to T; documented on do...
A two-state message field (either set/true or cleared/false).
const FloatField & referenceEffort() const
The internal effort reference offset (setting this matches the current effort to the given reference ...
const IoBank & e() const
I/O pin bank e (pins 1-8 available)
IoBank & b()
I/O pin bank b (pins 1-8 available)
A message field containing a numbered set of single-precision floating point values.
HebiCommandFlagField const field_
const Settings & settings() const
Module settings that are typically changed at a slower rate.
const IoBank & c() const
I/O pin bank c (pins 1-8 available)
HebiCommandPtr const internal_
const IoBank & b() const
I/O pin bank b (pins 1-8 available)
HebiCommandPtr const internal_
HebiCommandNumberedFloatField
Set the internal encoder reference offset so that the current position matches the given reference co...
HighResAngleField position_limit_max_
EnumField< ControlStrategy > & controlStrategy()
How the position, velocity, and effort PID loops are connected in order to control motor PWM...
HighResAngleField & positionLimitMin()
The firmware safety limit for the minimum allowed position.
HebiCommandLedField const field_
FloatField & velocity()
Velocity of the module output (post-spring), in radians/second.
HebiCommandPtr const internal_
Any available digital or analog output pins on the device.
EnumField< ControlStrategy > control_strategy_
const IoBank & d() const
I/O pin bank d (pins 1-8 available)
FloatField & referenceEffort()
The internal effort reference offset (setting this matches the current effort to the given reference ...
ROSCPP_DECL bool has(const std::string &key)
const FloatField & referencePosition() const
The internal encoder reference offset (setting this matches the current position to the given referen...
void clear()
Removes any currently set value for this field.
Actuator(HebiCommandPtr internal)
A combination of the position, velocity, and effort loops with P, V, and T feeding to PWM; documented...
IoBank & e()
I/O pin bank e (pins 1-8 available)
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
HighResAngleField position_
HighResAngleField position_limit_min_
A message field for an angle measurement which does not lose precision at very high angles...
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.
FlagField & boot()
Boot the module from bootloader into application.
HebiStatusCode hebiCommandGetEnum(HebiCommandPtr cmd, HebiCommandEnumField field, int32_t *value)
void hebiCommandSetEnum(HebiCommandPtr cmd, HebiCommandEnumField field, const int32_t *value)
const CommandGains & positionGains() const
Controller gains for the position PID loop.
NumberedFloatField & debug()
Values for internal debug functions (channel 1-9 available).
struct _HebiCommand * HebiCommandPtr
The C-style's API representation of a command.
HebiCommandEnumField const field_
Position of the module output (post-spring), in radians.
NumberedFloatField debug_
I/O pin bank d (pins 1-8 available)
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages)...
StringField & name()
Sets the name for this module. Name must be null-terminated character string for the name; must be <=...
HebiCommandStringField const field_
EnumField(HebiCommandPtr internal, HebiCommandEnumField field)
Settings(HebiCommandPtr internal)
const IoBank & f() const
I/O pin bank f (pins 1-8 available)
const FlagField & saveCurrentSettings() const
Indicates if the module should save the current values of all of its settings.
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.
const IoBank & a() const
I/O pin bank a (pins 1-8 available)
const HighResAngleField & positionLimitMax() const
The firmware safety limit for the maximum allowed position.
const EnumField< ControlStrategy > & controlStrategy() const
How the position, velocity, and effort PID loops are connected in order to control motor PWM...
const Actuator & actuator() const
Actuator-specific settings, such as controller gains.
A direct PWM value (-1 to 1) can be sent to the motor (subject to onboard safety limiting).
const CommandGains & effortGains() const
Controller gains for the effort PID loop.
Structure to describe an RGB color.
CommandGains & positionGains()
Controller gains for the position PID loop.
const StringField & family() const
Sets the family for this module. Name must be null-terminated character string for the family; must b...
A message field representable by a single-precision floating point value.
FloatField reference_position_
const HighResAngleField & position() const
Position of the module output (post-spring), in radians.
HebiCommandPtr const internal_
I/O pin bank c (pins 1-8 available)
I/O pin bank a (pins 1-8 available)
A simple lowpass filter applied to the controller output; needs to be between 0 and 1...
Io(HebiCommandPtr internal)
I/O pin bank e (pins 1-8 available)
A message field representable by an enum of a given type.
FloatField & effort()
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages)...
LedField & led()
The module's LED.