InertialNavFactor_GlobalVelocity.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
19 #pragma once
20 
23 #include <gtsam/geometry/Rot3.h>
24 #include <gtsam/base/Matrix.h>
25 
26 // Using numerical derivative to calculate d(Pose3::Expmap)/dw
28 
29 #include <ostream>
30 
31 namespace gtsam {
32 
33 /*
34  * NOTES:
35  * =====
36  * - The global frame (NED or ENU) is defined by the user by specifying the gravity vector in this frame.
37  * - The IMU frame is implicitly defined by the user via the rotation matrix between global and imu frames.
38  * - Camera and IMU frames are identical
39  * - The user should specify a continuous equivalent noise covariance, which can be calculated using
40  * the static function CalcEquivalentNoiseCov based on the IMU gyro and acc measurement noise covariance
41  * matrices and the process\modeling covariance matrix. The IneritalNavFactor converts this into a
42  * discrete form using the supplied delta_t between sub-sequential measurements.
43  * - Earth-rate correction:
44  * + Currently the user should supply R_ECEF_to_G, which is the rotation from ECEF to the global
45  * frame (Local-Level system: ENU or NED, see above).
46  * + R_ECEF_to_G can be calculated by approximated values of latitude and longitude of the system.
47  * + Currently it is assumed that a relatively small distance is traveled w.r.t. to initial pose, since R_ECEF_to_G is constant.
48  * Otherwise, R_ECEF_to_G should be updated each time using the current lat-lon.
49  *
50  * - Frame Notation:
51  * Quantities are written as {Frame of Representation/Destination Frame}_{Quantity Type}_{Quatity Description/Origination Frame}
52  * So, the rotational velocity of the sensor written in the body frame is: body_omega_sensor
53  * And the transformation from the body frame to the world frame would be: world_P_body
54  * This allows visual chaining. For example, converting the sensed angular velocity of the IMU
55  * (angular velocity of the sensor in the sensor frame) into the world frame can be performed as:
56  * world_R_body * body_R_sensor * sensor_omega_sensor = world_omega_sensor
57  *
58  *
59  * - Common Quantity Types
60  * P : pose/3d transformation
61  * R : rotation
62  * omega : angular velocity
63  * t : translation
64  * v : velocity
65  * a : acceleration
66  *
67  * - Common Frames
68  * sensor : the coordinate system attached to the sensor origin
69  * body : the coordinate system attached to body/inertial frame.
70  * Unless an optional frame transformation is provided, the
71  * sensor frame and the body frame will be identical
72  * world : the global/world coordinate frame. This is assumed to be
73  * a tangent plane to the earth's surface somewhere near the
74  * vehicle
75  */
76 template<class POSE, class VELOCITY, class IMUBIAS>
77 class InertialNavFactor_GlobalVelocity : public NoiseModelFactorN<POSE, VELOCITY, IMUBIAS, POSE, VELOCITY> {
78 
79 private:
80 
83 
86  double dt_;
87 
91 
92  std::optional<POSE> body_P_sensor_; // The pose of the sensor in the body frame
93 
94 public:
95 
96  // Provide access to the Matrix& version of evaluateError:
97  using Base::evaluateError;
98 
99  // shorthand for a smart pointer to a factor
100  typedef typename std::shared_ptr<InertialNavFactor_GlobalVelocity> shared_ptr;
101 
104 
106  InertialNavFactor_GlobalVelocity(const Key& Pose1, const Key& Vel1, const Key& IMUBias1, const Key& Pose2, const Key& Vel2,
107  const Vector& measurement_acc, const Vector& measurement_gyro, const double measurement_dt, const Vector world_g, const Vector world_rho,
108  const Vector& world_omega_earth, const noiseModel::Gaussian::shared_ptr& model_continuous, std::optional<POSE> body_P_sensor = {}) :
109  Base(calc_descrete_noise_model(model_continuous, measurement_dt ),
110  Pose1, Vel1, IMUBias1, Pose2, Vel2), measurement_acc_(measurement_acc), measurement_gyro_(measurement_gyro),
112 
114 
118  void print(const std::string& s = "InertialNavFactor_GlobalVelocity", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
119  std::cout << s << "("
120  << keyFormatter(this->key1()) << ","
121  << keyFormatter(this->key2()) << ","
122  << keyFormatter(this->key3()) << ","
123  << keyFormatter(this->key4()) << ","
124  << keyFormatter(this->key5()) << "\n";
125  std::cout << "acc measurement: " << this->measurement_acc_.transpose() << std::endl;
126  std::cout << "gyro measurement: " << this->measurement_gyro_.transpose() << std::endl;
127  std::cout << "dt: " << this->dt_ << std::endl;
128  std::cout << "gravity (in world frame): " << this->world_g_.transpose() << std::endl;
129  std::cout << "craft rate (in world frame): " << this->world_rho_.transpose() << std::endl;
130  std::cout << "earth's rotation (in world frame): " << this->world_omega_earth_.transpose() << std::endl;
131  if(this->body_P_sensor_)
132  this->body_P_sensor_->print(" sensor pose in body frame: ");
133  this->noiseModel_->print(" noise model");
134  }
135 
137  bool equals(const NonlinearFactor& expected, double tol=1e-9) const override {
138  const This *e = dynamic_cast<const This*> (&expected);
139  return e != nullptr && Base::equals(*e, tol)
140  && (measurement_acc_ - e->measurement_acc_).norm() < tol
141  && (measurement_gyro_ - e->measurement_gyro_).norm() < tol
142  && (dt_ - e->dt_) < tol
143  && (world_g_ - e->world_g_).norm() < tol
144  && (world_rho_ - e->world_rho_).norm() < tol
145  && (world_omega_earth_ - e->world_omega_earth_).norm() < tol
146  && ((!body_P_sensor_ && !e->body_P_sensor_) || (body_P_sensor_ && e->body_P_sensor_ && body_P_sensor_->equals(*e->body_P_sensor_)));
147  }
148 
149  POSE predictPose(const POSE& Pose1, const VELOCITY& Vel1, const IMUBIAS& Bias1) const {
150  // Calculate the corrected measurements using the Bias object
151  Vector GyroCorrected(Bias1.correctGyroscope(measurement_gyro_));
152 
153  const POSE& world_P1_body = Pose1;
154  const VELOCITY& world_V1_body = Vel1;
155 
156  // Calculate the acceleration and angular velocity of the body in the body frame (including earth-related rotations)
157  Vector body_omega_body;
158  if(body_P_sensor_) {
159  body_omega_body = body_P_sensor_->rotation().matrix() * GyroCorrected;
160  } else {
161  body_omega_body = GyroCorrected;
162  }
163 
164  // Convert earth-related terms into the body frame
165  Matrix body_R_world(world_P1_body.rotation().inverse().matrix());
166  Vector body_rho = body_R_world * world_rho_;
167  Vector body_omega_earth = body_R_world * world_omega_earth_;
168 
169  // Correct for earth-related terms
170  body_omega_body -= body_rho + body_omega_earth;
171 
172  // The velocity is in the global frame, so composing Pose1 with v*dt is incorrect
173  return POSE(Pose1.rotation() * POSE::Rotation::Expmap(body_omega_body*dt_), Pose1.translation() + typename POSE::Translation(world_V1_body*dt_));
174  }
175 
176  VELOCITY predictVelocity(const POSE& Pose1, const VELOCITY& Vel1, const IMUBIAS& Bias1) const {
177  // Calculate the corrected measurements using the Bias object
178  Vector AccCorrected(Bias1.correctAccelerometer(measurement_acc_));
179 
180  const POSE& world_P1_body = Pose1;
181  const VELOCITY& world_V1_body = Vel1;
182 
183  // Calculate the acceleration and angular velocity of the body in the body frame (including earth-related rotations)
184  Vector body_a_body, body_omega_body;
185  if(body_P_sensor_) {
186  Matrix body_R_sensor = body_P_sensor_->rotation().matrix();
187 
188  Vector GyroCorrected(Bias1.correctGyroscope(measurement_gyro_));
189  body_omega_body = body_R_sensor * GyroCorrected;
190  Matrix body_omega_body__cross = skewSymmetric(body_omega_body);
191  body_a_body = body_R_sensor * AccCorrected - body_omega_body__cross * body_omega_body__cross * body_P_sensor_->translation();
192  } else {
193  body_a_body = AccCorrected;
194  }
195 
196  // Correct for earth-related terms
197  Vector world_a_body = world_P1_body.rotation().matrix() * body_a_body + world_g_ - 2*skewSymmetric(world_rho_ + world_omega_earth_)*world_V1_body;
198 
199  // Calculate delta in the body frame
200  VELOCITY VelDelta(world_a_body*dt_);
201 
202  // Predict
203  return Vel1 + VelDelta;
204  }
205 
206  void predict(const POSE& Pose1, const VELOCITY& Vel1, const IMUBIAS& Bias1, POSE& Pose2, VELOCITY& Vel2) const {
207  Pose2 = predictPose(Pose1, Vel1, Bias1);
208  Vel2 = predictVelocity(Pose1, Vel1, Bias1);
209  }
210 
211  POSE evaluatePoseError(const POSE& Pose1, const VELOCITY& Vel1, const IMUBIAS& Bias1, const POSE& Pose2, const VELOCITY& Vel2) const {
212  // Predict
213  POSE Pose2Pred = predictPose(Pose1, Vel1, Bias1);
214 
215  // Calculate error
216  return Pose2.between(Pose2Pred);
217  }
218 
219  VELOCITY evaluateVelocityError(const POSE& Pose1, const VELOCITY& Vel1, const IMUBIAS& Bias1, const POSE& Pose2, const VELOCITY& Vel2) const {
220  // Predict
221  VELOCITY Vel2Pred = predictVelocity(Pose1, Vel1, Bias1);
222 
223  // Calculate error
224  return Vel2Pred - Vel2;
225  }
226 
228  Vector evaluateError(const POSE& Pose1, const VELOCITY& Vel1, const IMUBIAS& Bias1, const POSE& Pose2, const VELOCITY& Vel2,
230  OptionalMatrixType H5) const override {
231 
232  // TODO: Write analytical derivative calculations
233  // Jacobian w.r.t. Pose1
234  if (H1){
235  Matrix H1_Pose = gtsam::numericalDerivative11<POSE, POSE>(
237  this, std::placeholders::_1, Vel1, Bias1, Pose2, Vel2),
238  Pose1);
239  Matrix H1_Vel = gtsam::numericalDerivative11<VELOCITY, POSE>(
241  this, std::placeholders::_1, Vel1, Bias1, Pose2, Vel2),
242  Pose1);
243  *H1 = stack(2, &H1_Pose, &H1_Vel);
244  }
245 
246  // Jacobian w.r.t. Vel1
247  if (H2){
248  if (Vel1.size()!=3) throw std::runtime_error("Frank's hack to make this compile will not work if size != 3");
249  Matrix H2_Pose = gtsam::numericalDerivative11<POSE, Vector3>(
251  this, Pose1, std::placeholders::_1, Bias1, Pose2, Vel2),
252  Vel1);
253  Matrix H2_Vel = gtsam::numericalDerivative11<Vector3, Vector3>(
255  this, Pose1, std::placeholders::_1, Bias1, Pose2, Vel2),
256  Vel1);
257  *H2 = stack(2, &H2_Pose, &H2_Vel);
258  }
259 
260  // Jacobian w.r.t. IMUBias1
261  if (H3){
262  Matrix H3_Pose = gtsam::numericalDerivative11<POSE, IMUBIAS>(
264  this, Pose1, Vel1, std::placeholders::_1, Pose2, Vel2),
265  Bias1);
266  Matrix H3_Vel = gtsam::numericalDerivative11<VELOCITY, IMUBIAS>(
268  this, Pose1, Vel1, std::placeholders::_1, Pose2, Vel2),
269  Bias1);
270  *H3 = stack(2, &H3_Pose, &H3_Vel);
271  }
272 
273  // Jacobian w.r.t. Pose2
274  if (H4){
275  Matrix H4_Pose = gtsam::numericalDerivative11<POSE, POSE>(
277  this, Pose1, Vel1, Bias1, std::placeholders::_1, Vel2),
278  Pose2);
279  Matrix H4_Vel = gtsam::numericalDerivative11<VELOCITY, POSE>(
281  this, Pose1, Vel1, Bias1, std::placeholders::_1, Vel2),
282  Pose2);
283  *H4 = stack(2, &H4_Pose, &H4_Vel);
284  }
285 
286  // Jacobian w.r.t. Vel2
287  if (H5){
288  if (Vel2.size()!=3) throw std::runtime_error("Frank's hack to make this compile will not work if size != 3");
289  Matrix H5_Pose = gtsam::numericalDerivative11<POSE, Vector3>(
291  this, Pose1, Vel1, Bias1, Pose2, std::placeholders::_1),
292  Vel2);
293  Matrix H5_Vel = gtsam::numericalDerivative11<Vector3, Vector3>(
295  this, Pose1, Vel1, Bias1, Pose2, std::placeholders::_1),
296  Vel2);
297  *H5 = stack(2, &H5_Pose, &H5_Vel);
298  }
299 
300  Vector ErrPoseVector(POSE::Logmap(evaluatePoseError(Pose1, Vel1, Bias1, Pose2, Vel2)));
301  Vector ErrVelVector(evaluateVelocityError(Pose1, Vel1, Bias1, Pose2, Vel2));
302 
303  return concatVectors(2, &ErrPoseVector, &ErrVelVector);
304  }
305 
307  const noiseModel::Gaussian::shared_ptr& gaussian_process){
308 
309  Matrix cov_acc = ( gaussian_acc->R().transpose() * gaussian_acc->R() ).inverse();
310  Matrix cov_gyro = ( gaussian_gyro->R().transpose() * gaussian_gyro->R() ).inverse();
311  Matrix cov_process = ( gaussian_process->R().transpose() * gaussian_process->R() ).inverse();
312 
313  cov_process.block(0,0, 3,3) += cov_gyro;
314  cov_process.block(6,6, 3,3) += cov_acc;
315 
316  return noiseModel::Gaussian::Covariance(cov_process);
317  }
318 
319  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,
320  Vector& g_NED, Vector& rho_NED, Vector& omega_earth_NED) {
321 
322  Matrix ENU_to_NED = (Matrix(3, 3) <<
323  0.0, 1.0, 0.0,
324  1.0, 0.0, 0.0,
325  0.0, 0.0, -1.0).finished();
326 
327  Matrix NED_to_ENU = (Matrix(3, 3) <<
328  0.0, 1.0, 0.0,
329  1.0, 0.0, 0.0,
330  0.0, 0.0, -1.0).finished();
331 
332  // Convert incoming parameters to ENU
333  Vector Pos_ENU = NED_to_ENU * Pos_NED;
334  Vector Vel_ENU = NED_to_ENU * Vel_NED;
335  Vector Pos_ENU_Initial = NED_to_ENU * Pos_NED_Initial;
336 
337  // Call ENU version
338  Vector g_ENU;
339  Vector rho_ENU;
340  Vector omega_earth_ENU;
341  Calc_g_rho_omega_earth_ENU(Pos_ENU, Vel_ENU, LatLonHeight_IC, Pos_ENU_Initial, g_ENU, rho_ENU, omega_earth_ENU);
342 
343  // Convert output to NED
344  g_NED = ENU_to_NED * g_ENU;
345  rho_NED = ENU_to_NED * rho_ENU;
346  omega_earth_NED = ENU_to_NED * omega_earth_ENU;
347  }
348 
349  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,
350  Vector& g_ENU, Vector& rho_ENU, Vector& omega_earth_ENU){
351  double R0 = 6.378388e6;
352  double e = 1/297;
353  double Re( R0*( 1-e*(sin( LatLonHeight_IC(0) ))*(sin( LatLonHeight_IC(0) )) ) );
354 
355  // Calculate current lat, lon
356  Vector delta_Pos_ENU(Pos_ENU - Pos_ENU_Initial);
357  double delta_lat(delta_Pos_ENU(1)/Re);
358  double delta_lon(delta_Pos_ENU(0)/(Re*cos(LatLonHeight_IC(0))));
359  double lat_new(LatLonHeight_IC(0) + delta_lat);
360  double lon_new(LatLonHeight_IC(1) + delta_lon);
361 
362  // Rotation of lon about z axis
363  Rot3 C1(cos(lon_new), sin(lon_new), 0.0,
364  -sin(lon_new), cos(lon_new), 0.0,
365  0.0, 0.0, 1.0);
366 
367  // Rotation of lat about y axis
368  Rot3 C2(cos(lat_new), 0.0, sin(lat_new),
369  0.0, 1.0, 0.0,
370  -sin(lat_new), 0.0, cos(lat_new));
371 
372  Rot3 UEN_to_ENU(0, 1, 0,
373  0, 0, 1,
374  1, 0, 0);
375 
376  Rot3 R_ECEF_to_ENU( UEN_to_ENU * C2 * C1 );
377 
378  Vector omega_earth_ECEF(Vector3(0.0, 0.0, 7.292115e-5));
379  omega_earth_ENU = R_ECEF_to_ENU.matrix() * omega_earth_ECEF;
380 
381  // Calculating g
382  double height(LatLonHeight_IC(2));
383  double EQUA_RADIUS = 6378137.0; // equatorial radius of the earth; WGS-84
384  double ECCENTRICITY = 0.0818191908426; // eccentricity of the earth ellipsoid
385  double e2( pow(ECCENTRICITY,2) );
386  double den( 1-e2*pow(sin(lat_new),2) );
387  double Rm( (EQUA_RADIUS*(1-e2))/( pow(den,(3/2)) ) );
388  double Rp( EQUA_RADIUS/( sqrt(den) ) );
389  double Ro( sqrt(Rp*Rm) ); // mean earth radius of curvature
390  double g0( 9.780318*( 1 + 5.3024e-3 * pow(sin(lat_new),2) - 5.9e-6 * pow(sin(2*lat_new),2) ) );
391  double g_calc( g0/( pow(1 + height/Ro, 2) ) );
392  g_ENU = (Vector(3) << 0.0, 0.0, -g_calc).finished();
393 
394 
395  // Calculate rho
396  double Ve( Vel_ENU(0) );
397  double Vn( Vel_ENU(1) );
398  double rho_E = -Vn/(Rm + height);
399  double rho_N = Ve/(Rp + height);
400  double rho_U = Ve*tan(lat_new)/(Rp + height);
401  rho_ENU = (Vector(3) << rho_E, rho_N, rho_U).finished();
402  }
403 
405  /* Q_d (approx)= Q * delta_t */
406  /* In practice, square root of the information matrix is represented, so that:
407  * R_d (approx)= R / sqrt(delta_t)
408  * */
410  }
411 
412 private:
413 
414 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
415 
416  friend class boost::serialization::access;
417  template<class ARCHIVE>
418  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
419  ar & boost::serialization::make_nvp("NonlinearFactor2",
420  boost::serialization::base_object<Base>(*this));
421  }
422 #endif
423 
424 }; // \class InertialNavFactor_GlobalVelocity
425 
427 template<class POSE, class VELOCITY, class IMUBIAS>
428 struct traits<InertialNavFactor_GlobalVelocity<POSE, VELOCITY, IMUBIAS> > :
429  public Testable<InertialNavFactor_GlobalVelocity<POSE, VELOCITY, IMUBIAS> > {
430 };
431 
432 }
gtsam::InertialNavFactor_GlobalVelocity::predictPose
POSE predictPose(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1) const
Definition: InertialNavFactor_GlobalVelocity.h:149
gtsam::NoiseModelFactorN< POSE, VELOCITY, IMUBIAS, POSE, VELOCITY >::key4
Key key4() const
Definition: NonlinearFactor.h:745
gtsam::LieGroup::between
Class between(const Class &g) const
Definition: Lie.h:52
gtsam::InertialNavFactor_GlobalVelocity::predictVelocity
VELOCITY predictVelocity(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1) const
Definition: InertialNavFactor_GlobalVelocity.h:176
inverse
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Definition: ArrayCwiseUnaryOps.h:411
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::InertialNavFactor_GlobalVelocity::measurement_acc_
Vector measurement_acc_
Definition: InertialNavFactor_GlobalVelocity.h:84
ceres::sin
Jet< T, N > sin(const Jet< T, N > &f)
Definition: jet.h:439
gtsam::InertialNavFactor_GlobalVelocity::measurement_gyro_
Vector measurement_gyro_
Definition: InertialNavFactor_GlobalVelocity.h:85
C1
static double C1
Definition: ellpk.c:93
Matrix.h
typedef and functions to augment Eigen's MatrixXd
gtsam::NoiseModelFactorN< POSE, VELOCITY, IMUBIAS, POSE, VELOCITY >::evaluateError
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
gtsam::InertialNavFactor_GlobalVelocity::Calc_g_rho_omega_earth_NED
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)
Definition: InertialNavFactor_GlobalVelocity.h:319
gtsam::InertialNavFactor_GlobalVelocity::Calc_g_rho_omega_earth_ENU
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)
Definition: InertialNavFactor_GlobalVelocity.h:349
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::NoiseModelFactorN< POSE, VELOCITY, IMUBIAS, POSE, VELOCITY >::key5
Key key5() const
Definition: NonlinearFactor.h:750
gtsam::Factor
Definition: Factor.h:70
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
C2
Definition: test_operator_overloading.cpp:98
C2
static double C2[]
Definition: shichi.c:141
gtsam::NoiseModelFactor::noiseModel_
SharedNoiseModel noiseModel_
Definition: NonlinearFactor.h:205
world_g
static const Vector3 world_g(0.0, 0.0, 9.81)
gtsam::noiseModel::Gaussian::shared_ptr
std::shared_ptr< Gaussian > shared_ptr
Definition: NoiseModel.h:191
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))
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::skewSymmetric
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:400
gtsam::InertialNavFactor_GlobalVelocity::evaluateVelocityError
VELOCITY evaluateVelocityError(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, const POSE &Pose2, const VELOCITY &Vel2) const
Definition: InertialNavFactor_GlobalVelocity.h:219
gtsam::concatVectors
Vector concatVectors(const std::list< Vector > &vs)
Definition: Vector.cpp:301
ceres::cos
Jet< T, N > cos(const Jet< T, N > &f)
Definition: jet.h:426
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::InertialNavFactor_GlobalVelocity::shared_ptr
std::shared_ptr< InertialNavFactor_GlobalVelocity > shared_ptr
Definition: InertialNavFactor_GlobalVelocity.h:100
Rot3.h
3D rotation represented as a rotation matrix or quaternion
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
simple::R0
static Rot3 R0
Definition: testInitializePose3.cpp:48
gtsam::InertialNavFactor_GlobalVelocity
Definition: InertialNavFactor_GlobalVelocity.h:77
gtsam::InertialNavFactor_GlobalVelocity::~InertialNavFactor_GlobalVelocity
~InertialNavFactor_GlobalVelocity() override
Definition: InertialNavFactor_GlobalVelocity.h:113
numericalDerivative.h
Some functions to compute numerical derivatives.
gtsam::InertialNavFactor_GlobalVelocity::world_omega_earth_
Vector world_omega_earth_
Definition: InertialNavFactor_GlobalVelocity.h:90
world_rho
static const Vector3 world_rho(0.0, -1.5724e-05, 0.0)
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::KeyFormatter
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
gtsam::stack
Matrix stack(size_t nrMatrices,...)
Definition: Matrix.cpp:395
C1
Definition: test_operator_overloading.cpp:97
gtsam::NoiseModelFactorN
Definition: NonlinearFactor.h:431
gtsam::InertialNavFactor_GlobalVelocity::Base
NoiseModelFactorN< POSE, VELOCITY, IMUBIAS, POSE, VELOCITY > Base
Definition: InertialNavFactor_GlobalVelocity.h:82
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
gtsam::InertialNavFactor_GlobalVelocity::InertialNavFactor_GlobalVelocity
InertialNavFactor_GlobalVelocity()
Definition: InertialNavFactor_GlobalVelocity.h:103
gtsam::InertialNavFactor_GlobalVelocity::InertialNavFactor_GlobalVelocity
InertialNavFactor_GlobalVelocity(const Key &Pose1, const Key &Vel1, const Key &IMUBias1, const Key &Pose2, const Key &Vel2, const Vector &measurement_acc, const Vector &measurement_gyro, const double measurement_dt, const Vector world_g, const Vector world_rho, const Vector &world_omega_earth, const noiseModel::Gaussian::shared_ptr &model_continuous, std::optional< POSE > body_P_sensor={})
Definition: InertialNavFactor_GlobalVelocity.h:106
gtsam::noiseModel::Gaussian::SqrtInformation
static shared_ptr SqrtInformation(const Matrix &R, bool smart=true)
Definition: NoiseModel.cpp:83
gtsam::InertialNavFactor_GlobalVelocity::calc_descrete_noise_model
static noiseModel::Gaussian::shared_ptr calc_descrete_noise_model(const noiseModel::Gaussian::shared_ptr &model, double delta_t)
Definition: InertialNavFactor_GlobalVelocity.h:404
gtsam::NoiseModelFactor::equals
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Definition: NonlinearFactor.cpp:80
gtsam::NoiseModelFactorN< POSE, VELOCITY, IMUBIAS, POSE, VELOCITY >::key1
Key key1() const
Definition: NonlinearFactor.h:731
tan
const EIGEN_DEVICE_FUNC TanReturnType tan() const
Definition: ArrayCwiseUnaryOps.h:269
ceres::pow
Jet< T, N > pow(const Jet< T, N > &f, double g)
Definition: jet.h:570
gtsam::InertialNavFactor_GlobalVelocity::evaluatePoseError
POSE evaluatePoseError(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, const POSE &Pose2, const VELOCITY &Vel2) const
Definition: InertialNavFactor_GlobalVelocity.h:211
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
gtsam::InertialNavFactor_GlobalVelocity::world_g_
Vector world_g_
Definition: InertialNavFactor_GlobalVelocity.h:88
NonlinearFactor.h
Non-linear factor base classes.
gtsam::InertialNavFactor_GlobalVelocity::body_P_sensor_
std::optional< POSE > body_P_sensor_
Definition: InertialNavFactor_GlobalVelocity.h:92
gtsam::NoiseModelFactorN< POSE, VELOCITY, IMUBIAS, POSE, VELOCITY >::key2
Key key2() const
Definition: NonlinearFactor.h:735
gtsam::InertialNavFactor_GlobalVelocity::equals
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Definition: InertialNavFactor_GlobalVelocity.h:137
gtsam
traits
Definition: SFMdata.h:40
gtsam::Testable
Definition: Testable.h:152
gtsam::InertialNavFactor_GlobalVelocity::This
InertialNavFactor_GlobalVelocity< POSE, VELOCITY, IMUBIAS > This
Definition: InertialNavFactor_GlobalVelocity.h:81
NoiseModel.h
gtsam::traits
Definition: Group.h:36
gtsam::InertialNavFactor_GlobalVelocity::world_rho_
Vector world_rho_
Definition: InertialNavFactor_GlobalVelocity.h:89
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:68
gtsam::InertialNavFactor_GlobalVelocity::print
void print(const std::string &s="InertialNavFactor_GlobalVelocity", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: InertialNavFactor_GlobalVelocity.h:118
gtsam::InertialNavFactor_GlobalVelocity::CalcEquivalentNoiseCov
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)
Definition: InertialNavFactor_GlobalVelocity.h:306
gtsam::Rot3::matrix
Matrix3 matrix() const
Definition: Rot3M.cpp:218
gtsam::NoiseModelFactorN< POSE, VELOCITY, IMUBIAS, POSE, VELOCITY >::key3
Key key3() const
Definition: NonlinearFactor.h:740
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::OptionalMatrixType
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
gtsam::InertialNavFactor_GlobalVelocity::predict
void predict(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, POSE &Pose2, VELOCITY &Vel2) const
Definition: InertialNavFactor_GlobalVelocity.h:206
gtsam::InertialNavFactor_GlobalVelocity::dt_
double dt_
Definition: InertialNavFactor_GlobalVelocity.h:86
world_omega_earth
gtsam::Vector world_omega_earth(world_R_ECEF.matrix() *ECEF_omega_earth)
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::InertialNavFactor_GlobalVelocity::evaluateError
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
Definition: InertialNavFactor_GlobalVelocity.h:228
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
gtsam::noiseModel::Gaussian::Covariance
static shared_ptr Covariance(const Matrix &covariance, bool smart=true)
Definition: NoiseModel.cpp:114
gtsam::Pose2
Definition: Pose2.h:39


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:28