Class VelocityAngular3DStamped

Inheritance Relationships

Base Types

Class Documentation

class VelocityAngular3DStamped : public fuse_variables::FixedSizeVariable<3>, public fuse_variables::Stamped

Variable representing a 3D angular velocity (vroll, vpitch, vyaw) at a specific time, with a specific piece of hardware.

This is commonly used to represent a robot’s velocity. The UUID of this class is static after construction. As such, the timestamp and device ID cannot be modified. The value of the velocity can be modified.

Public Types

enum [anonymous]

Can be used to directly index variables in the data array.

Values:

enumerator ROLL
enumerator PITCH
enumerator YAW

Public Functions

VelocityAngular3DStamped() = default

Default constructor.

explicit VelocityAngular3DStamped(const rclcpp::Time &stamp, const fuse_core::UUID &device_id = fuse_core::uuid::NIL)

Construct a 3D angular velocity at a specific point in time.

Parameters:
  • stamp[in] The timestamp attached to this angular velocity.

  • device_id[in] An optional device id, for use when variables originate from multiple robots or devices

inline double &roll()

Read-write access to the roll (X-axis) angular velocity.

inline const double &roll() const

Read-only access to the roll (X-axis) angular velocity.

inline double &pitch()

Read-write access to the pitch (Y-axis) angular velocity.

inline const double &pitch() const

Read-only access to the pitch (Y-axis) angular velocity.

inline double &yaw()

Read-write access to the yaw (Z-axis) angular velocity.

inline const double &yaw() const

Read-only access to the yaw (Z-axis) angular velocity.

void print(std::ostream &stream = std::cout) const override

Print a human-readable description of the variable to the provided stream.

Parameters:

stream[out] The stream to write to. Defaults to stdout.

Friends

friend class boost::serialization::access