EquivInertialNavFactor_GlobalVel_NoBias.h
Go to the documentation of this file.
1 
2 /* ----------------------------------------------------------------------------
3 
4  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
5  * Atlanta, Georgia 30332-0415
6  * All Rights Reserved
7  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
8 
9  * See LICENSE for the license information
10 
11  * -------------------------------------------------------------------------- */
12 
20 #pragma once
21 
24 #include <gtsam/geometry/Rot3.h>
25 #include <gtsam/base/Matrix.h>
26 
27 // Using numerical derivative to calculate d(Pose3::Expmap)/dw
29 
30 #include <boost/optional.hpp>
31 
32 #include <ostream>
33 
34 namespace gtsam {
35 
36 /*
37  * NOTES:
38  * =====
39  * Concept: Based on [Lupton12tro]
40  * - Pre-integrate IMU measurements using the static function PreIntegrateIMUObservations.
41  * Pre-integrated quantities are expressed in the body system of t0 - the first time instant (in which pre-integration began).
42  * All sensor-to-body transformations are performed here.
43  * - If required, calculate inertial solution by calling the static functions: predictPose_inertial, predictVelocity_inertial.
44  * - When the time is right, incorporate pre-integrated IMU data by creating an EquivInertialNavFactor_GlobalVel_NoBias factor, which will
45  * relate between navigation variables at the two time instances (t0 and current time).
46  *
47  * Other notes:
48  * - The global frame (NED or ENU) is defined by the user by specifying the gravity vector in this frame.
49  * - The IMU frame is implicitly defined by the user via the rotation matrix between global and imu frames.
50  * - Camera and IMU frames are identical
51  * - The user should specify a continuous equivalent noise covariance, which can be calculated using
52  * the static function CalcEquivalentNoiseCov based on the IMU gyro and acc measurement noise covariance
53  * matrices and the process\modeling covariance matrix. The IneritalNavFactor converts this into a
54  * discrete form using the supplied delta_t between sub-sequential measurements.
55  * - Earth-rate correction:
56  * + Currently the user should supply R_ECEF_to_G, which is the rotation from ECEF to the global
57  * frame (Local-Level system: ENU or NED, see above).
58  * + R_ECEF_to_G can be calculated by approximated values of latitude and longitude of the system.
59  * + Currently it is assumed that a relatively small distance is traveled w.r.t. to initial pose, since R_ECEF_to_G is constant.
60  * Otherwise, R_ECEF_to_G should be updated each time using the current lat-lon.
61  *
62  * - Frame Notation:
63  * Quantities are written as {Frame of Representation/Destination Frame}_{Quantity Type}_{Quatity Description/Origination Frame}
64  * So, the rotational velocity of the sensor written in the body frame is: body_omega_sensor
65  * And the transformation from the body frame to the world frame would be: world_P_body
66  * This allows visual chaining. For example, converting the sensed angular velocity of the IMU
67  * (angular velocity of the sensor in the sensor frame) into the world frame can be performed as:
68  * world_R_body * body_R_sensor * sensor_omega_sensor = world_omega_sensor
69  *
70  *
71  * - Common Quantity Types
72  * P : pose/3d transformation
73  * R : rotation
74  * omega : angular velocity
75  * t : translation
76  * v : velocity
77  * a : acceleration
78  *
79  * - Common Frames
80  * sensor : the coordinate system attached to the sensor origin
81  * body : the coordinate system attached to body/inertial frame.
82  * Unless an optional frame transformation is provided, the
83  * sensor frame and the body frame will be identical
84  * world : the global/world coordinate frame. This is assumed to be
85  * a tangent plane to the earth's surface somewhere near the
86  * vehicle
87  */
88 
89 template<class POSE, class VELOCITY>
90 class EquivInertialNavFactor_GlobalVel_NoBias : public NoiseModelFactor4<POSE, VELOCITY, POSE, VELOCITY> {
91 
92 private:
93 
96 
100  double dt12_;
101 
105 
107 
108  boost::optional<POSE> body_P_sensor_; // The pose of the sensor in the body frame
109 
110 public:
111 
112  // shorthand for a smart pointer to a factor
113  typedef typename boost::shared_ptr<EquivInertialNavFactor_GlobalVel_NoBias> shared_ptr;
114 
117 
119  EquivInertialNavFactor_GlobalVel_NoBias(const Key& Pose1, const Key& Vel1, const Key& Pose2, const Key& Vel2,
120  const Vector& delta_pos_in_t0, const Vector& delta_vel_in_t0, const Vector3& delta_angles,
121  double dt12, const Vector world_g, const Vector world_rho,
122  const Vector& world_omega_earth, const noiseModel::Gaussian::shared_ptr& model_equivalent,
123  const Matrix& Jacobian_wrt_t0_Overall,
124  boost::optional<POSE> body_P_sensor = boost::none) :
125  Base(model_equivalent, Pose1, Vel1, Pose2, Vel2),
126  delta_pos_in_t0_(delta_pos_in_t0), delta_vel_in_t0_(delta_vel_in_t0), delta_angles_(delta_angles),
127  dt12_(dt12), world_g_(world_g), world_rho_(world_rho), world_omega_earth_(world_omega_earth), Jacobian_wrt_t0_Overall_(Jacobian_wrt_t0_Overall),
128  body_P_sensor_(body_P_sensor) { }
129 
131 
135  virtual void print(
136  const std::string& s = "EquivInertialNavFactor_GlobalVel_NoBias",
137  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
138  std::cout << s << "("
139  << keyFormatter(this->key1()) << ","
140  << keyFormatter(this->key2()) << ","
141  << keyFormatter(this->key3()) << ","
142  << keyFormatter(this->key4()) << "\n";
143  std::cout << "delta_pos_in_t0: " << this->delta_pos_in_t0_.transpose() << std::endl;
144  std::cout << "delta_vel_in_t0: " << this->delta_vel_in_t0_.transpose() << std::endl;
145  std::cout << "delta_angles: " << this->delta_angles_ << std::endl;
146  std::cout << "dt12: " << this->dt12_ << std::endl;
147  std::cout << "gravity (in world frame): " << this->world_g_.transpose() << std::endl;
148  std::cout << "craft rate (in world frame): " << this->world_rho_.transpose() << std::endl;
149  std::cout << "earth's rotation (in world frame): " << this->world_omega_earth_.transpose() << std::endl;
150  if(this->body_P_sensor_)
151  this->body_P_sensor_->print(" sensor pose in body frame: ");
152  this->noiseModel_->print(" noise model");
153  }
154 
156  bool equals(const NonlinearFactor& expected, double tol=1e-9) const override {
157  const This *e = dynamic_cast<const This*> (&expected);
158  return e != nullptr && Base::equals(*e, tol)
159  && (delta_pos_in_t0_ - e->delta_pos_in_t0_).norm() < tol
160  && (delta_vel_in_t0_ - e->delta_vel_in_t0_).norm() < tol
161  && (delta_angles_ - e->delta_angles_).norm() < tol
162  && (dt12_ - e->dt12_) < tol
163  && (world_g_ - e->world_g_).norm() < tol
164  && (world_rho_ - e->world_rho_).norm() < tol
165  && (world_omega_earth_ - e->world_omega_earth_).norm() < tol
166  && ((!body_P_sensor_ && !e->body_P_sensor_) || (body_P_sensor_ && e->body_P_sensor_ && body_P_sensor_->equals(*e->body_P_sensor_)));
167  }
168 
169 
170  POSE predictPose(const POSE& Pose1, const VELOCITY& Vel1) const {
171 
172  /* Position term */
173  Vector delta_pos_in_t0_corrected = delta_pos_in_t0_;
174 
175  /* Rotation term */
176  Vector delta_angles_corrected = delta_angles_;
177 
178  return predictPose_inertial(Pose1, Vel1,
179  delta_pos_in_t0_corrected, delta_angles_corrected,
180  dt12_, world_g_, world_rho_, world_omega_earth_);
181  }
182 
183  static inline POSE predictPose_inertial(const POSE& Pose1, const VELOCITY& Vel1,
184  const Vector& delta_pos_in_t0, const Vector3& delta_angles,
185  const double dt12, const Vector& world_g, const Vector& world_rho, const Vector& world_omega_earth){
186 
187  const POSE& world_P1_body = Pose1;
188  const VELOCITY& world_V1_body = Vel1;
189 
190  /* Position term */
191  Vector body_deltaPos_body = delta_pos_in_t0;
192 
193  Vector world_deltaPos_pls_body = world_P1_body.rotation().matrix() * body_deltaPos_body;
194  Vector world_deltaPos_body = world_V1_body * dt12 + 0.5*world_g*dt12*dt12 + world_deltaPos_pls_body;
195 
196  // Incorporate earth-related terms. Note - these are assumed to be constant between t1 and t2.
197  world_deltaPos_body -= 2*skewSymmetric(world_rho + world_omega_earth)*world_V1_body * dt12*dt12;
198 
199  /* TODO: the term dt12*dt12 in 0.5*world_g*dt12*dt12 is not entirely correct:
200  * the gravity should be canceled from the accelerometer measurements, bust since position
201  * is added with a delta velocity from a previous term, the actual delta time is more complicated.
202  * Need to figure out this in the future - currently because of this issue we'll get some more error
203  * in Z axis.
204  */
205 
206  /* Rotation term */
207  Vector body_deltaAngles_body = delta_angles;
208 
209  // Convert earth-related terms into the body frame
210  Matrix body_R_world(world_P1_body.rotation().inverse().matrix());
211  Vector body_rho = body_R_world * world_rho;
212  Vector body_omega_earth = body_R_world * world_omega_earth;
213 
214  // Incorporate earth-related terms. Note - these are assumed to be constant between t1 and t2.
215  body_deltaAngles_body -= (body_rho + body_omega_earth)*dt12;
216 
217  return POSE(Pose1.rotation() * POSE::Rotation::Expmap(body_deltaAngles_body), Pose1.translation() + typename POSE::Translation(world_deltaPos_body));
218 
219  }
220 
221  VELOCITY predictVelocity(const POSE& Pose1, const VELOCITY& Vel1) const {
222 
223 
224  Vector delta_vel_in_t0_corrected = delta_vel_in_t0_;
225 
226  return predictVelocity_inertial(Pose1, Vel1,
227  delta_vel_in_t0_corrected,
228  dt12_, world_g_, world_rho_, world_omega_earth_);
229  }
230 
231  static inline VELOCITY predictVelocity_inertial(const POSE& Pose1, const VELOCITY& Vel1,
232  const Vector& delta_vel_in_t0,
233  const double dt12, const Vector& world_g, const Vector& world_rho, const Vector& world_omega_earth) {
234 
235  const POSE& world_P1_body = Pose1;
236  const VELOCITY& world_V1_body = Vel1;
237 
238  Vector body_deltaVel_body = delta_vel_in_t0;
239  Vector world_deltaVel_body = world_P1_body.rotation().matrix() * body_deltaVel_body;
240 
241  VELOCITY VelDelta( world_deltaVel_body + world_g * dt12 );
242 
243  // Incorporate earth-related terms. Note - these are assumed to be constant between t1 and t2.
244  VelDelta -= 2*skewSymmetric(world_rho + world_omega_earth)*world_V1_body * dt12;
245 
246  // Predict
247  return Vel1.compose( VelDelta );
248 
249  }
250 
251  void predict(const POSE& Pose1, const VELOCITY& Vel1, POSE& Pose2, VELOCITY& Vel2) const {
252  Pose2 = predictPose(Pose1, Vel1);
253  Vel2 = predictVelocity(Pose1, Vel1);
254  }
255 
256  POSE evaluatePoseError(const POSE& Pose1, const VELOCITY& Vel1, const POSE& Pose2, const VELOCITY& Vel2) const {
257  // Predict
258  POSE Pose2Pred = predictPose(Pose1, Vel1);
259 
260  // Calculate error
261  return Pose2.between(Pose2Pred);
262  }
263 
264  VELOCITY evaluateVelocityError(const POSE& Pose1, const VELOCITY& Vel1, const POSE& Pose2, const VELOCITY& Vel2) const {
265  // Predict
266  VELOCITY Vel2Pred = predictVelocity(Pose1, Vel1);
267 
268  // Calculate error
269  return Vel2.between(Vel2Pred);
270  }
271 
272  Vector evaluateError(const POSE& Pose1, const VELOCITY& Vel1, const POSE& Pose2, const VELOCITY& Vel2,
273  boost::optional<Matrix&> H1 = boost::none,
274  boost::optional<Matrix&> H2 = boost::none,
275  boost::optional<Matrix&> H3 = boost::none,
276  boost::optional<Matrix&> H4 = boost::none) const {
277 
278  // TODO: Write analytical derivative calculations
279  // Jacobian w.r.t. Pose1
280  if (H1){
281  Matrix H1_Pose = numericalDerivative11<POSE, POSE>(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, _1, Vel1, Pose2, Vel2), Pose1);
282  Matrix H1_Vel = numericalDerivative11<VELOCITY, POSE>(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, _1, Vel1, Pose2, Vel2), Pose1);
283  *H1 = stack(2, &H1_Pose, &H1_Vel);
284  }
285 
286  // Jacobian w.r.t. Vel1
287  if (H2){
288  Matrix H2_Pose = numericalDerivative11<POSE, VELOCITY>(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, Pose1, _1, Pose2, Vel2), Vel1);
289  Matrix H2_Vel = numericalDerivative11<VELOCITY, VELOCITY>(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, Pose1, _1, Pose2, Vel2), Vel1);
290  *H2 = stack(2, &H2_Pose, &H2_Vel);
291  }
292 
293  // Jacobian w.r.t. Pose2
294  if (H3){
295  Matrix H3_Pose = numericalDerivative11<POSE, POSE>(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, Pose1, Vel1, _1, Vel2), Pose2);
296  Matrix H3_Vel = numericalDerivative11<VELOCITY, POSE>(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, Pose1, Vel1, _1, Vel2), Pose2);
297  *H3 = stack(2, &H3_Pose, &H3_Vel);
298  }
299 
300  // Jacobian w.r.t. Vel2
301  if (H4){
302  Matrix H4_Pose = numericalDerivative11<POSE, VELOCITY>(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, Pose1, Vel1, Pose2, _1), Vel2);
303  Matrix H4_Vel = numericalDerivative11<VELOCITY, VELOCITY>(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, Pose1, Vel1, Pose2, _1), Vel2);
304  *H4 = stack(2, &H4_Pose, &H4_Vel);
305  }
306 
307  Vector ErrPoseVector(POSE::Logmap(evaluatePoseError(Pose1, Vel1, Pose2, Vel2)));
308  Vector ErrVelVector(VELOCITY::Logmap(evaluateVelocityError(Pose1, Vel1, Pose2, Vel2)));
309 
310  return concatVectors(2, &ErrPoseVector, &ErrVelVector);
311  }
312 
313 
314 
315  static inline POSE PredictPoseFromPreIntegration(const POSE& Pose1, const VELOCITY& Vel1,
316  const Vector& delta_pos_in_t0, const Vector3& delta_angles,
317  double dt12, const Vector world_g, const Vector world_rho,
318  const Vector& world_omega_earth, const Matrix& Jacobian_wrt_t0_Overall) {
319 
320  /* Position term */
321  Vector delta_pos_in_t0_corrected = delta_pos_in_t0;
322 
323  /* Rotation term */
324  Vector delta_angles_corrected = delta_angles;
325  // Another alternative:
326  // Vector delta_angles_corrected = Rot3::Logmap( Rot3::Expmap(delta_angles_)*Rot3::Expmap(J_angles_wrt_BiasGyro*delta_BiasGyro) );
327 
328  return predictPose_inertial(Pose1, Vel1, delta_pos_in_t0_corrected, delta_angles_corrected, dt12, world_g, world_rho, world_omega_earth);
329  }
330 
331  static inline VELOCITY PredictVelocityFromPreIntegration(const POSE& Pose1, const VELOCITY& Vel1,
332  const Vector& delta_vel_in_t0, double dt12, const Vector world_g, const Vector world_rho,
333  const Vector& world_omega_earth, const Matrix& Jacobian_wrt_t0_Overall) {
334 
335  Vector delta_vel_in_t0_corrected = delta_vel_in_t0;
336 
337  return predictVelocity_inertial(Pose1, Vel1, delta_vel_in_t0_corrected, dt12, world_g, world_rho, world_omega_earth);
338  }
339 
340  static inline void PredictFromPreIntegration(const POSE& Pose1, const VELOCITY& Vel1, POSE& Pose2, VELOCITY& Vel2,
341  const Vector& delta_pos_in_t0, const Vector& delta_vel_in_t0, const Vector3& delta_angles,
342  double dt12, const Vector world_g, const Vector world_rho,
343  const Vector& world_omega_earth, const Matrix& Jacobian_wrt_t0_Overall) {
344 
345  Pose2 = PredictPoseFromPreIntegration(Pose1, Vel1, delta_pos_in_t0, delta_angles, dt12, world_g, world_rho, world_omega_earth, Jacobian_wrt_t0_Overall);
346  Vel2 = PredictVelocityFromPreIntegration(Pose1, Vel1, delta_vel_in_t0, dt12, world_g, world_rho, world_omega_earth, Jacobian_wrt_t0_Overall);
347  }
348 
349 
350  static inline void PreIntegrateIMUObservations(const Vector& msr_acc_t, const Vector& msr_gyro_t, const double msr_dt,
351  Vector& delta_pos_in_t0, Vector3& delta_angles, Vector& delta_vel_in_t0, double& delta_t,
352  const noiseModel::Gaussian::shared_ptr& model_continuous_overall,
353  Matrix& EquivCov_Overall, Matrix& Jacobian_wrt_t0_Overall,
354  boost::optional<POSE> p_body_P_sensor = boost::none){
355  // Note: all delta terms refer to an IMU\sensor system at t0
356  // Note: Earth-related terms are not accounted here but are incorporated in predict functions.
357 
358  POSE body_P_sensor = POSE();
359  bool flag_use_body_P_sensor = false;
360  if (p_body_P_sensor){
361  body_P_sensor = *p_body_P_sensor;
362  flag_use_body_P_sensor = true;
363  }
364 
365  delta_pos_in_t0 = PreIntegrateIMUObservations_delta_pos(msr_dt, delta_pos_in_t0, delta_vel_in_t0);
366  delta_vel_in_t0 = PreIntegrateIMUObservations_delta_vel(msr_gyro_t, msr_acc_t, msr_dt, delta_angles, delta_vel_in_t0, flag_use_body_P_sensor, body_P_sensor);
367  delta_angles = PreIntegrateIMUObservations_delta_angles(msr_gyro_t, msr_dt, delta_angles, flag_use_body_P_sensor, body_P_sensor);
368 
369  delta_t += msr_dt;
370 
371  // Update EquivCov_Overall
372  Matrix Z_3x3 = Z_3x3;
373  Matrix I_3x3 = I_3x3;
374 
375  Matrix H_pos_pos = numericalDerivative11<LieVector, LieVector>(boost::bind(&PreIntegrateIMUObservations_delta_pos, msr_dt, _1, delta_vel_in_t0), delta_pos_in_t0);
376  Matrix H_pos_vel = numericalDerivative11<LieVector, LieVector>(boost::bind(&PreIntegrateIMUObservations_delta_pos, msr_dt, delta_pos_in_t0, _1), delta_vel_in_t0);
377  Matrix H_pos_angles = Z_3x3;
378 
379  Matrix H_vel_vel = numericalDerivative11<LieVector, LieVector>(boost::bind(&PreIntegrateIMUObservations_delta_vel, msr_gyro_t, msr_acc_t, msr_dt, delta_angles, _1, flag_use_body_P_sensor, body_P_sensor), delta_vel_in_t0);
380  Matrix H_vel_angles = numericalDerivative11<LieVector, LieVector>(boost::bind(&PreIntegrateIMUObservations_delta_vel, msr_gyro_t, msr_acc_t, msr_dt, _1, delta_vel_in_t0, flag_use_body_P_sensor, body_P_sensor), delta_angles);
381  Matrix H_vel_pos = Z_3x3;
382 
383  Matrix H_angles_angles = numericalDerivative11<LieVector, LieVector>(boost::bind(&PreIntegrateIMUObservations_delta_angles, msr_gyro_t, msr_dt, _1, flag_use_body_P_sensor, body_P_sensor), delta_angles);
384  Matrix H_angles_pos = Z_3x3;
385  Matrix H_angles_vel = Z_3x3;
386 
387  Matrix F_angles = collect(3, &H_angles_angles, &H_angles_pos, &H_angles_vel);
388  Matrix F_pos = collect(3, &H_pos_angles, &H_pos_pos, &H_pos_vel);
389  Matrix F_vel = collect(3, &H_vel_angles, &H_vel_pos, &H_vel_vel);
390  Matrix F = stack(3, &F_angles, &F_pos, &F_vel);
391 
392  noiseModel::Gaussian::shared_ptr model_discrete_curr = calc_descrete_noise_model(model_continuous_overall, msr_dt );
393  Matrix Q_d = inverse(model_discrete_curr->R().transpose() * model_discrete_curr->R() );
394 
395  EquivCov_Overall = F * EquivCov_Overall * F.transpose() + Q_d;
396 
397  // Update Jacobian_wrt_t0_Overall
398  Jacobian_wrt_t0_Overall = F * Jacobian_wrt_t0_Overall;
399  }
400 
401  static inline Vector PreIntegrateIMUObservations_delta_pos(const double msr_dt,
402  const Vector& delta_pos_in_t0, const Vector& delta_vel_in_t0){
403 
404  // Note: all delta terms refer to an IMU\sensor system at t0
405  // Note: delta_vel_in_t0 is already in body frame, so no need to use the body_P_sensor transformation here.
406 
407  return delta_pos_in_t0 + delta_vel_in_t0 * msr_dt;
408  }
409 
410 
411 
412  static inline Vector PreIntegrateIMUObservations_delta_vel(const Vector& msr_gyro_t, const Vector& msr_acc_t, const double msr_dt,
413  const Vector3& delta_angles, const Vector& delta_vel_in_t0, const bool flag_use_body_P_sensor, const POSE& body_P_sensor){
414 
415  // Note: all delta terms refer to an IMU\sensor system at t0
416 
417  // Calculate the corrected measurements using the Bias object
418  Vector AccCorrected = msr_acc_t;
419  Vector body_t_a_body;
420  if (flag_use_body_P_sensor){
421  Matrix body_R_sensor = body_P_sensor.rotation().matrix();
422 
423  Vector GyroCorrected(msr_gyro_t);
424 
425  Vector body_omega_body = body_R_sensor * GyroCorrected;
426  Matrix body_omega_body__cross = skewSymmetric(body_omega_body);
427 
428  body_t_a_body = body_R_sensor * AccCorrected - body_omega_body__cross * body_omega_body__cross * body_P_sensor.translation().vector();
429  } else{
430  body_t_a_body = AccCorrected;
431  }
432 
433  Rot3 R_t_to_t0 = Rot3::Expmap(delta_angles);
434 
435  return delta_vel_in_t0 + R_t_to_t0.matrix() * body_t_a_body * msr_dt;
436  }
437 
438 
439  static inline Vector PreIntegrateIMUObservations_delta_angles(const Vector& msr_gyro_t, const double msr_dt,
440  const Vector3& delta_angles, const bool flag_use_body_P_sensor, const POSE& body_P_sensor){
441 
442  // Note: all delta terms refer to an IMU\sensor system at t0
443 
444  // Calculate the corrected measurements using the Bias object
445  Vector GyroCorrected = msr_gyro_t;
446 
447  Vector body_t_omega_body;
448  if (flag_use_body_P_sensor){
449  body_t_omega_body = body_P_sensor.rotation().matrix() * GyroCorrected;
450  } else {
451  body_t_omega_body = GyroCorrected;
452  }
453 
454  Rot3 R_t_to_t0 = Rot3::Expmap(delta_angles);
455 
456  R_t_to_t0 = R_t_to_t0 * Rot3::Expmap( body_t_omega_body*msr_dt );
457  return Rot3::Logmap(R_t_to_t0);
458  }
459 
461  const noiseModel::Gaussian::shared_ptr& gaussian_process){
462 
463  Matrix cov_acc = inverse( gaussian_acc->R().transpose() * gaussian_acc->R() );
464  Matrix cov_gyro = inverse( gaussian_gyro->R().transpose() * gaussian_gyro->R() );
465  Matrix cov_process = inverse( gaussian_process->R().transpose() * gaussian_process->R() );
466 
467  cov_process.block(0,0, 3,3) += cov_gyro;
468  cov_process.block(6,6, 3,3) += cov_acc;
469 
470  return noiseModel::Gaussian::Covariance(cov_process);
471  }
472 
474  const noiseModel::Gaussian::shared_ptr& gaussian_process,
475  Matrix& cov_acc, Matrix& cov_gyro, Matrix& cov_process_without_acc_gyro){
476 
477  cov_acc = inverse( gaussian_acc->R().transpose() * gaussian_acc->R() );
478  cov_gyro = inverse( gaussian_gyro->R().transpose() * gaussian_gyro->R() );
479  cov_process_without_acc_gyro = inverse( gaussian_process->R().transpose() * gaussian_process->R() );
480  }
481 
482  static inline void Calc_g_rho_omega_earth_NED(const Vector& Pos_NED, const Vector& Vel_NED, const Vector& LatLonHeight_IC, const Vector& Pos_NED_Initial,
483  Vector& g_NED, Vector& rho_NED, Vector& omega_earth_NED) {
484 
485  Matrix ENU_to_NED = (Matrix(3, 3) <<
486  0.0, 1.0, 0.0,
487  1.0, 0.0, 0.0,
488  0.0, 0.0, -1.0).finished();
489 
490  Matrix NED_to_ENU = (Matrix(3, 3) <<
491  0.0, 1.0, 0.0,
492  1.0, 0.0, 0.0,
493  0.0, 0.0, -1.0).finished();
494 
495  // Convert incoming parameters to ENU
496  Vector Pos_ENU = NED_to_ENU * Pos_NED;
497  Vector Vel_ENU = NED_to_ENU * Vel_NED;
498  Vector Pos_ENU_Initial = NED_to_ENU * Pos_NED_Initial;
499 
500  // Call ENU version
501  Vector g_ENU;
502  Vector rho_ENU;
503  Vector omega_earth_ENU;
504  Calc_g_rho_omega_earth_ENU(Pos_ENU, Vel_ENU, LatLonHeight_IC, Pos_ENU_Initial, g_ENU, rho_ENU, omega_earth_ENU);
505 
506  // Convert output to NED
507  g_NED = ENU_to_NED * g_ENU;
508  rho_NED = ENU_to_NED * rho_ENU;
509  omega_earth_NED = ENU_to_NED * omega_earth_ENU;
510  }
511 
512  static inline void Calc_g_rho_omega_earth_ENU(const Vector& Pos_ENU, const Vector& Vel_ENU, const Vector& LatLonHeight_IC, const Vector& Pos_ENU_Initial,
513  Vector& g_ENU, Vector& rho_ENU, Vector& omega_earth_ENU){
514  double R0 = 6.378388e6;
515  double e = 1/297;
516  double Re( R0*( 1-e*(sin( LatLonHeight_IC(0) ))*(sin( LatLonHeight_IC(0) )) ) );
517 
518  // Calculate current lat, lon
519  Vector delta_Pos_ENU(Pos_ENU - Pos_ENU_Initial);
520  double delta_lat(delta_Pos_ENU(1)/Re);
521  double delta_lon(delta_Pos_ENU(0)/(Re*cos(LatLonHeight_IC(0))));
522  double lat_new(LatLonHeight_IC(0) + delta_lat);
523  double lon_new(LatLonHeight_IC(1) + delta_lon);
524 
525  // Rotation of lon about z axis
526  Rot3 C1(cos(lon_new), sin(lon_new), 0.0,
527  -sin(lon_new), cos(lon_new), 0.0,
528  0.0, 0.0, 1.0);
529 
530  // Rotation of lat about y axis
531  Rot3 C2(cos(lat_new), 0.0, sin(lat_new),
532  0.0, 1.0, 0.0,
533  -sin(lat_new), 0.0, cos(lat_new));
534 
535  Rot3 UEN_to_ENU(0, 1, 0,
536  0, 0, 1,
537  1, 0, 0);
538 
539  Rot3 R_ECEF_to_ENU( UEN_to_ENU * C2 * C1 );
540 
541  Vector omega_earth_ECEF((Vector(3) << 0.0, 0.0, 7.292115e-5));
542  omega_earth_ENU = R_ECEF_to_ENU.matrix() * omega_earth_ECEF;
543 
544  // Calculating g
545  double height(LatLonHeight_IC(2));
546  double EQUA_RADIUS = 6378137.0; // equatorial radius of the earth; WGS-84
547  double ECCENTRICITY = 0.0818191908426; // eccentricity of the earth ellipsoid
548  double e2( pow(ECCENTRICITY,2) );
549  double den( 1-e2*pow(sin(lat_new),2) );
550  double Rm( (EQUA_RADIUS*(1-e2))/( pow(den,(3/2)) ) );
551  double Rp( EQUA_RADIUS/( sqrt(den) ) );
552  double Ro( sqrt(Rp*Rm) ); // mean earth radius of curvature
553  double g0( 9.780318*( 1 + 5.3024e-3 * pow(sin(lat_new),2) - 5.9e-6 * pow(sin(2*lat_new),2) ) );
554  double g_calc( g0/( pow(1 + height/Ro, 2) ) );
555  g_ENU = (Vector(3) << 0.0, 0.0, -g_calc);
556 
557 
558  // Calculate rho
559  double Ve( Vel_ENU(0) );
560  double Vn( Vel_ENU(1) );
561  double rho_E = -Vn/(Rm + height);
562  double rho_N = Ve/(Rp + height);
563  double rho_U = Ve*tan(lat_new)/(Rp + height);
564  rho_ENU = (Vector(3) << rho_E, rho_N, rho_U);
565  }
566 
568  /* Q_d (approx)= Q * delta_t */
569  /* In practice, square root of the information matrix is represented, so that:
570  * R_d (approx)= R / sqrt(delta_t)
571  * */
572  return noiseModel::Gaussian::SqrtInformation(model->R()/sqrt(delta_t));
573  }
574 private:
575 
578  template<class ARCHIVE>
579  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
580  ar & boost::serialization::make_nvp("NonlinearFactor2",
581  boost::serialization::base_object<Base>(*this));
582  }
583 
584 
585 
586 }; // \class EquivInertialNavFactor_GlobalVel_NoBias
587 
588 }
bool equals(const This &other, double tol=1e-9) const
check equality
Definition: Factor.cpp:42
POSE evaluatePoseError(const POSE &Pose1, const VELOCITY &Vel1, const POSE &Pose2, const VELOCITY &Vel2) const
VELOCITY predictVelocity(const POSE &Pose1, const VELOCITY &Vel1) const
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
VELOCITY evaluateVelocityError(const POSE &Pose1, const VELOCITY &Vel1, const POSE &Pose2, const VELOCITY &Vel2) const
static shared_ptr Covariance(const Matrix &covariance, bool smart=true)
Definition: NoiseModel.cpp:116
Eigen::Vector3d Vector3
Definition: Vector.h:43
EquivInertialNavFactor_GlobalVel_NoBias(const Key &Pose1, const Key &Vel1, 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, boost::optional< POSE > body_P_sensor=boost::none)
noiseModel::Diagonal::shared_ptr model
Matrix expected
Definition: testMatrix.cpp:974
NoiseModelFactor4< POSE, VELOCITY, POSE, VELOCITY > Base
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
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)
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Pose2_ Expmap(const Vector3_ &xi)
static VELOCITY PredictVelocityFromPreIntegration(const POSE &Pose1, const VELOCITY &Vel1, 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)
Some functions to compute numerical derivatives.
Matrix3 matrix() const
Definition: Rot3M.cpp:219
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)
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 KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
void predict(const POSE &Pose1, const VELOCITY &Vel1, POSE &Pose2, VELOCITY &Vel2) const
EIGEN_DEVICE_FUNC const CosReturnType cos() const
boost::shared_ptr< EquivInertialNavFactor_GlobalVel_NoBias > shared_ptr
Signature::Row F
Definition: Signature.cpp:53
static const Vector3 world_rho(0.0,-1.5724e-05, 0.0)
Eigen::VectorXd Vector
Definition: Vector.h:38
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)
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)
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY > This
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
static void PredictFromPreIntegration(const POSE &Pose1, const VELOCITY &Vel1, 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)
EIGEN_DEVICE_FUNC const TanReturnType tan() const
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
Definition: Rot3.h:377
virtual void print(const std::string &s="EquivInertialNavFactor_GlobalVel_NoBias", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
static const Vector3 world_g(0.0, 0.0, 9.81)
traits
Definition: chartTesting.h:28
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)
Vector evaluateError(const POSE &Pose1, const VELOCITY &Vel1, const POSE &Pose2, const VELOCITY &Vel2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none, boost::optional< Matrix & > H4=boost::none) const
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:404
SharedNoiseModel noiseModel_
static noiseModel::Gaussian::shared_ptr calc_descrete_noise_model(const noiseModel::Gaussian::shared_ptr &model, double delta_t)
Non-linear factor base classes.
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H=boost::none)
Definition: Rot3M.cpp:158
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 stack(size_t nrMatrices,...)
Definition: Matrix.cpp:396
static Vector PreIntegrateIMUObservations_delta_pos(const double msr_dt, const Vector &delta_pos_in_t0, const Vector &delta_vel_in_t0)
gtsam::Vector world_omega_earth(world_R_ECEF.matrix()*ECEF_omega_earth)
boost::shared_ptr< Gaussian > shared_ptr
Definition: NoiseModel.h:189
static Rot3 R0
Matrix collect(const std::vector< const Matrix * > &matrices, size_t m, size_t n)
Definition: Matrix.cpp:442
EIGEN_DEVICE_FUNC const SinReturnType sin() const
const G double tol
Definition: Group.h:83
static shared_ptr SqrtInformation(const Matrix &R, bool smart=true)
Definition: NoiseModel.cpp:85
Jet< T, N > pow(const Jet< T, N > &f, double g)
Definition: jet.h:570
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 POSE PredictPoseFromPreIntegration(const POSE &Pose1, const VELOCITY &Vel1, 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)
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, boost::optional< POSE > p_body_P_sensor=boost::none)
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
Vector concatVectors(const std::list< Vector > &vs)
Definition: Vector.cpp:302
POSE predictPose(const POSE &Pose1, const VELOCITY &Vel1) const
3D rotation represented as a rotation matrix or quaternion


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:02