9#include <gtsam_unstable/dllexport.h>
42 :
Base(pose,Vector3::Zero()) {}
49 PoseRTV(
double roll,
double pitch,
double yaw,
double x,
double y,
double z,
50 double vx,
double vy,
double vz);
53 explicit PoseRTV(
const Vector& v);
56 const Pose3& pose()
const {
return first; }
57 const Velocity3& v()
const {
return second; }
63 const Rot3& rotation()
const {
return pose().
rotation(); }
64 const Velocity3& velocity()
const {
return second; }
68 Vector vector()
const;
69 Vector translationVec()
const {
return pose().
translation(); }
70 const Velocity3& velocityVec()
const {
return velocity(); }
74 void print(
const std::string& s=
"")
const;
78 using Base::dimension;
82 using Base::localCoordinates;
83 using Base::LocalCoordinates;
90 double range(
const PoseRTV& other,
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 = boost::none,
150 static Matrix RRTMbn(
const Vector3& euler);
151 static Matrix RRTMbn(
const Rot3& att);
155 static Matrix RRTMnb(
const Vector3& euler);
156 static Matrix RRTMnb(
const Rot3& att);
161 friend class boost::serialization::access;
162 template<
class Archive>
163 void serialize(Archive & ar,
const unsigned int ) {
164 ar & BOOST_SERIALIZATION_NVP(first);
165 ar & BOOST_SERIALIZATION_NVP(second);
174template <
typename A1,
typename A2>
struct Range;
Group product of two Lie Groups.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:112
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:155
Matrix trans(const Matrix &A)
static transpose function, just calls Eigen transpose member function
Definition: Matrix.h:245
Vector3 Point3
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point3 to Vector3...
Definition: Point3.h:35
Vector3 Velocity3
Velocity is currently typedef'd to Vector3.
Definition: NavState.h:28
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Both LieGroupTraits and Testable.
Definition: Lie.h:229
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
Template to construct the product Lie group of two other Lie groups Assumes Lie group structure for G...
Definition: ProductLieGroup.h:29
Template to create a binary predicate.
Definition: Testable.h:111
Definition: BearingRange.h:39
Definition: BearingRange.h:193
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:303
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:310
Robot state for use with IMU measurements.
Definition: PoseRTV.h:23
Vector translationIntegrationVec(const PoseRTV &x2, double dt) const
Definition: PoseRTV.h:129
Point3 translationIntegration(const PoseRTV &x2, double dt) const
predict measurement and where Point3 for x2 should be, as a way of enforcing a velocity constraint Th...
Definition: PoseRTV.h:124