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


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