- 3.0.2 models module.
ct::models::QuadrotorLinear Class Referencefinal

#include <QuadrotorLinear.hpp>

Inheritance diagram for ct::models::QuadrotorLinear:
ct::core::LinearSystem< quadrotor::nStates, quadrotor::nControls > ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR > ct::core::System< STATE_DIM, SCALAR >

Public Types

typedef ct::core::StateVector< quadrotor::nStatesstate_vector_t
 
typedef ct::core::ControlVector< quadrotor::nControlscontrol_vector_t
 
typedef Eigen::Matrix< double, quadrotor::nStates, quadrotor::nStatesstate_matrix_t
 
typedef Eigen::Matrix< double, quadrotor::nStates, quadrotor::nControlsstate_control_matrix_t
 
- Public Types inherited from ct::core::LinearSystem< quadrotor::nStates, quadrotor::nControls >
typedef Base::time_t time_t
 
typedef StateVector< quadrotor::nStates, SCALARstate_vector_t
 
typedef ControlVector< quadrotor::nControls, SCALARcontrol_vector_t
 
typedef StateMatrix< quadrotor::nStates, SCALARstate_matrix_t
 
typedef StateControlMatrix< quadrotor::nStates, quadrotor::nControls, SCALARstate_control_matrix_t
 
- Public Types inherited from ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >
typedef std::shared_ptr< ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR > > Ptr
 
typedef Base::time_t time_t
 
- Public Types inherited from ct::core::System< STATE_DIM, SCALAR >
typedef SCALAR time_t
 

Public Member Functions

QuadrotorLinearclone () const override
 
const state_matrix_tgetDerivativeState (const state_vector_t &x, const control_vector_t &u, const ct::core::Time t=0.0) override
 
const state_control_matrix_tgetDerivativeControl (const state_vector_t &x, const control_vector_t &u, const ct::core::Time t=0.0) override
 
- Public Member Functions inherited from ct::core::LinearSystem< quadrotor::nStates, quadrotor::nControls >
 LinearSystem (const ct::core::SYSTEM_TYPE &type=ct::core::SYSTEM_TYPE::GENERAL)
 
virtual ~LinearSystem ()
 
virtual void computeControlledDynamics (const state_vector_t &state, const time_t &t, const control_vector_t &control, state_vector_t &derivative) override
 
virtual const state_matrix_tgetDerivativeState (const state_vector_t &x, const control_vector_t &u, const time_t t=time_t(0.0))=0
 
virtual const state_control_matrix_tgetDerivativeControl (const state_vector_t &x, const control_vector_t &u, const time_t t=time_t(0.0))=0
 
virtual void getDerivatives (state_matrix_t &A, state_control_matrix_t &B, const state_vector_t &x, const control_vector_t &u, const time_t t=time_t(0.0))
 
- Public Member Functions inherited from ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >
 ControlledSystem (const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 ControlledSystem (std::shared_ptr< ct::core::Controller< STATE_DIM, CONTROL_DIM, SCALAR >> controller, const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 ControlledSystem (const ControlledSystem &arg)
 
virtual ~ControlledSystem ()
 
void setController (const std::shared_ptr< Controller< STATE_DIM, CONTROL_DIM, SCALAR >> &controller)
 
void getController (std::shared_ptr< Controller< STATE_DIM, CONTROL_DIM, SCALAR >> &controller) const
 
std::shared_ptr< Controller< STATE_DIM, CONTROL_DIM, SCALAR > > getController ()
 
virtual void computeDynamics (const StateVector< STATE_DIM, SCALAR > &state, const time_t &t, StateVector< STATE_DIM, SCALAR > &derivative) override
 
virtual void computeControlledDynamics (const StateVector< STATE_DIM, SCALAR > &state, const time_t &t, const ControlVector< CONTROL_DIM, SCALAR > &control, StateVector< STATE_DIM, SCALAR > &derivative)=0
 
ControlVector< CONTROL_DIM, SCALARgetLastControlAction ()
 
- Public Member Functions inherited from ct::core::System< STATE_DIM, SCALAR >
 System (const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 System (const System &other)
 
virtual ~System ()
 
virtual void computeDynamics (const StateVector< STATE_DIM, SCALAR > &state, const time_t &t, StateVector< STATE_DIM, SCALAR > &derivative)=0
 
SYSTEM_TYPE getType () const
 
virtual bool isSymplectic () const
 

Additional Inherited Members

- Public Attributes inherited from ct::core::LinearSystem< quadrotor::nStates, quadrotor::nControls >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ControlledSystem< quadrotor::nStates, quadrotor::nControls, SCALARBase
 
- Public Attributes inherited from ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef System< STATE_DIM, SCALARBase
 
- Public Attributes inherited from ct::core::System< STATE_DIM, SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef SCALAR S
 
- Protected Attributes inherited from ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >
std::shared_ptr< Controller< STATE_DIM, CONTROL_DIM, SCALAR > > controller_
 
ControlVector< CONTROL_DIM, SCALARcontrolAction_
 
- Protected Attributes inherited from ct::core::System< STATE_DIM, SCALAR >
SYSTEM_TYPE type_
 

Member Typedef Documentation

◆ state_vector_t

◆ control_vector_t

◆ state_matrix_t

◆ state_control_matrix_t

Member Function Documentation

◆ clone()

QuadrotorLinear* ct::models::QuadrotorLinear::clone ( ) const
inlineoverridevirtual

◆ getDerivativeState()

const state_matrix_t& ct::models::QuadrotorLinear::getDerivativeState ( const state_vector_t x,
const control_vector_t u,
const ct::core::Time  t = 0.0 
)
inlineoverride

◆ getDerivativeControl()

const state_control_matrix_t& ct::models::QuadrotorLinear::getDerivativeControl ( const state_vector_t x,
const control_vector_t u,
const ct::core::Time  t = 0.0 
)
inlineoverride

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