Go to the documentation of this file.
30 *H1 << I_3x3, Z_3x3, Z_3x3;
32 *H2 << Z_3x3,
R.transpose(), Z_3x3;
34 *H3 << Z_3x3, Z_3x3,
R.transpose();
41 *H1 << I_3x3, Z_3x3, Z_3x3, I_3x3, Z_3x3, Z_3x3;
50 *
H << I_3x3, Z_3x3, Z_3x3;
57 *
H << Z_3x3,
R(), Z_3x3;
64 *
H << Z_3x3, Z_3x3,
R();
75 *
H << D_bv_nRb, Z_3x3, I_3x3;
81 Matrix3
R = this->
R();
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_;
92 os <<
"R: " <<
state.attitude() <<
"\n";
93 os <<
"p: " <<
state.position().transpose() <<
"\n";
94 os <<
"v: " <<
state.velocity().transpose();
100 std::cout << (
s.empty() ?
s :
s +
" ") << *
this << std::endl;
118 Vector3 w =
xi.head<3>(), rho =
xi.segment<3>(3), nu =
xi.tail<3>();
121 const bool nearZero = (
w.dot(
w) <= 1
e-5);
125 #ifdef GTSAM_USE_QUATERNIONS
128 const Rot3 R(local.expmap());
132 Matrix3 H_t_w, H_v_w;
133 const Vector3 t = local.applyLeftJacobian(rho, Hxi ? &H_t_w :
nullptr);
134 const Vector3 v = local.applyLeftJacobian(nu, Hxi ? &H_v_w :
nullptr);
137 const Matrix3 Jr = local.rightJacobian();
140 const Matrix3
M =
R.matrix();
141 *Hxi << Jr, Z_3x3, Z_3x3,
142 M.transpose() * H_t_w, Jr, Z_3x3,
143 M.transpose() * H_v_w, Z_3x3, Jr;
158 const double t = phi.norm();
167 const double Tan =
tan(0.5 *
t);
170 const Vector3 rho =
p - (0.5 *
t) * Wp + (1 -
t / (2. * Tan)) * (
W * Wp);
171 const Vector3 nu =
v - (0.5 *
t) * Wv + (1 -
t / (2. * Tan)) * (
W * Wv);
186 adj <<
R, Z_3x3, Z_3x3,
A,
R, Z_3x3,
B, Z_3x3,
R;
196 if (H_state) *H_state = -Ad *
adjointMap(xi_b);
197 if (H_xib) *H_xib = Ad;
208 adj << w_hat, Z_3x3, Z_3x3, v_hat, w_hat, Z_3x3, a_hat, Z_3x3, w_hat;
218 for (
int i = 0;
i < 9; ++
i) {
223 Hxi->col(
i) = Gi *
y;
228 if (H_y) *H_y = ad_xi;
248 const bool nearZero = (
w.dot(
w) <= 1
e-5);
252 Matrix3 H_t_w, H_v_w;
253 local.applyLeftJacobian(rho, H_t_w);
254 local.applyLeftJacobian(nu, H_v_w);
257 const Matrix3
R = local.expmap();
258 const Matrix3 Qt =
R.transpose() * H_t_w;
259 const Matrix3 Qv =
R.transpose() * H_v_w;
263 const Matrix3 Qt2 = -Jw * Qt * Jw;
264 const Matrix3 Qv2 = -Jw * Qv * Jw;
267 J << Jw, Z_3x3, Z_3x3,
290 Matrix3 D_bRc_xi, D_R_nRb, D_t_nRb, D_v_nRb;
292 const Rot3 nRc =
nRb.compose(bRc, H1 ? &D_R_nRb : 0);
296 *H1 << D_R_nRb, Z_3x3, Z_3x3,
305 *H2 << D_bRc_xi, Z_3x3, Z_3x3,
315 Matrix3 D_dR_R, D_dt_R, D_dv_R;
324 *H1 << D_xi_R * D_dR_R, Z_3x3, Z_3x3,
325 D_dt_R, -I_3x3, Z_3x3,
326 D_dv_R, Z_3x3, -I_3x3;
329 *H2 << D_xi_R, Z_3x3, Z_3x3,
330 Z_3x3,
dR.matrix(), Z_3x3,
331 Z_3x3, Z_3x3,
dR.matrix();
339 #define D_R_R(H) (H)->block<3,3>(0,0)
340 #define D_R_t(H) (H)->block<3,3>(0,3)
341 #define D_R_v(H) (H)->block<3,3>(0,6)
342 #define D_t_R(H) (H)->block<3,3>(3,0)
343 #define D_t_t(H) (H)->block<3,3>(3,3)
344 #define D_t_v(H) (H)->block<3,3>(3,6)
345 #define D_v_R(H) (H)->block<3,3>(6,0)
346 #define D_v_t(H) (H)->block<3,3>(6,3)
347 #define D_v_v(H) (H)->block<3,3>(6,6)
355 Matrix39 D_xiP_state;
357 double dt22 = 0.5 *
dt *
dt;
361 dP(
xi) <<
dt * b_v + dt22 * b_acceleration;
362 dV(
xi) <<
dt * b_acceleration;
371 F->middleRows<3>(3) +=
dt *
D_t_t(
F) * D_xiP_state;
380 *G1 = D_newState_xi.middleCols<3>(3) * dt22
381 + D_newState_xi.rightCols<3>() *
dt;
388 *G2 = D_newState_xi.leftCols<3>() *
dt;
399 const double dt2 =
dt *
dt;
404 Matrix3 D_dR_R, D_dP_R, D_dV_R, D_body_nav;
406 dP(n_xi) << ((-dt2) * omega_cross_vel);
407 dV(n_xi) << ((-2.0 *
dt) * omega_cross_vel);
410 dP(n_xi) -= (0.5 * dt2) * omega_cross2_t;
411 dV(n_xi) -=
dt * omega_cross2_t;
415 xi <<
nRb.unrotate(
dR(n_xi),
H ? &D_dR_R : 0,
H ? &D_body_nav : 0),
416 nRb.unrotate(
dP(n_xi),
H ? &D_dP_R : 0),
417 nRb.unrotate(
dV(n_xi),
H ? &D_dV_R : 0);
422 const Matrix3 D_cross_state = Omega *
R();
425 D_t_v(
H) << D_body_nav * (-dt2) * D_cross_state;
427 D_v_v(
H) << D_body_nav * (-2.0 *
dt) * D_cross_state;
430 const Matrix3 D_cross2_state = Omega * D_cross_state;
431 D_t_t(
H) -= D_body_nav * (0.5 * dt2) * D_cross2_state;
432 D_v_t(
H) -= D_body_nav *
dt * D_cross2_state;
445 const double dt22 = 0.5 *
dt *
dt;
448 Matrix3 D_dP_Ri1, D_dP_Ri2, D_dP_nv, D_dV_Ri;
451 +
dt *
nRb.unrotate(n_v, H1 ? &D_dP_Ri1 : 0, H2 ? &D_dP_nv : 0)
456 xi +=
coriolis(
dt, *omegaCoriolis, use2ndOrderCoriolis, H1);
460 Matrix3 Ri =
nRb.matrix();
465 D_t_R(H1) +=
dt * D_dP_Ri1 + dt22 * D_dP_Ri2;
466 D_t_v(H1) +=
dt * D_dP_nv * Ri;
Class between(const Class &g) const
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
static Eigen::Block< Vector9, 3, 1 > dR(Vector9 &v)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Point3 t_
position n_t, in nav frame
Vector3 Velocity3
Velocity is currently typedef'd to Vector3.
NavState()
Default constructor.
static Eigen::Block< Vector9, 3, 1 > dP(Vector9 &v)
static Vector9 adjoint(const Vector9 &xi, const Vector9 &y, OptionalJacobian< 9, 9 > Hxi={}, OptionalJacobian< 9, 9 > H_y={})
Matrix9 AdjointMap() const
static const Velocity3 vel(0.4, 0.5, 0.6)
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Eigen::Triplet< double > T
const EIGEN_DEVICE_FUNC LogReturnType log() const
Velocity3 bodyVelocity(OptionalJacobian< 3, 9 > H={}) const
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
const Vector3 & v() const
Return velocity as Vector3. Computation-free.
ofstream os("timeSchurFactors.csv")
Matrix3 skewSymmetric(double wx, double wy, double wz)
static Matrix9 adjointMap(const Vector9 &xi)
static Matrix3 LogmapDerivative(const Vector3 &x)
Derivative of Logmap.
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
rotate point from world to rotated frame
static Vector9 Local(const NavState &state, ChartJacobian Hstate={})
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
Pose2_ Expmap(const Vector3_ &xi)
JacobiRotation< float > J
const Rot3 & attitude(OptionalJacobian< 3, 9 > H={}) const
Vector9 Adjoint(const Vector9 &xi_b, OptionalJacobian< 9, 9 > H_this={}, OptionalJacobian< 9, 9 > H_xib={}) const
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Navigation state composing of attitude, position, and velocity.
Rot3 R_
Rotation nRb, rotates points/velocities in body to points/velocities in nav.
Velocity3 v_
velocity n_v in nav frame
Vector3 t() const
Return position as Vector3.
static NavState Expmap(const Vector9 &xi, OptionalJacobian< 9, 9 > Hxi={})
Matrix3 R() const
Return rotation matrix. Induces computation in quaternion mode.
const EIGEN_DEVICE_FUNC TanReturnType tan() const
static Matrix9 ExpmapDerivative(const Vector9 &xi)
Derivative of Expmap.
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.
Rot3 inverse() const
inverse of a rotation
void g(const string &key, int i)
static Eigen::Block< Vector9, 3, 1 > dV(Vector9 &v)
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
bool equals(const NavState &other, double tol=1e-8) const
equals
const Point3 & position(OptionalJacobian< 3, 9 > H={}) const
static Vector9 Logmap(const NavState &pose, OptionalJacobian< 9, 9 > Hpose={})
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
Array< int, Dynamic, 1 > v
Matrix3 transpose() const
const Velocity3 & velocity(OptionalJacobian< 3, 9 > H={}) const
NavState inverse() const
inverse transformation with derivatives
NavState retract(const Vector9 &v, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
retract with optional derivatives
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H={})
void print(const std::string &s="") const
print
static NavState Retract(const Vector9 &xi, ChartJacobian Hxi={})
Vector9 localCoordinates(const NavState &g, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
localCoordinates with optional derivatives
Vector9 coriolis(double dt, const Vector3 &omega, bool secondOrder=false, OptionalJacobian< 9, 9 > H={}) const
Compute tangent space contribution due to Coriolis forces.
bool equals(const Rot3 &p, double tol=1e-9) const
static Matrix9 LogmapDerivative(const NavState &xi)
Derivative of Logmap.
static NavState FromPoseVelocity(const Pose3 &pose, const Vector3 &vel, OptionalJacobian< 9, 6 > H1={}, OptionalJacobian< 9, 3 > H2={})
Named constructor with derivatives.
Rot2 R(Rot2::fromAngle(0.1))
Matrix< RealScalar, Dynamic, Dynamic > M
gtsam
Author(s):
autogenerated on Sun Feb 16 2025 04:02:13