Public Member Functions | Private Attributes | List of all members
exotica::QuadrotorDynamicsSolver Class Reference

Quadrotor dynamics with quaternion representation Based on D. Mellinger, N. Michael, and V. Kumar, "Trajectory generation and control for precise aggressive maneuvers with quadrotors", Proceedings of the 12th International Symposium on Experimental Robotics (ISER 2010), 2010. Cf. https://journals.sagepub.com/doi/abs/10.1177/0278364911434236. More...

#include <quadrotor_dynamics_solver.h>

Inheritance diagram for exotica::QuadrotorDynamicsSolver:
Inheritance graph
[legend]

Public Member Functions

void AssignScene (ScenePtr scene_in) override
 
StateVector f (const StateVector &x, const ControlVector &u) override
 
Eigen::MatrixXd fu (const StateVector &x, const ControlVector &u) override
 
Eigen::MatrixXd fx (const StateVector &x, const ControlVector &u) override
 
 QuadrotorDynamicsSolver ()
 
- Public Member Functions inherited from exotica::AbstractDynamicsSolver< class, NX, NU >
 AbstractDynamicsSolver ()
 
virtual void AssignScene (std::shared_ptr< Scene > scene_in)
 
void ClampToStateLimits (Eigen::Ref< Eigen::VectorXd > state_in)
 
virtual void ComputeDerivatives (const StateVector &x, const ControlVector &u)
 
virtual Hessian ddStateDelta (const StateVector &x_1, const StateVector &x_2, const ArgumentPosition first_or_second)
 
virtual Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > dStateDelta (const StateVector &x_1, const StateVector &x_2, const ArgumentPosition first_or_second)
 
virtual StateVector F (const StateVector &x, const ControlVector &u)
 
ControlDerivative fu_fd (const StateVector &x, const ControlVector &u)
 
virtual Eigen::Tensor< T, 3 > fuu (const StateVector &x, const ControlVector &u)
 
StateDerivative fx_fd (const StateVector &x, const ControlVector &u)
 
virtual Eigen::Tensor< T, 3 > fxu (const StateVector &x, const ControlVector &u)
 
virtual Eigen::Tensor< T, 3 > fxx (const StateVector &x, const ControlVector &u)
 
const Eigen::MatrixXd & get_control_limits ()
 
get_dt () const
 
const ControlDerivativeget_Fu () const
 
const ControlDerivativeget_fu () const
 
const StateDerivativeget_Fx () const
 
const StateDerivativeget_fx () const
 
const bool & get_has_second_order_derivatives () const
 
const bool & get_has_state_limits () const
 
Integrator get_integrator () const
 
int get_num_controls () const
 
int get_num_positions () const
 
int get_num_state () const
 
int get_num_state_derivative () const
 
int get_num_velocities () const
 
virtual Eigen::Matrix< T, Eigen::Dynamic, 1 > GetPosition (Eigen::VectorXdRefConst x_in)
 
virtual void InstantiateBase (const Initializer &init)
 
virtual void Integrate (const StateVector &x, const StateVector &dx, const double dt, StateVector &xout)
 
virtual ControlVector InverseDynamics (const StateVector &state)
 
void set_control_limits (Eigen::VectorXdRefConst control_limits_low, Eigen::VectorXdRefConst control_limits_high)
 
void set_integrator (Integrator integrator_in)
 
virtual void SetDt (double dt_in)
 
void SetIntegrator (const std::string &integrator_in)
 
StateVector Simulate (const StateVector &x, const ControlVector &u, T t)
 
void StateDelta (const StateVector &x_1, const StateVector &x_2, Eigen::VectorXdRef xout)
 
virtual StateVector StateDelta (const StateVector &x_1, const StateVector &x_2)
 
virtual ~AbstractDynamicsSolver ()
 
- Public Member Functions inherited from exotica::Object
std::string GetObjectName ()
 
void InstantiateObject (const Initializer &init)
 
 Object ()
 
virtual std::string Print (const std::string &prepend) const
 
virtual std::string type () const
 
virtual ~Object ()
 
- Public Member Functions inherited from exotica::InstantiableBase
 InstantiableBase ()=default
 
virtual ~InstantiableBase ()=default
 
- Public Member Functions inherited from exotica::Instantiable< QuadrotorDynamicsSolverInitializer >
std::vector< InitializerGetAllTemplates () const override
 
Initializer GetInitializerTemplate () override
 
const QuadrotorDynamicsSolverInitializer & GetParameters () const
 
virtual void Instantiate (const QuadrotorDynamicsSolverInitializer &init)
 
void InstantiateInternal (const Initializer &init) override
 

Private Attributes

double g_ = 9.81
 Gravity (m/s^2) More...
 
Eigen::Matrix3d J_
 Inertia matrix. More...
 
Eigen::Matrix3d J_inv_
 Inverted inertia matrix. More...
 
