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 //------------------------------------------------------------------------------
80 Matrix7 NavState::matrix() const {
81  Matrix3 R = this->R();
82  Matrix7 T;
83  T << R, Z_3x3, t(), Z_3x3, R, v(), Vector6::Zero().transpose(), 1.0;
84  return T;
85 }
86 
87 //------------------------------------------------------------------------------
88 std::ostream& operator<<(std::ostream& os, const NavState& state) {
89  os << "R: " << state.attitude() << "\n";
90  os << "p: " << state.position().transpose() << "\n";
91  os << "v: " << state.velocity().transpose();
92  return os;
93 }
94 
95 //------------------------------------------------------------------------------
96 void NavState::print(const std::string& s) const {
97  std::cout << (s.empty() ? s : s + " ") << *this << std::endl;
98 }
99 
100 //------------------------------------------------------------------------------
101 bool NavState::equals(const NavState& other, double tol) const {
102  return R_.equals(other.R_, tol) && traits<Point3>::Equals(t_, other.t_, tol)
103  && equal_with_abs_tol(v_, other.v_, tol);
104 }
105 
106 //------------------------------------------------------------------------------
107 NavState NavState::retract(const Vector9& xi, //
109  auto [nRb, n_t, n_v] = (*this);
110  Matrix3 D_bRc_xi, D_R_nRb, D_t_nRb, D_v_nRb;
111  const Rot3 bRc = Rot3::Expmap(dR(xi), H2 ? &D_bRc_xi : 0);
112  const Rot3 nRc = nRb.compose(bRc, H1 ? &D_R_nRb : 0);
113  const Point3 t = n_t + nRb.rotate(dP(xi), H1 ? &D_t_nRb : 0);
114  const Point3 v = n_v + nRb.rotate(dV(xi), H1 ? &D_v_nRb : 0);
115  if (H1) {
116  *H1 << D_R_nRb, Z_3x3, Z_3x3, //
117  // Note(frank): the derivative of n_t with respect to xi is nRb
118  // We pre-multiply with nRc' to account for NavState::Create
119  // Then we make use of the identity nRc' * nRb = bRc'
120  nRc.transpose() * D_t_nRb, bRc.transpose(), Z_3x3,
121  // Similar reasoning for v:
122  nRc.transpose() * D_v_nRb, Z_3x3, bRc.transpose();
123  }
124  if (H2) {
125  *H2 << D_bRc_xi, Z_3x3, Z_3x3, //
126  Z_3x3, bRc.transpose(), Z_3x3, //
127  Z_3x3, Z_3x3, bRc.transpose();
128  }
129  return NavState(nRc, t, v);
130 }
131 
132 //------------------------------------------------------------------------------
135  Matrix3 D_dR_R, D_dt_R, D_dv_R;
136  const Rot3 dR = R_.between(g.R_, H1 ? &D_dR_R : 0);
137  const Point3 dP = R_.unrotate(g.t_ - t_, H1 ? &D_dt_R : 0);
138  const Vector dV = R_.unrotate(g.v_ - v_, H1 ? &D_dv_R : 0);
139 
140  Vector9 xi;
141  Matrix3 D_xi_R;
142  xi << Rot3::Logmap(dR, (H1 || H2) ? &D_xi_R : 0), dP, dV;
143  if (H1) {
144  *H1 << D_xi_R * D_dR_R, Z_3x3, Z_3x3, //
145  D_dt_R, -I_3x3, Z_3x3, //
146  D_dv_R, Z_3x3, -I_3x3;
147  }
148  if (H2) {
149  *H2 << D_xi_R, Z_3x3, Z_3x3, //
150  Z_3x3, dR.matrix(), Z_3x3, //
151  Z_3x3, Z_3x3, dR.matrix();
152  }
153  return xi;
154 }
155 
156 //------------------------------------------------------------------------------
157 // sugar for derivative blocks
158 #define D_R_R(H) (H)->block<3,3>(0,0)
159 #define D_R_t(H) (H)->block<3,3>(0,3)
160 #define D_R_v(H) (H)->block<3,3>(0,6)
161 #define D_t_R(H) (H)->block<3,3>(3,0)
162 #define D_t_t(H) (H)->block<3,3>(3,3)
163 #define D_t_v(H) (H)->block<3,3>(3,6)
164 #define D_v_R(H) (H)->block<3,3>(6,0)
165 #define D_v_t(H) (H)->block<3,3>(6,3)
166 #define D_v_v(H) (H)->block<3,3>(6,6)
167 
168 //------------------------------------------------------------------------------
169 NavState NavState::update(const Vector3& b_acceleration, const Vector3& b_omega,
171  OptionalJacobian<9, 3> G2) const {
172 
173  Vector9 xi;
174  Matrix39 D_xiP_state;
175  Vector3 b_v = bodyVelocity(F ? &D_xiP_state : 0);
176  double dt22 = 0.5 * dt * dt;
177 
178  // Integrate on tangent space. TODO(frank): coriolis?
179  dR(xi) << dt * b_omega;
180  dP(xi) << dt * b_v + dt22 * b_acceleration;
181  dV(xi) << dt * b_acceleration;
182 
183  // Bring back to manifold
184  Matrix9 D_newState_xi;
185  NavState newState = retract(xi, F, G1 || G2 ? &D_newState_xi : 0);
186 
187  // Derivative wrt state is computed by retract directly
188  // However, as dP(xi) also depends on state, we need to add that contribution
189  if (F) {
190  F->middleRows<3>(3) += dt * D_t_t(F) * D_xiP_state;
191  }
192  // derivative wrt acceleration
193  if (G1) {
194  // D_newState_dPxi = D_newState_xi.middleCols<3>(3)
195  // D_dPxi_acc = dt22 * I_3x3
196  // D_newState_dVxi = D_newState_xi.rightCols<3>()
197  // D_dVxi_acc = dt * I_3x3
198  // *G2 = D_newState_acc = D_newState_dPxi * D_dPxi_acc + D_newState_dVxi * D_dVxi_acc
199  *G1 = D_newState_xi.middleCols<3>(3) * dt22
200  + D_newState_xi.rightCols<3>() * dt;
201  }
202  // derivative wrt omega
203  if (G2) {
204  // D_newState_dRxi = D_newState_xi.leftCols<3>()
205  // D_dRxi_omega = dt * I_3x3
206  // *G1 = D_newState_omega = D_newState_dRxi * D_dRxi_omega
207  *G2 = D_newState_xi.leftCols<3>() * dt;
208  }
209  return newState;
210 }
211 
212 //------------------------------------------------------------------------------
213 Vector9 NavState::coriolis(double dt, const Vector3& omega, bool secondOrder,
214  OptionalJacobian<9, 9> H) const {
215  auto [nRb, n_t, n_v] = (*this);
216 
217  const double dt2 = dt * dt;
218  const Vector3 omega_cross_vel = omega.cross(n_v);
219 
220  // Get perturbations in nav frame
221  Vector9 n_xi, xi;
222  Matrix3 D_dR_R, D_dP_R, D_dV_R, D_body_nav;
223  dR(n_xi) << ((-dt) * omega);
224  dP(n_xi) << ((-dt2) * omega_cross_vel); // NOTE(luca): we got rid of the 2 wrt INS paper
225  dV(n_xi) << ((-2.0 * dt) * omega_cross_vel);
226  if (secondOrder) {
227  const Vector3 omega_cross2_t = omega.cross(omega.cross(n_t));
228  dP(n_xi) -= (0.5 * dt2) * omega_cross2_t;
229  dV(n_xi) -= dt * omega_cross2_t;
230  }
231 
232  // Transform n_xi into the body frame
233  xi << nRb.unrotate(dR(n_xi), H ? &D_dR_R : 0, H ? &D_body_nav : 0),
234  nRb.unrotate(dP(n_xi), H ? &D_dP_R : 0),
235  nRb.unrotate(dV(n_xi), H ? &D_dV_R : 0);
236 
237  if (H) {
238  H->setZero();
239  const Matrix3 Omega = skewSymmetric(omega);
240  const Matrix3 D_cross_state = Omega * R();
241  H->setZero();
242  D_R_R(H) << D_dR_R;
243  D_t_v(H) << D_body_nav * (-dt2) * D_cross_state;
244  D_t_R(H) << D_dP_R;
245  D_v_v(H) << D_body_nav * (-2.0 * dt) * D_cross_state;
246  D_v_R(H) << D_dV_R;
247  if (secondOrder) {
248  const Matrix3 D_cross2_state = Omega * D_cross_state;
249  D_t_t(H) -= D_body_nav * (0.5 * dt2) * D_cross2_state;
250  D_v_t(H) -= D_body_nav * dt * D_cross2_state;
251  }
252  }
253  return xi;
254 }
255 
256 //------------------------------------------------------------------------------
257 Vector9 NavState::correctPIM(const Vector9& pim, double dt,
258  const Vector3& n_gravity, const std::optional<Vector3>& omegaCoriolis,
259  bool use2ndOrderCoriolis, OptionalJacobian<9, 9> H1,
260  OptionalJacobian<9, 9> H2) const {
261  const Rot3& nRb = R_;
262  const Velocity3& n_v = v_; // derivative is Ri !
263  const double dt22 = 0.5 * dt * dt;
264 
265  Vector9 xi;
266  Matrix3 D_dP_Ri1, D_dP_Ri2, D_dP_nv, D_dV_Ri;
267  dR(xi) = dR(pim);
268  dP(xi) = dP(pim)
269  + dt * nRb.unrotate(n_v, H1 ? &D_dP_Ri1 : 0, H2 ? &D_dP_nv : 0)
270  + dt22 * nRb.unrotate(n_gravity, H1 ? &D_dP_Ri2 : 0);
271  dV(xi) = dV(pim) + dt * nRb.unrotate(n_gravity, H1 ? &D_dV_Ri : 0);
272 
273  if (omegaCoriolis) {
274  xi += coriolis(dt, *omegaCoriolis, use2ndOrderCoriolis, H1);
275  }
276 
277  if (H1 || H2) {
278  Matrix3 Ri = nRb.matrix();
279 
280  if (H1) {
281  if (!omegaCoriolis)
282  H1->setZero(); // if coriolis H1 is already initialized
283  D_t_R(H1) += dt * D_dP_Ri1 + dt22 * D_dP_Ri2;
284  D_t_v(H1) += dt * D_dP_nv * Ri;
285  D_v_R(H1) += dt * D_dV_Ri;
286  }
287  if (H2) {
288  H2->setIdentity();
289  }
290  }
291 
292  return xi;
293 }
294 //------------------------------------------------------------------------------
295 
296 }
Key F(std::uint64_t j)
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const NavState &state)
Output stream operator.
Definition: NavState.cpp:88
Eigen::Vector3d Vector3
Definition: Vector.h:43
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:169
static const Velocity3 vel(0.4, 0.5, 0.6)
Velocity3 bodyVelocity(OptionalJacobian< 3, 9 > H={}) const
Definition: NavState.cpp:69
bool equals(const Rot3 &p, double tol=1e-9) const
Definition: Rot3.cpp:99
Vector3 Velocity3
Velocity is currently typedef&#39;d to Vector3.
Definition: NavState.h:28
NavState()
Default constructor.
Definition: NavState.h:55
Rot2 R(Rot2::fromAngle(0.1))
static Eigen::Block< Vector9, 3, 1 > dP(Vector9 &v)
Definition: NavState.h:141
Point3 t_
position n_t, in nav frame
Definition: NavState.h:40
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
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:257
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
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
Definition: Rot3.h:374
void g(const string &key, int i)
Definition: testBTree.cpp:41
Rot3 R_
Rotation nRb, rotates points/velocities in body to points/velocities in nav.
Definition: NavState.h:39
const double dt
Velocity3 v_
velocity n_v in nav frame
Definition: NavState.h:41
const Vector3 & v() const
Return velocity as Vector3. Computation-free.
Definition: NavState.h:107
const Rot3 nRb
Eigen::VectorXd Vector
Definition: Vector.h:38
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
rotate point from world to rotated frame
Definition: Rot3.cpp:135
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H={})
Definition: Rot3M.cpp:157
static Eigen::Block< Vector9, 3, 1 > dV(Vector9 &v)
Definition: NavState.h:144
Array< int, Dynamic, 1 > v
Eigen::Triplet< double > T
Vector::Scalar omega(const Vector &t, const Vector &s, RealScalar angle)
Definition: IDRS.h:36
RealScalar s
const Rot3 & attitude(OptionalJacobian< 3, 9 > H={}) const
Definition: NavState.cpp:48
Vector3 t() const
Return position as Vector3.
Definition: NavState.h:103
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:80
Vector xi
Definition: testPose2.cpp:148
const Velocity3 & velocity(OptionalJacobian< 3, 9 > H={}) const
Definition: NavState.cpp:62
Matrix7 matrix() const
Definition: NavState.cpp:80
traits
Definition: chartTesting.h:28
Matrix3 R() const
Return rotation matrix. Induces computation in quaternion mode.
Definition: NavState.h:95
NavState retract(const Vector9 &v, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
retract with optional derivatives
Definition: NavState.cpp:107
void print(const std::string &s="") const
print
Definition: NavState.cpp:96
const Point3 & position(OptionalJacobian< 3, 9 > H={}) const
Definition: NavState.cpp:55
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:400
ofstream os("timeSchurFactors.csv")
Class between(const Class &g) const
Definition: Lie.h:52
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:213
Matrix3 matrix() const
Definition: Rot3M.cpp:218
Vector9 localCoordinates(const NavState &g, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
localCoordinates with optional derivatives
Definition: NavState.cpp:133
bool equals(const NavState &other, double tol=1e-8) const
equals
Definition: NavState.cpp:101
const Pose3 pose() const
Definition: NavState.h:86
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Definition: Pose3.cpp:315
const G double tol
Definition: Group.h:86
Vector3 Point3
Definition: Point3.h:38
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
Matrix3 transpose() const
Definition: Rot3M.cpp:143
static Eigen::Block< Vector9, 3, 1 > dR(Vector9 &v)
Definition: NavState.h:138
Point2 t(10, 10)


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:56