gtsam  4.0.0
gtsam
gtsam::AcceleratingScenario Class Reference

Detailed Description

Accelerating from an arbitrary initial state, with optional rotation.

+ Inheritance diagram for gtsam::AcceleratingScenario:

Public Member Functions

 AcceleratingScenario (const Rot3 &nRb, const Point3 &p0, const Vector3 &v0, const Vector3 &a_n, const Vector3 &omega_b=Vector3::Zero())
 Construct scenario with constant acceleration in navigation frame and optional angular velocity in body: rotating while translating... More...
 
Pose3 pose (double t) const override
 pose at time t
 
Vector3 omega_b (double t) const override
 angular velocity in body frame
 
Vector3 velocity_n (double t) const override
 velocity at time t, in nav frame
 
Vector3 acceleration_n (double t) const override
 acceleration in nav frame
 
- Public Member Functions inherited from gtsam::Scenario
virtual ~Scenario ()
 virtual destructor
 
Rot3 rotation (double t) const
 
NavState navState (double t) const
 
Vector3 velocity_b (double t) const
 
Vector3 acceleration_b (double t) const
 

Constructor & Destructor Documentation

◆ AcceleratingScenario()

gtsam::AcceleratingScenario::AcceleratingScenario ( const Rot3 nRb,
const Point3 p0,
const Vector3 &  v0,
const Vector3 &  a_n,
const Vector3 &  omega_b = Vector3::Zero() 
)
inline

Construct scenario with constant acceleration in navigation frame and optional angular velocity in body: rotating while translating...


The documentation for this class was generated from the following file: