Template Class AbsoluteConstraint
- Defined in File absolute_constraint.hpp 
Inheritance Relationships
Base Type
- public fuse_core::Constraint
Class Documentation
- 
template<class Variable>
 class AbsoluteConstraint : public fuse_core::Constraint
- A constraint that represents prior information about a variable or a direct measurement of the variable. - 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 an IMU, provide direct measurements of certain state variables (e.g. linear acceleration). And localization systems often match laserscans to a prior map (scan-to-map measurements). This constraint holds the measured variable value and the measurement uncertainty/covariance. - Public Functions - 
AbsoluteConstraint() = default
- Default constructor. 
 - 
AbsoluteConstraint(const std::string &source, const Variable &variable, const fuse_core::VectorXd &mean, const fuse_core::MatrixXd &covariance)
- Create a constraint using a measurement/prior of all dimensions of the target variable. - Parameters:
- source – [in] The name of the sensor or motion model that generated this constraint 
- variable – [in] An object derived from fuse_core::Variable. 
- mean – [in] The measured/prior value of all variable dimensions 
- covariance – [in] The measurement/prior uncertainty of all variable dimensions 
 
 
 - 
AbsoluteConstraint(const std::string &source, const Variable &variable, const fuse_core::VectorXd &partial_mean, const fuse_core::MatrixXd &partial_covariance, const std::vector<size_t> &indices)
- Create a constraint using a measurement/prior of only a partial set of dimensions of the target variable. - Parameters:
- source – [in] The name of the sensor or motion model that generated this constraint 
- variable – [in] An object derived from fuse_core::Variable. 
- partial_mean – [in] The measured value of the subset of dimensions in the order defined by - indices
- partial_covariance – [in] The uncertainty of the subset of dimensions in the order defined by - indices.
- indices – [in] The set of indices corresponding to the measured dimensions 
 
 
 - 
virtual ~AbsoluteConstraint() = default
- Destructor. 
 - 
inline const fuse_core::VectorXd &mean() const
- Read-only access to the measured/prior vector of mean values. - All dimensions are present, even if only a partial set of dimensions were measured. Dimensions are in the order defined by the variable, not the order defined by the - indicesparameter. All unmeasured variable dimensions are set to zero.
 - 
inline const fuse_core::MatrixXd &sqrtInformation() const
- Read-only access to the square root information matrix. - Dimensions are in the order defined by the variable, not the order defined by the - indicesparameter. The square root information matrix will have size measured_dimensions X variable_dimensions. If only a partial set of dimensions are measured, then this matrix will not be square.
 - 
fuse_core::MatrixXd covariance() const
- Compute the measurement covariance matrix. - Dimensions are in the order defined by the variable, not the order defined by the - indicesparameter. The covariance matrix will always be square, with size variable_dimensions X variable_dimensions. If only a subset of dimensions are measured, then some rows/columns will be zero. This will result in a rank-deficient covariance matrix. You have been warned.
 - 
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. 
 
 - 
inline ceres::CostFunction *costFunction() const
 - Protected Attributes - 
fuse_core::VectorXd 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
 
- 
AbsoluteConstraint() = default