double k_f_ = 1
 Thrust coefficient, 6.11*10^-8;. More...
 
double k_m_ = 0.0245
 Moment coefficient. More...
 
double L_ = 0.1750
 Distance between motors. More...
 
double mass_ = .5
 Mass. More...
 

Additional Inherited Members

- Public Types inherited from exotica::AbstractDynamicsSolver< class, NX, NU >
typedef Eigen::Matrix< T, NX, NU > ControlDerivative
 
typedef Eigen::Matrix< T, NU, 1 > ControlVector
 
typedef Eigen::Matrix< T, NX, NX > StateDerivative
 
typedef Eigen::Matrix< T, NX, 1 > StateVector
 
- Public Attributes inherited from exotica::Object
bool debug_
 
std::string ns_
 
std::string object_name_
 
- Protected Member Functions inherited from exotica::AbstractDynamicsSolver< class, NX, NU >
void InitializeSecondOrderDerivatives ()
 
virtual StateVector SimulateOneStep (const StateVector &x, const ControlVector &u)
 
- Protected Attributes inherited from exotica::AbstractDynamicsSolver< class, NX, NU >
Eigen::MatrixXd control_limits_
 
dt_
 
Eigen::MatrixXd Fu_
 
Eigen::MatrixXd fu_
 
Eigen::Tensor< T, 3 > fuu_default_
 
Eigen::MatrixXd fx_
 
Eigen::MatrixXd Fx_
 
Eigen::Tensor< T, 3 > fxu_default_
 
Eigen::Tensor< T, 3 > fxx_default_
 
bool has_second_order_derivatives_
 
bool has_state_limits_
 
Integrator integrator_
 
int num_controls_
 
int num_positions_
 
int num_state_
 
int num_state_derivative_
 
int num_velocities_
 
bool second_order_derivatives_initialized_
 
Eigen::VectorXd state_limits_lower_
 
Eigen::VectorXd state_limits_upper_
 
- Protected Attributes inherited from exotica::Instantiable< QuadrotorDynamicsSolverInitializer >
QuadrotorDynamicsSolverInitializer parameters_
 

Detailed Description

Quadrotor dynamics with quaternion representation Based on D. Mellinger, N. Michael, and V. Kumar, "Trajectory generation and control for precise aggressive maneuvers with quadrotors", Proceedings of the 12th International Symposium on Experimental Robotics (ISER 2010), 2010. Cf. https://journals.sagepub.com/doi/abs/10.1177/0278364911434236.

StateVector X ∈ R^12 = [x, y, z, r, p, y, xdot, ydot, zdot, omega1, omega2, omega3]

Definition at line 47 of file quadrotor_dynamics_solver.h.

Constructor & Destructor Documentation

exotica::QuadrotorDynamicsSolver::QuadrotorDynamicsSolver ( )

Definition at line 36 of file quadrotor_dynamics_solver.cpp.

Member Function Documentation

void exotica::QuadrotorDynamicsSolver::AssignScene ( ScenePtr  scene_in)
override

Definition at line 49 of file quadrotor_dynamics_solver.cpp.

Eigen::VectorXd exotica::QuadrotorDynamicsSolver::f ( const StateVector x,
const ControlVector u 
)
overridevirtual
Eigen::MatrixXd exotica::QuadrotorDynamicsSolver::fu ( const StateVector x,
const ControlVector u 
)
overridevirtual
Eigen::MatrixXd exotica::QuadrotorDynamicsSolver::fx ( const StateVector x,
const ControlVector u 
)
overridevirtual

Member Data Documentation

double exotica::QuadrotorDynamicsSolver::g_ = 9.81
private

Gravity (m/s^2)

Definition at line 63 of file quadrotor_dynamics_solver.h.

Eigen::Matrix3d exotica::QuadrotorDynamicsSolver::J_
private

Inertia matrix.

Definition at line 59 of file quadrotor_dynamics_solver.h.

Eigen::Matrix3d exotica::QuadrotorDynamicsSolver::J_inv_
private

Inverted inertia matrix.

Definition at line 60 of file quadrotor_dynamics_solver.h.

double exotica::QuadrotorDynamicsSolver::k_f_ = 1
private

Thrust coefficient, 6.11*10^-8;.

Definition at line 71 of file quadrotor_dynamics_solver.h.

double exotica::QuadrotorDynamicsSolver::k_m_ = 0.0245
private

Moment coefficient.

Definition at line 72 of file quadrotor_dynamics_solver.h.

double exotica::QuadrotorDynamicsSolver::L_ = 0.1750
private

Distance between motors.

Definition at line 64 of file quadrotor_dynamics_solver.h.

double exotica::QuadrotorDynamicsSolver::mass_ = .5
private

Mass.

Definition at line 62 of file quadrotor_dynamics_solver.h.


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


exotica_quadrotor_dynamics_solver
Author(s):
autogenerated on Sat Apr 10 2021 02:36:44