Class AccelerationAngular2DStamped

Inheritance Relationships

Base Types

Class Documentation

class AccelerationAngular2DStamped : public fuse_variables::FixedSizeVariable<1>, public fuse_variables::Stamped

Variable representing a 2D angular acceleration at a specific time, with a specific piece of hardware.

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

Public Types

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

Values:

enumerator YAW

Public Functions

AccelerationAngular2DStamped() = default

Default constructor.

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

Construct a 2D acceleration at a specific point in time.

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

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

inline double &yaw()

Read-write access to the angular acceleration.

inline const double &yaw() const

Read-only access to the angular acceleration.

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