feedback.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include "hebi.h"
4 #include "color.hpp"
5 #include "vector_3_f.hpp"
6 #include "quaternion_f.hpp"
7 #include "util.hpp"
8 
9 namespace hebi {
10 
30 class Feedback final
31  {
32  public:
33  enum class TemperatureState
34  {
36  Normal,
38  Critical,
43  };
44 
45  enum class MstopState
46  {
48  Triggered,
50  NotTriggered,
51  };
52 
53  enum class PositionLimitState
54  {
56  Below,
58  AtLower,
60  Inside,
62  AtUpper,
64  Above,
66  Uninitialized,
67  };
68 
69  enum class VelocityLimitState
70  {
72  Below,
74  AtLower,
76  Inside,
78  AtUpper,
80  Above,
82  Uninitialized,
83  };
84 
85  enum class EffortLimitState
86  {
88  Below,
90  AtLower,
92  Inside,
94  AtUpper,
96  Above,
98  Uninitialized,
99  };
100 
102  {
104  Unlocked,
106  LockedByOther,
108  LockedBySender,
109  };
110 
111  // Note: this is 'protected' instead of 'private' for easier use with Doxygen
112  protected:
114  class FloatField final
115  {
116  public:
117  #ifndef DOXYGEN_OMIT_INTERNAL
119  #endif // DOXYGEN_OMIT_INTERNAL
120  explicit operator bool() const;
134  bool has() const;
137  float get() const;
138 
139  private:
142 
144  };
150  class HighResAngleField final
151  {
152  public:
153  #ifndef DOXYGEN_OMIT_INTERNAL
155  #endif // DOXYGEN_OMIT_INTERNAL
156  explicit operator bool() const;
170  bool has() const;
176  double get() const;
188  void get(int64_t* revolutions, float* radian_offset) const;
189 
190  private:
193 
195  };
196 
199  class NumberedFloatField final
200  {
201  public:
202  #ifndef DOXYGEN_OMIT_INTERNAL
204  #endif // DOXYGEN_OMIT_INTERNAL
205  bool has(size_t fieldNumber) const;
216  float get(size_t fieldNumber) const;
217 
218  private:
221 
223  };
224 
226  class UInt64Field final
227  {
228  public:
229  #ifndef DOXYGEN_OMIT_INTERNAL
231  #endif // DOXYGEN_OMIT_INTERNAL
232  explicit operator bool() const;
246  bool has() const;
249  uint64_t get() const;
250 
251  private:
254 
256  };
259  class Vector3fField final
260  {
261  public:
262  #ifndef DOXYGEN_OMIT_INTERNAL
264  #endif // DOXYGEN_OMIT_INTERNAL
265  explicit operator bool() const;
279  bool has() const;
282  Vector3f get() const;
283 
284  private:
287 
289  };
290 
293  class QuaternionfField final {
294  public:
295  #ifndef DOXYGEN_OMIT_INTERNAL
297  #endif // DOXYGEN_OMIT_INTERNAL
298  explicit operator bool() const;
312  bool has() const;
315  Quaternionf get() const;
316 
317  private:
320 
322  };
323 
325  template <typename T>
326  class EnumField final
327  {
328  public:
329  #ifndef DOXYGEN_OMIT_INTERNAL
331  : internal_(internal), field_(field) {}
332  #endif // DOXYGEN_OMIT_INTERNAL
333  explicit operator bool() const { return has(); }
347  bool has() const { return (hebiFeedbackGetEnum(internal_, field_, nullptr) == HebiStatusSuccess); }
350  T get() const { int32_t ret; hebiFeedbackGetEnum(internal_, field_, &ret); return static_cast<T>(ret); }
351 
352  private:
355 
357  };
358 
360  class IoBank final
361  {
362  public:
363  #ifndef DOXYGEN_OMIT_INTERNAL
365  #endif // DOXYGEN_OMIT_INTERNAL
366  bool hasInt(size_t pinNumber) const;
377  bool hasFloat(size_t pinNumber) const;
383  int64_t getInt(size_t pinNumber) const;
390  float getFloat(size_t pinNumber) const;
391 
392  private:
395 
397  };
399  class LedField final
400  {
401  public:
402  #ifndef DOXYGEN_OMIT_INTERNAL
404  #endif // DOXYGEN_OMIT_INTERNAL
405  explicit operator bool() const { return hasColor(); }
419  bool hasColor() const;
421  Color getColor() const;
422 
423  private:
426 
428  };
429 
431  class Io final
432  {
433  public:
434  #ifndef DOXYGEN_OMIT_INTERNAL
435  Io(HebiFeedbackPtr internal)
436  : internal_(internal),
443  {
444  }
445  #endif // DOXYGEN_OMIT_INTERNAL
446 
447  // With all submessage and field getters: Note that the returned reference
448  // should not be used after the lifetime of this parent.
449 
450  // Subfields ----------------
451 
453  const IoBank& a() const { return a_; }
455  const IoBank& b() const { return b_; }
457  const IoBank& c() const { return c_; }
459  const IoBank& d() const { return d_; }
461  const IoBank& e() const { return e_; }
463  const IoBank& f() const { return f_; }
464 
465  private:
467 
474 
476  };
477 
479  class Actuator final
480  {
481  public:
482  #ifndef DOXYGEN_OMIT_INTERNAL
484  : internal_(internal),
487  velocity_command_(internal, HebiFeedbackFloatVelocityCommand),
488  effort_command_(internal, HebiFeedbackFloatEffortCommand),
490  deflection_velocity_(internal, HebiFeedbackFloatDeflectionVelocity),
491  motor_velocity_(internal, HebiFeedbackFloatMotorVelocity),
492  motor_current_(internal, HebiFeedbackFloatMotorCurrent),
493  motor_sensor_temperature_(internal, HebiFeedbackFloatMotorSensorTemperature),
494  motor_winding_current_(internal, HebiFeedbackFloatMotorWindingCurrent),
495  motor_winding_temperature_(internal, HebiFeedbackFloatMotorWindingTemperature),
496  motor_housing_temperature_(internal, HebiFeedbackFloatMotorHousingTemperature),
499  sequence_number_(internal, HebiFeedbackUInt64SequenceNumber),
500  receive_time_(internal, HebiFeedbackUInt64ReceiveTime),
501  transmit_time_(internal, HebiFeedbackUInt64TransmitTime),
502  hardware_receive_time_(internal, HebiFeedbackUInt64HardwareReceiveTime),
503  hardware_transmit_time_(internal, HebiFeedbackUInt64HardwareTransmitTime),
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  {
512  }
513  #endif // DOXYGEN_OMIT_INTERNAL
514 
515  // With all submessage and field getters: Note that the returned reference
516  // should not be used after the lifetime of this parent.
517 
518  // Subfields ----------------
519 
521  const FloatField& velocity() const { return velocity_; }
523  const FloatField& effort() const { return effort_; }
525  const FloatField& velocityCommand() const { return velocity_command_; }
527  const FloatField& effortCommand() const { return effort_command_; }
529  const FloatField& deflection() const { return deflection_; }
531  const FloatField& deflectionVelocity() const { return deflection_velocity_; }
533  const FloatField& motorVelocity() const { return motor_velocity_; }
535  const FloatField& motorCurrent() const { return motor_current_; }
537  const FloatField& motorSensorTemperature() const { return motor_sensor_temperature_; }
539  const FloatField& motorWindingCurrent() const { return motor_winding_current_; }
541  const FloatField& motorWindingTemperature() const { return motor_winding_temperature_; }
543  const FloatField& motorHousingTemperature() const { return motor_housing_temperature_; }
545  const HighResAngleField& position() const { return position_; }
547  const HighResAngleField& positionCommand() const { return position_command_; }
549  const UInt64Field& sequenceNumber() const { return sequence_number_; }
551  const UInt64Field& receiveTime() const { return receive_time_; }
553  const UInt64Field& transmitTime() const { return transmit_time_; }
555  const UInt64Field& hardwareReceiveTime() const { return hardware_receive_time_; }
557  const UInt64Field& hardwareTransmitTime() const { return hardware_transmit_time_; }
559  const UInt64Field& senderId() const { return sender_id_; }
561  const EnumField<TemperatureState>& temperatureState() const { return temperature_state_; }
563  const EnumField<MstopState>& mstopState() const { return mstop_state_; }
565  const EnumField<PositionLimitState>& positionLimitState() const { return position_limit_state_; }
567  const EnumField<VelocityLimitState>& velocityLimitState() const { return velocity_limit_state_; }
569  const EnumField<EffortLimitState>& effortLimitState() const { return effort_limit_state_; }
571  const EnumField<CommandLifetimeState>& commandLifetimeState() const { return command_lifetime_state_; }
572 
573  private:
575 
602 
604  };
605 
607  class Imu final
608  {
609  public:
610  #ifndef DOXYGEN_OMIT_INTERNAL
612  : internal_(internal),
616  {
617  }
618  #endif // DOXYGEN_OMIT_INTERNAL
619 
620  // With all submessage and field getters: Note that the returned reference
621  // should not be used after the lifetime of this parent.
622 
623  // Subfields ----------------
624 
626  const Vector3fField& accelerometer() const { return accelerometer_; }
628  const Vector3fField& gyro() const { return gyro_; }
630  const QuaternionfField& orientation() const { return orientation_; }
631 
632  private:
634 
638 
640  };
641 
642  private:
648 
649  public:
650  #ifndef DOXYGEN_OMIT_INTERNAL
651 
656  #endif // DOXYGEN_OMIT_INTERNAL
657 
660  Feedback(Feedback&& other);
664  ~Feedback() noexcept; /* annotating specified destructor as noexcept is best-practice */
665 
666  // With all submessage and field getters: Note that the returned reference
667  // should not be used after the lifetime of this parent.
668 
669  // Submessages -------------------------------------------------------------
670 
672  const Io& io() const { return io_; }
674  const Actuator& actuator() const { return actuator_; }
676  const Imu& imu() const { return imu_; }
677 
678  // Subfields -------------------------------------------------------------
679 
681  const FloatField& boardTemperature() const;
683  const FloatField& processorTemperature() const;
685  const FloatField& voltage() const;
686  #ifndef DOXYGEN_OMIT_INTERNAL
687  const NumberedFloatField& debug() const;
689  #endif // DOXYGEN_OMIT_INTERNAL
690  const LedField& led() const;
692 
693  private:
697 
703 
708 
709  /* Disable move assigment operator. */
710  Feedback& operator= (const Feedback&& other) = delete;
711 };
712 
713 } // namespace hebi
HebiFeedbackQuaternionfField
Definition: hebi.h:169
const EnumField< MstopState > & mstopState() const
Current status of the MStop.
Definition: feedback.hpp:563
UInt64Field sequence_number_
Definition: feedback.hpp:590
Timestamp of when message was received from module (local)
Definition: hebi.h:158
const Imu & imu() const
Inertial measurement unit feedback (accelerometers and gyros).
Definition: feedback.hpp:676
HebiFeedbackPtr const internal_
Definition: feedback.hpp:424
const EnumField< CommandLifetimeState > & commandLifetimeState() const
The state of the command lifetime safety controller, with respect to the current group.
Definition: feedback.hpp:571
FloatField processor_temperature_
Definition: feedback.hpp:699
UInt64Field hardware_receive_time_
Definition: feedback.hpp:593
HebiFeedbackIoPinBank const bank_
Definition: feedback.hpp:394
Io(HebiFeedbackPtr internal)
Definition: feedback.hpp:435
const NumberedFloatField & debug() const
Values for internal debug functions (channel 1-9 available).
Definition: feedback.cpp:264
EnumField(HebiFeedbackPtr internal, HebiFeedbackEnumField field)
Definition: feedback.hpp:330
const UInt64Field & transmitTime() const
Timestamp of when message was transmitted to module (local)
Definition: feedback.hpp:553
FloatField board_temperature_
Definition: feedback.hpp:698
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:586
#define HEBI_DISABLE_COPY(Class)
Definition: util.hpp:17
Difference (in radians) between the pre-spring and post-spring output position.
Definition: hebi.h:137
Feedback(HebiFeedbackPtr)
Wraps an existing C-style object that is managed by its parent. NOTE: this should not be used except ...
Definition: feedback.cpp:221
HebiFeedbackVector3fField
Definition: hebi.h:164
FloatField voltage_
Definition: feedback.hpp:700
HebiFeedbackPtr const internal_
Definition: feedback.hpp:574
EnumField< CommandLifetimeState > command_lifetime_state_
Definition: feedback.hpp:601
const FloatField & boardTemperature() const
Ambient temperature inside the module (measured at the IMU chip), in degrees Celsius.
Definition: feedback.cpp:252
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:527
Software-controlled bounds on the allowable position of the module; user settable.
Definition: hebi.h:177
HebiFeedbackPtr const internal_
Definition: feedback.hpp:191
~Feedback() noexcept
Cleans up feedback object as necessary.
Definition: feedback.cpp:233
Current status of the MStop.
Definition: hebi.h:176
HebiFeedbackHighResAngleField
Definition: hebi.h:146
const IoBank & c() const
I/O pin bank c (pins 1-8 available)
Definition: feedback.hpp:457
LedField led_
Definition: feedback.hpp:702
Software-controlled bounds on the allowable velocity of the module.
Definition: hebi.h:178
HebiFeedbackPtr const internal_
Definition: feedback.hpp:140
HebiFeedbackEnumField
Definition: hebi.h:173
EnumField< EffortLimitState > effort_limit_state_
Definition: feedback.hpp:600
Definition: color.hpp:5
const FloatField & deflectionVelocity() const
Velocity (in radians/second) of the difference between the pre-spring and post-spring output position...
Definition: feedback.hpp:531
HebiFeedbackNumberedFloatField
Definition: hebi.h:151
const UInt64Field & hardwareTransmitTime() const
Timestamp of when message was transmitted from module (remote)
Definition: feedback.hpp:557
The velocity (in radians/second) of the motor shaft.
Definition: hebi.h:139
const FloatField & motorSensorTemperature() const
The temperature from a sensor near the motor housing.
Definition: feedback.hpp:537
const EnumField< TemperatureState > & temperatureState() const
Describes how the temperature inside the module is limiting the output of the motor.
Definition: feedback.hpp:561
const FloatField & motorWindingTemperature() const
The estimated temperature of the motor windings.
Definition: feedback.hpp:541
Vector3fField accelerometer_
Definition: feedback.hpp:635
FloatField effort_command_
Definition: feedback.hpp:579
HebiFeedbackLedField
Definition: hebi.h:191
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:549
HebiFeedbackPtr const internal_
Definition: feedback.hpp:633
const IoBank & d() const
I/O pin bank d (pins 1-8 available)
Definition: feedback.hpp:459
NumberedFloatField debug_
Definition: feedback.hpp:701
HebiFeedbackFloatField
Definition: hebi.h:128
const FloatField & motorWindingCurrent() const
The estimated current in the motor windings.
Definition: feedback.hpp:539
HebiFeedbackPtr const internal_
Definition: feedback.hpp:466
HebiFeedbackLedField const field_
Definition: feedback.hpp:425
const UInt64Field & hardwareReceiveTime() const
Timestamp of when message was received by module (remote)
Definition: feedback.hpp:555
Sequence number going to module (local)
Definition: hebi.h:157
HebiFeedbackUInt64Field const field_
Definition: feedback.hpp:253
FloatField motor_winding_current_
Definition: feedback.hpp:585
const QuaternionfField & orientation() const
On-board filtered orientation estimate.
Definition: feedback.hpp:630
HebiFeedbackVector3fField const field_
Definition: feedback.hpp:286
#define HEBI_DISABLE_COPY_MOVE(Class)
Definition: util.hpp:7
A message field representable by a single-precision floating point value.
Definition: feedback.hpp:114
const FloatField & motorHousingTemperature() const
The estimated temperature of the motor housing.
Definition: feedback.hpp:543
Inertial measurement unit feedback (accelerometers and gyros).
Definition: feedback.hpp:607
Feedback objects have various fields representing feedback from modules; which fields are populated d...
Definition: feedback.hpp:30
I/O pin bank e (pins 1-8 available)
Definition: hebi.h:188
A message field for interfacing with a bank of I/O pins.
Definition: feedback.hpp:360
Accelerometer data, in m/s^2.
Definition: hebi.h:166
QuaternionfField orientation_
Definition: feedback.hpp:637
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages)...
Definition: hebi.h:134
HebiFeedbackPtr const internal_
Definition: feedback.hpp:252
HighResAngleField position_
Definition: feedback.hpp:588
I/O pin bank b (pins 1-8 available)
Definition: hebi.h:185
const UInt64Field & receiveTime() const
Timestamp of when message was received from module (local)
Definition: feedback.hpp:551
A message field representable by a 3-D vector of single-precision floating point values.
Definition: feedback.hpp:293
const FloatField & motorVelocity() const
The velocity (in radians/second) of the motor shaft.
Definition: feedback.hpp:533
Bus voltage that the module is running at (in Volts).
Definition: hebi.h:132
const EnumField< PositionLimitState > & positionLimitState() const
Software-controlled bounds on the allowable position of the module; user settable.
Definition: feedback.hpp:565
Actuator(HebiFeedbackPtr internal)
Definition: feedback.hpp:483
HebiFeedbackPtr const internal_
Definition: feedback.hpp:393
const HighResAngleField & position() const
Position of the module output (post-spring), in radians.
Definition: feedback.hpp:545
const LedField & led() const
The module&#39;s LED.
Definition: feedback.cpp:268
FloatField motor_housing_temperature_
Definition: feedback.hpp:587
A message field for an angle measurement which does not lose precision at very high angles...
Definition: feedback.hpp:150
HebiFeedbackPtr const internal_
Definition: feedback.hpp:353
HebiFeedbackUInt64Field
Definition: hebi.h:155
A message field representable by an enum of a given type.
Definition: feedback.hpp:326
const FloatField & deflection() const
Difference (in radians) between the pre-spring and post-spring output position.
Definition: feedback.hpp:529
const Actuator & actuator() const
Actuator-specific feedback.
Definition: feedback.hpp:674
const IoBank & e() const
I/O pin bank e (pins 1-8 available)
Definition: feedback.hpp:461
Current supplied to the motor.
Definition: hebi.h:140
EnumField< VelocityLimitState > velocity_limit_state_
Definition: feedback.hpp:599
I/O pin bank c (pins 1-8 available)
Definition: hebi.h:186
Temperature within normal range.
The estimated temperature of the motor windings.
Definition: hebi.h:143
Timestamp of when message was transmitted to module (local)
Definition: hebi.h:159
const FloatField & velocityCommand() const
Commanded velocity of the module output (post-spring), in radians/second.
Definition: feedback.hpp:525
HebiFeedbackHighResAngleField const field_
Definition: feedback.hpp:192
UInt64Field hardware_transmit_time_
Definition: feedback.hpp:594
HebiStatusCode hebiFeedbackGetEnum(HebiFeedbackPtr, HebiFeedbackEnumField, int32_t *)
A message field for interfacing with an LED.
Definition: feedback.hpp:399
const FloatField & voltage() const
Bus voltage that the module is running at (in Volts).
Definition: feedback.cpp:260
const FloatField & motorCurrent() const
Current supplied to the motor.
Definition: feedback.hpp:535
ROSCPP_DECL bool has(const std::string &key)
bool has() const
True if (and only if) the field has a value.
Definition: feedback.hpp:347
FloatField motor_velocity_
Definition: feedback.hpp:582
EnumField< MstopState > mstop_state_
Definition: feedback.hpp:597
const EnumField< EffortLimitState > & effortLimitState() const
Software-controlled bounds on the allowable effort of the module.
Definition: feedback.hpp:569
HebiFeedbackPtr const internal_
Definition: feedback.hpp:318
The estimated current in the motor windings.
Definition: hebi.h:142
Timestamp of when message was transmitted from module (remote)
Definition: hebi.h:161
const IoBank & f() const
I/O pin bank f (pins 1-8 available)
Definition: feedback.hpp:463
HighResAngleField position_command_
Definition: feedback.hpp:589
Motor output beginning to be limited due to high temperature.
The temperature from a sensor near the motor housing.
Definition: hebi.h:141
Feedback from any available I/O pins on the device.
Definition: feedback.hpp:431
A message field representable by an unsigned 64 bit integer value.
Definition: feedback.hpp:226
const UInt64Field & senderId() const
Unique ID of the module transmitting this feedback.
Definition: feedback.hpp:559
Temperature exceeds max allowable for electronics; motor output disabled.
struct _HebiFeedback * HebiFeedbackPtr
The C-style&#39;s API representation of feedback.
Definition: hebi.h:322
const IoBank & a() const
I/O pin bank a (pins 1-8 available)
Definition: feedback.hpp:453
FloatField deflection_velocity_
Definition: feedback.hpp:581
Temperature exceeds max allowable for motor; motor output disabled.
Actuator actuator_
Definition: feedback.hpp:695
const FloatField & processorTemperature() const
Temperature of the processor chip, in degrees Celsius.
Definition: feedback.cpp:256
FloatField motor_sensor_temperature_
Definition: feedback.hpp:584
Actuator-specific feedback.
Definition: feedback.hpp:479
UInt64Field receive_time_
Definition: feedback.hpp:591
Imu(HebiFeedbackPtr internal)
Definition: feedback.hpp:611
const Io & io() const
Feedback from any available I/O pins on the device.
Definition: feedback.hpp:672
EnumField< TemperatureState > temperature_state_
Definition: feedback.hpp:596
Commanded velocity of the module output (post-spring), in radians/second.
Definition: hebi.h:135
I/O pin bank d (pins 1-8 available)
Definition: hebi.h:187
HebiFeedbackPtr const internal_
Definition: feedback.hpp:219
EnumField< PositionLimitState > position_limit_state_
Definition: feedback.hpp:598
const Vector3fField & accelerometer() const
Accelerometer data, in m/s^2.
Definition: feedback.hpp:626
HebiFeedbackFloatField const field_
Definition: feedback.hpp:141
FloatField velocity_command_
Definition: feedback.hpp:578
Velocity (in radians/second) of the difference between the pre-spring and post-spring output position...
Definition: hebi.h:138
HebiFeedbackQuaternionfField const field_
Definition: feedback.hpp:319
const IoBank & b() const
I/O pin bank b (pins 1-8 available)
Definition: feedback.hpp:455
const HighResAngleField & positionCommand() const
Commanded position of the module output (post-spring), in radians.
Definition: feedback.hpp:547
HebiFeedbackPtr const internal_
Definition: feedback.hpp:285
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:175
HebiFeedbackNumberedFloatField const field_
Definition: feedback.hpp:220
Timestamp of when message was received by module (remote)
Definition: hebi.h:160
I/O pin bank a (pins 1-8 available)
Definition: hebi.h:184
HebiFeedbackIoPinBank
Definition: hebi.h:182
const FloatField & velocity() const
Velocity of the module output (post-spring), in radians/second.
Definition: feedback.hpp:521
A message field containing a numbered set of single-precision floating point values.
Definition: feedback.hpp:199
Position of the module output (post-spring), in radians.
Definition: hebi.h:148
A message field representable by a 3-D vector of single-precision floating point values.
Definition: feedback.hpp:259
Vector3fField gyro_
Definition: feedback.hpp:636
const EnumField< VelocityLimitState > & velocityLimitState() const
Software-controlled bounds on the allowable velocity of the module.
Definition: feedback.hpp:567
Software-controlled bounds on the allowable effort of the module.
Definition: hebi.h:179
HebiFeedbackPtr internal_
Definition: feedback.hpp:647
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:523
const Vector3fField & gyro() const
Gyro data, in radians/second.
Definition: feedback.hpp:628
Commanded effort at the module output; units vary (e.g., N * m for rotational joints and N for linear...
Definition: hebi.h:136
Velocity of the module output (post-spring), in radians/second.
Definition: hebi.h:133
HebiFeedbackEnumField const field_
Definition: feedback.hpp:354
UInt64Field transmit_time_
Definition: feedback.hpp:592


hebiros
Author(s): Xavier Artache , Matthew Tesch
autogenerated on Thu Sep 3 2020 04:08:11