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,
49  NotTriggered,
50  };
51 
52  enum class PositionLimitState {
55  Below,
57  AtLower,
59  Inside,
61  AtUpper,
64  Above,
66  Uninitialized,
67  };
68 
69  enum class VelocityLimitState {
72  Below,
74  AtLower,
76  Inside,
78  AtUpper,
81  Above,
83  Uninitialized,
84  };
85 
86  enum class EffortLimitState {
89  Below,
91  AtLower,
93  Inside,
95  AtUpper,
98  Above,
100  Uninitialized,
101  };
102 
103  enum class CommandLifetimeState {
105  Unlocked,
107  LockedByOther,
109  LockedBySender,
110  };
111 
112  enum class ArQuality {
114  ArQualityNotAvailable,
116  ArQualityLimitedUnknown,
118  ArQualityLimitedInitializing,
120  ArQualityLimitedRelocalizing,
122  ArQualityLimitedExcessiveMotion,
125  ArQualityLimitedInsufficientFeatures,
127  ArQualityNormal,
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)
488  : velocity_(internal, HebiFeedbackFloatVelocity),
489  effort_(internal, HebiFeedbackFloatEffort),
490  velocity_command_(internal, HebiFeedbackFloatVelocityCommand),
491  effort_command_(internal, HebiFeedbackFloatEffortCommand),
492  deflection_(internal, HebiFeedbackFloatDeflection),
493  deflection_velocity_(internal, HebiFeedbackFloatDeflectionVelocity),
494  motor_velocity_(internal, HebiFeedbackFloatMotorVelocity),
495  motor_current_(internal, HebiFeedbackFloatMotorCurrent),
496  motor_sensor_temperature_(internal, HebiFeedbackFloatMotorSensorTemperature),
497  motor_winding_current_(internal, HebiFeedbackFloatMotorWindingCurrent),
498  motor_winding_temperature_(internal, HebiFeedbackFloatMotorWindingTemperature),
499  motor_housing_temperature_(internal, HebiFeedbackFloatMotorHousingTemperature),
500  pwm_command_(internal, HebiFeedbackFloatPwmCommand),
501  position_(internal, HebiFeedbackHighResAnglePosition),
502  position_command_(internal, HebiFeedbackHighResAnglePositionCommand),
503  motor_position_(internal, HebiFeedbackHighResAngleMotorPosition),
504  sequence_number_(internal, HebiFeedbackUInt64SequenceNumber),
505  temperature_state_(internal, HebiFeedbackEnumTemperatureState),
506  mstop_state_(internal, HebiFeedbackEnumMstopState),
507  position_limit_state_(internal, HebiFeedbackEnumPositionLimitState),
508  velocity_limit_state_(internal, HebiFeedbackEnumVelocityLimitState),
509  effort_limit_state_(internal, HebiFeedbackEnumEffortLimitState),
510  command_lifetime_state_(internal, HebiFeedbackEnumCommandLifetimeState) {}
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_; }
529  const FloatField& deflectionVelocity() const { return deflection_velocity_; }
531  const FloatField& motorVelocity() const { return motor_velocity_; }
533  const FloatField& motorCurrent() const { return motor_current_; }
535  const FloatField& motorSensorTemperature() const { return motor_sensor_temperature_; }
537  const FloatField& motorWindingCurrent() const { return motor_winding_current_; }
539  const FloatField& motorWindingTemperature() const { return motor_winding_temperature_; }
541  const FloatField& motorHousingTemperature() const { return motor_housing_temperature_; }
543  const FloatField& pwmCommand() const { return pwm_command_; }
545  const HighResAngleField& position() const { return position_; }
547  const HighResAngleField& positionCommand() const { return position_command_; }
549  const HighResAngleField& motorPosition() const { return motor_position_; }
551  const UInt64Field& sequenceNumber() const { return sequence_number_; }
553  const EnumField<TemperatureState>& temperatureState() const { return temperature_state_; }
555  const EnumField<MstopState>& mstopState() const { return mstop_state_; }
557  const EnumField<PositionLimitState>& positionLimitState() const { return position_limit_state_; }
559  const EnumField<VelocityLimitState>& velocityLimitState() const { return velocity_limit_state_; }
561  const EnumField<EffortLimitState>& effortLimitState() const { return effort_limit_state_; }
563  const EnumField<CommandLifetimeState>& commandLifetimeState() const { return command_lifetime_state_; }
564 
566  private:
590  };
591 
593  class Mobile final {
594  public:
595 #ifndef DOXYGEN_OMIT_INTERNAL
596  Mobile(const HebiFeedbackRef& internal)
597  : battery_level_(internal, HebiFeedbackFloatBatteryLevel),
598  ar_position_(internal, HebiFeedbackVector3fArPosition),
599  ar_orientation_(internal, HebiFeedbackQuaternionfArOrientation),
600  ar_quality_(internal, HebiFeedbackEnumArQuality) {}
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)
630  : accelerometer_(internal, HebiFeedbackVector3fAccelerometer),
631  gyro_(internal, HebiFeedbackVector3fGyro),
632  orientation_(internal, HebiFeedbackQuaternionfOrientation) {}
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
HebiFeedbackQuaternionfField
Definition: hebi.h:206
struct HebiFeedback_ * HebiFeedbackPtr
The C-style&#39;s API representation of feedback.
Definition: hebi.h:451
const EnumField< MstopState > & mstopState() const
Current status of the MStop.
Definition: feedback.hpp:555
UInt64Field sequence_number_
Definition: feedback.hpp:583
UInt64Field hardware_receive_time_us_
Definition: feedback.hpp:734
const Imu & imu() const
Inertial measurement unit feedback (accelerometers and gyros).
Definition: feedback.hpp:687
const FloatField & pwmCommand() const
Commanded PWM signal sent to the motor; final output of PID controllers.
Definition: feedback.hpp:543
const HebiFeedbackRef & internal_
Definition: feedback.hpp:297
const EnumField< CommandLifetimeState > & commandLifetimeState() const
The state of the command lifetime safety controller, with respect to the current group.
Definition: feedback.hpp:563
FloatField processor_temperature_
Definition: feedback.hpp:729
HebiFeedbackIoPinBank const bank_
Definition: feedback.hpp:406
UInt64Field transmit_time_us_
Definition: feedback.hpp:733
FloatField board_temperature_
Definition: feedback.hpp:728
Structure to hold a 3-D floating point vector (i.e., x/y/z components)
Definition: vector_3_f.hpp:8
FloatField motor_winding_temperature_
Definition: feedback.hpp:577
const HebiFeedbackRef & internal_
Definition: feedback.hpp:329
#define HEBI_DISABLE_COPY(Class)
Definition: util.hpp:16
Difference between the pre-spring and post-spring output position.
Definition: hebi.h:170
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
HebiFeedbackVector3fField
Definition: hebi.h:200
FloatField voltage_
Definition: feedback.hpp:730
const HighResAngleField & motorPosition() const
The position of an actuator’s internal motor before the gear reduction, in radians.
Definition: feedback.hpp:549
const UInt64Field & hardwareTransmitTimeUs() const
Timestamp of when message was transmitted from module (remote; microseconds)
Definition: feedback.hpp:708
EnumField< CommandLifetimeState > command_lifetime_state_
Definition: feedback.hpp:589
Charge level of the device’s battery (in percent).
Definition: hebi.h:178
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
Software-controlled bounds on the allowable position of the module; user settable.
Definition: hebi.h:215
Current status of the MStop.
Definition: hebi.h:214
HebiFeedbackHighResAngleField
Definition: hebi.h:181
HighResAngleField motor_position_
Definition: feedback.hpp:582
const IoBank & c() const
I/O pin bank c (pins 1-8 available)
Definition: feedback.hpp:463
LedField led_
Definition: feedback.hpp:737
Software-controlled bounds on the allowable velocity of the module.
Definition: hebi.h:216
HebiFeedbackEnumField
Definition: hebi.h:211
const HebiFeedbackRef & internal_
Definition: feedback.hpp:158
EnumField< EffortLimitState > effort_limit_state_
Definition: feedback.hpp:588
Definition: arm.cpp:5
const FloatField & deflectionVelocity() const
Velocity (in radians/second) of the difference between the pre-spring and post-spring output position...
Definition: feedback.hpp:529
HebiFeedbackNumberedFloatField
Definition: hebi.h:187
const UInt64Field & senderId() const
Unique ID of the module transmitting this feedback.
Definition: feedback.hpp:710
The velocity of the motor shaft.
Definition: hebi.h:172
const FloatField & motorSensorTemperature() const
The temperature from a sensor near the motor housing.
Definition: feedback.hpp:535
const EnumField< TemperatureState > & temperatureState() const
Describes how the temperature inside the module is limiting the output of the motor.
Definition: feedback.hpp:553
const FloatField & motorWindingTemperature() const
The estimated temperature of the motor windings.
Definition: feedback.hpp:539
Vector3fField accelerometer_
Definition: feedback.hpp:649
FloatField effort_command_
Definition: feedback.hpp:570
HebiFeedbackLedField
Definition: hebi.h:230
Structure to hold a floating point quaternion (i.e., w/x/y/z components)
Definition: quaternion_f.hpp:8
const UInt64Field & sequenceNumber() const
Sequence number going to module (local)
Definition: feedback.hpp:551
const IoBank & d() const
I/O pin bank d (pins 1-8 available)
Definition: feedback.hpp:465
HebiFeedbackRef internal_ref_
Definition: feedback.hpp:660
NumberedFloatField debug_
Definition: feedback.hpp:731
HebiFeedbackFloatField
Feedback Enums.
Definition: hebi.h:161
const Vector3fField & arPosition() const
A device&#39;s position in the world as calculated from an augmented reality framework, in meters.
Definition: feedback.hpp:611
const FloatField & motorWindingCurrent() const
The estimated current in the motor windings.
Definition: feedback.hpp:537
HebiFeedbackLedField const field_
Definition: feedback.hpp:436
HebiFeedbackUInt64Field const field_
Definition: feedback.hpp:266
UInt64Field receive_time_us_
Definition: feedback.hpp:732
FloatField motor_winding_current_
Definition: feedback.hpp:576
const EnumField< ArQuality > & arQuality() const
The status of the augmented reality tracking, if using an AR enabled device.
Definition: feedback.hpp:615
const QuaternionfField & orientation() const
A filtered estimate of the orientation of the module.
Definition: feedback.hpp:645
HebiFeedbackVector3fField const field_
Definition: feedback.hpp:298
#define HEBI_DISABLE_COPY_MOVE(Class)
Definition: util.hpp:6
Imu(const HebiFeedbackRef &internal)
Definition: feedback.hpp:629
UInt64Field hardware_transmit_time_us_
Definition: feedback.hpp:735
const HebiFeedbackRef & internal_
Definition: feedback.hpp:234
A message field representable by a single-precision floating point value.
Definition: feedback.hpp:132
const FloatField & motorHousingTemperature() const
The estimated temperature of the motor housing.
Definition: feedback.hpp:541
Inertial measurement unit feedback (accelerometers and gyros).
Definition: feedback.hpp:626
Feedback objects have various fields representing feedback from modules; which fields are populated d...
Definition: feedback.hpp:32
I/O pin bank e (pins 1-8 available)
Definition: hebi.h:227
A message field for interfacing with a bank of I/O pins.
Definition: feedback.hpp:372
Accelerometer data.
Definition: hebi.h:202
QuaternionfField orientation_
Definition: feedback.hpp:651
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages)...
Definition: hebi.h:167
HighResAngleField position_
Definition: feedback.hpp:580
I/O pin bank b (pins 1-8 available)
Definition: hebi.h:224
A message field representable by a 3-D vector of single-precision floating point values.
Definition: feedback.hpp:303
The state of the command lifetime safety controller, with respect to the current group.
Definition: hebi.h:218
const FloatField & motorVelocity() const
The velocity (in radians/second) of the motor shaft.
Definition: feedback.hpp:531
Bus voltage at which the module is running.
Definition: hebi.h:165
const EnumField< PositionLimitState > & positionLimitState() const
Software-controlled bounds on the allowable position of the module; user settable.
Definition: feedback.hpp:557
Mobile(const HebiFeedbackRef &internal)
Definition: feedback.hpp:596
Commanded position of the module output (post-spring).
Definition: hebi.h:184
const HighResAngleField & position() const
Position of the module output (post-spring), in radians.
Definition: feedback.hpp:545
EnumField(const HebiFeedbackRef &internal, HebiFeedbackEnumField field)
Definition: feedback.hpp:338
FloatField motor_housing_temperature_
Definition: feedback.hpp:578
A message field for an angle measurement which does not lose precision at very high angles...
Definition: feedback.hpp:167
HebiStatusCode enumGetter(const RefT &ref, MetadataT &metadata, int field, int32_t *value)
HebiFeedbackUInt64Field
Definition: hebi.h:191
A message field representable by an enum of a given type.
Definition: feedback.hpp:335
const FloatField & deflection() const
Difference (in radians) between the pre-spring and post-spring output position.
Definition: feedback.hpp:527
const Actuator & actuator() const
Actuator-specific feedback.
Definition: feedback.hpp:683
const IoBank & e() const
I/O pin bank e (pins 1-8 available)
Definition: feedback.hpp:467
Current supplied to the motor.
Definition: hebi.h:173
EnumField< VelocityLimitState > velocity_limit_state_
Definition: feedback.hpp:587
I/O pin bank c (pins 1-8 available)
Definition: hebi.h:225
Temperature within normal range.
The estimated temperature of the motor windings.
Definition: hebi.h:176
const UInt64Field & hardwareReceiveTimeUs() const
Timestamp of when message was received by module (remote; microseconds)
Definition: feedback.hpp:706
const FloatField & velocityCommand() const
Commanded velocity of the module output (post-spring), in radians/second.
Definition: feedback.hpp:523
HebiFeedbackHighResAngleField const field_
Definition: feedback.hpp:209
A message field for interfacing with an LED.
Definition: feedback.hpp:410
A filtered estimate of the orientation of the module.
Definition: hebi.h:208
const HebiFeedbackRef & internal_
Definition: feedback.hpp:208
const FloatField & motorCurrent() const
Current supplied to the motor.
Definition: feedback.hpp:533
const FloatField & batteryLevel() const
Charge level of the device’s battery (in percent).
Definition: feedback.hpp:609
bool has() const
True if (and only if) the field has a value.
Definition: feedback.hpp:354
FloatField motor_velocity_
Definition: feedback.hpp:573
EnumField< MstopState > mstop_state_
Definition: feedback.hpp:585
Mobile mobile_
Definition: feedback.hpp:725
Feedback generally from a mobile device such as a phone or tablet.
Definition: feedback.hpp:593
const EnumField< EffortLimitState > & effortLimitState() const
Software-controlled bounds on the allowable effort of the module.
Definition: feedback.hpp:561
const NumberedFloatField & debug() const
Values for internal debug functions (channel 1-9 available).
Definition: feedback.hpp:699
The estimated current in the motor windings.
Definition: hebi.h:175
const HebiFeedbackRef & internal_
Definition: feedback.hpp:435
const IoBank & f() const
I/O pin bank f (pins 1-8 available)
Definition: feedback.hpp:469
const HebiFeedbackRef & internal_
Definition: feedback.hpp:405
HighResAngleField position_command_
Definition: feedback.hpp:581
Motor output beginning to be limited due to high temperature.
const HebiFeedbackRef & internal_
Definition: feedback.hpp:265
The temperature from a sensor near the motor housing.
Definition: hebi.h:174
Feedback from any available I/O pins on the device.
Definition: feedback.hpp:440
const LedField & led() const
The module&#39;s LED.
Definition: feedback.hpp:712
A message field representable by an unsigned 64 bit integer value.
Definition: feedback.hpp:239
Feedback & operator=(Feedback &&other)=delete
Temperature exceeds max allowable for electronics; motor output disabled.
const IoBank & a() const
I/O pin bank a (pins 1-8 available)
Definition: feedback.hpp:459
Io(const HebiFeedbackRef &internal)
Definition: feedback.hpp:443
FloatField deflection_velocity_
Definition: feedback.hpp:572
const Mobile & mobile() const
Feedback generally from a mobile device such as a phone or tablet.
Definition: feedback.hpp:685
Temperature exceeds max allowable for motor; motor output disabled.
Actuator actuator_
Definition: feedback.hpp:724
FloatField motor_sensor_temperature_
Definition: feedback.hpp:575
Actuator-specific feedback.
Definition: feedback.hpp:484
const HebiFeedbackRef & internal_
Definition: feedback.hpp:473
const Io & io() const
Feedback from any available I/O pins on the device.
Definition: feedback.hpp:681
EnumField< TemperatureState > temperature_state_
Definition: feedback.hpp:584
FloatField battery_level_
Definition: feedback.hpp:619
Commanded velocity of the module output (post-spring)
Definition: hebi.h:168
I/O pin bank d (pins 1-8 available)
Definition: hebi.h:226
const UInt64Field & transmitTimeUs() const
Timestamp of when message was transmitted to module (local; microseconds)
Definition: feedback.hpp:704
EnumField< PositionLimitState > position_limit_state_
Definition: feedback.hpp:586
const Vector3fField & accelerometer() const
Accelerometer data, in m/s^2.
Definition: feedback.hpp:641
const UInt64Field & receiveTimeUs() const
Timestamp of when message was received from module (local; microseconds)
Definition: feedback.hpp:702
The estimated temperature of the motor housing.
Definition: hebi.h:177
HebiFeedbackFloatField const field_
Definition: feedback.hpp:159
FloatField velocity_command_
Definition: feedback.hpp:569
Vector3fField ar_position_
Definition: feedback.hpp:620
EnumField< ArQuality > ar_quality_
Definition: feedback.hpp:622
Velocity of the difference between the pre-spring and post-spring output position.
Definition: hebi.h:171
HebiFeedbackQuaternionfField const field_
Definition: feedback.hpp:330
const IoBank & b() const
I/O pin bank b (pins 1-8 available)
Definition: feedback.hpp:461
const HighResAngleField & positionCommand() const
Commanded position of the module output (post-spring), in radians.
Definition: feedback.hpp:547
const HebiFeedbackRef & internal_
Definition: feedback.hpp:367
Structure to describe an RGB color.
Definition: color.hpp:8
Describes how the temperature inside the module is limiting the output of the motor.
Definition: hebi.h:213
const FloatField & voltage() const
Bus voltage that the module is running at (in Volts).
Definition: feedback.hpp:696
HebiFeedbackNumberedFloatField const field_
Definition: feedback.hpp:235
I/O pin bank a (pins 1-8 available)
Definition: hebi.h:223
HebiFeedbackIoPinBank
Definition: hebi.h:221
const FloatField & velocity() const
Velocity of the module output (post-spring), in radians/second.
Definition: feedback.hpp:519
UInt64Field sender_id_
Definition: feedback.hpp:736
A message field containing a numbered set of single-precision floating point values.
Definition: feedback.hpp:214
const QuaternionfField & arOrientation() const
A device&#39;s orientation in the world as calculated from an augmented reality framework.
Definition: feedback.hpp:613
Position of the module output (post-spring).
Definition: hebi.h:183
A message field representable by a 3-D vector of single-precision floating point values.
Definition: feedback.hpp:271
const FloatField & processorTemperature() const
Temperature of the processor chip, in degrees Celsius.
Definition: feedback.hpp:694
Vector3fField gyro_
Definition: feedback.hpp:650
Actuator(const HebiFeedbackRef &internal)
Definition: feedback.hpp:487
const EnumField< VelocityLimitState > & velocityLimitState() const
Software-controlled bounds on the allowable velocity of the module.
Definition: feedback.hpp:559
Software-controlled bounds on the allowable effort of the module.
Definition: hebi.h:217
HebiFeedbackPtr internal_
Definition: feedback.hpp:659
const FloatField & boardTemperature() const
Ambient temperature inside the module (measured at the IMU chip), in degrees Celsius.
Definition: feedback.hpp:692
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
const Vector3fField & gyro() const
Gyro data, in radians/second.
Definition: feedback.hpp:643
QuaternionfField ar_orientation_
Definition: feedback.hpp:621
Commanded effort at the module output; units vary (e.g., N * m for rotational joints and N for linear...
Definition: hebi.h:169
Velocity of the module output (post-spring).
Definition: hebi.h:166
HebiFeedbackEnumField const field_
Definition: feedback.hpp:368


hebi_cpp_api_ros
Author(s): Chris Bollinger , Matthew Tesch
autogenerated on Thu May 28 2020 03:14:44