Class AbsolutePose2DStampedConstraint
Defined in File absolute_pose_2d_stamped_constraint.hpp
Inheritance Relationships
Base Type
public fuse_core::Constraint
Class Documentation
-
class AbsolutePose2DStampedConstraint : public fuse_core::Constraint
A constraint that represents either prior information about a 2D pose, or a direct measurement of the 2D pose.
A 2D pose is the combination of a 2D position and a 2D orientation variable. As a convenience, this class applies an absolute constraint on both variables at once. This type of constraint arises in many situations. In mapping it is common to define the very first pose as the origin. Some sensors, such as GPS, provide direct measurements of the robot’s pose in the global frame. And localization systems often match laserscans to a prior map (scan-to-map measurements). This constraint holds the measured 2D pose and the measurement uncertainty/covariance. It also permits measurement of a subset of the pose provided in the position and orientation varables.
Public Functions
-
AbsolutePose2DStampedConstraint() = default
Default constructor.
-
AbsolutePose2DStampedConstraint(const std::string &source, const fuse_variables::Position2DStamped &position, const fuse_variables::Orientation2DStamped &orientation, const fuse_core::VectorXd &partial_mean, const fuse_core::MatrixXd &partial_covariance, const std::vector<size_t> &linear_indices = {fuse_variables::Position2DStamped::X, fuse_variables::Position2DStamped::Y}, const std::vector<size_t> &angular_indices = {fuse_variables::Orientation2DStamped::YAW})
Create a constraint using a measurement/prior of the 2D pose.
Note that, when measuring subset of dimensions, empty axis vectors are permitted. This signifies, e.g., that you don’t want to measure any of the quantities in that variable.
The mean is given as a vector. The first components (if any) will be dictated, both in content and in ordering, by the value of the
linear_indices
. The final component (if any) is dictated by theangular_indices
. The covariance matrix follows the same ordering.- Parameters:
source – [in] The name of the sensor or motion model that generated this constraint
position – [in] The variable representing the position components of the pose
orientation – [in] The variable representing the orientation components of the pose
partial_mean – [in] The measured/prior pose as a vector (max 3x1 vector, components are dictated by
linear_indices
andangular_indices
)partial_covariance – [in] The measurement/prior covariance (max 3x3 matrix, components are dictated by
linear_indices
andangular_indices
)linear_indices – [in]
The set of indices corresponding to the measured position dimensions e.g. “{fuse_variables::Position2DStamped::X,
fuse_variables::Position2DStamped::Y}”
angular_indices – [in] The set of indices corresponding to the measured orientation dimensions e.g. “{fuse_variables::Orientation2DStamped::Yaw}”
-
virtual ~AbsolutePose2DStampedConstraint() = default
Destructor.
-
inline const fuse_core::Vector3d &mean() const
Read-only access to the measured/prior vector of mean values.
Order is (x, y, yaw). Note that the returned vector will be full sized (3x1) and in the stated order.
-
inline const fuse_core::MatrixXd &sqrtInformation() const
Read-only access to the square root information matrix.
If only a partial covariance matrix was provided in the constructor, this covariance matrix will not be square.
-
fuse_core::Matrix3d covariance() const
Compute the measurement covariance matrix.
Order is (x, y, yaw). Note that the returned covariance matrix will be full sized (3x3) and in the stated order. If only a partial covariance matrix was provided in the constructor, this covariance matrix may be a different size and in a different order than the constructor input.
-
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::Vector3d mean_
The measured/prior mean vector for this variable.
-
fuse_core::MatrixXd sqrt_information_
The square root information matrix.
Friends
- friend class boost::serialization::access
-
AbsolutePose2DStampedConstraint() = default