Public Member Functions | Private Attributes | List of all members
gtsam::ConstantTwistScenario Class Reference

#include <Scenario.h>

Inheritance diagram for gtsam::ConstantTwistScenario:
Inheritance graph
[legend]

Public Member Functions

Vector3 acceleration_n (double t) const override
 acceleration in nav frame More...
 
 ConstantTwistScenario (const Vector3 &w, const Vector3 &v, const Pose3 &nTb0=Pose3())
 Construct scenario with constant twist [w,v]. More...
 
Vector3 omega_b (double t) const override
 angular velocity in body frame More...
 
Pose3 pose (double t) const override
 pose at time t More...
 
Vector3 velocity_n (double t) const override
 velocity at time t, in nav frame More...
 
- Public Member Functions inherited from gtsam::Scenario
Vector3 acceleration_b (double t) const
 
NavState navState (double t) const
 
Rot3 rotation (double t) const
 
Vector3 velocity_b (double t) const
 
virtual ~Scenario ()
 virtual destructor More...
 

Private Attributes

const Vector3 a_b_
 
const Pose3 nTb0_
 
const Vector6 twist_
 

Detailed Description

Scenario with constant twist 3D trajectory. Note that a plane flying level does not feel any acceleration: gravity is being perfectly compensated by the lift generated by the wings, and drag is compensated by thrust. The accelerometer will add the gravity component back in, as modeled by the specificForce method in ScenarioRunner.

Definition at line 60 of file Scenario.h.

Constructor & Destructor Documentation

◆ ConstantTwistScenario()

gtsam::ConstantTwistScenario::ConstantTwistScenario ( const Vector3 w,
const Vector3 v,
const Pose3 nTb0 = Pose3() 
)
inline

Construct scenario with constant twist [w,v].

Definition at line 63 of file Scenario.h.

Member Function Documentation

◆ acceleration_n()

Vector3 gtsam::ConstantTwistScenario::acceleration_n ( double  t) const
inlineoverridevirtual

acceleration in nav frame

Implements gtsam::Scenario.

Definition at line 74 of file Scenario.h.

◆ omega_b()

Vector3 gtsam::ConstantTwistScenario::omega_b ( double  t) const
inlineoverridevirtual

angular velocity in body frame

Implements gtsam::Scenario.

Definition at line 70 of file Scenario.h.

◆ pose()

Pose3 gtsam::ConstantTwistScenario::pose ( double  t) const
inlineoverridevirtual

pose at time t

Implements gtsam::Scenario.

Definition at line 67 of file Scenario.h.

◆ velocity_n()

Vector3 gtsam::ConstantTwistScenario::velocity_n ( double  t) const
inlineoverridevirtual

velocity at time t, in nav frame

Implements gtsam::Scenario.

Definition at line 71 of file Scenario.h.

Member Data Documentation

◆ a_b_

const Vector3 gtsam::ConstantTwistScenario::a_b_
private

Definition at line 78 of file Scenario.h.

◆ nTb0_

const Pose3 gtsam::ConstantTwistScenario::nTb0_
private

Definition at line 79 of file Scenario.h.

◆ twist_

const Vector6 gtsam::ConstantTwistScenario::twist_
private

Definition at line 77 of file Scenario.h.


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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:46:16