87 template<
class POSE,
class VELOCITY,
class IMUBIAS>
115 typedef typename std::shared_ptr<EquivInertialNavFactor_GlobalVel>
shared_ptr;
125 const Matrix& Jacobian_wrt_t0_Overall,
126 std::optional<IMUBIAS> Bias_initial = {}, std::optional<POSE>
body_P_sensor = {}) :
127 Base(model_equivalent, Pose1, Vel1, IMUBias1, Pose2, Vel2),
138 std::cout <<
s <<
"(" 139 << keyFormatter(this->
key1()) <<
"," 140 << keyFormatter(this->
key2()) <<
"," 141 << keyFormatter(this->
key3()) <<
"," 142 << keyFormatter(this->
key4()) <<
"," 143 << keyFormatter(this->
key5()) <<
"\n";
144 std::cout <<
"delta_pos_in_t0: " << this->delta_pos_in_t0_.transpose() << std::endl;
145 std::cout <<
"delta_vel_in_t0: " << this->delta_vel_in_t0_.transpose() << std::endl;
146 std::cout <<
"delta_angles: " << this->delta_angles_ << std::endl;
147 std::cout <<
"dt12: " << this->dt12_ << std::endl;
148 std::cout <<
"gravity (in world frame): " << this->world_g_.transpose() << std::endl;
149 std::cout <<
"craft rate (in world frame): " << this->world_rho_.transpose() << std::endl;
150 std::cout <<
"earth's rotation (in world frame): " << this->world_omega_earth_.transpose() << std::endl;
151 if(this->body_P_sensor_)
152 this->body_P_sensor_->print(
" sensor pose in body frame: ");
158 const This *
e =
dynamic_cast<const This*
> (&
expected);
160 && (delta_pos_in_t0_ - e->delta_pos_in_t0_).norm() <
tol 161 && (delta_vel_in_t0_ - e->delta_vel_in_t0_).norm() <
tol 162 && (delta_angles_ - e->delta_angles_).norm() <
tol 163 && (dt12_ - e->dt12_) <
tol 164 && (world_g_ - e->world_g_).norm() <
tol 165 && (world_rho_ - e->world_rho_).norm() <
tol 166 && (world_omega_earth_ - e->world_omega_earth_).norm() <
tol 167 && ((!body_P_sensor_ && !e->body_P_sensor_) || (body_P_sensor_ && e->body_P_sensor_ && body_P_sensor_->
equals(*e->body_P_sensor_)));
171 POSE
predictPose(
const POSE& Pose1,
const VELOCITY& Vel1,
const IMUBIAS& Bias1)
const {
174 Vector delta_BiasAcc = Bias1.accelerometer();
175 Vector delta_BiasGyro = Bias1.gyroscope();
177 delta_BiasAcc -= Bias_initial_->accelerometer();
178 delta_BiasGyro -= Bias_initial_->gyroscope();
181 Matrix J_Pos_wrt_BiasAcc = Jacobian_wrt_t0_Overall_.block(4,9,3,3);
182 Matrix J_Pos_wrt_BiasGyro = Jacobian_wrt_t0_Overall_.block(4,12,3,3);
183 Matrix J_angles_wrt_BiasGyro = Jacobian_wrt_t0_Overall_.block(0,12,3,3);
186 Vector delta_pos_in_t0_corrected = delta_pos_in_t0_ + J_Pos_wrt_BiasAcc*delta_BiasAcc + J_Pos_wrt_BiasGyro*delta_BiasGyro;
189 Vector delta_angles_corrected = delta_angles_ + J_angles_wrt_BiasGyro*delta_BiasGyro;
194 delta_pos_in_t0_corrected, delta_angles_corrected,
195 dt12_, world_g_, world_rho_, world_omega_earth_);
200 const double dt12,
const Vector& world_g,
const Vector& world_rho,
const Vector& world_omega_earth){
202 const POSE& world_P1_body = Pose1;
203 const VELOCITY& world_V1_body = Vel1;
206 Vector body_deltaPos_body = delta_pos_in_t0;
208 Vector world_deltaPos_pls_body = world_P1_body.rotation().matrix() * body_deltaPos_body;
209 Vector world_deltaPos_body = world_V1_body * dt12 + 0.5*world_g*dt12*dt12 + world_deltaPos_pls_body;
212 world_deltaPos_body -= 2*
skewSymmetric(world_rho + world_omega_earth)*world_V1_body * dt12*dt12;
222 Vector body_deltaAngles_body = delta_angles;
225 Matrix body_R_world(world_P1_body.rotation().inverse().matrix());
230 body_deltaAngles_body -= (body_rho + body_omega_earth)*dt12;
232 return POSE(Pose1.rotation() *
POSE::Rotation::Expmap(body_deltaAngles_body), Pose1.translation() +
typename POSE::Translation(world_deltaPos_body));
236 VELOCITY
predictVelocity(
const POSE& Pose1,
const VELOCITY& Vel1,
const IMUBIAS& Bias1)
const {
239 Vector delta_BiasAcc = Bias1.accelerometer();
240 Vector delta_BiasGyro = Bias1.gyroscope();
242 delta_BiasAcc -= Bias_initial_->accelerometer();
243 delta_BiasGyro -= Bias_initial_->gyroscope();
246 Matrix J_Vel_wrt_BiasAcc = Jacobian_wrt_t0_Overall_.block(6,9,3,3);
247 Matrix J_Vel_wrt_BiasGyro = Jacobian_wrt_t0_Overall_.block(6,12,3,3);
249 Vector delta_vel_in_t0_corrected = delta_vel_in_t0_ + J_Vel_wrt_BiasAcc*delta_BiasAcc + J_Vel_wrt_BiasGyro*delta_BiasGyro;
252 delta_vel_in_t0_corrected,
253 dt12_, world_g_, world_rho_, world_omega_earth_);
257 const Vector& delta_vel_in_t0,
258 const double dt12,
const Vector& world_g,
const Vector& world_rho,
const Vector& world_omega_earth) {
260 const POSE& world_P1_body = Pose1;
261 const VELOCITY& world_V1_body = Vel1;
263 Vector body_deltaVel_body = delta_vel_in_t0;
264 Vector world_deltaVel_body = world_P1_body.rotation().matrix() * body_deltaVel_body;
266 VELOCITY VelDelta( world_deltaVel_body + world_g * dt12 );
269 VelDelta -= 2*
skewSymmetric(world_rho + world_omega_earth)*world_V1_body * dt12;
272 return Vel1 + VelDelta;
276 void predict(
const POSE& Pose1,
const VELOCITY& Vel1,
const IMUBIAS& Bias1, POSE& Pose2, VELOCITY& Vel2)
const {
281 POSE
evaluatePoseError(
const POSE& Pose1,
const VELOCITY& Vel1,
const IMUBIAS& Bias1,
const POSE& Pose2,
const VELOCITY& Vel2)
const {
286 POSE DiffPose( Pose2.rotation().between(Pose2Pred.rotation()), Pose2Pred.translation() - Pose2.translation() );
293 VELOCITY
evaluateVelocityError(
const POSE& Pose1,
const VELOCITY& Vel1,
const IMUBIAS& Bias1,
const POSE& Pose2,
const VELOCITY& Vel2)
const {
298 return Vel2Pred-Vel2;
301 Vector evaluateError(
const POSE& Pose1,
const VELOCITY& Vel1,
const IMUBIAS& Bias1,
const POSE& Pose2,
const VELOCITY& Vel2,
308 Matrix H1_Pose = numericalDerivative11<POSE, POSE>(
310 this, std::placeholders::_1, Vel1, Bias1, Pose2, Vel2),
312 Matrix H1_Vel = numericalDerivative11<VELOCITY, POSE>(
314 this, std::placeholders::_1, Vel1, Bias1, Pose2, Vel2),
316 *H1 =
stack(2, &H1_Pose, &H1_Vel);
321 if (Vel1.size()!=3)
throw std::runtime_error(
"Frank's hack to make this compile will not work if size != 3");
322 Matrix H2_Pose = numericalDerivative11<POSE, Vector3>(
324 this, Pose1, std::placeholders::_1, Bias1, Pose2, Vel2),
326 Matrix H2_Vel = numericalDerivative11<Vector3, Vector3>(
328 this, Pose1, std::placeholders::_1, Bias1, Pose2, Vel2),
330 *H2 =
stack(2, &H2_Pose, &H2_Vel);
335 Matrix H3_Pose = numericalDerivative11<POSE, IMUBIAS>(
337 this, Pose1, Vel1, std::placeholders::_1, Pose2, Vel2),
339 Matrix H3_Vel = numericalDerivative11<VELOCITY, IMUBIAS>(
341 this, Pose1, Vel1, std::placeholders::_1, Pose2, Vel2),
343 *H3 =
stack(2, &H3_Pose, &H3_Vel);
348 Matrix H4_Pose = numericalDerivative11<POSE, POSE>(
350 this, Pose1, Vel1, Bias1, std::placeholders::_1, Vel2),
352 Matrix H4_Vel = numericalDerivative11<VELOCITY, POSE>(
354 this, Pose1, Vel1, Bias1, std::placeholders::_1, Vel2),
356 *H4 =
stack(2, &H4_Pose, &H4_Vel);
361 if (Vel2.size()!=3)
throw std::runtime_error(
"Frank's hack to make this compile will not work if size != 3");
362 Matrix H5_Pose = numericalDerivative11<POSE, Vector3>(
364 this, Pose1, Vel1, Bias1, Pose2, std::placeholders::_1),
366 Matrix H5_Vel = numericalDerivative11<Vector3, Vector3>(
368 this, Pose1, Vel1, Bias1, Pose2, std::placeholders::_1),
370 *H5 =
stack(2, &H5_Pose, &H5_Vel);
383 double dt12,
const Vector world_g,
const Vector world_rho,
384 const Vector& world_omega_earth,
const Matrix& Jacobian_wrt_t0_Overall,
385 const std::optional<IMUBIAS>& Bias_initial = {}) {
389 Vector delta_BiasAcc = Bias1.accelerometer();
390 Vector delta_BiasGyro = Bias1.gyroscope();
392 delta_BiasAcc -= Bias_initial->accelerometer();
393 delta_BiasGyro -= Bias_initial->gyroscope();
396 Matrix J_Pos_wrt_BiasAcc = Jacobian_wrt_t0_Overall.block(4,9,3,3);
397 Matrix J_Pos_wrt_BiasGyro = Jacobian_wrt_t0_Overall.block(4,12,3,3);
398 Matrix J_angles_wrt_BiasGyro = Jacobian_wrt_t0_Overall.block(0,12,3,3);
401 Vector delta_pos_in_t0_corrected = delta_pos_in_t0 + J_Pos_wrt_BiasAcc*delta_BiasAcc + J_Pos_wrt_BiasGyro*delta_BiasGyro;
404 Vector delta_angles_corrected = delta_angles + J_angles_wrt_BiasGyro*delta_BiasGyro;
408 return predictPose_inertial(Pose1, Vel1, delta_pos_in_t0_corrected, delta_angles_corrected, dt12, world_g, world_rho, world_omega_earth);
412 const Vector& delta_vel_in_t0,
double dt12,
const Vector world_g,
const Vector world_rho,
413 const Vector& world_omega_earth,
const Matrix& Jacobian_wrt_t0_Overall,
414 const std::optional<IMUBIAS>& Bias_initial = {}) {
417 Vector delta_BiasAcc = Bias1.accelerometer();
418 Vector delta_BiasGyro = Bias1.gyroscope();
420 delta_BiasAcc -= Bias_initial->accelerometer();
421 delta_BiasGyro -= Bias_initial->gyroscope();
424 Matrix J_Vel_wrt_BiasAcc = Jacobian_wrt_t0_Overall.block(6,9,3,3);
425 Matrix J_Vel_wrt_BiasGyro = Jacobian_wrt_t0_Overall.block(6,12,3,3);
427 Vector delta_vel_in_t0_corrected = delta_vel_in_t0 + J_Vel_wrt_BiasAcc*delta_BiasAcc + J_Vel_wrt_BiasGyro*delta_BiasGyro;
429 return predictVelocity_inertial(Pose1, Vel1, delta_vel_in_t0_corrected, dt12, world_g, world_rho, world_omega_earth);
432 static inline void PredictFromPreIntegration(
const POSE& Pose1,
const VELOCITY& Vel1,
const IMUBIAS& Bias1, POSE& Pose2, VELOCITY& Vel2,
434 double dt12,
const Vector world_g,
const Vector world_rho,
435 const Vector& world_omega_earth,
const Matrix& Jacobian_wrt_t0_Overall,
436 const std::optional<IMUBIAS>& Bias_initial = {}) {
438 Pose2 =
PredictPoseFromPreIntegration(Pose1, Vel1, Bias1, delta_pos_in_t0, delta_angles, dt12, world_g, world_rho, world_omega_earth, Jacobian_wrt_t0_Overall, Bias_initial);
439 Vel2 =
PredictVelocityFromPreIntegration(Pose1, Vel1, Bias1, delta_vel_in_t0, dt12, world_g, world_rho, world_omega_earth, Jacobian_wrt_t0_Overall, Bias_initial);
446 Matrix& EquivCov_Overall,
Matrix& Jacobian_wrt_t0_Overall,
const IMUBIAS Bias_t0 = IMUBIAS(),
447 std::optional<POSE> p_body_P_sensor = {}){
451 POSE body_P_sensor = POSE();
452 bool flag_use_body_P_sensor =
false;
453 if (p_body_P_sensor){
454 body_P_sensor = *p_body_P_sensor;
455 flag_use_body_P_sensor =
true;
468 Matrix H_pos_pos = numericalDerivative11<Vector3, Vector3>(
470 std::placeholders::_1, delta_vel_in_t0),
472 Matrix H_pos_vel = numericalDerivative11<Vector3, Vector3>(
474 delta_pos_in_t0, std::placeholders::_1),
476 Matrix H_pos_angles = Z_3x3;
479 Matrix H_vel_vel = numericalDerivative11<Vector3, Vector3>(
481 msr_acc_t, msr_dt, delta_angles, std::placeholders::_1,
482 flag_use_body_P_sensor, body_P_sensor, Bias_t0),
484 Matrix H_vel_angles = numericalDerivative11<Vector3, Vector3>(
486 msr_acc_t, msr_dt, std::placeholders::_1, delta_vel_in_t0,
487 flag_use_body_P_sensor, body_P_sensor, Bias_t0),
489 Matrix H_vel_bias = numericalDerivative11<Vector3, IMUBIAS>(
491 msr_acc_t, msr_dt, delta_angles, delta_vel_in_t0,
492 flag_use_body_P_sensor, body_P_sensor,
493 std::placeholders::_1),
497 Matrix H_angles_angles = numericalDerivative11<Vector3, Vector3>(
499 msr_dt, std::placeholders::_1, flag_use_body_P_sensor,
500 body_P_sensor, Bias_t0),
502 Matrix H_angles_bias = numericalDerivative11<Vector3, IMUBIAS>(
504 msr_dt, delta_angles, flag_use_body_P_sensor, body_P_sensor,
505 std::placeholders::_1),
507 Matrix H_angles_pos = Z_3x3;
508 Matrix H_angles_vel = Z_3x3;
510 Matrix F_angles =
collect(4, &H_angles_angles, &H_angles_pos, &H_angles_vel, &H_angles_bias);
511 Matrix F_pos =
collect(4, &H_pos_angles, &H_pos_pos, &H_pos_vel, &H_pos_bias);
512 Matrix F_vel =
collect(4, &H_vel_angles, &H_vel_pos, &H_vel_vel, &H_vel_bias);
513 Matrix F_bias_a =
collect(5, &Z_3x3, &Z_3x3, &Z_3x3, &I_3x3, &Z_3x3);
514 Matrix F_bias_g =
collect(5, &Z_3x3, &Z_3x3, &Z_3x3, &Z_3x3, &I_3x3);
515 Matrix F =
stack(5, &F_angles, &F_pos, &F_vel, &F_bias_a, &F_bias_g);
519 Matrix Q_d = (model_discrete_curr->R().transpose() * model_discrete_curr->R()).
inverse();
521 EquivCov_Overall = F * EquivCov_Overall * F.transpose() + Q_d;
526 Jacobian_wrt_t0_Overall = F * Jacobian_wrt_t0_Overall;
530 const Vector& delta_pos_in_t0,
const Vector& delta_vel_in_t0){
535 return delta_pos_in_t0 + delta_vel_in_t0 * msr_dt;
541 const Vector3& delta_angles,
const Vector& delta_vel_in_t0,
const bool flag_use_body_P_sensor,
const POSE& body_P_sensor,
542 IMUBIAS Bias_t0 = IMUBIAS()){
547 Vector AccCorrected = Bias_t0.correctAccelerometer(msr_acc_t);
549 if (flag_use_body_P_sensor){
550 Matrix body_R_sensor = body_P_sensor.rotation().matrix();
552 Vector GyroCorrected(Bias_t0.correctGyroscope(msr_gyro_t));
554 Vector body_omega_body = body_R_sensor * GyroCorrected;
557 body_t_a_body = body_R_sensor * AccCorrected - body_omega_body__cross * body_omega_body__cross * body_P_sensor.translation().vector();
559 body_t_a_body = AccCorrected;
564 return delta_vel_in_t0 + R_t_to_t0.
matrix() * body_t_a_body * msr_dt;
569 const Vector3& delta_angles,
const bool flag_use_body_P_sensor,
const POSE& body_P_sensor,
570 IMUBIAS Bias_t0 = IMUBIAS()){
575 Vector GyroCorrected = Bias_t0.correctGyroscope(msr_gyro_t);
578 if (flag_use_body_P_sensor){
579 body_t_omega_body = body_P_sensor.rotation().matrix() * GyroCorrected;
581 body_t_omega_body = GyroCorrected;
586 R_t_to_t0 = R_t_to_t0 *
Rot3::Expmap( body_t_omega_body*msr_dt );
594 Matrix cov_acc = ( gaussian_acc->R().transpose() * gaussian_acc->R() ).
inverse();
595 Matrix cov_gyro = ( gaussian_gyro->R().transpose() * gaussian_gyro->R() ).
inverse();
596 Matrix cov_process = ( gaussian_process->R().transpose() * gaussian_process->R() ).
inverse();
598 cov_process.block(0,0, 3,3) += cov_gyro;
599 cov_process.block(6,6, 3,3) += cov_acc;
608 cov_acc = ( gaussian_acc->R().transpose() * gaussian_acc->R() ).
inverse();
609 cov_gyro = ( gaussian_gyro->R().transpose() * gaussian_gyro->R() ).
inverse();
610 cov_process_without_acc_gyro = ( gaussian_process->R().transpose() * gaussian_process->R() ).
inverse();
619 0.0, 0.0, -1.0).finished();
624 0.0, 0.0, -1.0).finished();
627 Vector Pos_ENU = NED_to_ENU * Pos_NED;
628 Vector Vel_ENU = NED_to_ENU * Vel_NED;
629 Vector Pos_ENU_Initial = NED_to_ENU * Pos_NED_Initial;
638 g_NED = ENU_to_NED * g_ENU;
639 rho_NED = ENU_to_NED * rho_ENU;
640 omega_earth_NED = ENU_to_NED * omega_earth_ENU;
645 double R0 = 6.378388e6;
647 double Re( R0*( 1-e*(
sin( LatLonHeight_IC(0) ))*(
sin( LatLonHeight_IC(0) )) ) );
650 Vector delta_Pos_ENU(Pos_ENU - Pos_ENU_Initial);
651 double delta_lat(delta_Pos_ENU(1)/Re);
652 double delta_lon(delta_Pos_ENU(0)/(Re*
cos(LatLonHeight_IC(0))));
653 double lat_new(LatLonHeight_IC(0) + delta_lat);
654 double lon_new(LatLonHeight_IC(1) + delta_lon);
658 -
sin(lon_new),
cos(lon_new), 0.0,
664 -
sin(lat_new), 0.0,
cos(lat_new));
666 Rot3 UEN_to_ENU(0, 1, 0,
670 Rot3 R_ECEF_to_ENU( UEN_to_ENU * C2 * C1 );
673 omega_earth_ENU = R_ECEF_to_ENU.
matrix() * omega_earth_ECEF;
676 double height(LatLonHeight_IC(2));
677 double EQUA_RADIUS = 6378137.0;
678 double ECCENTRICITY = 0.0818191908426;
679 double e2(
pow(ECCENTRICITY,2) );
680 double den( 1-e2*
pow(
sin(lat_new),2) );
681 double Rm( (EQUA_RADIUS*(1-e2))/(
pow(den,(3/2)) ) );
682 double Rp( EQUA_RADIUS/(
sqrt(den) ) );
683 double Ro(
sqrt(Rp*Rm) );
684 double g0( 9.780318*( 1 + 5.3024e-3 *
pow(
sin(lat_new),2) - 5.9e-6 *
pow(
sin(2*lat_new),2) ) );
685 double g_calc( g0/(
pow(1 + height/Ro, 2) ) );
686 g_ENU = (
Vector(3) << 0.0, 0.0, -g_calc).finished();
690 double Ve( Vel_ENU(0) );
691 double Vn( Vel_ENU(1) );
692 double rho_E = -Vn/(Rm + height);
693 double rho_N = Ve/(Rp + height);
694 double rho_U = Ve*
tan(lat_new)/(Rp + height);
695 rho_ENU = (
Vector(3) << rho_E, rho_N, rho_U).finished();
707 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 709 friend class boost::serialization::access;
710 template<
class ARCHIVE>
711 void serialize(ARCHIVE & ar,
const unsigned int ) {
712 ar & boost::serialization::make_nvp(
"NonlinearFactor2",
713 boost::serialization::base_object<Base>(*
this));
Jet< T, N > cos(const Jet< T, N > &f)
NoiseModelFactorN< POSE, VELOCITY, IMUBIAS, POSE, VELOCITY > Base
static shared_ptr Covariance(const Matrix &covariance, bool smart=true)
static Vector PreIntegrateIMUObservations_delta_angles(const Vector &msr_gyro_t, const double msr_dt, const Vector3 &delta_angles, const bool flag_use_body_P_sensor, const POSE &body_P_sensor, IMUBIAS Bias_t0=IMUBIAS())
std::string serialize(const T &input)
serializes to a string
noiseModel::Diagonal::shared_ptr model
VELOCITY evaluateVelocityError(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, const POSE &Pose2, const VELOCITY &Vel2) const
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
static VELOCITY PredictVelocityFromPreIntegration(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, const Vector &delta_vel_in_t0, double dt12, const Vector world_g, const Vector world_rho, const Vector &world_omega_earth, const Matrix &Jacobian_wrt_t0_Overall, const std::optional< IMUBIAS > &Bias_initial={})
std::optional< POSE > body_P_sensor_
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
Jet< T, N > sin(const Jet< T, N > &f)
Vector world_omega_earth_
Pose2_ Expmap(const Vector3_ &xi)
Some functions to compute numerical derivatives.
POSE predictPose(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1) const
void predict(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, POSE &Pose2, VELOCITY &Vel2) const
static void PreIntegrateIMUObservations(const Vector &msr_acc_t, const Vector &msr_gyro_t, const double msr_dt, Vector &delta_pos_in_t0, Vector3 &delta_angles, Vector &delta_vel_in_t0, double &delta_t, const noiseModel::Gaussian::shared_ptr &model_continuous_overall, Matrix &EquivCov_Overall, Matrix &Jacobian_wrt_t0_Overall, const IMUBIAS Bias_t0=IMUBIAS(), std::optional< POSE > p_body_P_sensor={})
static const KeyFormatter DefaultKeyFormatter
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
void print(const std::string &s="EquivInertialNavFactor_GlobalVel", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
gtsam::Vector world_omega_earth(world_R_ECEF.matrix() *ECEF_omega_earth)
static noiseModel::Gaussian::shared_ptr CalcEquivalentNoiseCov(const noiseModel::Gaussian::shared_ptr &gaussian_acc, const noiseModel::Gaussian::shared_ptr &gaussian_gyro, const noiseModel::Gaussian::shared_ptr &gaussian_process)
Matrix * OptionalMatrixType
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H={})
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
static POSE PredictPoseFromPreIntegration(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, const Vector &delta_pos_in_t0, const Vector3 &delta_angles, double dt12, const Vector world_g, const Vector world_rho, const Vector &world_omega_earth, const Matrix &Jacobian_wrt_t0_Overall, const std::optional< IMUBIAS > &Bias_initial={})
Matrix stack(size_t nrMatrices,...)
~EquivInertialNavFactor_GlobalVel() override
Vector evaluateError(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, const POSE &Pose2, const VELOCITY &Vel2, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3, OptionalMatrixType H4, OptionalMatrixType H5) const override
Matrix collect(const std::vector< const Matrix *> &matrices, size_t m, size_t n)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static void Calc_g_rho_omega_earth_ENU(const Vector &Pos_ENU, const Vector &Vel_ENU, const Vector &LatLonHeight_IC, const Vector &Pos_ENU_Initial, Vector &g_ENU, Vector &rho_ENU, Vector &omega_earth_ENU)
static Vector PreIntegrateIMUObservations_delta_pos(const double msr_dt, const Vector &delta_pos_in_t0, const Vector &delta_vel_in_t0)
static void CalcEquivalentNoiseCov_DifferentParts(const noiseModel::Gaussian::shared_ptr &gaussian_acc, const noiseModel::Gaussian::shared_ptr &gaussian_gyro, const noiseModel::Gaussian::shared_ptr &gaussian_process, Matrix &cov_acc, Matrix &cov_gyro, Matrix &cov_process_without_acc_gyro)
static const Vector3 world_g(0.0, 0.0, 9.81)
static VELOCITY predictVelocity_inertial(const POSE &Pose1, const VELOCITY &Vel1, const Vector &delta_vel_in_t0, const double dt12, const Vector &world_g, const Vector &world_rho, const Vector &world_omega_earth)
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
EquivInertialNavFactor_GlobalVel(const Key &Pose1, const Key &Vel1, const Key &IMUBias1, const Key &Pose2, const Key &Vel2, const Vector &delta_pos_in_t0, const Vector &delta_vel_in_t0, const Vector3 &delta_angles, double dt12, const Vector world_g, const Vector world_rho, const Vector &world_omega_earth, const noiseModel::Gaussian::shared_ptr &model_equivalent, const Matrix &Jacobian_wrt_t0_Overall, std::optional< IMUBIAS > Bias_initial={}, std::optional< POSE > body_P_sensor={})
Matrix3 skewSymmetric(double wx, double wy, double wz)
SharedNoiseModel noiseModel_
Matrix Jacobian_wrt_t0_Overall_
static noiseModel::Gaussian::shared_ptr calc_descrete_noise_model(const noiseModel::Gaussian::shared_ptr &model, double delta_t)
Non-linear factor base classes.
static void Calc_g_rho_omega_earth_NED(const Vector &Pos_NED, const Vector &Vel_NED, const Vector &LatLonHeight_IC, const Vector &Pos_NED_Initial, Vector &g_NED, Vector &rho_NED, Vector &omega_earth_NED)
static const Vector3 world_rho(0.0, -1.5724e-05, 0.0)
EIGEN_DEVICE_FUNC const TanReturnType tan() const
static POSE predictPose_inertial(const POSE &Pose1, const VELOCITY &Vel1, const Vector &delta_pos_in_t0, const Vector3 &delta_angles, const double dt12, const Vector &world_g, const Vector &world_rho, const Vector &world_omega_earth)
Jet< T, N > sqrt(const Jet< T, N > &f)
static shared_ptr SqrtInformation(const Matrix &R, bool smart=true)
static Vector PreIntegrateIMUObservations_delta_vel(const Vector &msr_gyro_t, const Vector &msr_acc_t, const double msr_dt, const Vector3 &delta_angles, const Vector &delta_vel_in_t0, const bool flag_use_body_P_sensor, const POSE &body_P_sensor, IMUBIAS Bias_t0=IMUBIAS())
std::shared_ptr< Gaussian > shared_ptr
EquivInertialNavFactor_GlobalVel()
Jet< T, N > pow(const Jet< T, N > &f, double g)
std::shared_ptr< EquivInertialNavFactor_GlobalVel > shared_ptr
static void PredictFromPreIntegration(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, POSE &Pose2, VELOCITY &Vel2, const Vector &delta_pos_in_t0, const Vector &delta_vel_in_t0, const Vector3 &delta_angles, double dt12, const Vector world_g, const Vector world_rho, const Vector &world_omega_earth, const Matrix &Jacobian_wrt_t0_Overall, const std::optional< IMUBIAS > &Bias_initial={})
VELOCITY predictVelocity(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1) const
Vector concatVectors(const std::list< Vector > &vs)
std::uint64_t Key
Integer nonlinear key type.
POSE evaluatePoseError(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, const POSE &Pose2, const VELOCITY &Vel2) const
3D rotation represented as a rotation matrix or quaternion
bool equals(const This &other, double tol=1e-9) const
check equality
std::optional< IMUBIAS > Bias_initial_
EquivInertialNavFactor_GlobalVel< POSE, VELOCITY, IMUBIAS > This