Class Orientation3DStamped
Defined in File orientation_3d_stamped.hpp
Inheritance Relationships
Base Types
public fuse_variables::FixedSizeVariable< 4 >
(Template Class FixedSizeVariable)public fuse_variables::Stamped
(Class Stamped)
Class Documentation
-
class Orientation3DStamped : public fuse_variables::FixedSizeVariable<4>, public fuse_variables::Stamped
Variable representing a 3D orientation as a quaternion at a specific time and for a specific piece of hardware (e.g., robot)
This is commonly used to represent a robot orientation 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 orientation can be modified.
The internal representation for this is different from the typical ROS representation, as w is the first component. This is necessary to use the Ceres local parameterization for quaternions.
Public Types
Public Functions
-
Orientation3DStamped() = default
Default constructor.
-
explicit Orientation3DStamped(const rclcpp::Time &stamp, const fuse_core::UUID &device_id = fuse_core::uuid::NIL)
Construct a 3D orientation 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 &w()
Read-write access to the quaternion w component.
-
inline const double &w() const
Read-only access to the quaternion w component.
-
inline double &x()
Read-write access to the quaternion x component.
-
inline const double &x() const
Read-only access to the quaternion x component.
-
inline double &y()
Read-write access to the quaternion y component.
-
inline const double &y() const
Read-only access to the quaternion y component.
-
inline double &z()
Read-write access to the quaternion z component.
-
inline const double &z() const
Read-only access to the quaternion z component.
-
inline double roll()
Read-only access to quaternion’s Euler roll angle component.
-
inline double pitch()
Read-only access to quaternion’s Euler pitch angle component.
-
inline double yaw()
Read-only access to quaternion’s Euler yaw angle component.
-
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.
-
inline size_t localSize() const override
Returns the number of elements of the local parameterization space.
While a quaternion has 4 parameters, a 3D rotation only has 3 degrees of freedom. Hence, the local parameterization space is only size 3.
-
fuse_core::LocalParameterization *localParameterization() const override
Provides a Ceres local parameterization for the quaternion.
- Returns:
A pointer to a local parameterization object that indicates how to “add” increments to the quaternion
Friends
- friend class boost::serialization::access
-
Orientation3DStamped() = default