Go to the documentation of this file.
56 t_(0, 0, 0), v_(
Vector3::Zero()) {
68 R_(
R), t_(tv.
head<3>()), v_(tv.
tail<3>()) {
127 void print(
const std::string&
s =
"")
const;
130 bool equals(
const NavState&
other,
double tol = 1
e-8)
const;
139 return v.segment<3>(0);
142 return v.segment<3>(3);
145 return v.segment<3>(6);
148 return v.segment<3>(0);
151 return v.segment<3>(3);
154 return v.segment<3>(6);
163 Vector9 localCoordinates(
const NavState&
g,
164 OptionalJacobian<9, 9> H1 = {}, OptionalJacobian<9, 9> H2 =
174 const double dt, OptionalJacobian<9, 9>
F, OptionalJacobian<9, 3> G1,
175 OptionalJacobian<9, 3> G2)
const;
179 OptionalJacobian<9, 9>
H = {})
const;
184 const std::optional<Vector3>& omegaCoriolis,
bool use2ndOrderCoriolis =
185 false, OptionalJacobian<9, 9> H1 = {},
186 OptionalJacobian<9, 9> H2 = {})
const;
193 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
194 friend class boost::serialization::access;
195 template<
class ARCHIVE>
196 void serialize(ARCHIVE & ar,
const unsigned int ) {
197 ar & BOOST_SERIALIZATION_NVP(R_);
198 ar & BOOST_SERIALIZATION_NVP(t_);
199 ar & BOOST_SERIALIZATION_NVP(v_);
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)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE FixedSegmentReturnType< internal::get_fixed_value< NType >::value >::Type tail(NType n)
static Eigen::Block< const Vector9, 3, 1 > dV(const Vector9 &v)
Point3_ translation(const Pose3_ &pose)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Expression of a fixed-size or dynamic-size block.
typedef and functions to augment Eigen's VectorXd
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)
Point3_ position(const NavState_ &X)
std::pair< Point3, Velocity3 > PositionAndVelocity
NavState(const Rot3 &R, const Point3 &t, const Velocity3 &v)
Construct from attitude, position, velocity.
static const Velocity3 vel(0.4, 0.5, 0.6)
def retract(a, np.ndarray xi)
Both ManifoldTraits and Testable.
const Vector3 & v() const
Return velocity as Vector3. Computation-free.
ofstream os("timeSchurFactors.csv")
NavState(const Matrix3 &R, const Vector6 &tv)
Construct from SO(3) and R^6.
Rot3_ attitude(const NavState_ &X)
void print(const Matrix &A, const string &s, ostream &stream)
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Rot3 R_
Rotation nRb, rotates points/velocities in body to points/velocities in nav.
static Eigen::Block< const Vector9, 3, 1 > dP(const Vector9 &v)
gtsam::Quaternion toQuaternion() const
Velocity3 v_
velocity n_v in nav frame
Vector3 t() const
Return position as Vector3.
Vector3 bodyVelocity(const Pose3 &w_t_b, const Vector3 &vec_w, OptionalJacobian< 3, 6 > Hpose={}, OptionalJacobian< 3, 3 > Hvel={})
Matrix3 R() const
Return rotation matrix. Induces computation in quaternion mode.
Base class and basic functions for Manifold types.
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE FixedSegmentReturnType< internal::get_fixed_value< NType >::value >::Type head(NType n)
void g(const string &key, int i)
static Eigen::Block< Vector9, 3, 1 > dV(Vector9 &v)
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
The quaternion class used to represent 3D orientations and rotations.
Rot3_ rotation(const Pose3_ &pose)
std::function< Vector9(const NavState &, const bool &)> coriolis
Array< int, Dynamic, 1 > v
Quaternion quaternion() const
Return quaternion. Induces computation in matrix mode.
static Eigen::Block< const Vector9, 3, 1 > dR(const Vector9 &v)
NavState(const Pose3 &pose, const Velocity3 &v)
Construct from pose and velocity.
Rot2 R(Rot2::fromAngle(0.1))
Velocity3_ velocity(const NavState_ &X)
gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:33:49