9#include <gtsam_unstable/dllexport.h>
34 : Base(
Pose3(rot, t), vel) {}
36 : Base(
Pose3(rot, t), vel) {}
37 explicit PoseRTV(
const Point3& t)
38 : Base(
Pose3(
Rot3(), t),Vector3::Zero()) {}
41 explicit PoseRTV(
const Pose3& pose)
42 : Base(pose,Vector3::Zero()) {}
45 PoseRTV(
const Base& base)
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; }
58 const Point3& t()
const {
return pose().translation(); }
59 const Rot3& R()
const {
return pose().rotation(); }
62 const Point3& translation()
const {
return pose().translation(); }
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(); }
73 bool equals(
const PoseRTV& other,
double tol=1e-6)
const;
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;
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
Matrix trans(const Matrix &A)
static transpose function, just calls Eigen transpose member function
Definition Matrix.h:242
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:36
Vector3 Velocity3
Velocity is currently typedef'd to Vector3.
Definition NavState.h:28
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:41
ProductLieGroup()
Definition ProductLieGroup.h:40
Definition BearingRange.h:40
Definition BearingRange.h:194
A 3D pose (R,t) : (Rot3,Point3).
Definition Pose3.h:37
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition Rot3.h:58
Robot state for use with IMU measurements.
Definition PoseRTV.h:23
Point3 translationIntegration(const Rot3 &r2, const Velocity3 &v2, double dt) const
predict measurement and where Point3 for x2 should be, as a way of enforcing a velocity constraint Th...
Definition PoseRTV.cpp:161
Vector translationIntegrationVec(const PoseRTV &x2, double dt) const
Definition PoseRTV.h:129
PoseRTV flyingDynamics(double pitch_rate, double heading_rate, double lift_control, double dt) const
Simulates flying robot with simple flight model Integrates state x1 -> x2 given controls x1 = {p1,...
Definition PoseRTV.cpp:85
PoseRTV planarDynamics(double vel_rate, double heading_rate, double max_accel, double dt) const
Dynamics integrator for ground robots Always move from time 1 to time 2.
Definition PoseRTV.cpp:60
PoseRTV generalDynamics(const Vector &accel, const Vector &gyro, double dt) const
General Dynamics update - supply control inputs in body frame.
Definition PoseRTV.cpp:118
Vector6 imuPrediction(const PoseRTV &x2, double dt) const
Dynamics predictor for both ground and flying robots, given states at 1 and 2 Always move from time 1...
Definition PoseRTV.cpp:133
double range(const PoseRTV &other, OptionalJacobian< 1, 9 > H1=boost::none, OptionalJacobian< 1, 9 > H2=boost::none) const
range between translations
Definition PoseRTV.cpp:169
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