Class AbsoluteOrientation3DStampedConstraint
Inheritance Relationships
Base Type
public fuse_core::Constraint
Class Documentation
-
class AbsoluteOrientation3DStampedConstraint : public fuse_core::Constraint
A constraint that represents either prior information about a 3D orientation, or a direct measurement of the 3D orientation.
This constraint holds the measured 3D orientation and the measurement uncertainty/covariance.
Public Functions
-
AbsoluteOrientation3DStampedConstraint() = default
Default constructor.
-
AbsoluteOrientation3DStampedConstraint(const std::string &source, const fuse_variables::Orientation3DStamped &orientation, const fuse_core::Vector4d &mean, const fuse_core::Matrix3d &covariance)
Create a constraint using a measurement/prior of a 3D orientation.
- Parameters:
source – [in] The name of the sensor or motion model that generated this constraint
orientation – [in] The variable representing the orientation components of the pose
mean – [in] The measured/prior orientation as a quaternion (4x1 vector: w, x, y, z)
covariance – [in] The measurement/prior covariance (3x3 matrix: qx, qy, qz)
-
AbsoluteOrientation3DStampedConstraint(const std::string &source, const fuse_variables::Orientation3DStamped &orientation, const Eigen::Quaterniond &mean, const fuse_core::Matrix3d &covariance)
Create a constraint using a measurement/prior of a 3D orientation.
- Parameters:
source – [in] The name of the sensor or motion model that generated this constraint
orientation – [in] The variable representing the orientation components of the pose
mean – [in] The measured/prior orientation as an Eigen quaternion
covariance – [in] The measurement/prior covariance (3x3 matrix: qx, qy, qz)
-
AbsoluteOrientation3DStampedConstraint(const std::string &source, const fuse_variables::Orientation3DStamped &orientation, const geometry_msgs::msg::Quaternion &mean, const std::array<double, 9> &covariance)
Create a constraint using a measurement/prior of a 3D orientation.
- Parameters:
source – [in] The name of the sensor or motion model that generated this constraint
orientation – [in] The variable representing the orientation components of the pose
mean – [in] The measured/prior orientation as a ROS quaternion message
covariance – [in] The measurement/prior covariance (3x3 matrix: qx, qy, qz)
-
virtual ~AbsoluteOrientation3DStampedConstraint() = default
Destructor.
-
inline const fuse_core::Vector4d &mean() const
Read-only access to the measured/prior vector of mean values.
Order is (w, x, y, z)
-
inline const fuse_core::Matrix3d &sqrtInformation() const
Read-only access to the square root information matrix.
Order is (x, y, z)
-
fuse_core::Matrix3d covariance() const
Compute the measurement covariance matrix.
Order is (x, y, z)
-
void print(std::ostream &stream = std::cout) const override
Print a human-readable description of the constraint to the provided stream.
- Parameters:
stream – [out] The stream to write to. Defaults to stdout.
-
ceres::CostFunction *costFunction() const override
Construct an instance of this constraint’s cost function.
The function caller will own the new cost function instance. It is the responsibility of the caller to delete the cost function object when it is no longer needed. If the pointer is provided to a Ceres::Problem object, the Ceres::Problem object will takes ownership of the pointer and delete it during destruction.
- Returns:
A base pointer to an instance of a derived CostFunction.
Protected Attributes
-
fuse_core::Vector4d mean_
The measured/prior mean vector for this variable.
-
fuse_core::Matrix3d sqrt_information_
The square root information matrix.
Protected Static Functions
-
static fuse_core::Vector4d toEigen(const Eigen::Quaterniond &quaternion)
Utility method to convert an Eigen quaternion to an Eigen Vector4d.
- Parameters:
quaternion – [in] - The input Eigen quaternion
- Returns:
The
quaternion
, converted to an Eigen Vector4d
-
static fuse_core::Vector4d toEigen(const geometry_msgs::msg::Quaternion &quaternion)
Utility method to convert an ROS quaternion message to an Eigen Vector4d.
- Parameters:
quaternion – [in] - The input ROS quaternion message
- Returns:
The
quaternion
, converted to an Eigen Vector4d
-
static fuse_core::Matrix3d toEigen(const std::array<double, 9> &covariance)
Utility method to convert a flat 1D array to a 3x3 Eigen matrix.
- Parameters:
covariance – [in] - The input covariance array
- Returns:
The
covariance
, converted to an Eigen Matrix3d
Friends
- friend class boost::serialization::access
-
AbsoluteOrientation3DStampedConstraint() = default