22 #ifndef OV_INIT_CERES_GENERICPRIOR_H 23 #define OV_INIT_CERES_GENERICPRIOR_H 25 #include <ceres/ceres.h> 89 Factor_GenericPrior(
const Eigen::MatrixXd &x_lin_,
const std::vector<std::string> &x_type_,
const Eigen::MatrixXd &prior_Info,
90 const Eigen::MatrixXd &prior_grad);
97 bool Evaluate(
double const *
const *parameters,
double *residuals,
double **jacobians)
const override;
102 #endif // OV_INIT_CERES_GENERICPRIOR_H virtual ~Factor_GenericPrior()
Factor for generic state priors for specific types.
Eigen::MatrixXd sqrtI
The square-root of the information s.t. sqrtI^T * sqrtI = marginal information.
Eigen::MatrixXd x_lin
State estimates at the time of marginalization to linearize the problem.
std::vector< std::string > x_type
State type for each variable in x_lin. Can be [quat, quat_yaw, vec3, vec8].
bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const override
Error residual and Jacobian calculation.
State initialization code.
Factor_GenericPrior(const Eigen::MatrixXd &x_lin_, const std::vector< std::string > &x_type_, const Eigen::MatrixXd &prior_Info, const Eigen::MatrixXd &prior_grad)
Default constructor.
Eigen::MatrixXd b
Constant term inside the cost s.t. sqrtI^T * b = marginal gradient (can be zero)