Go to the documentation of this file.
9 #include <gtsam_unstable/dllexport.h>
49 PoseRTV(
double roll,
double pitch,
double yaw,
double x,
double y,
double z,
50 double vx,
double vy,
double vz);
74 void print(
const std::string&
s=
"")
const;
78 using Base::dimension;
82 using Base::localCoordinates;
83 using Base::LocalCoordinates;
92 OptionalJacobian<1,9> H2={})
const;
100 PoseRTV planarDynamics(
double vel_rate,
double heading_rate,
double max_accel,
double dt)
const;
106 PoseRTV flyingDynamics(
double pitch_rate,
double heading_rate,
double lift_control,
double dt)
const;
109 PoseRTV generalDynamics(
const Vector& accel,
const Vector& gyro,
double dt)
const;
114 Vector6 imuPrediction(
const PoseRTV&
x2,
double dt)
const;
125 return translationIntegration(
x2.rotation(),
x2.velocity(),
dt);
130 return translationIntegration(
x2,
dt);
141 ChartJacobian Dglobal = {},
142 OptionalJacobian<9, 6> Dtrans = {})
const;
151 static Matrix RRTMbn(
const Rot3& att);
156 static Matrix RRTMnb(
const Rot3& att);
160 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
162 friend class boost::serialization::access;
163 template<
class Archive>
164 void serialize(Archive & ar,
const unsigned int ) {
165 ar & BOOST_SERIALIZATION_NVP(first);
166 ar & BOOST_SERIALIZATION_NVP(second);
176 template <
typename A1,
typename A2>
struct Range;
Annotation indicating that a class derives from another given type.
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
PoseRTV(const Rot3 &rot, const Point3 &t, const Velocity3 &vel)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Vector3 Velocity3
Velocity is currently typedef'd to Vector3.
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 x
static const Velocity3 vel(0.4, 0.5, 0.6)
ProductLieGroup< Pose3, Velocity3 > Base
def retract(a, np.ndarray xi)
PoseRTV(const Pose3 &pose)
const Rot3 & rotation() const
OptionalJacobian< 9, 9 > ChartJacobian
int EIGEN_BLAS_FUNC() rot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps)
Group product of two Lie Groups.
Double_ range(const Point2_ &p, const Point2_ &q)
Point3 translationIntegration(const PoseRTV &x2, double dt) const
void print(const Matrix &A, const string &s, ostream &stream)
StridedVectorType vy(make_vector(y, *n, std::abs(*incy)))
Both LieGroupTraits and Testable.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
const Velocity3 & v() const
const Point3 & translation() const
Vector translationVec() const
const Velocity3 & velocity() const
PoseRTV(const Point3 &t, const Rot3 &rot, const Velocity3 &vel)
Matrix trans(const Matrix &A)
Array< int, Dynamic, 1 > v
PoseRTV(const Base &base)
Vector translationIntegrationVec(const PoseRTV &x2, double dt) const
PoseRTV(const Pose3 &pose, const Velocity3 &vel)
const Pose3 & pose() const
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
StridedVectorType vx(make_vector(x, *n, std::abs(*incx)))
const Velocity3 & velocityVec() const
Velocity3_ velocity(const NavState_ &X)
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:03:36