feedback.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include "hebi.h"
4 
5 #include "color.hpp"
6 #include "quaternion_f.hpp"
7 #include "message_helpers.hpp"
8 #include "util.hpp"
9 #include "vector_3_f.hpp"
10 
11 namespace hebi {
12 
32 class Feedback final {
33 public:
34  enum class TemperatureState {
36  Normal,
38  Critical,
43  };
44 
45  enum class MstopState {
47  Triggered,
50  };
51 
52  enum class PositionLimitState {
55  Below,
57  AtLower,
59  Inside,
61  AtUpper,
64  Above,
67  };
68 
69  enum class VelocityLimitState {
72  Below,
74  AtLower,
76  Inside,
78  AtUpper,
81  Above,
84  };
85 
86  enum class EffortLimitState {
89  Below,
91  AtLower,
93  Inside,
95  AtUpper,
98  Above,
101  };
102 
103  enum class CommandLifetimeState {
105  Unlocked,
110  };
111 
112  enum class ArQuality {
128  };
129 
130 protected:
132  class FloatField final {
133  public:
134 #ifndef DOXYGEN_OMIT_INTERNAL
135  FloatField(const HebiFeedbackRef& internal, HebiFeedbackFloatField field);
136 #endif // DOXYGEN_OMIT_INTERNAL
137  explicit operator bool() const { return has(); }
151  bool has() const;
154  float get() const;
155 
157  private:
160  };
161 
167  class HighResAngleField final {
168  public:
169 #ifndef DOXYGEN_OMIT_INTERNAL
171 #endif // DOXYGEN_OMIT_INTERNAL
172  explicit operator bool() const { return has(); }
186  bool has() const;
192  double get() const;
204  void get(int64_t* revolutions, float* radian_offset) const;
205 
207  private:
210  };
211 
214  class NumberedFloatField final {
215  public:
216 #ifndef DOXYGEN_OMIT_INTERNAL
218 #endif // DOXYGEN_OMIT_INTERNAL
219  bool has(size_t fieldNumber) const;
230  float get(size_t fieldNumber) const;
231 
233  private:
236  };
237 
239  class UInt64Field final {
240  public:
241 #ifndef DOXYGEN_OMIT_INTERNAL
242  UInt64Field(const HebiFeedbackRef& internal, HebiFeedbackUInt64Field field);
243 #endif // DOXYGEN_OMIT_INTERNAL
244  explicit operator bool() const { return has(); }
258  bool has() const;
261  uint64_t get() const;
262 
264  private:
267  };
268 
271  class Vector3fField final {
272  public:
273 #ifndef DOXYGEN_OMIT_INTERNAL
275 #endif // DOXYGEN_OMIT_INTERNAL
276  explicit operator bool() const { return has(); }
290  bool has() const;
293  Vector3f get() const;
294 
296  private:
299  };
300 
303  class QuaternionfField final {
304  public:
305 #ifndef DOXYGEN_OMIT_INTERNAL
307 #endif // DOXYGEN_OMIT_INTERNAL
308  explicit operator bool() const { return has(); }
322  bool has() const;
325  Quaternionf get() const;
326 
328  private:
331  };
332 
334  template<typename T>
335  class EnumField final {
336  public:
337 #ifndef DOXYGEN_OMIT_INTERNAL
338  EnumField(const HebiFeedbackRef& internal, HebiFeedbackEnumField field) : internal_(internal), field_(field) {}
339 #endif // DOXYGEN_OMIT_INTERNAL
340  explicit operator bool() const { return has(); }
354  bool has() const {
355  return (enumGetter(internal_, field_, nullptr) == HebiStatusSuccess);
356  }
359  T get() const {
360  int32_t ret{};
361  enumGetter(internal_, field_, &ret);
362  return static_cast<T>(ret);
363  }
364 
366  private:
369  };
370 
372  class IoBank final {
373  public:
374 #ifndef DOXYGEN_OMIT_INTERNAL
375  IoBank(const HebiFeedbackRef& internal, HebiFeedbackIoPinBank bank);
376 #endif // DOXYGEN_OMIT_INTERNAL
377  bool hasInt(size_t pinNumber) const;
388  bool hasFloat(size_t pinNumber) const;
394  int64_t getInt(size_t pinNumber) const;
401  float getFloat(size_t pinNumber) const;
402 
404  private:
407  };
408 
410  class LedField final {
411  public:
412 #ifndef DOXYGEN_OMIT_INTERNAL
413  LedField(const HebiFeedbackRef& internal, HebiFeedbackLedField field);
414 #endif // DOXYGEN_OMIT_INTERNAL
415  explicit operator bool() const { return hasColor(); }
429  bool hasColor() const;
431  Color getColor() const;
432 
434  private:
437  };
438 
440  class Io final {
441  public:
442 #ifndef DOXYGEN_OMIT_INTERNAL
443  Io(const HebiFeedbackRef& internal)
444  : internal_(internal),
445  a_(internal, HebiFeedbackIoBankA),
446  b_(internal, HebiFeedbackIoBankB),
447  c_(internal, HebiFeedbackIoBankC),
448  d_(internal, HebiFeedbackIoBankD),
449  e_(internal, HebiFeedbackIoBankE),
450  f_(internal, HebiFeedbackIoBankF) {}
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  const IoBank& a() const { return a_; }
461  const IoBank& b() const { return b_; }
463  const IoBank& c() const { return c_; }
465  const IoBank& d() const { return d_; }
467  const IoBank& e() const { return e_; }
469  const IoBank& f() const { return f_; }
470 
472  private:
474 
481  };
482 
484  class Actuator final {
485  public:
486 #ifndef DOXYGEN_OMIT_INTERNAL
487  Actuator(const HebiFeedbackRef& internal)
489  effort_(internal, HebiFeedbackFloatEffort),
511 #endif // DOXYGEN_OMIT_INTERNAL
512 
513  // With all submessage and field getters: Note that the returned reference
514  // should not be used after the lifetime of this parent.
515 
516  // Subfields ----------------
517 
519  const FloatField& velocity() const { return velocity_; }
521  const FloatField& effort() const { return effort_; }
523  const FloatField& velocityCommand() const { return velocity_command_; }
525  const FloatField& effortCommand() const { return effort_command_; }
527  const FloatField& deflection() const { return deflection_; }
531  const FloatField& motorVelocity() const { return motor_velocity_; }
533  const FloatField& motorCurrent() const { return motor_current_; }
543  const FloatField& pwmCommand() const { return pwm_command_; }
545  const HighResAngleField& position() const { return position_; }
551  const UInt64Field& sequenceNumber() const { return sequence_number_; }
555  const EnumField<MstopState>& mstopState() const { return mstop_state_; }
564 
566  private:
590  };
591 
593  class Mobile final {
594  public:
595 #ifndef DOXYGEN_OMIT_INTERNAL
596  Mobile(const HebiFeedbackRef& internal)
601 #endif // DOXYGEN_OMIT_INTERNAL
602 
603  // With all submessage and field getters: Note that the returned reference
604  // should not be used after the lifetime of this parent.
605 
606  // Subfields ----------------
607 
609  const FloatField& batteryLevel() const { return battery_level_; }
611  const Vector3fField& arPosition() const { return ar_position_; }
613  const QuaternionfField& arOrientation() const { return ar_orientation_; }
615  const EnumField<ArQuality>& arQuality() const { return ar_quality_; }
616 
618  private:
623  };
624 
626  class Imu final {
627  public:
628 #ifndef DOXYGEN_OMIT_INTERNAL
629  Imu(const HebiFeedbackRef& internal)
631  gyro_(internal, HebiFeedbackVector3fGyro),
633 #endif // DOXYGEN_OMIT_INTERNAL
634 
635  // With all submessage and field getters: Note that the returned reference
636  // should not be used after the lifetime of this parent.
637 
638  // Subfields ----------------
639 
641  const Vector3fField& accelerometer() const { return accelerometer_; }
643  const Vector3fField& gyro() const { return gyro_; }
645  const QuaternionfField& orientation() const { return orientation_; }
646 
648  private:
652  };
653 
654 private:
661 
662 public:
663 #ifndef DOXYGEN_OMIT_INTERNAL
664 
669 #endif // DOXYGEN_OMIT_INTERNAL
670 
673  Feedback(Feedback&& other);
674 
675  // With all submessage and field getters: Note that the returned reference
676  // should not be used after the lifetime of this parent.
677 
678  // Submessages -------------------------------------------------------------
679 
681  const Io& io() const { return io_; }
683  const Actuator& actuator() const { return actuator_; }
685  const Mobile& mobile() const { return mobile_; }
687  const Imu& imu() const { return imu_; }
688 
689  // Subfields -------------------------------------------------------------
690 
692  const FloatField& boardTemperature() const { return board_temperature_; }
696  const FloatField& voltage() const { return voltage_; }
697 #ifndef DOXYGEN_OMIT_INTERNAL
698  const NumberedFloatField& debug() const { return debug_; }
700 #endif // DOXYGEN_OMIT_INTERNAL
701  const UInt64Field& receiveTimeUs() const { return receive_time_us_; }
704  const UInt64Field& transmitTimeUs() const { return transmit_time_us_; }
710  const UInt64Field& senderId() const { return sender_id_; }
712  const LedField& led() const { return led_; }
713 
718 
719  /* Disable move assigment operator. */
720  Feedback& operator=(Feedback&& other) = delete;
721 
722 private:
727 
738 };
739 
740 } // namespace hebi
HebiFeedbackFloatBatteryLevel
@ HebiFeedbackFloatBatteryLevel
The estimated temperature of the motor housing.
Definition: hebi.h:177
hebi::Feedback::CommandLifetimeState::Unlocked
@ Unlocked
There is not command lifetime active on this module.
hebi::Feedback::NumberedFloatField::internal_
const HebiFeedbackRef & internal_
Definition: feedback.hpp:234
hebi::Feedback::Actuator::temperatureState
const EnumField< TemperatureState > & temperatureState() const
Describes how the temperature inside the module is limiting the output of the motor.
Definition: feedback.hpp:553
hebi::Feedback::VelocityLimitState::Uninitialized
@ Uninitialized
The module has not been inside the safety limits since it was booted or the safety limits were set.
hebi::Feedback::Vector3fField::field_
const HebiFeedbackVector3fField field_
Definition: feedback.hpp:298
hebi::Feedback::Actuator::motor_housing_temperature_
FloatField motor_housing_temperature_
Definition: feedback.hpp:578
hebi::Feedback::Imu::gyro
const Vector3fField & gyro() const
Gyro data, in radians/second.
Definition: feedback.hpp:643
hebi::Feedback::IoBank::IoBank
IoBank(const HebiFeedbackRef &internal, HebiFeedbackIoPinBank bank)
Definition: feedback.cpp:114
hebi::Feedback::EffortLimitState::AtLower
@ AtLower
The effort of the module was near the lower safety limit, and the motor output is being limited or re...
hebi::Feedback::FloatField::has
bool has() const
True if (and only if) the field has a value.
Definition: feedback.cpp:14
hebi::Feedback::EnumField::has
bool has() const
True if (and only if) the field has a value.
Definition: feedback.hpp:354
HebiFeedbackHighResAnglePosition
@ HebiFeedbackHighResAnglePosition
Definition: hebi.h:182
hebi::Feedback::TemperatureState::ExceedMaxMotor
@ ExceedMaxMotor
Temperature exceeds max allowable for motor; motor output disabled.
HebiFeedbackEnumEffortLimitState
@ HebiFeedbackEnumEffortLimitState
Software-controlled bounds on the allowable velocity of the module.
Definition: hebi.h:216
hebi::Feedback::Actuator::motor_current_
FloatField motor_current_
Definition: feedback.hpp:574
hebi::Feedback::Actuator::effort_
FloatField effort_
Definition: feedback.hpp:568
hebi::Feedback::Actuator::effortCommand
const FloatField & effortCommand() const
Commanded effort at the module output; units vary (e.g., N * m for rotational joints and N for linear...
Definition: feedback.hpp:525
hebi::Feedback::UInt64Field::internal_
const HebiFeedbackRef & internal_
Definition: feedback.hpp:265
hebi::Feedback::operator=
Feedback & operator=(Feedback &&other)=delete
hebi::Feedback::UInt64Field::field_
const HebiFeedbackUInt64Field field_
Definition: feedback.hpp:266
hebi::Feedback::Actuator::mstop_state_
EnumField< MstopState > mstop_state_
Definition: feedback.hpp:585
HebiFeedbackFloatMotorCurrent
@ HebiFeedbackFloatMotorCurrent
The velocity of the motor shaft.
Definition: hebi.h:172
HebiFeedbackIoBankB
@ HebiFeedbackIoBankB
I/O pin bank a (pins 1-8 available)
Definition: hebi.h:223
hebi::Feedback::Io::e_
IoBank e_
Definition: feedback.hpp:479
hebi::Color
Structure to describe an RGB color.
Definition: color.hpp:8
hebi::Feedback::Actuator::commandLifetimeState
const EnumField< CommandLifetimeState > & commandLifetimeState() const
The state of the command lifetime safety controller, with respect to the current group.
Definition: feedback.hpp:563
hebi::Feedback::HighResAngleField::field_
const HebiFeedbackHighResAngleField field_
Definition: feedback.hpp:209
hebi::Feedback::UInt64Field::has
bool has() const
True if (and only if) the field has a value.
Definition: feedback.cpp:67
hebi::Feedback::ArQuality::ArQualityLimitedExcessiveMotion
@ ArQualityLimitedExcessiveMotion
The device is moving too fast for accurate image-based position tracking.
hebi::Feedback::FloatField::FloatField
FloatField(const HebiFeedbackRef &internal, HebiFeedbackFloatField field)
Definition: feedback.cpp:11
hebi::Feedback::Actuator::motorHousingTemperature
const FloatField & motorHousingTemperature() const
The estimated temperature of the motor housing.
Definition: feedback.hpp:541
HebiStatusSuccess
@ HebiStatusSuccess
Definition: hebi.h:24
hebi::Feedback::VelocityLimitState::AtUpper
@ AtUpper
The velocity of the module was near the upper safety limit, and the motor output is being limited or ...
hebi::Vector3f
Structure to hold a 3-D floating point vector (i.e., x/y/z components)
Definition: vector_3_f.hpp:8
HebiFeedbackFloatVelocityCommand
@ HebiFeedbackFloatVelocityCommand
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages).
Definition: hebi.h:167
HebiFeedbackIoBankC
@ HebiFeedbackIoBankC
I/O pin bank b (pins 1-8 available)
Definition: hebi.h:224
hebi::Feedback::EffortLimitState::Below
@ Below
hebi::Feedback::MstopState::Triggered
@ Triggered
The MStop is pressed.
hebi::Feedback::Actuator::motorWindingCurrent
const FloatField & motorWindingCurrent() const
The estimated current in the motor windings.
Definition: feedback.hpp:537
hebi::Feedback::Imu::gyro_
Vector3fField gyro_
Definition: feedback.hpp:650
HebiFeedbackEnumTemperatureState
@ HebiFeedbackEnumTemperatureState
Definition: hebi.h:212
hebi::Feedback::receiveTimeUs
const UInt64Field & receiveTimeUs() const
Timestamp of when message was received from module (local; microseconds)
Definition: feedback.hpp:702
hebi::Feedback::imu
const Imu & imu() const
Inertial measurement unit feedback (accelerometers and gyros).
Definition: feedback.hpp:687
hebi::Feedback::Imu::accelerometer_
Vector3fField accelerometer_
Definition: feedback.hpp:649
hebi::Feedback::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: feedback.cpp:116
HebiFeedbackQuaternionfField
HebiFeedbackQuaternionfField
Definition: hebi.h:206
hebi::Feedback::TemperatureState::Critical
@ Critical
Motor output beginning to be limited due to high temperature.
hebi::Quaternionf
Structure to hold a floating point quaternion (i.e., w/x/y/z components)
Definition: quaternion_f.hpp:8
HebiFeedbackHighResAngleMotorPosition
@ HebiFeedbackHighResAngleMotorPosition
Commanded position of the module output (post-spring).
Definition: hebi.h:184
hebi::Feedback::PositionLimitState::AtUpper
@ AtUpper
The position of the module was near the upper safety limit, and the motor output is being limited or ...
hebi::Feedback::Actuator::deflectionVelocity
const FloatField & deflectionVelocity() const
Velocity (in radians/second) of the difference between the pre-spring and post-spring output position...
Definition: feedback.hpp:529
hebi::Feedback::transmitTimeUs
const UInt64Field & transmitTimeUs() const
Timestamp of when message was transmitted to module (local; microseconds)
Definition: feedback.hpp:704
HebiFeedbackHighResAnglePositionCommand
@ HebiFeedbackHighResAnglePositionCommand
Position of the module output (post-spring).
Definition: hebi.h:183
hebi::Feedback::Actuator::motor_velocity_
FloatField motor_velocity_
Definition: feedback.hpp:573
hebi::Feedback::Actuator::deflection_velocity_
FloatField deflection_velocity_
Definition: feedback.hpp:572
hebi::Feedback::led
const LedField & led() const
The module's LED.
Definition: feedback.hpp:712
hebi::Feedback::Vector3fField::Vector3fField
Vector3fField(const HebiFeedbackRef &internal, HebiFeedbackVector3fField field)
Definition: feedback.cpp:79
hebi::Feedback::Actuator::motor_sensor_temperature_
FloatField motor_sensor_temperature_
Definition: feedback.hpp:575
hebi::Feedback::UInt64Field
A message field representable by an unsigned 64 bit integer value.
Definition: feedback.hpp:239
HebiFeedbackUInt64Field
HebiFeedbackUInt64Field
Definition: hebi.h:191
hebi::Feedback::PositionLimitState::Uninitialized
@ Uninitialized
The module has not been inside the safety limits since it was booted or the safety limits were set.
hebi::Feedback::Actuator::velocityCommand
const FloatField & velocityCommand() const
Commanded velocity of the module output (post-spring), in radians/second.
Definition: feedback.hpp:523
hebi::Feedback::Actuator::motorSensorTemperature
const FloatField & motorSensorTemperature() const
The temperature from a sensor near the motor housing.
Definition: feedback.hpp:535
hebi::Feedback::ArQuality::ArQualityLimitedInsufficientFeatures
@ ArQualityLimitedInsufficientFeatures
hebi::Feedback::MstopState
MstopState
Definition: feedback.hpp:45
hebi::Feedback::Io::b
const IoBank & b() const
I/O pin bank b (pins 1-8 available)
Definition: feedback.hpp:461
hebi::Feedback::Mobile::ar_quality_
EnumField< ArQuality > ar_quality_
Definition: feedback.hpp:622
hebi::Feedback::actuator
const Actuator & actuator() const
Actuator-specific feedback.
Definition: feedback.hpp:683
HebiFeedbackHighResAngleField
HebiFeedbackHighResAngleField
Definition: hebi.h:181
hebi::Feedback::Mobile
Feedback generally from a mobile device such as a phone or tablet.
Definition: feedback.hpp:593
hebi::Feedback::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: feedback.cpp:124
hebi::Feedback::Actuator::position_command_
HighResAngleField position_command_
Definition: feedback.hpp:581
HebiFeedbackFloatEffort
@ HebiFeedbackFloatEffort
Velocity of the module output (post-spring).
Definition: hebi.h:166
hebi::Feedback::Actuator::positionLimitState
const EnumField< PositionLimitState > & positionLimitState() const
Software-controlled bounds on the allowable position of the module; user settable.
Definition: feedback.hpp:557
hebi::Feedback::LedField::internal_
const HebiFeedbackRef & internal_
Definition: feedback.hpp:435
hebi::Feedback::Imu::orientation
const QuaternionfField & orientation() const
A filtered estimate of the orientation of the module.
Definition: feedback.hpp:645
HebiFeedbackFloatVelocity
@ HebiFeedbackFloatVelocity
Bus voltage at which the module is running.
Definition: hebi.h:165
HEBI_DISABLE_COPY
#define HEBI_DISABLE_COPY(Class)
Definition: util.hpp:16
hebi::Feedback::Io::c
const IoBank & c() const
I/O pin bank c (pins 1-8 available)
Definition: feedback.hpp:463
hebi::Feedback::mobile_
Mobile mobile_
Definition: feedback.hpp:725
hebi::Feedback::internal_
HebiFeedbackPtr internal_
Definition: feedback.hpp:659
HebiFeedbackFloatMotorHousingTemperature
@ HebiFeedbackFloatMotorHousingTemperature
The estimated temperature of the motor windings.
Definition: hebi.h:176
HebiFeedbackIoBankA
@ HebiFeedbackIoBankA
Definition: hebi.h:222
hebi::Feedback::io
const Io & io() const
Feedback from any available I/O pins on the device.
Definition: feedback.hpp:681
HebiFeedbackPtr
struct HebiFeedback_ * HebiFeedbackPtr
The C-style's API representation of feedback.
Definition: hebi.h:451
hebi::Feedback::Mobile::battery_level_
FloatField battery_level_
Definition: feedback.hpp:619
hebi::Feedback::Mobile::arQuality
const EnumField< ArQuality > & arQuality() const
The status of the augmented reality tracking, if using an AR enabled device.
Definition: feedback.hpp:615
HebiFeedbackRef_
Definition: hebi.h:690
hebi::Feedback::Mobile::arPosition
const Vector3fField & arPosition() const
A device's position in the world as calculated from an augmented reality framework,...
Definition: feedback.hpp:611
hebi::Feedback::Actuator::motorPosition
const HighResAngleField & motorPosition() const
The position of an actuator’s internal motor before the gear reduction, in radians.
Definition: feedback.hpp:549
hebi::Feedback::hardwareReceiveTimeUs
const UInt64Field & hardwareReceiveTimeUs() const
Timestamp of when message was received by module (remote; microseconds)
Definition: feedback.hpp:706
hebi::Feedback::Mobile::Mobile
Mobile(const HebiFeedbackRef &internal)
Definition: feedback.hpp:596
hebi::Feedback::Imu::Imu
Imu(const HebiFeedbackRef &internal)
Definition: feedback.hpp:629
hebi::Feedback::Actuator::position_limit_state_
EnumField< PositionLimitState > position_limit_state_
Definition: feedback.hpp:586
hebi::Feedback::IoBank::bank_
const HebiFeedbackIoPinBank bank_
Definition: feedback.hpp:406
hebi::Feedback::EffortLimitState::Uninitialized
@ Uninitialized
The module has not been inside the safety limits since it was booted or the safety limits were set.
hebi::Feedback::FloatField::field_
const HebiFeedbackFloatField field_
Definition: feedback.hpp:159
hebi::Feedback::Vector3fField::internal_
const HebiFeedbackRef & internal_
Definition: feedback.hpp:297
hebi::Feedback::LedField::field_
const HebiFeedbackLedField field_
Definition: feedback.hpp:436
vector_3_f.hpp
hebi::Feedback::Io::a_
IoBank a_
Definition: feedback.hpp:475
hebi::Feedback::ArQuality
ArQuality
Definition: feedback.hpp:112
HebiFeedbackFloatMotorSensorTemperature
@ HebiFeedbackFloatMotorSensorTemperature
Current supplied to the motor.
Definition: hebi.h:173
hebi::Feedback::QuaternionfField::QuaternionfField
QuaternionfField(const HebiFeedbackRef &internal, HebiFeedbackQuaternionfField field)
Definition: feedback.cpp:96
hebi::Feedback::EffortLimitState::Inside
@ Inside
The effort of the module was within the safety limits.
HEBI_DISABLE_COPY_MOVE
#define HEBI_DISABLE_COPY_MOVE(Class)
Definition: util.hpp:6
hebi::Feedback::EffortLimitState
EffortLimitState
Definition: feedback.hpp:86
HebiFeedbackUInt64SequenceNumber
@ HebiFeedbackUInt64SequenceNumber
Definition: hebi.h:192
hebi::Feedback::Actuator::deflection_
FloatField deflection_
Definition: feedback.hpp:571
HebiFeedbackIoBankD
@ HebiFeedbackIoBankD
I/O pin bank c (pins 1-8 available)
Definition: hebi.h:225
HebiFeedbackFloatPwmCommand
@ HebiFeedbackFloatPwmCommand
Charge level of the device’s battery (in percent).
Definition: hebi.h:178
hebi::Feedback::processor_temperature_
FloatField processor_temperature_
Definition: feedback.hpp:729
hebi::Feedback::QuaternionfField::has
bool has() const
True if (and only if) the field has a value.
Definition: feedback.cpp:99
hebi::Feedback::CommandLifetimeState::LockedByOther
@ LockedByOther
Commands are locked out due to control from other users.
hebi::Feedback::Io::c_
IoBank c_
Definition: feedback.hpp:477
hebi::Feedback::LedField::getColor
Color getColor() const
Returns the led color.
Definition: feedback.cpp:143
hebi::Feedback::TemperatureState::ExceedMaxBoard
@ ExceedMaxBoard
Temperature exceeds max allowable for electronics; motor output disabled.
hebi::Feedback::Actuator::temperature_state_
EnumField< TemperatureState > temperature_state_
Definition: feedback.hpp:584
hebi::Feedback::MstopState::NotTriggered
@ NotTriggered
The MStop is not pressed.
hebi::Feedback::Imu
Inertial measurement unit feedback (accelerometers and gyros).
Definition: feedback.hpp:626
hebi::Feedback::Imu::accelerometer
const Vector3fField & accelerometer() const
Accelerometer data, in m/s^2.
Definition: feedback.hpp:641
hebi::Feedback::hardware_receive_time_us_
UInt64Field hardware_receive_time_us_
Definition: feedback.hpp:734
hebi::Feedback::Actuator::pwmCommand
const FloatField & pwmCommand() const
Commanded PWM signal sent to the motor; final output of PID controllers.
Definition: feedback.hpp:543
HebiFeedbackEnumVelocityLimitState
@ HebiFeedbackEnumVelocityLimitState
Software-controlled bounds on the allowable position of the module; user settable.
Definition: hebi.h:215
hebi::Feedback::VelocityLimitState::Inside
@ Inside
The velocity of the module was within the safety limits.
hebi::Feedback::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: feedback.cpp:120
hebi::Feedback::Actuator::velocity_command_
FloatField velocity_command_
Definition: feedback.hpp:569
HebiFeedbackEnumPositionLimitState
@ HebiFeedbackEnumPositionLimitState
Current status of the MStop.
Definition: hebi.h:214
HebiFeedbackFloatMotorWindingCurrent
@ HebiFeedbackFloatMotorWindingCurrent
The temperature from a sensor near the motor housing.
Definition: hebi.h:174
hebi::Feedback::Actuator::sequenceNumber
const UInt64Field & sequenceNumber() const
Sequence number going to module (local)
Definition: feedback.hpp:551
hebi::Feedback::NumberedFloatField::has
bool has(size_t fieldNumber) const
True if (and only if) the particular numbered subvalue of this field has a value.
Definition: feedback.cpp:52
HebiFeedbackQuaternionfArOrientation
@ HebiFeedbackQuaternionfArOrientation
A filtered estimate of the orientation of the module.
Definition: hebi.h:208
hebi::Feedback::EnumField
A message field representable by an enum of a given type.
Definition: feedback.hpp:335
hebi::Feedback::ArQuality::ArQualityLimitedInitializing
@ ArQualityLimitedInitializing
The AR session has not yet gathered enough camera or motion data to provide tracking information.
hebi::Feedback::PositionLimitState
PositionLimitState
Definition: feedback.hpp:52
hebi::Feedback::actuator_
Actuator actuator_
Definition: feedback.hpp:724
hebi::Feedback::UInt64Field::get
uint64_t get() const
If the field has a value, returns that value; otherwise, returns a default.
Definition: feedback.cpp:71
HebiFeedbackVector3fArPosition
@ HebiFeedbackVector3fArPosition
Gyro data.
Definition: hebi.h:203
hebi::Feedback::Actuator::deflection
const FloatField & deflection() const
Difference (in radians) between the pre-spring and post-spring output position.
Definition: feedback.hpp:527
hebi::Feedback::Vector3fField
A message field representable by a 3-D vector of single-precision floating point values.
Definition: feedback.hpp:271
hebi::Feedback::Actuator::Actuator
Actuator(const HebiFeedbackRef &internal)
Definition: feedback.hpp:487
hebi::Feedback::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: feedback.cpp:56
hebi::Feedback::EffortLimitState::Above
@ Above
hebi::Feedback::NumberedFloatField::NumberedFloatField
NumberedFloatField(const HebiFeedbackRef &internal, HebiFeedbackNumberedFloatField field)
Definition: feedback.cpp:49
hebi::Feedback::transmit_time_us_
UInt64Field transmit_time_us_
Definition: feedback.hpp:733
hebi::Feedback::EnumField::EnumField
EnumField(const HebiFeedbackRef &internal, HebiFeedbackEnumField field)
Definition: feedback.hpp:338
hebi::Feedback::HighResAngleField::get
double get() const
If the field has a value, returns that value as a double; otherwise, returns a default.
Definition: feedback.cpp:33
hebi::Feedback::FloatField
A message field representable by a single-precision floating point value.
Definition: feedback.hpp:132
hebi::Feedback::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: feedback.cpp:130
hebi::Feedback::ArQuality::ArQualityLimitedRelocalizing
@ ArQualityLimitedRelocalizing
The AR session is attempting to resume after an interruption.
HebiFeedbackEnumArQuality
@ HebiFeedbackEnumArQuality
The state of the command lifetime safety controller, with respect to the current group.
Definition: hebi.h:218
hebi::Feedback::VelocityLimitState::Below
@ Below
hebi::Feedback::UInt64Field::UInt64Field
UInt64Field(const HebiFeedbackRef &internal, HebiFeedbackUInt64Field field)
Definition: feedback.cpp:64
hebi::Feedback::Io::f_
IoBank f_
Definition: feedback.hpp:480
hebi::Feedback::hardwareTransmitTimeUs
const UInt64Field & hardwareTransmitTimeUs() const
Timestamp of when message was transmitted from module (remote; microseconds)
Definition: feedback.hpp:708
HebiFeedbackVector3fAccelerometer
@ HebiFeedbackVector3fAccelerometer
Definition: hebi.h:201
hebi::Feedback::led_
LedField led_
Definition: feedback.hpp:737
hebi::Feedback::Actuator::motorVelocity
const FloatField & motorVelocity() const
The velocity (in radians/second) of the motor shaft.
Definition: feedback.hpp:531
HebiFeedbackQuaternionfOrientation
@ HebiFeedbackQuaternionfOrientation
Definition: hebi.h:207
hebi
Definition: arm.cpp:5
hebi::Feedback::ArQuality::ArQualityNormal
@ ArQualityNormal
Camera position tracking is providing optimal results.
hebi::Feedback::HighResAngleField::has
bool has() const
True if (and only if) the field has a value.
Definition: feedback.cpp:29
HebiFeedbackIoBankF
@ HebiFeedbackIoBankF
I/O pin bank e (pins 1-8 available)
Definition: hebi.h:227
hebi::Feedback::QuaternionfField::field_
const HebiFeedbackQuaternionfField field_
Definition: feedback.hpp:330
hebi::Feedback::Actuator::motorCurrent
const FloatField & motorCurrent() const
Current supplied to the motor.
Definition: feedback.hpp:533
hebi::Feedback::HighResAngleField
A message field for an angle measurement which does not lose precision at very high angles.
Definition: feedback.hpp:167
hebi::Feedback::VelocityLimitState::AtLower
@ AtLower
The velocity of the module was near the lower safety limit, and the motor output is being limited or ...
hebi::Feedback::Actuator::motor_winding_temperature_
FloatField motor_winding_temperature_
Definition: feedback.hpp:577
hebi::Feedback::EnumField::internal_
const HebiFeedbackRef & internal_
Definition: feedback.hpp:367
hebi::Feedback::Vector3fField::get
Vector3f get() const
If the field has a value, returns that value; otherwise, returns a default.
Definition: feedback.cpp:86
HebiFeedbackVector3fGyro
@ HebiFeedbackVector3fGyro
Accelerometer data.
Definition: hebi.h:202
hebi::Feedback::Actuator::sequence_number_
UInt64Field sequence_number_
Definition: feedback.hpp:583
hebi::Feedback::PositionLimitState::Below
@ Below
hebi::Feedback::QuaternionfField::internal_
const HebiFeedbackRef & internal_
Definition: feedback.hpp:329
hebi::Feedback::CommandLifetimeState::LockedBySender
@ LockedBySender
Commands from others are locked out due to control from this group.
hebi::Feedback::TemperatureState::Normal
@ Normal
Temperature within normal range.
hebi::Feedback::EffortLimitState::AtUpper
@ AtUpper
The effort of the module was near the upper safety limit, and the motor output is being limited or re...
hebi::Feedback::sender_id_
UInt64Field sender_id_
Definition: feedback.hpp:736
hebi::Feedback::debug
const NumberedFloatField & debug() const
Values for internal debug functions (channel 1-9 available).
Definition: feedback.hpp:699
hebi::Feedback::Imu::orientation_
QuaternionfField orientation_
Definition: feedback.hpp:651
hebi::Feedback::mobile
const Mobile & mobile() const
Feedback generally from a mobile device such as a phone or tablet.
Definition: feedback.hpp:685
hebi::Feedback::Io
Feedback from any available I/O pins on the device.
Definition: feedback.hpp:440
hebi::Feedback::voltage
const FloatField & voltage() const
Bus voltage that the module is running at (in Volts).
Definition: feedback.hpp:696
hebi::Feedback::Feedback
Feedback(HebiFeedbackPtr)
Wraps an existing C-style object that is managed by its parent. NOTE: this should not be used except ...
Definition: feedback.cpp:154
hebi::Feedback::QuaternionfField
A message field representable by a 3-D vector of single-precision floating point values.
Definition: feedback.hpp:303
hebi::Feedback::VelocityLimitState
VelocityLimitState
Definition: feedback.hpp:69
hebi::Feedback::EnumField::get
T get() const
If the field has a value, returns that value; otherwise, returns a default.
Definition: feedback.hpp:359
HebiFeedbackEnumMstopState
@ HebiFeedbackEnumMstopState
Describes how the temperature inside the module is limiting the output of the motor.
Definition: hebi.h:213
hebi::Feedback::Io::internal_
const HebiFeedbackRef & internal_
Definition: feedback.hpp:473
quaternion_f.hpp
hebi::Feedback::Mobile::batteryLevel
const FloatField & batteryLevel() const
Charge level of the device’s battery (in percent).
Definition: feedback.hpp:609
color.hpp
hebi::Feedback::Actuator::command_lifetime_state_
EnumField< CommandLifetimeState > command_lifetime_state_
Definition: feedback.hpp:589
HebiFeedbackFloatField
HebiFeedbackFloatField
Feedback Enums.
Definition: hebi.h:161
hebi::Feedback::Actuator::effort_limit_state_
EnumField< EffortLimitState > effort_limit_state_
Definition: feedback.hpp:588
HebiFeedbackEnumField
HebiFeedbackEnumField
Definition: hebi.h:211
hebi::Feedback::Actuator::motor_position_
HighResAngleField motor_position_
Definition: feedback.hpp:582
HebiFeedbackNumberedFloatField
HebiFeedbackNumberedFloatField
Definition: hebi.h:187
hebi::Feedback::Actuator::effort_command_
FloatField effort_command_
Definition: feedback.hpp:570
hebi::Feedback::board_temperature_
FloatField board_temperature_
Definition: feedback.hpp:728
hebi::Feedback::LedField::hasColor
bool hasColor() const
Returns true if the LED color is set, and false otherwise.
Definition: feedback.cpp:139
hebi::Feedback::NumberedFloatField::field_
const HebiFeedbackNumberedFloatField field_
Definition: feedback.hpp:235
hebi::Feedback::internal_ref_
HebiFeedbackRef internal_ref_
Definition: feedback.hpp:660
hebi::Feedback::Actuator::mstopState
const EnumField< MstopState > & mstopState() const
Current status of the MStop.
Definition: feedback.hpp:555
hebi::Feedback::Vector3fField::has
bool has() const
True if (and only if) the field has a value.
Definition: feedback.cpp:82
hebi::Feedback::hardware_transmit_time_us_
UInt64Field hardware_transmit_time_us_
Definition: feedback.hpp:735
message_helpers.hpp
HebiFeedbackFloatMotorVelocity
@ HebiFeedbackFloatMotorVelocity
Velocity of the difference between the pre-spring and post-spring output position.
Definition: hebi.h:171
hebi::enumGetter
HebiStatusCode enumGetter(const RefT &ref, MetadataT &metadata, int field, int32_t *value)
Definition: message_helpers.cpp:298
HebiFeedbackFloatDeflection
@ HebiFeedbackFloatDeflection
Commanded effort at the module output; units vary (e.g., N * m for rotational joints and N for linear...
Definition: hebi.h:169
hebi::Feedback::CommandLifetimeState
CommandLifetimeState
Definition: feedback.hpp:103
hebi::Feedback::Io::e
const IoBank & e() const
I/O pin bank e (pins 1-8 available)
Definition: feedback.hpp:467
hebi::Feedback::Actuator::effortLimitState
const EnumField< EffortLimitState > & effortLimitState() const
Software-controlled bounds on the allowable effort of the module.
Definition: feedback.hpp:561
hebi::Feedback::NumberedFloatField
A message field containing a numbered set of single-precision floating point values.
Definition: feedback.hpp:214
hebi::Feedback::voltage_
FloatField voltage_
Definition: feedback.hpp:730
hebi::Feedback::Mobile::ar_position_
Vector3fField ar_position_
Definition: feedback.hpp:620
hebi::Feedback::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: feedback.hpp:521
hebi::Feedback::EnumField::field_
const HebiFeedbackEnumField field_
Definition: feedback.hpp:368
hebi::Feedback::PositionLimitState::Above
@ Above
HebiFeedbackIoPinBank
HebiFeedbackIoPinBank
Definition: hebi.h:221
hebi::Feedback::ArQuality::ArQualityNotAvailable
@ ArQualityNotAvailable
Camera position tracking is not available.
hebi::Feedback::imu_
Imu imu_
Definition: feedback.hpp:726
hebi::Feedback::HighResAngleField::internal_
const HebiFeedbackRef & internal_
Definition: feedback.hpp:208
hebi::Feedback::Actuator::velocity_
FloatField velocity_
Definition: feedback.hpp:567
hebi.h
HebiFeedbackEnumCommandLifetimeState
@ HebiFeedbackEnumCommandLifetimeState
Software-controlled bounds on the allowable effort of the module.
Definition: hebi.h:217
hebi::Feedback::Io::d
const IoBank & d() const
I/O pin bank d (pins 1-8 available)
Definition: feedback.hpp:465
hebi::Feedback::Actuator::positionCommand
const HighResAngleField & positionCommand() const
Commanded position of the module output (post-spring), in radians.
Definition: feedback.hpp:547
hebi::Feedback::QuaternionfField::get
Quaternionf get() const
If the field has a value, returns that value; otherwise, returns a default.
Definition: feedback.cpp:103
hebi::Feedback::Actuator::velocity
const FloatField & velocity() const
Velocity of the module output (post-spring), in radians/second.
Definition: feedback.hpp:519
HebiFeedbackFloatDeflectionVelocity
@ HebiFeedbackFloatDeflectionVelocity
Difference between the pre-spring and post-spring output position.
Definition: hebi.h:170
HebiFeedbackVector3fField
HebiFeedbackVector3fField
Definition: hebi.h:200
HebiFeedbackLedField
HebiFeedbackLedField
Definition: hebi.h:230
hebi::Feedback::receive_time_us_
UInt64Field receive_time_us_
Definition: feedback.hpp:732
hebi::Feedback::Actuator::position_
HighResAngleField position_
Definition: feedback.hpp:580
hebi::Feedback::PositionLimitState::AtLower
@ AtLower
The position of the module was near the lower safety limit, and the motor output is being limited or ...
hebi::Feedback::LedField::LedField
LedField(const HebiFeedbackRef &internal, HebiFeedbackLedField field)
Definition: feedback.cpp:136
hebi::Feedback::Actuator::velocityLimitState
const EnumField< VelocityLimitState > & velocityLimitState() const
Software-controlled bounds on the allowable velocity of the module.
Definition: feedback.hpp:559
hebi::Feedback::PositionLimitState::Inside
@ Inside
The position of the module was within the safety limits.
hebi::Feedback::Actuator::motor_winding_current_
FloatField motor_winding_current_
Definition: feedback.hpp:576
hebi::Feedback::Io::b_
IoBank b_
Definition: feedback.hpp:476
hebi::Feedback::senderId
const UInt64Field & senderId() const
Unique ID of the module transmitting this feedback.
Definition: feedback.hpp:710
hebi::Feedback
Feedback objects have various fields representing feedback from modules; which fields are populated d...
Definition: feedback.hpp:32
hebi::Feedback::Io::Io
Io(const HebiFeedbackRef &internal)
Definition: feedback.hpp:443
hebi::Feedback::IoBank
A message field for interfacing with a bank of I/O pins.
Definition: feedback.hpp:372
hebi::Feedback::Actuator::motorWindingTemperature
const FloatField & motorWindingTemperature() const
The estimated temperature of the motor windings.
Definition: feedback.hpp:539
hebi::Feedback::LedField
A message field for interfacing with an LED.
Definition: feedback.hpp:410
HebiFeedbackFloatMotorWindingTemperature
@ HebiFeedbackFloatMotorWindingTemperature
The estimated current in the motor windings.
Definition: hebi.h:175
hebi::Feedback::Actuator
Actuator-specific feedback.
Definition: feedback.hpp:484
hebi::Feedback::Mobile::arOrientation
const QuaternionfField & arOrientation() const
A device's orientation in the world as calculated from an augmented reality framework.
Definition: feedback.hpp:613
hebi::Feedback::Actuator::position
const HighResAngleField & position() const
Position of the module output (post-spring), in radians.
Definition: feedback.hpp:545
hebi::Feedback::VelocityLimitState::Above
@ Above
hebi::Feedback::Io::a
const IoBank & a() const
I/O pin bank a (pins 1-8 available)
Definition: feedback.hpp:459
hebi::Feedback::boardTemperature
const FloatField & boardTemperature() const
Ambient temperature inside the module (measured at the IMU chip), in degrees Celsius.
Definition: feedback.hpp:692
hebi::Feedback::FloatField::get
float get() const
If the field has a value, returns that value; otherwise, returns a default.
Definition: feedback.cpp:18
hebi::Feedback::FloatField::internal_
const HebiFeedbackRef & internal_
Definition: feedback.hpp:158
hebi::Feedback::debug_
NumberedFloatField debug_
Definition: feedback.hpp:731
hebi::Feedback::Actuator::pwm_command_
FloatField pwm_command_
Definition: feedback.hpp:579
hebi::Feedback::Io::f
const IoBank & f() const
I/O pin bank f (pins 1-8 available)
Definition: feedback.hpp:469
hebi::Feedback::processorTemperature
const FloatField & processorTemperature() const
Temperature of the processor chip, in degrees Celsius.
Definition: feedback.hpp:694
util.hpp
hebi::Feedback::HighResAngleField::HighResAngleField
HighResAngleField(const HebiFeedbackRef &internal, HebiFeedbackHighResAngleField field)
Definition: feedback.cpp:26
hebi::Feedback::Actuator::velocity_limit_state_
EnumField< VelocityLimitState > velocity_limit_state_
Definition: feedback.hpp:587
hebi::Feedback::io_
Io io_
Definition: feedback.hpp:723
hebi::Feedback::Mobile::ar_orientation_
QuaternionfField ar_orientation_
Definition: feedback.hpp:621
hebi::Feedback::Io::d_
IoBank d_
Definition: feedback.hpp:478
HebiFeedbackFloatEffortCommand
@ HebiFeedbackFloatEffortCommand
Commanded velocity of the module output (post-spring)
Definition: hebi.h:168
hebi::Feedback::ArQuality::ArQualityLimitedUnknown
@ ArQualityLimitedUnknown
Tracking is available albeit suboptimal for an unknown reason.
hebi::Feedback::TemperatureState
TemperatureState
Definition: feedback.hpp:34
hebi::Feedback::IoBank::internal_
const HebiFeedbackRef & internal_
Definition: feedback.hpp:405
HebiFeedbackIoBankE
@ HebiFeedbackIoBankE
I/O pin bank d (pins 1-8 available)
Definition: hebi.h:226


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