Added Scenario class

release/4.3a0
Frank Dellaert 2018-10-14 10:34:02 -04:00
parent 2f5a60d039
commit c68d00fd55
1 changed files with 22 additions and 1 deletions

23
gtsam.h
View File

@ -2509,7 +2509,7 @@ virtual class PreintegratedRotationParams {
Matrix getGyroscopeCovariance() const;
// TODO(frank): allow optional
// boost::optional<Vector3> getOmegaCoriolis() const;
// boost::optional<Vector> getOmegaCoriolis() const;
// boost::optional<Pose3> getBodyPSensor() const;
};
@ -2660,6 +2660,27 @@ virtual class Pose3AttitudeFactor : gtsam::NonlinearFactor{
gtsam::Unit3 bRef() const;
};
#include <gtsam/navigation/Scenario.h>
virtual class Scenario {};
virtual class ConstantTwistScenario : gtsam::Scenario {
ConstantTwistScenario(const Vector& w, const Vector& v);
gtsam::Pose3 pose(double t) const;
Vector omega_b(double t) const;
Vector velocity_n(double t) const;
Vector acceleration_n(double t) const;
};
virtual class AcceleratingScenario : gtsam::Scenario {
AcceleratingScenario(const gtsam::Rot3& nRb, const gtsam::Point3& p0,
const Vector& v0, const Vector& a_n,
const Vector& omega_b);
gtsam::Pose3 pose(double t) const;
Vector omega_b(double t) const;
Vector velocity_n(double t) const;
Vector acceleration_n(double t) const;
};
//*************************************************************************
// Utilities
//*************************************************************************