Class Feedback
Defined in File feedback.hpp
Nested Relationships
Nested Types
Class Documentation
-
class Feedback
Feedback objects have various fields representing feedback from modules; which fields are populated depends on the module type and various other settings.
This object has a hierarchical structure — there are some direct general-purpose fields at the top level, and many more specific fields contained in different nested subobjects.
The subobjects contain references to the parent feedback object, and so should not be used after the parent object has been destroyed.
The fields in the feedback object are typed; generally, these are optional-style read-only fields (i.e., have the concept of has/get), although the return types and exact interface vary slightly between fields. Where appropriate, the explicit bool operator has been overridden so that you can shortcut
if
(field.has()) by callingif(field)
.Although this header file can be used to look at the hierarchy of the messages, in general the online documentation at apidocs.hebi.us presents this information. in a more readable form.
Public Types
-
enum class TemperatureState
Values:
-
enumerator Normal
Temperature within normal range.
-
enumerator Critical
Motor output beginning to be limited due to high temperature.
-
enumerator ExceedMaxMotor
Temperature exceeds max allowable for motor; motor output disabled.
-
enumerator ExceedMaxBoard
Temperature exceeds max allowable for electronics; motor output disabled.
-
enumerator Normal
-
enum class MstopState
Values:
-
enumerator Triggered
The MStop is pressed.
-
enumerator NotTriggered
The MStop is not pressed.
-
enumerator Triggered
-
enum class PositionLimitState
Values:
-
enumerator Below
The position of the module was below the lower safety limit; the motor output is set to return the module to within the limits
-
enumerator AtLower
The position of the module was near the lower safety limit, and the motor output is being limited or reversed.
-
enumerator Inside
The position of the module was within the safety limits.
-
enumerator AtUpper
The position of the module was near the upper safety limit, and the motor output is being limited or reversed.
-
enumerator Above
The position of the module was above the upper safety limit; the motor output is set to return the module to within the limits
-
enumerator Uninitialized
The module has not been inside the safety limits since it was booted or the safety limits were set.
-
enumerator Below
-
enum class VelocityLimitState
Values:
-
enumerator Below
The velocity of the module was below the lower safety limit; the motor output is set to return the module to within the limits
-
enumerator AtLower
The velocity of the module was near the lower safety limit, and the motor output is being limited or reversed.
-
enumerator Inside
The velocity of the module was within the safety limits.
-
enumerator AtUpper
The velocity of the module was near the upper safety limit, and the motor output is being limited or reversed.
-
enumerator Above
The velocity of the module was above the upper safety limit; the motor output is set to return the module to within the limits
-
enumerator Uninitialized
The module has not been inside the safety limits since it was booted or the safety limits were set.
-
enumerator Below
-
enum class EffortLimitState
Values:
-
enumerator Below
The effort of the module was below the lower safety limit; the motor output is set to return the module to within the limits
-
enumerator AtLower
The effort of the module was near the lower safety limit, and the motor output is being limited or reversed.
-
enumerator Inside
The effort of the module was within the safety limits.
-
enumerator AtUpper
The effort of the module was near the upper safety limit, and the motor output is being limited or reversed.
-
enumerator Above
The effort of the module was above the upper safety limit; the motor output is set to return the module to within the limits
-
enumerator Uninitialized
The module has not been inside the safety limits since it was booted or the safety limits were set.
-
enumerator Below
-
enum class CommandLifetimeState
Values:
-
enumerator Unlocked
There is not command lifetime active on this module.
-
enumerator LockedByOther
Commands are locked out due to control from other users.
-
enumerator LockedBySender
Commands from others are locked out due to control from this group.
-
enumerator Unlocked
-
enum class ArQuality
Values:
-
enumerator ArQualityNotAvailable
Camera position tracking is not available.
-
enumerator ArQualityLimitedUnknown
Tracking is available albeit suboptimal for an unknown reason.
-
enumerator ArQualityLimitedInitializing
The AR session has not yet gathered enough camera or motion data to provide tracking information.
-
enumerator ArQualityLimitedRelocalizing
The AR session is attempting to resume after an interruption.
-
enumerator ArQualityLimitedExcessiveMotion
The device is moving too fast for accurate image-based position tracking.
-
enumerator ArQualityLimitedInsufficientFeatures
The scene visible to the camera does not contain enough distinguishable features for image-based position tracking.
-
enumerator ArQualityNormal
Camera position tracking is providing optimal results.
-
enumerator ArQualityNotAvailable
Public Functions
-
Feedback(HebiFeedbackPtr)
Wraps an existing C-style object that is managed by its parent. NOTE: this should not be used except by internal library functions!
-
inline const Mobile &mobile() const
Feedback generally from a mobile device such as a phone or tablet.
-
inline const FloatField &boardTemperature() const
Ambient temperature inside the module (measured at the IMU chip), in degrees Celsius.
-
inline const FloatField &processorTemperature() const
Temperature of the processor chip, in degrees Celsius.
-
inline const FloatField &voltage() const
Bus voltage that the module is running at (in Volts).
-
inline const NumberedFloatField &debug() const
Values for internal debug functions (channel 1-9 available).
-
inline const UInt64Field &sequenceNumber() const
Sequence number going to module (local)
-
inline const UInt64Field &receiveTimeUs() const
Timestamp of when message was received from module (local; microseconds)
-
inline const UInt64Field &transmitTimeUs() const
Timestamp of when message was transmitted to module (local; microseconds)
-
inline const UInt64Field &hardwareReceiveTimeUs() const
Timestamp of when message was received by module (remote; microseconds)
-
inline const UInt64Field &hardwareTransmitTimeUs() const
Timestamp of when message was transmitted from module (remote; microseconds)
-
inline const UInt64Field &senderId() const
Unique ID of the module transmitting this feedback.
-
inline const UInt64Field &rxSequenceNumber() const
Sequence number of incoming packet per module (local)
-
class Actuator
Actuator-specific feedback.
Public Functions
-
inline Actuator(const HebiFeedbackRef &internal)
-
inline const FloatField &velocity() const
Velocity of the module output (post-spring), in radians/second.
-
inline const FloatField &effort() const
Effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages).
-
inline const FloatField &velocityCommand() const
Commanded velocity of the module output (post-spring), in radians/second.
-
inline const FloatField &effortCommand() const
Commanded effort at the module output; units vary (e.g., N * m for rotational joints and N for linear stages).
-
inline const FloatField &deflection() const
Difference (in radians) between the pre-spring and post-spring output position.
-
inline const FloatField &deflectionVelocity() const
Velocity (in radians/second) of the difference between the pre-spring and post-spring output position.
-
inline const FloatField &motorVelocity() const
The velocity (in radians/second) of the motor shaft.
-
inline const FloatField &motorCurrent() const
Current supplied to the motor.
-
inline const FloatField &motorSensorTemperature() const
The temperature from a sensor near the motor housing.
-
inline const FloatField &motorWindingCurrent() const
The estimated current in the motor windings.
-
inline const FloatField &motorWindingTemperature() const
The estimated temperature of the motor windings.
-
inline const FloatField &motorHousingTemperature() const
The estimated temperature of the motor housing.
-
inline const FloatField &pwmCommand() const
Commanded PWM signal sent to the motor; final output of PID controllers.
-
inline const FloatField &innerEffortCommand() const
In control strategies 2 and 4, this is the torque of force command going to the inner torque PID loop.
-
inline const HighResAngleField &position() const
Position of the module output (post-spring), in radians.
-
inline const HighResAngleField &positionCommand() const
Commanded position of the module output (post-spring), in radians.
-
inline const HighResAngleField &motorPosition() const
The position of an actuator’s internal motor before the gear reduction, in radians.
-
inline const EnumField<TemperatureState> &temperatureState() const
Describes how the temperature inside the module is limiting the output of the motor.
-
inline const EnumField<MstopState> &mstopState() const
Current status of the MStop.
-
inline const EnumField<PositionLimitState> &positionLimitState() const
Software-controlled bounds on the allowable position of the module; user settable.
-
inline const EnumField<VelocityLimitState> &velocityLimitState() const
Software-controlled bounds on the allowable velocity of the module.
-
inline const EnumField<EffortLimitState> &effortLimitState() const
Software-controlled bounds on the allowable effort of the module.
-
inline const EnumField<CommandLifetimeState> &commandLifetimeState() const
The state of the command lifetime safety controller, with respect to the current group.
-
inline Actuator(const HebiFeedbackRef &internal)
-
template<typename T>
class EnumField A message field representable by an enum of a given type.
Public Functions
-
inline EnumField(const HebiFeedbackRef &internal, HebiFeedbackEnumField field)
-
inline explicit operator bool() const
Allows casting to a bool to check if the field has a value without directly calling
has()
.This can be used as in the following (assuming ‘parent’ is a parent message, and this field is called ‘myField’)
Feedback::EnumField& f = parent.myField(); if (f) std::cout << "Field has value: " << f.get() << std::endl; else std::cout << "Field has no value!" << std::endl;
-
inline bool has() const
True if (and only if) the field has a value.
-
inline EnumField(const HebiFeedbackRef &internal, HebiFeedbackEnumField field)
-
class FloatField
A message field representable by a single-precision floating point value.
Public Functions
-
FloatField(const HebiFeedbackRef &internal, HebiFeedbackFloatField field)
-
inline explicit operator bool() const
Allows casting to a bool to check if the field has a value without directly calling
has()
.This can be used as in the following (assuming ‘parent’ is a parent message, and this field is called ‘myField’)
Feedback::FloatField& f = parent.myField(); if (f) std::cout << "Field has value: " << f.get() << std::endl; else std::cout << "Field has no value!" << std::endl;
-
bool has() const
True if (and only if) the field has a value.
-
float get() const
If the field has a value, returns that value; otherwise, returns a default.
-
FloatField(const HebiFeedbackRef &internal, HebiFeedbackFloatField field)
-
class HighResAngleField
A message field for an angle measurement which does not lose precision at very high angles.
This field is represented as an int64_t for the number of revolutions and a float for the radian offset from that number of revolutions.
Public Functions
-
HighResAngleField(const HebiFeedbackRef &internal, HebiFeedbackHighResAngleField field)
-
inline explicit operator bool() const
Allows casting to a bool to check if the field has a value without directly calling
has()
.This can be used as in the following (assuming ‘parent’ is a parent message, and this field is called ‘myField’)
Feedback::HighResAngleField& f = parent.myField(); if (f) std::cout << "Field has value: " << f.get() << std::endl; else std::cout << "Field has no value!" << std::endl;
-
bool has() const
True if (and only if) the field has a value.
-
double get() const
If the field has a value, returns that value as a double; otherwise, returns a default.
Note that some precision might be lost converting to a double at very high number of revolutions.
-
void get(int64_t *revolutions, float *radian_offset) const
If the field has a value, returns that value in the int64 and float parameters passed in; otherwise, returns a default.
Note that this maintains the full precision of the underlying angle measurement, even for very large numbers of revolutions.
- Parameters:
revolutions – The number of full revolutions
radian_offset – The offset from the given number of full revolutions. Note that this is usually between 0 and
2*M_PI
, but callers should not assume this.
-
HighResAngleField(const HebiFeedbackRef &internal, HebiFeedbackHighResAngleField field)
-
class Imu
Inertial measurement unit feedback (accelerometers and gyros).
Public Functions
-
inline Imu(const HebiFeedbackRef &internal)
-
inline const Vector3fField &accelerometer() const
Accelerometer data, in m/s^2.
-
inline const Vector3fField &gyro() const
Gyro data, in radians/second.
-
inline const QuaternionfField &orientation() const
A filtered estimate of the orientation of the module.
-
inline Imu(const HebiFeedbackRef &internal)
-
class Io
Feedback from any available I/O pins on the device.
Public Functions
-
inline Io(const HebiFeedbackRef &internal)
-
inline Io(const HebiFeedbackRef &internal)
-
class IoBank
A message field for interfacing with a bank of I/O pins.
Public Functions
-
IoBank(const HebiFeedbackRef &internal, HebiFeedbackIoPinBank bank)
-
bool hasInt(size_t pinNumber) const
True if (and only if) the particular numbered pin in this bank has an integer (e.g., digital) value.
- Parameters:
pinNumber – Which pin to check; valid values for pinNumber depend on the bank.
-
bool hasFloat(size_t pinNumber) const
True if (and only if) the particular numbered pin in this bank has an floating point (e.g., analog or PWM) value.
- Parameters:
pinNumber – Which pin to check; valid values for pinNumber depend on the bank.
-
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 returns a default.
- Parameters:
pinNumber – Which pin to get; valid values for pinNumber depend on the bank.
-
float getFloat(size_t pinNumber) const
If this numbered pin in this bank has an floating point (e.g., analog or PWM) value, returns that value; otherwise returns a default.
- Parameters:
pinNumber – Which pin to get; valid values for pinNumber depend on the bank.
-
IoBank(const HebiFeedbackRef &internal, HebiFeedbackIoPinBank bank)
-
class LedField
A message field for interfacing with an LED.
Public Functions
-
LedField(const HebiFeedbackRef &internal, HebiFeedbackLedField field)
-
inline explicit operator bool() const
Allows casting to a bool to check if the LED color is set without directly calling
hasColor()
.This can be used as in the following (assuming ‘parent’ is a parent message, and this field is called ‘myField’)
Feedback::LedField& f = parent.myField(); if (f) std::cout << "Field has color!" << std::endl; else std::cout << "Field has no value!" << std::endl;
-
bool hasColor() const
Returns true if the LED color is set, and false otherwise.
-
LedField(const HebiFeedbackRef &internal, HebiFeedbackLedField field)
-
class Mobile
Feedback generally from a mobile device such as a phone or tablet.
Public Functions
-
inline Mobile(const HebiFeedbackRef &internal)
-
inline const FloatField &batteryLevel() const
Charge level of the device’s battery (in percent).
-
inline const Vector3fField &arPosition() const
A device’s position in the world as calculated from an augmented reality framework, in meters.
-
inline const QuaternionfField &arOrientation() const
A device’s orientation in the world as calculated from an augmented reality framework.
-
inline Mobile(const HebiFeedbackRef &internal)
-
class NumberedFloatField
A message field containing a numbered set of single-precision floating point values.
Public Functions
-
NumberedFloatField(const HebiFeedbackRef &internal, HebiFeedbackNumberedFloatField field)
-
bool has(size_t fieldNumber) const
True if (and only if) the particular numbered subvalue of this field has a value.
- Parameters:
fieldNumber – Which subvalue to check; valid values for fieldNumber depend on the field type.
-
float get(size_t fieldNumber) const
If the particular numbered subvalue of this field has a value, returns that value; otherwise returns a default.
- Parameters:
fieldNumber – Which subvalue to get; valid values for fieldNumber depend on the field type.
-
NumberedFloatField(const HebiFeedbackRef &internal, HebiFeedbackNumberedFloatField field)
-
class QuaternionfField
A message field representable by a 3-D vector of single-precision floating point values.
Public Functions
-
QuaternionfField(const HebiFeedbackRef &internal, HebiFeedbackQuaternionfField field)
-
inline explicit operator bool() const
Allows casting to a bool to check if the field has a value without directly calling
has()
.This can be used as in the following (assuming ‘parent’ is a parent message, and this field is called ‘myField’)
Feedback::QuaternionfField& f = parent.myField(); if (f) std::cout << "Field has value!" << std::endl; else std::cout << "Field has no value!" << std::endl;
-
bool has() const
True if (and only if) the field has a value.
-
Quaternionf get() const
If the field has a value, returns that value; otherwise, returns a default.
-
QuaternionfField(const HebiFeedbackRef &internal, HebiFeedbackQuaternionfField field)
-
class UInt64Field
A message field representable by an unsigned 64 bit integer value.
Public Functions
-
UInt64Field(const HebiFeedbackRef &internal, HebiFeedbackUInt64Field field)
-
inline explicit operator bool() const
Allows casting to a bool to check if the field has a value without directly calling
has()
.This can be used as in the following (assuming ‘parent’ is a parent message, and this field is called ‘myField’)
Feedback::UInt64Field& f = parent.myField(); if (f) std::cout << "Field has value: " << f.get() << std::endl; else std::cout << "Field has no value!" << std::endl;
-
bool has() const
True if (and only if) the field has a value.
-
uint64_t get() const
If the field has a value, returns that value; otherwise, returns a default.
-
UInt64Field(const HebiFeedbackRef &internal, HebiFeedbackUInt64Field field)
-
class Vector3fField
A message field representable by a 3-D vector of single-precision floating point values.
Public Functions
-
Vector3fField(const HebiFeedbackRef &internal, HebiFeedbackVector3fField field)
-
inline explicit operator bool() const
Allows casting to a bool to check if the field has a value without directly calling
has()
.This can be used as in the following (assuming ‘parent’ is a parent message, and this field is called ‘myField’)
Feedback::Vector3fField& f = parent.myField(); if (f) std::cout << "Field has value!" << std::endl; else std::cout << "Field has no value!" << std::endl;
-
bool has() const
True if (and only if) the field has a value.
-
Vector3fField(const HebiFeedbackRef &internal, HebiFeedbackVector3fField field)
-
enum class TemperatureState