Class Position3DStamped

Inheritance Relationships

Base Types

Class Documentation

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

Variable representing a 3D position (x, y, z) at a specific time and for a specific piece of hardware (e.g., robot)

This is commonly used to represent a robot position in single or multi-robot systems. The UUID of this class is static after construction. As such, the timestamp and device ID cannot be modified. The value of the position can be modified.

Public Types

enum [anonymous]

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

Values:

enumerator X
enumerator Y
enumerator Z

Public Functions

Position3DStamped() = default

Default constructor.

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

Construct a 3D position at a specific point in time.

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

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

inline double &x()

Read-write access to the X-axis position.

inline const double &x() const

Read-only access to the X-axis position.

inline double &y()

Read-write access to the Y-axis position.

inline const double &y() const

Read-only access to the Y-axis position.

inline double &z()

Read-write access to the Z-axis position.

inline const double &z() const

Read-only access to the Z-axis position.

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

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

Parameters:

stream – The stream to write to. Defaults to stdout.

Friends

friend class boost::serialization::access