NavState.cpp
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 
20 
21 #include <string>
22 
23 namespace gtsam {
24 
25 //------------------------------------------------------------------------------
26 NavState NavState::Create(const Rot3& R, const Point3& t, const Velocity3& v,
29  if (H1)
30  *H1 << I_3x3, Z_3x3, Z_3x3;
31  if (H2)
32  *H2 << Z_3x3, R.transpose(), Z_3x3;
33  if (H3)
34  *H3 << Z_3x3, Z_3x3, R.transpose();
35  return NavState(R, t, v);
36 }
37 //------------------------------------------------------------------------------
40  if (H1)
41  *H1 << I_3x3, Z_3x3, Z_3x3, I_3x3, Z_3x3, Z_3x3;
42  if (H2)
43  *H2 << Z_3x3, Z_3x3, pose.rotation().transpose();
44  return NavState(pose, vel);
45 }
46 
47 //------------------------------------------------------------------------------
49  if (H)
50  *H << I_3x3, Z_3x3, Z_3x3;
51  return R_;
52 }
53 
54 //------------------------------------------------------------------------------
56  if (H)
57  *H << Z_3x3, R(), Z_3x3;
58  return t_;
59 }
60 
61 //------------------------------------------------------------------------------
63  if (H)
64  *H << Z_3x3, Z_3x3, R();
65  return v_;
66 }
67 
68 //------------------------------------------------------------------------------
70  const Rot3& nRb = R_;
71  const Vector3& n_v = v_;
72  Matrix3 D_bv_nRb;
73  Vector3 b_v = nRb.unrotate(n_v, H ? &D_bv_nRb : 0);
74  if (H)
75  *H << D_bv_nRb, Z_3x3, I_3x3;
76  return b_v;
77 }
78 
79 //------------------------------------------------------------------------------
81  Matrix3 R = this->R();
82 
83  Matrix5 T = Matrix5::Identity();
84  T.block<3, 3>(0, 0) = R;
85  T.block<3, 1>(0, 3) = t_;
86  T.block<3, 1>(0, 4) = v_;
87  return T;
88 }
89 
90 //------------------------------------------------------------------------------
91 std::ostream& operator<<(std::ostream& os, const NavState& state) {
92  os << "R: " << state.attitude() << "\n";
93  os << "p: " << state.position().transpose() << "\n";
94  os << "v: " << state.velocity().transpose();
95  return os;
96 }
97 
98 //------------------------------------------------------------------------------
99 void NavState::print(const std::string& s) const {
100  std::cout << (s.empty() ? s : s + " ") << *this << std::endl;
101 }
102 
103 //------------------------------------------------------------------------------
104 bool NavState::equals(const NavState& other, double tol) const {
105  return R_.equals(other.R_, tol) && traits<Point3>::Equals(t_, other.t_, tol)
106  && equal_with_abs_tol(v_, other.v_, tol);
107 }
108 
109 //------------------------------------------------------------------------------
111  Rot3 Rt = R_.inverse();
112  return NavState(Rt, Rt * (-t_), Rt * -(v_));
113 }
114 
115 //------------------------------------------------------------------------------
117  // Get angular velocity w and components rho (for t) and nu (for v) from xi
118  Vector3 w = xi.head<3>(), rho = xi.segment<3>(3), nu = xi.tail<3>();
119 
120  // Instantiate functor for Dexp-related operations:
121  const so3::DexpFunctor local(w);
122 
123  // Compute rotation using Expmap
124 #ifdef GTSAM_USE_QUATERNIONS
126 #else
127  const Rot3 R(local.expmap());
128 #endif
129 
130  // Compute translation and velocity. See Pose3::Expmap
131  Matrix3 H_t_w, H_v_w;
132  const Vector3 t = local.applyLeftJacobian(rho, Hxi ? &H_t_w : nullptr);
133  const Vector3 v = local.applyLeftJacobian(nu, Hxi ? &H_v_w : nullptr);
134 
135  if (Hxi) {
136  const Matrix3 Jr = local.rightJacobian();
137  // We are creating a NavState, so we still need to chain H_t_w and H_v_w
138  // with R^T, the Jacobian of Navstate::Create with respect to both t and v.
139  const Matrix3 M = R.matrix();
140  *Hxi << Jr, Z_3x3, Z_3x3, // Jr here *is* the Jacobian of expmap
141  M.transpose() * H_t_w, Jr, Z_3x3, //
142  M.transpose() * H_v_w, Z_3x3, Jr;
143  // In the last two rows, Jr = R^T * J_l, see Barfoot eq. (8.83).
144  // J_l is the Jacobian of applyLeftJacobian in the second argument.
145  }
146 
147  return NavState(R, t, v);
148 }
149 
150 //------------------------------------------------------------------------------
152  if (Hstate) *Hstate = LogmapDerivative(state);
153 
154  const Vector3 phi = Rot3::Logmap(state.rotation());
155  const Vector3& p = state.position();
156  const Vector3& v = state.velocity();
157  const double t = phi.norm();
158  if (t < 1e-8) {
159  Vector9 log;
160  log << phi, p, v;
161  return log;
162 
163  } else {
164  const Matrix3 W = skewSymmetric(phi / t);
165 
166  const double Tan = tan(0.5 * t);
167  const Vector3 Wp = W * p;
168  const Vector3 Wv = W * v;
169  const Vector3 rho = p - (0.5 * t) * Wp + (1 - t / (2. * Tan)) * (W * Wp);
170  const Vector3 nu = v - (0.5 * t) * Wv + (1 - t / (2. * Tan)) * (W * Wv);
171  Vector9 log;
172  // Order is ω, p, v
173  log << phi, rho, nu;
174  return log;
175  }
176 }
177 
178 //------------------------------------------------------------------------------
180  const Matrix3 R = R_.matrix();
181  Matrix3 A = skewSymmetric(t_.x(), t_.y(), t_.z()) * R;
182  Matrix3 B = skewSymmetric(v_.x(), v_.y(), v_.z()) * R;
183  // Eqn 2 in Barrau20icra
184  Matrix9 adj;
185  adj << R, Z_3x3, Z_3x3, A, R, Z_3x3, B, Z_3x3, R;
186  return adj;
187 }
188 
189 //------------------------------------------------------------------------------
190 Vector9 NavState::Adjoint(const Vector9& xi_b, OptionalJacobian<9, 9> H_state,
191  OptionalJacobian<9, 9> H_xib) const {
192  const Matrix9 Ad = AdjointMap();
193 
194  // Jacobians
195  if (H_state) *H_state = -Ad * adjointMap(xi_b);
196  if (H_xib) *H_xib = Ad;
197 
198  return Ad * xi_b;
199 }
200 
201 //------------------------------------------------------------------------------
202 Matrix9 NavState::adjointMap(const Vector9& xi) {
203  Matrix3 w_hat = skewSymmetric(xi(0), xi(1), xi(2));
204  Matrix3 v_hat = skewSymmetric(xi(3), xi(4), xi(5));
205  Matrix3 a_hat = skewSymmetric(xi(6), xi(7), xi(8));
206  Matrix9 adj;
207  adj << w_hat, Z_3x3, Z_3x3, v_hat, w_hat, Z_3x3, a_hat, Z_3x3, w_hat;
208  return adj;
209 }
210 
211 //------------------------------------------------------------------------------
212 Vector9 NavState::adjoint(const Vector9& xi, const Vector9& y,
215  if (Hxi) {
216  Hxi->setZero();
217  for (int i = 0; i < 9; ++i) {
218  Vector9 dxi;
219  dxi.setZero();
220  dxi(i) = 1.0;
221  Matrix9 Gi = adjointMap(dxi);
222  Hxi->col(i) = Gi * y;
223  }
224  }
225 
226  const Matrix9& ad_xi = adjointMap(xi);
227  if (H_y) *H_y = ad_xi;
228 
229  return ad_xi * y;
230 }
231 
232 //------------------------------------------------------------------------------
234  Matrix9 J;
235  Expmap(xi, J);
236  return J;
237 }
238 
239 //------------------------------------------------------------------------------
241  const Vector3 w = xi.head<3>();
242  Vector3 rho = xi.segment<3>(3);
243  Vector3 nu = xi.tail<3>();
244 
245  // Instantiate functor for Dexp-related operations:
246  const so3::DexpFunctor local(w);
247 
248  // Call applyLeftJacobian to get its Jacobians
249  Matrix3 H_t_w, H_v_w;
250  local.applyLeftJacobian(rho, H_t_w);
251  local.applyLeftJacobian(nu, H_v_w);
252 
253  // Multiply with R^T to account for NavState::Create Jacobian.
254  const Matrix3 R = local.expmap();
255  const Matrix3 Qt = R.transpose() * H_t_w;
256  const Matrix3 Qv = R.transpose() * H_v_w;
257 
258  // Now compute the blocks of the LogmapDerivative Jacobian
259  const Matrix3 Jw = Rot3::LogmapDerivative(w);
260  const Matrix3 Qt2 = -Jw * Qt * Jw;
261  const Matrix3 Qv2 = -Jw * Qv * Jw;
262 
263  Matrix9 J;
264  J << Jw, Z_3x3, Z_3x3,
265  Qt2, Jw, Z_3x3,
266  Qv2, Z_3x3, Jw;
267  return J;
268 }
269 
270 //------------------------------------------------------------------------------
272  const Vector9 xi = Logmap(state);
273  return LogmapDerivative(xi);
274 }
275 
276 //------------------------------------------------------------------------------
277 Matrix5 NavState::Hat(const Vector9& xi) {
278  Matrix5 X;
279  const double wx = xi(0), wy = xi(1), wz = xi(2);
280  const double px = xi(3), py = xi(4), pz = xi(5);
281  const double vx = xi(6), vy = xi(7), vz = xi(8);
282  X << 0., -wz, wy, px, vx,
283  wz, 0., -wx, py, vy,
284  -wy, wx, 0., pz, vz,
285  0., 0., 0., 0., 0.,
286  0., 0., 0., 0., 0.;
287  return X;
288 }
289 
290 //------------------------------------------------------------------------------
291 Vector9 NavState::Vee(const Matrix5& Xi) {
292  Vector9 xi;
293  xi << Xi(2, 1), Xi(0, 2), Xi(1, 0),
294  Xi(0, 3), Xi(1, 3), Xi(2, 3),
295  Xi(0, 4), Xi(1, 4), Xi(2, 4);
296  return xi;
297 }
298 
299 //------------------------------------------------------------------------------
301  ChartJacobian Hxi) {
302  return Expmap(xi, Hxi);
303 }
304 
305 //------------------------------------------------------------------------------
307  ChartJacobian Hstate) {
308  return Logmap(state, Hstate);
309 }
310 
311 //------------------------------------------------------------------------------
312 NavState NavState::retract(const Vector9& xi, //
314  Rot3 nRb = R_;
315  Point3 n_t = t_, n_v = v_;
316  Matrix3 D_bRc_xi, D_R_nRb, D_t_nRb, D_v_nRb;
317  const Rot3 bRc = Rot3::Expmap(dR(xi), H2 ? &D_bRc_xi : 0);
318  const Rot3 nRc = nRb.compose(bRc, H1 ? &D_R_nRb : 0);
319  const Point3 t = n_t + nRb.rotate(dP(xi), H1 ? &D_t_nRb : 0);
320  const Point3 v = n_v + nRb.rotate(dV(xi), H1 ? &D_v_nRb : 0);
321  if (H1) {
322  *H1 << D_R_nRb, Z_3x3, Z_3x3, //
323  // Note(frank): the derivative of n_t with respect to xi is nRb
324  // We pre-multiply with nRc' to account for NavState::Create
325  // Then we make use of the identity nRc' * nRb = bRc'
326  nRc.transpose() * D_t_nRb, bRc.transpose(), Z_3x3,
327  // Similar reasoning for v:
328  nRc.transpose() * D_v_nRb, Z_3x3, bRc.transpose();
329  }
330  if (H2) {
331  *H2 << D_bRc_xi, Z_3x3, Z_3x3, //
332  Z_3x3, bRc.transpose(), Z_3x3, //
333  Z_3x3, Z_3x3, bRc.transpose();
334  }
335  return NavState(nRc, t, v);
336 }
337 
338 //------------------------------------------------------------------------------
341  Matrix3 D_dR_R, D_dt_R, D_dv_R;
342  const Rot3 dR = R_.between(g.R_, H1 ? &D_dR_R : 0);
343  const Point3 dP = R_.unrotate(g.t_ - t_, H1 ? &D_dt_R : 0);
344  const Vector dV = R_.unrotate(g.v_ - v_, H1 ? &D_dv_R : 0);
345 
346  Vector9 xi;
347  Matrix3 D_xi_R;
348  xi << Rot3::Logmap(dR, (H1 || H2) ? &D_xi_R : 0), dP, dV;
349  if (H1) {
350  *H1 << D_xi_R * D_dR_R, Z_3x3, Z_3x3, //
351  D_dt_R, -I_3x3, Z_3x3, //
352  D_dv_R, Z_3x3, -I_3x3;
353  }
354  if (H2) {
355  *H2 << D_xi_R, Z_3x3, Z_3x3, //
356  Z_3x3, dR.matrix(), Z_3x3, //
357  Z_3x3, Z_3x3, dR.matrix();
358  }
359 
360  return xi;
361 }
362 
363 //------------------------------------------------------------------------------
364 // sugar for derivative blocks
365 #define D_R_R(H) (H)->block<3,3>(0,0)
366 #define D_R_t(H) (H)->block<3,3>(0,3)
367 #define D_R_v(H) (H)->block<3,3>(0,6)
368 #define D_t_R(H) (H)->block<3,3>(3,0)
369 #define D_t_t(H) (H)->block<3,3>(3,3)
370 #define D_t_v(H) (H)->block<3,3>(3,6)
371 #define D_v_R(H) (H)->block<3,3>(6,0)
372 #define D_v_t(H) (H)->block<3,3>(6,3)
373 #define D_v_v(H) (H)->block<3,3>(6,6)
374 
375 //------------------------------------------------------------------------------
376 NavState NavState::update(const Vector3& b_acceleration, const Vector3& b_omega,
378  OptionalJacobian<9, 3> G2) const {
379 
380  Vector9 xi;
381  Matrix39 D_xiP_state;
382  Vector3 b_v = bodyVelocity(F ? &D_xiP_state : 0);
383  double dt22 = 0.5 * dt * dt;
384 
385  // Integrate on tangent space. TODO(frank): coriolis?
386  dR(xi) << dt * b_omega;
387  dP(xi) << dt * b_v + dt22 * b_acceleration;
388  dV(xi) << dt * b_acceleration;
389 
390  // Bring back to manifold
391  Matrix9 D_newState_xi;
392  NavState newState = retract(xi, F, G1 || G2 ? &D_newState_xi : 0);
393 
394  // Derivative wrt state is computed by retract directly
395  // However, as dP(xi) also depends on state, we need to add that contribution
396  if (F) {
397  F->middleRows<3>(3) += dt * D_t_t(F) * D_xiP_state;
398  }
399  // derivative wrt acceleration
400  if (G1) {
401  // D_newState_dPxi = D_newState_xi.middleCols<3>(3)
402  // D_dPxi_acc = dt22 * I_3x3
403  // D_newState_dVxi = D_newState_xi.rightCols<3>()
404  // D_dVxi_acc = dt * I_3x3
405  // *G2 = D_newState_acc = D_newState_dPxi * D_dPxi_acc + D_newState_dVxi * D_dVxi_acc
406  *G1 = D_newState_xi.middleCols<3>(3) * dt22
407  + D_newState_xi.rightCols<3>() * dt;
408  }
409  // derivative wrt omega
410  if (G2) {
411  // D_newState_dRxi = D_newState_xi.leftCols<3>()
412  // D_dRxi_omega = dt * I_3x3
413  // *G1 = D_newState_omega = D_newState_dRxi * D_dRxi_omega
414  *G2 = D_newState_xi.leftCols<3>() * dt;
415  }
416  return newState;
417 }
418 
419 //------------------------------------------------------------------------------
420 Vector9 NavState::coriolis(double dt, const Vector3& omega, bool secondOrder,
421  OptionalJacobian<9, 9> H) const {
422  Rot3 nRb = R_;
423  Point3 n_t = t_, n_v = v_;
424 
425  const double dt2 = dt * dt;
426  const Vector3 omega_cross_vel = omega.cross(n_v);
427 
428  // Get perturbations in nav frame
429  Vector9 n_xi, xi;
430  Matrix3 D_dR_R, D_dP_R, D_dV_R, D_body_nav;
431  dR(n_xi) << ((-dt) * omega);
432  dP(n_xi) << ((-dt2) * omega_cross_vel); // NOTE(luca): we got rid of the 2 wrt INS paper
433  dV(n_xi) << ((-2.0 * dt) * omega_cross_vel);
434  if (secondOrder) {
435  const Vector3 omega_cross2_t = omega.cross(omega.cross(n_t));
436  dP(n_xi) -= (0.5 * dt2) * omega_cross2_t;
437  dV(n_xi) -= dt * omega_cross2_t;
438  }
439 
440  // Transform n_xi into the body frame
441  xi << nRb.unrotate(dR(n_xi), H ? &D_dR_R : 0, H ? &D_body_nav : 0),
442  nRb.unrotate(dP(n_xi), H ? &D_dP_R : 0),
443  nRb.unrotate(dV(n_xi), H ? &D_dV_R : 0);
444 
445  if (H) {
446  H->setZero();
447  const Matrix3 Omega = skewSymmetric(omega);
448  const Matrix3 D_cross_state = Omega * R();
449  H->setZero();
450  D_R_R(H) << D_dR_R;
451  D_t_v(H) << D_body_nav * (-dt2) * D_cross_state;
452  D_t_R(H) << D_dP_R;
453  D_v_v(H) << D_body_nav * (-2.0 * dt) * D_cross_state;
454  D_v_R(H) << D_dV_R;
455  if (secondOrder) {
456  const Matrix3 D_cross2_state = Omega * D_cross_state;
457  D_t_t(H) -= D_body_nav * (0.5 * dt2) * D_cross2_state;
458  D_v_t(H) -= D_body_nav * dt * D_cross2_state;
459  }
460  }
461  return xi;
462 }
463 
464 //------------------------------------------------------------------------------
465 Vector9 NavState::correctPIM(const Vector9& pim, double dt,
466  const Vector3& n_gravity, const std::optional<Vector3>& omegaCoriolis,
467  bool use2ndOrderCoriolis, OptionalJacobian<9, 9> H1,
468  OptionalJacobian<9, 9> H2) const {
469  const Rot3& nRb = R_;
470  const Velocity3& n_v = v_; // derivative is Ri !
471  const double dt22 = 0.5 * dt * dt;
472 
473  Vector9 xi;
474  Matrix3 D_dP_Ri1, D_dP_Ri2, D_dP_nv, D_dV_Ri;
475  dR(xi) = dR(pim);
476  dP(xi) = dP(pim)
477  + dt * nRb.unrotate(n_v, H1 ? &D_dP_Ri1 : 0, H2 ? &D_dP_nv : 0)
478  + dt22 * nRb.unrotate(n_gravity, H1 ? &D_dP_Ri2 : 0);
479  dV(xi) = dV(pim) + dt * nRb.unrotate(n_gravity, H1 ? &D_dV_Ri : 0);
480 
481  if (omegaCoriolis) {
482  xi += coriolis(dt, *omegaCoriolis, use2ndOrderCoriolis, H1);
483  }
484 
485  if (H1 || H2) {
486  Matrix3 Ri = nRb.matrix();
487 
488  if (H1) {
489  if (!omegaCoriolis)
490  H1->setZero(); // if coriolis H1 is already initialized
491  D_t_R(H1) += dt * D_dP_Ri1 + dt22 * D_dP_Ri2;
492  D_t_v(H1) += dt * D_dP_nv * Ri;
493  D_v_R(H1) += dt * D_dV_Ri;
494  }
495  if (H2) {
496  H2->setIdentity();
497  }
498  }
499 
500  return xi;
501 }
502 //------------------------------------------------------------------------------
503 
504 }
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
gtsam::LieGroup::between
Class between(const Class &g) const
Definition: Lie.h:52
H
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
Definition: gnuplot_common_settings.hh:74
gtsam::NavState::dR
static Eigen::Block< Vector9, 3, 1 > dR(Vector9 &v)
Definition: NavState.h:168
D_R_R
#define D_R_R(H)
Definition: NavState.cpp:365
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::operator<<
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
D_v_R
#define D_v_R(H)
Definition: NavState.cpp:371
gtsam::NavState::t_
Point3 t_
position n_t, in nav frame
Definition: NavState.h:44
screwPose2::xi
Vector xi
Definition: testPose2.cpp:169
gtsam::Velocity3
Vector3 Velocity3
Velocity is currently typedef'd to Vector3.
Definition: Gal3.h:33
gtsam::NavState::NavState
NavState()
Default constructor.
Definition: NavState.h:56
gtsam::NavState::dP
static Eigen::Block< Vector9, 3, 1 > dP(Vector9 &v)
Definition: NavState.h:171
gtsam::NavState::adjoint
static Vector9 adjoint(const Vector9 &xi, const Vector9 &y, OptionalJacobian< 9, 9 > Hxi={}, OptionalJacobian< 9, 9 > H_y={})
Definition: NavState.cpp:212
B
Definition: test_numpy_dtypes.cpp:301
dt
const double dt
Definition: testVelocityConstraint.cpp:15
gtsam::NavState::AdjointMap
Matrix9 AdjointMap() const
Definition: NavState.cpp:179
vel
static const Velocity3 vel(0.4, 0.5, 0.6)
gtsam::equal_with_abs_tol
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:80
gtsam::NavState
Definition: NavState.h:38
T
Eigen::Triplet< double > T
Definition: Tutorial_sparse_example.cpp:6
log
const EIGEN_DEVICE_FUNC LogReturnType log() const
Definition: ArrayCwiseUnaryOps.h:128
gtsam::NavState::bodyVelocity
Velocity3 bodyVelocity(OptionalJacobian< 3, 9 > H={}) const
Definition: NavState.cpp:69
X
#define X
Definition: icosphere.cpp:20
initial::nRb
const Rot3 nRb
Definition: testScenarioRunner.cpp:149
D_t_t
#define D_t_t(H)
Definition: NavState.cpp:369
gtsam::NavState::update
NavState update(const Vector3 &b_acceleration, const Vector3 &b_omega, const double dt, OptionalJacobian< 9, 9 > F={}, OptionalJacobian< 9, 3 > G1={}, OptionalJacobian< 9, 3 > G2={}) const
Definition: NavState.cpp:376
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
gtsam::NavState::v
const Vector3 & v() const
Return velocity as Vector3. Computation-free.
Definition: NavState.h:120
os
ofstream os("timeSchurFactors.csv")
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::skewSymmetric
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:381
gtsam::Rot3::Expmap
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
Definition: Rot3M.cpp:156
gtsam::NavState::adjointMap
static Matrix9 adjointMap(const Vector9 &xi)
Definition: NavState.cpp:202
gtsam::Rot3::LogmapDerivative
static Matrix3 LogmapDerivative(const Vector3 &x)
Derivative of Logmap.
Definition: Rot3.cpp:244
gtsam::Rot3::unrotate
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
rotate point from world to rotated frame
Definition: Rot3.cpp:136
gtsam::NavState::LogmapDerivative
static Matrix9 LogmapDerivative(const Vector9 &xi)
Derivative of Logmap.
Definition: NavState.cpp:240
gtsam::NavState::ChartAtOrigin::Local
static Vector9 Local(const NavState &state, ChartJacobian Hstate={})
Definition: NavState.cpp:306
gtsam::NavState::correctPIM
Vector9 correctPIM(const Vector9 &pim, double dt, const Vector3 &n_gravity, const std::optional< Vector3 > &omegaCoriolis, bool use2ndOrderCoriolis=false, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
Definition: NavState.cpp:465
biased_x_rotation::omega
const double omega
Definition: testPreintegratedRotation.cpp:32
gtsam::NavState::Hat
static Matrix5 Hat(const Vector9 &xi)
Hat maps from tangent vector to Lie algebra.
Definition: NavState.cpp:277
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
J
JacobiRotation< float > J
Definition: Jacobi_makeJacobi.cpp:3
A
Definition: test_numpy_dtypes.cpp:300
vy
StridedVectorType vy(make_vector(y, *n, std::abs(*incy)))
gtsam::NavState::attitude
const Rot3 & attitude(OptionalJacobian< 3, 9 > H={}) const
Definition: NavState.cpp:48
gtsam::NavState::Vee
static Vector9 Vee(const Matrix5 &X)
Vee maps from Lie algebra to tangent vector.
Definition: NavState.cpp:291
gtsam::NavState::Adjoint
Vector9 Adjoint(const Vector9 &xi_b, OptionalJacobian< 9, 9 > H_this={}, OptionalJacobian< 9, 9 > H_xib={}) const
Definition: NavState.cpp:190
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Pose3
Definition: Pose3.h:37
NavState.h
Navigation state composing of attitude, position, and velocity.
gtsam::NavState::R_
Rot3 R_
Rotation nRb, rotates points/velocities in body to points/velocities in nav.
Definition: NavState.h:43
gtsam::NavState::v_
Velocity3 v_
velocity n_v in nav frame
Definition: NavState.h:45
gtsam::NavState::t
Vector3 t() const
Return position as Vector3.
Definition: NavState.h:116
gtsam::NavState::Expmap
static NavState Expmap(const Vector9 &xi, OptionalJacobian< 9, 9 > Hxi={})
Definition: NavState.cpp:116
gtsam::NavState::R
Matrix3 R() const
Return rotation matrix. Induces computation in quaternion mode.
Definition: NavState.h:108
Eigen::Triplet< double >
tan
const EIGEN_DEVICE_FUNC TanReturnType tan() const
Definition: ArrayCwiseUnaryOps.h:269
gtsam::symbol_shorthand::F
Key F(std::uint64_t j)
Definition: inference/Symbol.h:153
gtsam::NavState::ExpmapDerivative
static Matrix9 ExpmapDerivative(const Vector9 &xi)
Derivative of Expmap.
Definition: NavState.cpp:233
gtsam::NavState::Create
static NavState Create(const Rot3 &R, const Point3 &t, const Velocity3 &v, OptionalJacobian< 9, 3 > H1={}, OptionalJacobian< 9, 3 > H2={}, OptionalJacobian< 9, 3 > H3={})
Named constructor with derivatives.
Definition: NavState.cpp:26
gtsam::Rot3::inverse
Rot3 inverse() const
inverse of a rotation
Definition: Rot3.h:312
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
gtsam::NavState::dV
static Eigen::Block< Vector9, 3, 1 > dV(Vector9 &v)
Definition: NavState.h:174
y
Scalar * y
Definition: level1_cplx_impl.h:124
gtsam::NavState::matrix
Matrix5 matrix() const
Definition: NavState.cpp:80
gtsam::so3::DexpFunctor
Definition: SO3.h:165
D_v_v
#define D_v_v(H)
Definition: NavState.cpp:373
gtsam::Pose3::rotation
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Definition: Pose3.cpp:348
D_v_t
#define D_v_t(H)
Definition: NavState.cpp:372
D_t_v
#define D_t_v(H)
Definition: NavState.cpp:370
gtsam
traits
Definition: ABC.h:17
gtsam::traits
Definition: Group.h:36
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::NavState::equals
bool equals(const NavState &other, double tol=1e-8) const
equals
Definition: NavState.cpp:104
gtsam::symbol_shorthand::W
Key W(std::uint64_t j)
Definition: inference/Symbol.h:170
gtsam::NavState::position
const Point3 & position(OptionalJacobian< 3, 9 > H={}) const
Definition: NavState.cpp:55
gtsam::NavState::Logmap
static Vector9 Logmap(const NavState &pose, OptionalJacobian< 9, 9 > Hpose={})
Definition: NavState.cpp:151
p
float * p
Definition: Tutorial_Map_using.cpp:9
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::Rot3::transpose
Matrix3 transpose() const
Definition: Rot3M.cpp:143
gtsam::NavState::velocity
const Velocity3 & velocity(OptionalJacobian< 3, 9 > H={}) const
Definition: NavState.cpp:62
gtsam::Rot3::matrix
Matrix3 matrix() const
Definition: Rot3M.cpp:222
gtsam::NavState::inverse
NavState inverse() const
inverse transformation with derivatives
Definition: NavState.cpp:110
gtsam::NavState::retract
NavState retract(const Vector9 &v, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
retract with optional derivatives
Definition: NavState.cpp:312
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
pybind11
Definition: wrap/pybind11/pybind11/__init__.py:1
gtsam::Rot3::Logmap
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H={})
Definition: Rot3M.cpp:161
gtsam::NavState::print
void print(const std::string &s="") const
print
Definition: NavState.cpp:99
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
py
int RealScalar int RealScalar * py
Definition: level1_cplx_impl.h:119
gtsam.examples.ImuFactorISAM2Example.n_gravity
def n_gravity
Definition: ImuFactorISAM2Example.py:31
gtsam::NavState::ChartAtOrigin::Retract
static NavState Retract(const Vector9 &xi, ChartJacobian Hxi={})
Definition: NavState.cpp:300
gtsam::NavState::localCoordinates
Vector9 localCoordinates(const NavState &g, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
localCoordinates with optional derivatives
Definition: NavState.cpp:339
D_t_R
#define D_t_R(H)
Definition: NavState.cpp:368
M
abc_eqf_lib::State< N > M
Definition: ABC_EQF_Demo.cpp:17
gtsam::NavState::pose
const Pose3 pose() const
Definition: NavState.h:99
gtsam::NavState::coriolis
Vector9 coriolis(double dt, const Vector3 &omega, bool secondOrder=false, OptionalJacobian< 9, 9 > H={}) const
Compute tangent space contribution due to Coriolis forces.
Definition: NavState.cpp:420
align_3::t
Point2 t(10, 10)
gtsam::Rot3::equals
bool equals(const Rot3 &p, double tol=1e-9) const
Definition: Rot3.cpp:100
gtsam::NavState::FromPoseVelocity
static NavState FromPoseVelocity(const Pose3 &pose, const Vector3 &vel, OptionalJacobian< 9, 6 > H1={}, OptionalJacobian< 9, 3 > H2={})
Named constructor with derivatives.
Definition: NavState.cpp:38
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
R
Rot2 R(Rot2::fromAngle(0.1))
vx
StridedVectorType vx(make_vector(x, *n, std::abs(*incx)))
make_changelog.state
state
Definition: make_changelog.py:29
px
RealScalar RealScalar * px
Definition: level1_cplx_impl.h:28


gtsam
Author(s):
autogenerated on Wed May 28 2025 03:02:11