Factor_GenericPrior.h
Go to the documentation of this file.
1 /*
2  * OpenVINS: An Open Platform for Visual-Inertial Research
3  * Copyright (C) 2018-2023 Patrick Geneva
4  * Copyright (C) 2018-2023 Guoquan Huang
5  * Copyright (C) 2018-2023 OpenVINS Contributors
6  * Copyright (C) 2018-2019 Kevin Eckenhoff
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program. If not, see <https://www.gnu.org/licenses/>.
20  */
21 
22 #ifndef OV_INIT_CERES_GENERICPRIOR_H
23 #define OV_INIT_CERES_GENERICPRIOR_H
24 
25 #include <ceres/ceres.h>
26 
27 namespace ov_init {
28 
72 class Factor_GenericPrior : public ceres::CostFunction {
73 public:
75  Eigen::MatrixXd x_lin;
76 
78  std::vector<std::string> x_type;
79 
81  Eigen::MatrixXd sqrtI;
82 
84  Eigen::MatrixXd b;
85 
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);
91 
92  virtual ~Factor_GenericPrior() {}
93 
97  bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const override;
98 };
99 
100 } // namespace ov_init
101 
102 #endif // OV_INIT_CERES_GENERICPRIOR_H
ov_init::Factor_GenericPrior::Evaluate
bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const override
Error residual and Jacobian calculation.
Definition: Factor_GenericPrior.cpp:94
ov_init::Factor_GenericPrior::sqrtI
Eigen::MatrixXd sqrtI
The square-root of the information s.t. sqrtI^T * sqrtI = marginal information.
Definition: Factor_GenericPrior.h:81
ov_init::Factor_GenericPrior::~Factor_GenericPrior
virtual ~Factor_GenericPrior()
Definition: Factor_GenericPrior.h:92
ov_init::Factor_GenericPrior::x_lin
Eigen::MatrixXd x_lin
State estimates at the time of marginalization to linearize the problem.
Definition: Factor_GenericPrior.h:75
ov_init::Factor_GenericPrior
Factor for generic state priors for specific types.
Definition: Factor_GenericPrior.h:72
ov_init
State initialization code.
Definition: Factor_GenericPrior.h:27
ov_init::Factor_GenericPrior::Factor_GenericPrior
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.
Definition: Factor_GenericPrior.cpp:28
ov_init::Factor_GenericPrior::b
Eigen::MatrixXd b
Constant term inside the cost s.t. sqrtI^T * b = marginal gradient (can be zero)
Definition: Factor_GenericPrior.h:84
ov_init::Factor_GenericPrior::x_type
std::vector< std::string > x_type
State type for each variable in x_lin. Can be [quat, quat_yaw, vec3, vec8].
Definition: Factor_GenericPrior.h:78


ov_init
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:51