command.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include "hebi.h"
4 
5 #include <string>
6 
7 #include "color.hpp"
8 #include "gains.hpp"
9 #include "message_helpers.hpp"
10 #include "util.hpp"
11 
12 namespace hebi {
13 
33 class Command final {
34 public:
35  enum class ControlStrategy {
37  Off,
39  DirectPWM,
42  Strategy2,
45  Strategy3,
48  Strategy4,
49  };
50 
51  enum class MstopStrategy {
53  Disabled,
55  MotorOff,
58  };
59 
60  enum class PositionLimitStrategy {
66  MotorOff,
68  Disabled,
69  };
70 
71 protected:
73  class FloatField final {
74  public:
75 #ifndef DOXYGEN_OMIT_INTERNAL
77 #endif // DOXYGEN_OMIT_INTERNAL
78  explicit operator bool() const { return has(); }
92  bool has() const;
95  float get() const;
97  void set(float value);
99  void clear();
100 
102  private:
105  };
106 
112  class HighResAngleField final {
113  public:
114 #ifndef DOXYGEN_OMIT_INTERNAL
116 #endif // DOXYGEN_OMIT_INTERNAL
117  explicit operator bool() const { return has(); }
131  bool has() const;
137  double get() const;
149  void get(int64_t* revolutions, float* radian_offset) const;
154  void set(double radians);
161  void set(int64_t revolutions, float radian_offset);
163  void clear();
164 
166  private:
169  };
170 
173  class NumberedFloatField final {
174  public:
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);
202 
204  private:
207  };
208 
210  class BoolField final {
211  public:
212 #ifndef DOXYGEN_OMIT_INTERNAL
214 #endif // DOXYGEN_OMIT_INTERNAL
215  bool has() const;
219  bool get() const;
221  void set(bool value);
223  void clear();
224 
226  private:
229  };
230 
232  class StringField final {
233  public:
234 #ifndef DOXYGEN_OMIT_INTERNAL
236 #endif // DOXYGEN_OMIT_INTERNAL
237  explicit operator bool() const { return has(); }
251  bool has() const;
254  std::string get() const;
256  void set(const std::string& value);
258  void clear();
259 
261  private:
264  };
265 
267  class FlagField final {
268  public:
269 #ifndef DOXYGEN_OMIT_INTERNAL
271 #endif // DOXYGEN_OMIT_INTERNAL
272  explicit operator bool() const { return has(); }
286  bool has() const;
288  void set();
290  void clear();
291 
293  private:
296  };
297 
299  template<typename T>
300  class EnumField final {
301  public:
302 #ifndef DOXYGEN_OMIT_INTERNAL
303  EnumField(HebiCommandRef& internal, HebiCommandEnumField field) : internal_(internal), field_(field) {}
304 #endif // DOXYGEN_OMIT_INTERNAL
305  explicit operator bool() const { return has(); }
319  bool has() const {
320  return enumGetter(internal_, field_, nullptr) == HebiStatusSuccess;
321  }
324  T get() const {
325  int32_t ret{};
326  enumGetter(internal_, field_, &ret);
327  return static_cast<T>(ret);
328  }
330  void set(T _value) {
331  int32_t value = static_cast<int32_t>(_value);
333  }
335  void clear() {
337  }
338 
340  private:
343  };
344 
346  class IoBank final {
347  public:
348 #ifndef DOXYGEN_OMIT_INTERNAL
349  IoBank(HebiCommandRef& internal, HebiCommandIoPinBank bank);
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);
393 
395  private:
398  };
400  class LedField final {
401  public:
402 #ifndef DOXYGEN_OMIT_INTERNAL
403  LedField(HebiCommandRef& internal, HebiCommandLedField field);
404 #endif // DOXYGEN_OMIT_INTERNAL
405  bool has() const;
420  Color get() const;
426  void set(const Color& color);
431  void clear();
432 
434  private:
437  };
438 
440  class Io final {
441  public:
442 #ifndef DOXYGEN_OMIT_INTERNAL
443  Io(HebiCommandRef& internal)
444  : internal_(internal),
445  a_(internal, HebiCommandIoBankA),
446  b_(internal, HebiCommandIoBankB),
447  c_(internal, HebiCommandIoBankC),
448  d_(internal, HebiCommandIoBankD),
449  e_(internal, HebiCommandIoBankE),
450  f_(internal, HebiCommandIoBankF) {}
451 #endif // DOXYGEN_OMIT_INTERNAL
452 
453  // With all submessage and field getters: Note that the returned reference
454  // should not be used after the lifetime of this parent.
455 
456  // Subfields ----------------
457 
459  IoBank& a() { return a_; }
461  const IoBank& a() const { return a_; }
463  IoBank& b() { return b_; }
465  const IoBank& b() const { return b_; }
467  IoBank& c() { return c_; }
469  const IoBank& c() const { return c_; }
471  IoBank& d() { return d_; }
473  const IoBank& d() const { return d_; }
475  IoBank& e() { return e_; }
477  const IoBank& e() const { return e_; }
479  IoBank& f() { return f_; }
481  const IoBank& f() const { return f_; }
482 
484  private:
486 
493  };
494 
496 
498  class Settings final {
499  protected:
501  class Actuator final {
502  public:
503 #ifndef DOXYGEN_OMIT_INTERNAL
521 #endif // DOXYGEN_OMIT_INTERNAL
522 
523  // With all submessage and field getters: Note that the returned reference
524  // should not be used after the lifetime of this parent.
525 
526  // Submessages ----------------
527 
531  const CommandGains& positionGains() const { return position_gains_; }
535  const CommandGains& velocityGains() const { return velocity_gains_; }
539  const CommandGains& effortGains() const { return effort_gains_; }
540 
541  // Subfields ----------------
542 
546  const FloatField& springConstant() const { return spring_constant_; }
556  const FloatField& referenceEffort() const { return reference_effort_; }
568  const FloatField& effortLimitMin() const { return effort_limit_min_; }
572  const FloatField& effortLimitMax() const { return effort_limit_max_; }
597 
599  private:
603 
617  };
618 
620  class Imu final {
621  public:
622 #ifndef DOXYGEN_OMIT_INTERNAL
623  Imu(HebiCommandRef& internal)
625 #endif // DOXYGEN_OMIT_INTERNAL
626 
627  // With all submessage and field getters: Note that the returned reference
628  // should not be used after the lifetime of this parent.
629 
630  // Subfields ----------------
631 
636 
638  private:
640 
642  };
643 
644  public:
645 #ifndef DOXYGEN_OMIT_INTERNAL
646  Settings(HebiCommandPtr internal_ptr, HebiCommandRef& internal)
647  : internal_(internal),
648  actuator_(internal),
649  imu_(internal),
650  name_(internal_ptr, HebiCommandStringName),
651  family_(internal_ptr, HebiCommandStringFamily),
653 #endif // DOXYGEN_OMIT_INTERNAL
654 
655  // With all submessage and field getters: Note that the returned reference
656  // should not be used after the lifetime of this parent.
657 
658  // Submessages ----------------
659 
661  Actuator& actuator() { return actuator_; }
663  const Actuator& actuator() const { return actuator_; }
665  Imu& imu() { return imu_; }
667  const Imu& imu() const { return imu_; }
668 
669  // Subfields ----------------
670 
673  StringField& name() { return name_; }
676  const StringField& name() const { return name_; }
679  StringField& family() { return family_; }
682  const StringField& family() const { return family_; }
687 
689 
690  private:
692 
695 
699  };
700 
702  class Actuator final {
703  public:
704 #ifndef DOXYGEN_OMIT_INTERNAL
706  : internal_(internal),
708  effort_(internal, HebiCommandFloatEffort),
710 #endif // DOXYGEN_OMIT_INTERNAL
711 
712  // With all submessage and field getters: Note that the returned reference
713  // should not be used after the lifetime of this parent.
714 
715  // Subfields ----------------
716 
720  const FloatField& velocity() const { return velocity_; }
722  FloatField& effort() { return effort_; }
724  const FloatField& effort() const { return effort_; }
728  const HighResAngleField& position() const { return position_; }
729 
731  private:
733 
737  };
738 
739 private:
746 
747 public:
748 #ifndef DOXYGEN_OMIT_INTERNAL
749 
754 #endif // DOXYGEN_OMIT_INTERNAL
755 
758  Command(Command&& other);
759 
760  // With all submessage and field getters: Note that the returned reference
761  // should not be used after the lifetime of this parent.
762 
763  // Submessages -------------------------------------------------------------
764 
766  Io& io() { return io_; }
768  const Io& io() const { return io_; }
770  Settings& settings() { return settings_; }
772  const Settings& settings() const { return settings_; }
774  Actuator& actuator() { return actuator_; }
776  const Actuator& actuator() const { return actuator_; }
777 
778  // Subfields -------------------------------------------------------------
779 
780 #ifndef DOXYGEN_OMIT_INTERNAL
781  NumberedFloatField& debug() { return debug_; }
784  const NumberedFloatField& debug() const { return debug_; }
785 #endif // DOXYGEN_OMIT_INTERNAL
786  StringField& appendLog() { return append_log_; }
789  const StringField& appendLog() const { return append_log_; }
791  FlagField& reset() { return reset_; }
793  const FlagField& reset() const { return reset_; }
795  FlagField& boot() { return boot_; }
797  const FlagField& boot() const { return boot_; }
801  const FlagField& stopBoot() const { return stop_boot_; }
805  const FlagField& clearLog() const { return clear_log_; }
807  LedField& led() { return led_; }
809  const LedField& led() const { return led_; }
810 
815 
816  /* Disable move assigment operator. */
817  Command& operator=(Command&& other) = delete;
818 
819 private:
823 
831 };
832 
833 } // namespace hebi
hebi::Command::LedField::internal_
HebiCommandRef & internal_
Definition: command.hpp:435
hebi::Command::Actuator::velocity
FloatField & velocity()
Velocity of the module output (post-spring), in radians/second.
Definition: command.hpp:718
hebi::Command::Settings::Imu::Imu
Imu(HebiCommandRef &internal)
Definition: command.hpp:623
hebi::Command::Settings::Actuator::velocityLimitMax
FloatField & velocityLimitMax()
The firmware safety limit for the maximum allowed velocity.
Definition: command.hpp:562
hebi::Command::StringField::has
bool has() const
True if (and only if) the field has a value.
Definition: command.cpp:113
hebi::Command::Settings::Actuator::positionGains
const CommandGains & positionGains() const
Controller gains for the position PID loop.
Definition: command.hpp:531
hebi::Command::Settings::Imu
IMU-specific settings.
Definition: command.hpp:620
HebiCommandFloatEffortLimitMin
@ HebiCommandFloatEffortLimitMin
The firmware safety limit for the maximum allowed velocity.
Definition: hebi.h:102
HebiCommandBoolPositionDOnError
@ HebiCommandBoolPositionDOnError
Definition: hebi.h:117
hebi::Command::Settings::name
const StringField & name() const
Definition: command.hpp:676
hebi::Command::internal_
HebiCommandPtr internal_
Definition: command.hpp:744
hebi::Command::NumberedFloatField
A message field containing a numbered set of single-precision floating point values.
Definition: command.hpp:173
hebi::Command::HighResAngleField::clear
void clear()
Removes any currently set value for this field.
Definition: command.cpp:67
hebi::Command::HighResAngleField::set
void set(double radians)
Sets the field to a given double value (in radians). Note that double precision floating point number...
Definition: command.cpp:52
hebi::Command::EnumField::set
void set(T _value)
Sets the field to a given value.
Definition: command.hpp:330
hebi::Command::Settings::Actuator::effortLimitMin
FloatField & effortLimitMin()
The firmware safety limit for the minimum allowed effort.
Definition: command.hpp:566
hebi::Command::NumberedFloatField::field_
const HebiCommandNumberedFloatField field_
Definition: command.hpp:206
HebiCommandFloatPositionKp
@ HebiCommandFloatPositionKp
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages).
Definition: hebi.h:58
hebi::Command::StringField::StringField
StringField(HebiCommandPtr internal, HebiCommandStringField field)
Definition: command.cpp:110
hebi::Command::operator=
Command & operator=(Command &&other)=delete
hebi::Command::actuator
const Actuator & actuator() const
Actuator-specific commands.
Definition: command.hpp:776
hebi::Command::Settings::Actuator::effortLimitMax
const FloatField & effortLimitMax() const
The firmware safety limit for the maximum allowed effort.
Definition: command.hpp:572
hebi::Command::Settings::Actuator::effort_limit_min_
FloatField effort_limit_min_
Definition: command.hpp:609
hebi::Command::Actuator::position
HighResAngleField & position()
Position of the module output (post-spring), in radians.
Definition: command.hpp:726
hebi::Command::stopBoot
FlagField & stopBoot()
Stop the module from automatically booting into application.
Definition: command.hpp:799
hebi::Command::EnumField::clear
void clear()
Removes any currently set value for this field.
Definition: command.hpp:335
hebi::Command::Actuator::position
const HighResAngleField & position() const
Position of the module output (post-spring), in radians.
Definition: command.hpp:728
HebiCommandLedField
HebiCommandLedField
Definition: hebi.h:153
HebiCommandIoBankC
@ HebiCommandIoBankC
I/O pin bank b (pins 1-8 available)
Definition: hebi.h:147
hebi::Command::Settings::Settings
Settings(HebiCommandPtr internal_ptr, HebiCommandRef &internal)
Definition: command.hpp:646
hebi::Color
Structure to describe an RGB color.
Definition: color.hpp:8
hebi::Command::HighResAngleField::field_
const HebiCommandHighResAngleField field_
Definition: command.hpp:168
hebi::Command::ControlStrategy::DirectPWM
@ DirectPWM
A direct PWM value (-1 to 1) can be sent to the motor (subject to onboard safety limiting).
hebi::Command::Settings::Imu::accel_includes_gravity_
BoolField accel_includes_gravity_
Definition: command.hpp:641
HebiStatusSuccess
@ HebiStatusSuccess
Definition: hebi.h:24
hebi::Command::Actuator::effort_
FloatField effort_
Definition: command.hpp:735
hebi::Command::Settings::Actuator::referencePosition
FloatField & referencePosition()
Definition: command.hpp:549
hebi::Command::Settings::Actuator::springConstant
const FloatField & springConstant() const
The spring constant of the module.
Definition: command.hpp:546
hebi::Command::boot
FlagField & boot()
Boot the module from bootloader into application.
Definition: command.hpp:795
hebi::Command::Settings::Imu::accelIncludesGravity
const BoolField & accelIncludesGravity() const
Whether to include acceleration due to gravity in acceleration feedback.
Definition: command.hpp:635
HebiCommandIoBankD
@ HebiCommandIoBankD
I/O pin bank c (pins 1-8 available)
Definition: hebi.h:148
HebiCommandBoolVelocityDOnError
@ HebiCommandBoolVelocityDOnError
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
Definition: hebi.h:118
hebi::Command::FlagField::field_
const HebiCommandFlagField field_
Definition: command.hpp:295
hebi::Command::Settings::Actuator::controlStrategy
const EnumField< ControlStrategy > & controlStrategy() const
How the position, velocity, and effort PID loops are connected in order to control motor PWM.
Definition: command.hpp:584
hebi::Command::clearLog
const FlagField & clearLog() const
Clears the log message on the module.
Definition: command.hpp:805
HebiCommandFloatField
HebiCommandFloatField
Command Enums.
Definition: hebi.h:55
hebi::Command::Settings::Actuator
Actuator-specific settings, such as controller gains.
Definition: command.hpp:501
HebiCommandIoBankF
@ HebiCommandIoBankF
I/O pin bank e (pins 1-8 available)
Definition: hebi.h:150
hebi::Command::Settings::Actuator::mstop_strategy_
EnumField< MstopStrategy > mstop_strategy_
Definition: command.hpp:614
hebi::Command::Settings::Actuator::effortLimitMax
FloatField & effortLimitMax()
The firmware safety limit for the maximum allowed effort.
Definition: command.hpp:570
hebi::Command::Settings::Actuator::mstopStrategy
const EnumField< MstopStrategy > & mstopStrategy() const
The motion stop strategy for the actuator.
Definition: command.hpp:588
HebiCommandStringFamily
@ HebiCommandStringFamily
The name for this module. The string must be null-terminated and less than 21 characters.
Definition: hebi.h:125
hebi::Command::boot_
FlagField boot_
Definition: command.hpp:827
hebi::Command::EnumField
A message field representable by an enum of a given type.
Definition: command.hpp:300
hebi::Command::Io::e_
IoBank e_
Definition: command.hpp:491
hebi::Command::Settings::actuator_
Actuator actuator_
Definition: command.hpp:693
hebi::Command::Settings::Actuator::Actuator
Actuator(HebiCommandRef &internal)
Definition: command.hpp:504
HebiCommandFlagSaveCurrentSettings
@ HebiCommandFlagSaveCurrentSettings
Definition: hebi.h:130
hebi::Command::BoolField
A message field representable by a bool value.
Definition: command.hpp:210
hebi::Command::EnumField::get
T get() const
If the field has a value, returns that value; otherwise, returns a default.
Definition: command.hpp:324
hebi::Command::BoolField::field_
const HebiCommandBoolField field_
Definition: command.hpp:228
hebi::Command::Io::f
const IoBank & f() const
I/O pin bank f (pins 1-8 available)
Definition: command.hpp:481
hebi::Command::Settings::Actuator::velocityGains
const CommandGains & velocityGains() const
Controller gains for the velocity PID loop.
Definition: command.hpp:535
hebi::Command::Settings::family_
StringField family_
Definition: command.hpp:697
hebi::Command::Actuator::velocity_
FloatField velocity_
Definition: command.hpp:734
hebi::Command::NumberedFloatField::internal_
HebiCommandRef & internal_
Definition: command.hpp:205
hebi::Command::Settings::saveCurrentSettings
FlagField & saveCurrentSettings()
Indicates if the module should save the current values of all of its settings.
Definition: command.hpp:684
hebi::Command::Settings::Actuator::max_position_limit_strategy_
EnumField< PositionLimitStrategy > max_position_limit_strategy_
Definition: command.hpp:616
hebi::Command::NumberedFloatField::set
void set(size_t fieldNumber, float value)
Sets the particular numbered subvalue of this field to a given value.
Definition: command.cpp:84
hebi::Command::MstopStrategy::MotorOff
@ MotorOff
Triggering the M-Stop results in the control strategy being set to 'off'. Remains 'off' until changed...
HebiCommandBoolAccelIncludesGravity
@ HebiCommandBoolAccelIncludesGravity
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
Definition: hebi.h:120
hebi::Command::stopBoot
const FlagField & stopBoot() const
Stop the module from automatically booting into application.
Definition: command.hpp:801
hebi::Command::settings
Settings & settings()
Module settings that are typically changed at a slower rate.
Definition: command.hpp:770
hebi::Command::LedField::clear
void clear()
Removes any currently set value for this field, so that the module maintains its previous state of LE...
Definition: command.cpp:204
HEBI_DISABLE_COPY
#define HEBI_DISABLE_COPY(Class)
Definition: util.hpp:16
hebi::Command::StringField::get
std::string get() const
If the field has a value, returns a copy of that value; otherwise, returns a default.
Definition: command.cpp:117
hebi::Command::settings
const Settings & settings() const
Module settings that are typically changed at a slower rate.
Definition: command.hpp:772
hebi::Command::StringField::clear
void clear()
Removes any currently set value for this field.
Definition: command.cpp:137
hebi::Command::Settings::Actuator::position_gains_
CommandGains position_gains_
Definition: command.hpp:600
hebi::Command::appendLog
const StringField & appendLog() const
Appends to the current log message on the module.
Definition: command.hpp:789
hebi::Command::PositionLimitStrategy::HoldPosition
@ HoldPosition
Exceeding the position limit results in the actuator holding the position. Needs to be manually set t...
hebi::Command::Settings::Actuator::controlStrategy
EnumField< ControlStrategy > & controlStrategy()
How the position, velocity, and effort PID loops are connected in order to control motor PWM.
Definition: command.hpp:582
hebi::Command::Actuator::internal_
const HebiCommandRef & internal_
Definition: command.hpp:732
hebi::Command::HighResAngleField
A message field for an angle measurement which does not lose precision at very high angles.
Definition: command.hpp:112
hebi::Command::IoBank::hasInt
bool hasInt(size_t pinNumber) const
True if (and only if) the particular numbered pin in this bank has an integer (e.g....
Definition: command.cpp:150
hebi::Command::NumberedFloatField::NumberedFloatField
NumberedFloatField(HebiCommandRef &internal, HebiCommandNumberedFloatField field)
Definition: command.cpp:69
hebi::Command::Io::Io
Io(HebiCommandRef &internal)
Definition: command.hpp:443
hebi::Command::Settings::Actuator::reference_effort_
FloatField reference_effort_
Definition: command.hpp:606
hebi::Command::Actuator
Actuator-specific commands.
Definition: command.hpp:702
hebi::Command::StringField::field_
const HebiCommandStringField field_
Definition: command.hpp:263
hebi::Command::Settings::Actuator::maxPositionLimitStrategy
EnumField< PositionLimitStrategy > & maxPositionLimitStrategy()
The position limit strategy (at the maximum position) for the actuator.
Definition: command.hpp:594
hebi::Command::Settings::name
StringField & name()
Definition: command.hpp:673
HebiCommandNumberedFloatField
HebiCommandNumberedFloatField
Definition: hebi.h:112
hebi::Command::Io::internal_
HebiCommandRef & internal_
Definition: command.hpp:485
hebi::Command::ControlStrategy
ControlStrategy
Definition: command.hpp:35
hebi::Command::BoolField::set
void set(bool value)
Sets the field to a given value.
Definition: command.cpp:103
hebi::Command::Settings::Actuator::velocityGains
CommandGains & velocityGains()
Controller gains for the velocity PID loop.
Definition: command.hpp:533
hebi::Command::Settings::Actuator::minPositionLimitStrategy
const EnumField< PositionLimitStrategy > & minPositionLimitStrategy() const
The position limit strategy (at the minimum position) for the actuator.
Definition: command.hpp:592
hebi::Command::internal_ref_
HebiCommandRef internal_ref_
Definition: command.hpp:745
hebi::Command::Settings::Actuator::effortLimitMin
const FloatField & effortLimitMin() const
The firmware safety limit for the minimum allowed effort.
Definition: command.hpp:568
hebi::Command::IoBank::bank_
const HebiCommandIoPinBank bank_
Definition: command.hpp:397
hebi::Command::HighResAngleField::has
bool has() const
True if (and only if) the field has a value.
Definition: command.cpp:32
hebi::Command::Io::e
const IoBank & e() const
I/O pin bank e (pins 1-8 available)
Definition: command.hpp:477
hebi::Command::BoolField::internal_
HebiCommandRef & internal_
Definition: command.hpp:227
hebi::Command::Actuator::effort
FloatField & effort()
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages).
Definition: command.hpp:722
hebi::Command::Settings::Actuator::minPositionLimitStrategy
EnumField< PositionLimitStrategy > & minPositionLimitStrategy()
The position limit strategy (at the minimum position) for the actuator.
Definition: command.hpp:590
hebi::Command::FloatField::field_
const HebiCommandFloatField field_
Definition: command.hpp:104
hebi::Command::EnumField::internal_
HebiCommandRef & internal_
Definition: command.hpp:341
hebi::Command::Io::b
const IoBank & b() const
I/O pin bank b (pins 1-8 available)
Definition: command.hpp:465
hebi::Command::Settings::Actuator::velocityLimitMin
FloatField & velocityLimitMin()
The firmware safety limit for the minimum allowed velocity.
Definition: command.hpp:558
HEBI_DISABLE_COPY_MOVE
#define HEBI_DISABLE_COPY_MOVE(Class)
Definition: util.hpp:6
hebi::Command::Settings::save_current_settings_
FlagField save_current_settings_
Definition: command.hpp:698
hebi::hebiCommandSetEnum
void hebiCommandSetEnum(HebiCommandRef &command, HebiCommandEnumField field, const int32_t *value)
Definition: message_helpers.cpp:388
hebi::Command::Io::b_
IoBank b_
Definition: command.hpp:488
hebi::Command::Settings::Actuator::positionLimitMin
HighResAngleField & positionLimitMin()
The firmware safety limit for the minimum allowed position.
Definition: command.hpp:574
hebi::Command::EnumField::has
bool has() const
True if (and only if) the field has a value.
Definition: command.hpp:319
HebiCommandHighResAnglePositionLimitMax
@ HebiCommandHighResAnglePositionLimitMax
The firmware safety limit for the minimum allowed position.
Definition: hebi.h:109
hebi::Command::Settings::Actuator::mstopStrategy
EnumField< MstopStrategy > & mstopStrategy()
The motion stop strategy for the actuator.
Definition: command.hpp:586
HebiCommandEnumControlStrategy
@ HebiCommandEnumControlStrategy
Definition: hebi.h:138
HebiCommandFloatVelocity
@ HebiCommandFloatVelocity
Definition: hebi.h:56
hebi::Command::PositionLimitStrategy::MotorOff
@ MotorOff
Exceeding the position limit results in the control strategy being set to 'off'. Remains 'off' until ...
hebi::Command::PositionLimitStrategy
PositionLimitStrategy
Definition: command.hpp:60
HebiCommandFlagField
HebiCommandFlagField
Definition: hebi.h:129
hebi::Command::Actuator::Actuator
Actuator(HebiCommandRef &internal)
Definition: command.hpp:705
hebi::Command::HighResAngleField::HighResAngleField
HighResAngleField(HebiCommandRef &internal, HebiCommandHighResAngleField field)
Definition: command.cpp:29
hebi::Command::ControlStrategy::Strategy2
@ Strategy2
hebi::Command::clear_log_
FlagField clear_log_
Definition: command.hpp:829
hebi::Command::io
const Io & io() const
Any available digital or analog output pins on the device.
Definition: command.hpp:768
hebi::Command::NumberedFloatField::clear
void clear(size_t fieldNumber)
Removes any currently set value for the numbered subvalue of this field.
Definition: command.cpp:88
hebi::Command::debug
NumberedFloatField & debug()
Values for internal debug functions (channel 1-9 available).
Definition: command.hpp:782
hebi::Command::LedField
A message field for interfacing with an LED.
Definition: command.hpp:400
hebi::Command::Actuator::effort
const FloatField & effort() const
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages).
Definition: command.hpp:724
hebi::Command::led
const LedField & led() const
The module's LED.
Definition: command.hpp:809
hebi::Command::Settings::Actuator::position_limit_max_
HighResAngleField position_limit_max_
Definition: command.hpp:612
HebiCommandPtr
struct HebiCommand_ * HebiCommandPtr
Typedefs.
Definition: hebi.h:444
hebi::Command::Actuator::velocity
const FloatField & velocity() const
Velocity of the module output (post-spring), in radians/second.
Definition: command.hpp:720
hebi::Command::EnumField::field_
const HebiCommandEnumField field_
Definition: command.hpp:342
hebi::Command::ControlStrategy::Strategy3
@ Strategy3
gains.hpp
HebiCommandEnumMaxPositionLimitStrategy
@ HebiCommandEnumMaxPositionLimitStrategy
The position limit strategy (at the minimum position) for the actuator.
Definition: hebi.h:141
hebi::Command::BoolField::has
bool has() const
True if (and only if) the field has a value.
Definition: command.cpp:95
hebi::Command::BoolField::get
bool get() const
If the field has a value, returns that value; otherwise, returns false.
Definition: command.cpp:97
hebi::Gains< HebiCommandRef, FloatField, BoolField, HebiCommandFloatField, HebiCommandBoolField >
hebi::Command::HighResAngleField::get
double get() const
If the field has a value, returns that value as a double; otherwise, returns a default.
Definition: command.cpp:36
hebi::Command::debug_
NumberedFloatField debug_
Definition: command.hpp:824
hebi::Command::debug
const NumberedFloatField & debug() const
Values for internal debug functions (channel 1-9 available).
Definition: command.hpp:784
hebi::Command::reset
FlagField & reset()
Restart the module.
Definition: command.hpp:791
hebi::Command::ControlStrategy::Off
@ Off
The motor is not given power (equivalent to a 0 PWM value)
hebi::Command::Io::c
IoBank & c()
I/O pin bank c (pins 1-8 available)
Definition: command.hpp:467
HebiCommandHighResAnglePositionLimitMin
@ HebiCommandHighResAnglePositionLimitMin
Position of the module output (post-spring).
Definition: hebi.h:108
hebi::Command::FlagField::clear
void clear()
Clears this flag (e.g., sets it to false/off).
Definition: command.cpp:146
hebi::Command::IoBank::internal_
HebiCommandRef & internal_
Definition: command.hpp:396
HebiCommandEnumField
HebiCommandEnumField
Definition: hebi.h:137
hebi::Command::Settings::family
StringField & family()
Definition: command.hpp:679
hebi::Command::Settings::Actuator::velocityLimitMax
const FloatField & velocityLimitMax() const
The firmware safety limit for the maximum allowed velocity.
Definition: command.hpp:564
hebi::Command::actuator_
Actuator actuator_
Definition: command.hpp:822
hebi::Command::Settings::Actuator::position_limit_min_
HighResAngleField position_limit_min_
Definition: command.hpp:611
hebi::Command::Io::a
const IoBank & a() const
I/O pin bank a (pins 1-8 available)
Definition: command.hpp:461
hebi::Command::Io
Any available digital or analog output pins on the device.
Definition: command.hpp:440
hebi::Command::IoBank::setFloat
void setFloat(size_t pinNumber, float value)
Sets the particular pin to a floating point value (representing a PWM output).
Definition: command.cpp:174
hebi::Command::IoBank
A message field for interfacing with a bank of I/O pins.
Definition: command.hpp:346
hebi::Command::Settings::Actuator::velocity_gains_
CommandGains velocity_gains_
Definition: command.hpp:601
hebi::Command::FloatField::set
void set(float value)
Sets the field to a given value.
Definition: command.cpp:25
hebi::Command::Settings::imu_
Imu imu_
Definition: command.hpp:694
hebi::Command::Settings::Actuator::positionLimitMax
HighResAngleField & positionLimitMax()
The firmware safety limit for the maximum allowed position.
Definition: command.hpp:578
hebi::Command::IoBank::getInt
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...
Definition: command.cpp:158
hebi::Command::Io::c
const IoBank & c() const
I/O pin bank c (pins 1-8 available)
Definition: command.hpp:469
hebi::Command::LedField::get
Color get() const
Returns the current LED command.
Definition: command.cpp:189
HebiCommandIoBankA
@ HebiCommandIoBankA
Definition: hebi.h:145
hebi
Definition: arm.cpp:5
hebi::Command::MstopStrategy::HoldPosition
@ HoldPosition
Triggering the M-Stop results in the motor holding the motor position. Operations resume to normal on...
hebi::Command::Settings::Actuator::maxPositionLimitStrategy
const EnumField< PositionLimitStrategy > & maxPositionLimitStrategy() const
The position limit strategy (at the maximum position) for the actuator.
Definition: command.hpp:596
hebi::Command::Settings::Actuator::min_position_limit_strategy_
EnumField< PositionLimitStrategy > min_position_limit_strategy_
Definition: command.hpp:615
hebi::Command::Settings::Actuator::effort_gains_
CommandGains effort_gains_
Definition: command.hpp:602
hebi::Command::FloatField::has
bool has() const
True if (and only if) the field has a value.
Definition: command.cpp:15
HebiCommandHighResAngleField
HebiCommandHighResAngleField
Definition: hebi.h:106
hebi::Command::clearLog
FlagField & clearLog()
Clears the log message on the module.
Definition: command.hpp:803
hebi::Command::FlagField::FlagField
FlagField(HebiCommandRef &internal, HebiCommandFlagField field)
Definition: command.cpp:139
hebi::Command::boot
const FlagField & boot() const
Boot the module from bootloader into application.
Definition: command.hpp:797
HebiCommandBoolField
HebiCommandBoolField
Definition: hebi.h:116
hebi::Command::io_
Io io_
Definition: command.hpp:820
hebi::Command::FlagField
A two-state message field (either set/true or cleared/false).
Definition: command.hpp:267
HebiCommandFloatEffort
@ HebiCommandFloatEffort
Velocity of the module output (post-spring).
Definition: hebi.h:57
hebi::Command
Command objects have various fields that can be set; when sent to the module, these fields control in...
Definition: command.hpp:33
hebi::Command::reset
const FlagField & reset() const
Restart the module.
Definition: command.hpp:793
hebi::Command::Io::d
IoBank & d()
I/O pin bank d (pins 1-8 available)
Definition: command.hpp:471
hebi::Command::Settings::Actuator::positionLimitMax
const HighResAngleField & positionLimitMax() const
The firmware safety limit for the maximum allowed position.
Definition: command.hpp:580
hebi::Command::settings_
Settings settings_
Definition: command.hpp:821
hebi::Command::BoolField::clear
void clear()
Removes any currently set value for this field.
Definition: command.cpp:108
hebi::Command::Settings::Actuator::referenceEffort
const FloatField & referenceEffort() const
The internal effort reference offset (setting this matches the current effort to the given reference ...
Definition: command.hpp:556
hebi::Command::Settings::Actuator::spring_constant_
FloatField spring_constant_
Definition: command.hpp:604
hebi::Command::io
Io & io()
Any available digital or analog output pins on the device.
Definition: command.hpp:766
HebiCommandStringField
HebiCommandStringField
Definition: hebi.h:123
HebiCommandIoPinBank
HebiCommandIoPinBank
Definition: hebi.h:144
hebi::Command::Settings::Actuator::referencePosition
const FloatField & referencePosition() const
Definition: command.hpp:552
hebi::Command::HighResAngleField::internal_
HebiCommandRef & internal_
Definition: command.hpp:167
hebi::Command::FloatField::FloatField
FloatField(HebiCommandRef &internal, HebiCommandFloatField field)
Definition: command.cpp:12
hebi::Command::IoBank::clear
void clear(size_t pinNumber)
Removes any currently set value for this pin.
Definition: command.cpp:178
color.hpp
hebi::Command::Settings::Actuator::effort_limit_max_
FloatField effort_limit_max_
Definition: command.hpp:610
hebi::Command::IoBank::setInt
void setInt(size_t pinNumber, int64_t value)
Sets the particular pin to a integer value (representing a digital output).
Definition: command.cpp:170
HebiCommandStringName
@ HebiCommandStringName
Definition: hebi.h:124
hebi::Command::ControlStrategy::Strategy4
@ Strategy4
hebi::Command::Settings::imu
Imu & imu()
IMU-specific settings.
Definition: command.hpp:665
hebi::Command::append_log_
StringField append_log_
Definition: command.hpp:825
hebi::Command::Settings::Actuator::velocity_limit_max_
FloatField velocity_limit_max_
Definition: command.hpp:608
hebi::Command::led
LedField & led()
The module's LED.
Definition: command.hpp:807
HebiCommandHighResAnglePosition
@ HebiCommandHighResAnglePosition
Definition: hebi.h:107
hebi::Command::led_
LedField led_
Definition: command.hpp:830
hebi::Command::NumberedFloatField::has
bool has(size_t fieldNumber) const
True if (and only if) the particular numbered subvalue of this field has a value.
Definition: command.cpp:72
hebi::Command::Io::b
IoBank & b()
I/O pin bank b (pins 1-8 available)
Definition: command.hpp:463
hebi::Command::Io::f_
IoBank f_
Definition: command.hpp:492
HebiCommandIoBankB
@ HebiCommandIoBankB
I/O pin bank a (pins 1-8 available)
Definition: hebi.h:146
hebi::Command::Settings::imu
const Imu & imu() const
IMU-specific settings.
Definition: command.hpp:667
hebi::Command::Command
Command(HebiCommandPtr)
Wraps an existing C-style object that is managed by its parent. NOTE: this should not be used except ...
Definition: command.cpp:208
hebi::Command::LedField::field_
const HebiCommandLedField field_
Definition: command.hpp:436
hebi::Command::BoolField::BoolField
BoolField(HebiCommandRef &internal, HebiCommandBoolField field)
Definition: command.cpp:92
message_helpers.hpp
hebi::enumGetter
HebiStatusCode enumGetter(const RefT &ref, MetadataT &metadata, int field, int32_t *value)
Definition: message_helpers.cpp:298
hebi::Command::FloatField::get
float get() const
If the field has a value, returns that value; otherwise, returns a default.
Definition: command.cpp:17
hebi::Command::appendLog
StringField & appendLog()
Appends to the current log message on the module.
Definition: command.hpp:787
hebi::Command::Actuator::position_
HighResAngleField position_
Definition: command.hpp:736
hebi::Command::Io::d
const IoBank & d() const
I/O pin bank d (pins 1-8 available)
Definition: command.hpp:473
hebi::Command::IoBank::IoBank
IoBank(HebiCommandRef &internal, HebiCommandIoPinBank bank)
Definition: command.cpp:148
hebi::Command::Settings::Actuator::referenceEffort
FloatField & referenceEffort()
The internal effort reference offset (setting this matches the current effort to the given reference ...
Definition: command.hpp:554
hebi::Command::Settings::Actuator::velocity_limit_min_
FloatField velocity_limit_min_
Definition: command.hpp:607
hebi::Command::NumberedFloatField::get
float get(size_t fieldNumber) const
If the particular numbered subvalue of this field has a value, returns that value; otherwise returns ...
Definition: command.cpp:76
HebiCommandFloatReferenceEffort
@ HebiCommandFloatReferenceEffort
Set the internal encoder reference offset so that the current position matches the given reference co...
Definition: hebi.h:99
hebi::Command::StringField
A message field representable by a std::string.
Definition: command.hpp:232
hebi::Command::IoBank::getFloat
float getFloat(size_t pinNumber) const
If this numbered pin in this bank has an floating point (e.g., analog or PWM) value,...
Definition: command.cpp:164
hebi::Command::Settings::name_
StringField name_
Definition: command.hpp:696
hebi::Command::LedField::has
bool has() const
Returns true if the LED command has been set, and false otherwise.
Definition: command.cpp:185
hebi.h
hebi::Command::Io::e
IoBank & e()
I/O pin bank e (pins 1-8 available)
Definition: command.hpp:475
hebi::Command::Io::a
IoBank & a()
I/O pin bank a (pins 1-8 available)
Definition: command.hpp:459
hebi::Command::Settings::Actuator::control_strategy_
EnumField< ControlStrategy > control_strategy_
Definition: command.hpp:613
HebiCommandEnumMstopStrategy
@ HebiCommandEnumMstopStrategy
How the position, velocity, and effort PID loops are connected in order to control motor PWM.
Definition: hebi.h:139
hebi::Command::Settings::saveCurrentSettings
const FlagField & saveCurrentSettings() const
Indicates if the module should save the current values of all of its settings.
Definition: command.hpp:686
HebiCommandFloatReferencePosition
@ HebiCommandFloatReferencePosition
The spring constant of the module.
Definition: hebi.h:98
hebi::Command::stop_boot_
FlagField stop_boot_
Definition: command.hpp:828
HebiCommandEnumMinPositionLimitStrategy
@ HebiCommandEnumMinPositionLimitStrategy
The motion stop strategy for the actuator.
Definition: hebi.h:140
hebi::Command::Settings::Actuator::effortGains
const CommandGains & effortGains() const
Controller gains for the effort PID loop.
Definition: command.hpp:539
hebi::Command::FloatField::internal_
HebiCommandRef & internal_
Definition: command.hpp:103
HebiCommandFloatSpringConstant
@ HebiCommandFloatSpringConstant
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
Definition: hebi.h:97
hebi::Command::MstopStrategy::Disabled
@ Disabled
Triggering the M-Stop has no effect.
hebi::Command::Io::d_
IoBank d_
Definition: command.hpp:490
hebi::Command::StringField::set
void set(const std::string &value)
Sets the field to a given value.
Definition: command.cpp:131
hebi::Command::Settings::family
const StringField & family() const
Definition: command.hpp:682
hebi::Command::actuator
Actuator & actuator()
Actuator-specific commands.
Definition: command.hpp:774
hebi::Command::Io::a_
IoBank a_
Definition: command.hpp:487
hebi::Command::Settings::internal_
HebiCommandRef & internal_
Definition: command.hpp:691
HebiCommandRef_
Definition: hebi.h:632
HebiCommandFloatEffortKp
@ HebiCommandFloatEffortKp
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
Definition: hebi.h:84
hebi::Command::Settings
Module settings that are typically changed at a slower rate.
Definition: command.hpp:498
hebi::Command::EnumField::EnumField
EnumField(HebiCommandRef &internal, HebiCommandEnumField field)
Definition: command.hpp:303
hebi::Command::Io::c_
IoBank c_
Definition: command.hpp:489
hebi::Command::FlagField::has
bool has() const
Returns true if the flag is set, false if it is cleared.
Definition: command.cpp:142
hebi::Command::reset_
FlagField reset_
Definition: command.hpp:826
hebi::Command::PositionLimitStrategy::DampedSpring
@ DampedSpring
Exceeding the position limit results in a virtual spring that pushes the actuator back to within the ...
hebi::Command::Settings::Actuator::reference_position_
FloatField reference_position_
Definition: command.hpp:605
hebi::Command::Io::f
IoBank & f()
I/O pin bank f (pins 1-8 available)
Definition: command.hpp:479
HebiCommandFloatVelocityKp
@ HebiCommandFloatVelocityKp
A simple lowpass filter applied to the controller output; needs to be between 0 and 1....
Definition: hebi.h:71
hebi::Command::Settings::Actuator::positionLimitMin
const HighResAngleField & positionLimitMin() const
The firmware safety limit for the minimum allowed position.
Definition: command.hpp:576
hebi::Command::FloatField::clear
void clear()
Removes any currently set value for this field.
Definition: command.cpp:27
hebi::Command::Settings::Actuator::springConstant
FloatField & springConstant()
The spring constant of the module.
Definition: command.hpp:544
hebi::Command::PositionLimitStrategy::Disabled
@ Disabled
Exceeding the position limit has no effect.
hebi::Command::IoBank::hasFloat
bool hasFloat(size_t pinNumber) const
True if (and only if) the particular numbered pin in this bank has an floating point (e....
Definition: command.cpp:154
hebi::Command::Settings::actuator
Actuator & actuator()
Actuator-specific settings, such as controller gains.
Definition: command.hpp:661
hebi::Command::FlagField::set
void set()
Sets this flag.
Definition: command.cpp:144
hebi::Command::Settings::Actuator::velocityLimitMin
const FloatField & velocityLimitMin() const
The firmware safety limit for the minimum allowed velocity.
Definition: command.hpp:560
hebi::Command::Settings::Actuator::positionGains
CommandGains & positionGains()
Controller gains for the position PID loop.
Definition: command.hpp:529
hebi::Command::StringField::internal_
const HebiCommandPtr internal_
Definition: command.hpp:262
hebi::Command::LedField::set
void set(const Color &color)
Commands a color that overrides the module's control of the LED (if the alpha channel is 255),...
Definition: command.cpp:200
hebi::Command::FloatField
A message field representable by a single-precision floating point value.
Definition: command.hpp:73
HebiCommandIoBankE
@ HebiCommandIoBankE
I/O pin bank d (pins 1-8 available)
Definition: hebi.h:149
hebi::Command::Settings::Actuator::effortGains
CommandGains & effortGains()
Controller gains for the effort PID loop.
Definition: command.hpp:537
HebiCommandFloatVelocityLimitMax
@ HebiCommandFloatVelocityLimitMax
The firmware safety limit for the minimum allowed velocity.
Definition: hebi.h:101
hebi::Command::MstopStrategy
MstopStrategy
Definition: command.hpp:51
HebiCommandBoolEffortDOnError
@ HebiCommandBoolEffortDOnError
Controls whether the Kd term uses the "derivative of error" or "derivative of measurement....
Definition: hebi.h:119
util.hpp
HebiCommandFloatVelocityLimitMin
@ HebiCommandFloatVelocityLimitMin
Set the internal effort reference offset so that the current effort matches the given reference comma...
Definition: hebi.h:100
hebi::Command::LedField::LedField
LedField(HebiCommandRef &internal, HebiCommandLedField field)
Definition: command.cpp:183
HebiCommandFloatEffortLimitMax
@ HebiCommandFloatEffortLimitMax
The firmware safety limit for the minimum allowed effort.
Definition: hebi.h:103
hebi::Command::Settings::Imu::internal_
const HebiCommandRef & internal_
Definition: command.hpp:639
hebi::Command::FlagField::internal_
HebiCommandRef & internal_
Definition: command.hpp:294
hebi::Command::Settings::Imu::accelIncludesGravity
BoolField & accelIncludesGravity()
Whether to include acceleration due to gravity in acceleration feedback.
Definition: command.hpp:633
hebi::Command::Settings::actuator
const Actuator & actuator() const
Actuator-specific settings, such as controller gains.
Definition: command.hpp:663


hebi_cpp_api_ros
Author(s): Chris Bollinger , Matthew Tesch
autogenerated on Fri Aug 2 2024 08:35:18