24 #include <boost/serialization/export.hpp> 38 cout <<
"biasAccCovariance:\n[\n" << biasAccCovariance <<
"\n]" 40 cout <<
"biasOmegaCovariance:\n[\n" << biasOmegaCovariance <<
"\n]" 42 cout <<
"biasAccOmegaInt:\n[\n" << biasAccOmegaInt <<
"\n]" 63 cout <<
" preintMeasCov [ " << preintMeasCov_ <<
" ]" << endl;
76 preintMeasCov_.setZero();
81 #define D_R_R(H) (H)->block<3,3>(0,0) 82 #define D_R_t(H) (H)->block<3,3>(0,3) 83 #define D_R_v(H) (H)->block<3,3>(0,6) 84 #define D_t_R(H) (H)->block<3,3>(3,0) 85 #define D_t_t(H) (H)->block<3,3>(3,3) 86 #define D_t_v(H) (H)->block<3,3>(3,6) 87 #define D_v_R(H) (H)->block<3,3>(6,0) 88 #define D_v_t(H) (H)->block<3,3>(6,3) 89 #define D_v_v(H) (H)->block<3,3>(6,6) 90 #define D_a_a(H) (H)->block<3,3>(9,9) 91 #define D_g_g(H) (H)->block<3,3>(12,12) 109 Matrix3 theta_H_biasOmega = -C.topRows<3>();
110 Matrix3 vel_H_biasAcc = -B.bottomRows<3>();
115 F.block<9, 9>(0, 0) = A;
116 F.block<3, 3>(0, 12) = theta_H_biasOmega;
117 F.block<3, 3>(6, 9) = vel_H_biasAcc;
118 F.block<6, 6>(9, 9) = I_6x6;
122 const Matrix3& aCov =
p().accelerometerCovariance;
123 const Matrix3& wCov =
p().gyroscopeCovariance;
124 const Matrix3& iCov =
p().integrationCovariance;
133 D_t_t(&G_measCov_Gt) = dt * iCov;
134 D_v_v(&G_measCov_Gt) = (1 /
dt) * vel_H_biasAcc
135 * (aCov +
p().biasAccOmegaInt.block<3, 3>(0, 0))
136 * (vel_H_biasAcc.transpose());
137 D_R_R(&G_measCov_Gt) = (1 /
dt) * theta_H_biasOmega
138 * (wCov +
p().biasAccOmegaInt.block<3, 3>(3, 3))
139 * (theta_H_biasOmega.transpose());
140 D_a_a(&G_measCov_Gt) = dt *
p().biasAccCovariance;
141 D_g_g(&G_measCov_Gt) = dt *
p().biasOmegaCovariance;
144 Matrix3 temp = vel_H_biasAcc *
p().biasAccOmegaInt.block<3, 3>(3, 0)
145 * theta_H_biasOmega.transpose();
146 D_v_R(&G_measCov_Gt) = temp;
147 D_R_v(&G_measCov_Gt) = temp.transpose();
148 preintMeasCov_ = F * preintMeasCov_ * F.transpose() + G_measCov_Gt;
157 Base(noiseModel::Gaussian::Covariance(pim.preintMeasCov_), pose_i, vel_i,
158 pose_j, vel_j, bias_i, bias_j), _PIM_(pim) {
170 cout << (s.empty() ? s : s +
"\n") <<
"CombinedImuFactor(" 171 << keyFormatter(this->
key1()) <<
"," << keyFormatter(this->
key2()) <<
"," 172 << keyFormatter(this->
key3()) <<
"," << keyFormatter(this->
key4()) <<
"," 173 << keyFormatter(this->
key5()) <<
"," << keyFormatter(this->
key6())
181 const This*
e =
dynamic_cast<const This*
>(&other);
189 boost::optional<Matrix&> H1, boost::optional<Matrix&> H2,
190 boost::optional<Matrix&> H3, boost::optional<Matrix&> H4,
191 boost::optional<Matrix&> H5, boost::optional<Matrix&> H6)
const {
194 Matrix6 Hbias_i, Hbias_j;
196 H6 ? &Hbias_j : 0, H5 ? &Hbias_i : 0).vector();
198 Matrix96 D_r_pose_i, D_r_pose_j, D_r_bias_i;
203 bias_i, H1 ? &D_r_pose_i : 0, H2 ? &D_r_vel_i : 0, H3 ? &D_r_pose_j : 0,
204 H4 ? &D_r_vel_j : 0, H5 ? &D_r_bias_i : 0);
209 H1->block<9, 6>(0, 0) = D_r_pose_i;
211 H1->block<6, 6>(9, 0).
setZero();
215 H2->block<9, 3>(0, 0) = D_r_vel_i;
217 H2->block<6, 3>(9, 0).
setZero();
221 H3->block<9, 6>(0, 0) = D_r_pose_j;
223 H3->block<6, 6>(9, 0).
setZero();
227 H4->block<9, 3>(0, 0) = D_r_vel_j;
229 H4->block<6, 3>(9, 0).
setZero();
233 H5->block<9, 6>(0, 0) = D_r_bias_i;
235 H5->block<6, 6>(9, 0) = Hbias_i;
239 H6->block<9, 6>(0, 0).
setZero();
241 H6->block<6, 6>(9, 0) = Hbias_j;
252 f.
_PIM_.
print(
"combined preintegrated measurements:\n");
253 os <<
" noise model sigmas: " << f.
noiseModel_->sigmas().transpose();
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
equals
bool equals(const PreintegratedRotationParams &other, double tol) const override
void print(const std::string &s="") const override
void print(const std::string &s="") const override
void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
gtsam::NonlinearFactor::shared_ptr clone() const override
void resetIntegration() override
Re-initialize PreintegratedCombinedMeasurements.
void resetIntegration() override
Matrix< SCALARB, Dynamic, Dynamic > B
bool equals(const ManifoldPreintegration &other, double tol) const
void print(const std::string &s="Preintegrated Measurements:") const override
void update(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt, Matrix9 *A, Matrix93 *B, Matrix93 *C) override
boost::shared_ptr< This > shared_ptr
BOOST_CLASS_EXPORT_IMPLEMENT(gtsam::PreintegrationCombinedParams)
namespace gtsam
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
BetweenFactor< Rot3 > Between
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const Vector3 measuredAcc
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const CombinedImuFactor &)
Matrix< Scalar, Dynamic, Dynamic > C
PreintegratedCombinedMeasurements _PIM_
static const Vector3 measuredOmega(w, 0, 0)
SharedNoiseModel noiseModel_
ofstream os("timeSchurFactors.csv")
Eigen::Matrix< double, 15, 15 > preintMeasCov_
bool equals(const PreintegratedRotationParams &other, double tol) const override
virtual void print(const std::string &s="") const
Vector9 computeErrorAndJacobians(const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H1=boost::none, OptionalJacobian< 9, 3 > H2=boost::none, OptionalJacobian< 9, 6 > H3=boost::none, OptionalJacobian< 9, 3 > H4=boost::none, OptionalJacobian< 9, 6 > H5=boost::none) const
bool equals(const PreintegratedCombinedMeasurements &expected, double tol=1e-9) const
equals
std::uint64_t Key
Integer nonlinear key type.
Vector evaluateError(const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, const imuBias::ConstantBias &bias_j, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none, boost::optional< Matrix & > H4=boost::none, boost::optional< Matrix & > H5=boost::none, boost::optional< Matrix & > H6=boost::none) const override
vector of errors