Exotica
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
Collaboration diagram for exotica::QuadrotorDynamicsSolver:
Collaboration graph

Public Member Functions

 QuadrotorDynamicsSolver ()
 
void AssignScene (ScenePtr scene_in) override
 
StateVector f (const StateVector &x, const ControlVector &u) override
 Forward dynamics. This computes the differential dynamics. More...
 
Eigen::MatrixXd fx (const StateVector &x, const ControlVector &u) override
 Derivative of the forward dynamics w.r.t. the state. More...
 
Eigen::MatrixXd fu (const StateVector &x, const ControlVector &u) override
 Derivative of the forward dynamics w.r.t. the control. More...
 
- Public Member Functions inherited from exotica::AbstractDynamicsSolver< T, NX, NU >
 AbstractDynamicsSolver ()
 
virtual ~AbstractDynamicsSolver ()
 
virtual void InstantiateBase (const Initializer &init)
 Instantiates the base properties of the DynamicsSolver. More...
 
virtual void AssignScene (std::shared_ptr< Scene > scene_in)
 Passes the Scene of the PlanningProblem to the DynamicsSolver. More...
 
virtual void SetDt (double dt_in)
 Sets the timestep dt to be used for integration. More...
 
virtual StateVector F (const StateVector &x, const ControlVector &u)
 State transition function. This internally computes the differential dynamics and applies the chosen integration scheme. More...
 
virtual void ComputeDerivatives (const StateVector &x, const ControlVector &u)
 Computes derivatives fx, fu, Fx, Fu [single call for efficiency, derivatives can be retrieved with get_fx, get_fu, get_Fx, get_Fu]. More...
 
const StateDerivativeget_Fx () const
 Returns derivative Fx computed by ComputeDerivatives. More...
 
const ControlDerivativeget_Fu () const
 Returns derivative Fu computed by ComputeDerivatives. More...
 
const StateDerivativeget_fx () const
 Returns derivative fx computed by ComputeDerivatives. More...
 
const ControlDerivativeget_fu () const
 Returns derivative fu computed by ComputeDerivatives. More...
 
StateDerivative fx_fd (const StateVector &x, const ControlVector &u)
 Derivative of the forward dynamics w.r.t. the state [finite differencing]. More...
 
ControlDerivative fu_fd (const StateVector &x, const ControlVector &u)
 Derivative of the forward dynamics w.r.t. the control [finite differencing]. More...
 
const bool & get_has_second_order_derivatives () const
 Returns whether second-order derivatives are available. More...
 
virtual Eigen::Tensor< T, 3 > fxx (const StateVector &x, const ControlVector &u)
 
virtual Eigen::Tensor< T, 3 > fuu (const StateVector &x, const ControlVector &u)
 
virtual Eigen::Tensor< T, 3 > fxu (const StateVector &x, const ControlVector &u)
 
StateVector Simulate (const StateVector &x, const ControlVector &u, T t)
 Simulates the dynamic system from starting state x using control u for t seconds. More...
 
virtual StateVector StateDelta (const StateVector &x_1, const StateVector &x_2)
 Return the difference of two state vectors. Used when e.g. angle differences need to be wrapped from [-pi; pi] Returns x_1-x_2. More...
 
void StateDelta (const StateVector &x_1, const StateVector &x_2, Eigen::VectorXdRef xout)
 
virtual Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > dStateDelta (const StateVector &x_1, const StateVector &x_2, const ArgumentPosition first_or_second)
 Return the difference of the StateDelta operation between two state vectors. The ArgumentPosition argument can be used to select whether to take derivative w.r.t. x_1 or x_2. More...
 
virtual Hessian ddStateDelta (const StateVector &x_1, const StateVector &x_2, const ArgumentPosition first_or_second)
 
virtual Eigen::Matrix< T, Eigen::Dynamic, 1 > GetPosition (Eigen::VectorXdRefConst x_in)
 Returns the position-part of the state vector to update the scene. For types including SE(3) and rotation, convert to the appropriate representation here by overriding this method. More...
 
int get_num_controls () const
 Returns number of controls. More...
 
int get_num_positions () const
 Returns number of positions. More...
 
int get_num_velocities () const
 Returns number of velocities. More...
 
int get_num_state () const
 Returns size of state space (nx) More...
 
int get_num_state_derivative () const
 Returns size of derivative vector of state space (ndx) More...
 
get_dt () const
 Returns integration timestep dt. More...
 
Integrator get_integrator () const
 Returns used integration scheme. More...
 
void set_integrator (Integrator integrator_in)
 Sets integrator type. More...
 
void SetIntegrator (const std::string &integrator_in)
 Sets integrator type based on request string. More...
 
const Eigen::MatrixXd & get_control_limits ()
 Returns the control limits vector. More...
 
void set_control_limits (Eigen::VectorXdRefConst control_limits_low, Eigen::VectorXdRefConst control_limits_high)
 Sets the control limits. More...
 
const bool & get_has_state_limits () const
 Returns whether state limits are available. More...
 
void ClampToStateLimits (Eigen::Ref< Eigen::VectorXd > state_in)
 Clamps the passed in state to the state limits. More...
 
virtual ControlVector InverseDynamics (const StateVector &state)
 Returns a control vector corresponding to the state vector assuming zero acceleration. More...
 
virtual void Integrate (const StateVector &x, const StateVector &dx, const double dt, StateVector &xout)
 Integrates without performing dynamics. More...
 
- Public Member Functions inherited from exotica::Object
 Object ()
 
virtual ~Object ()
 
virtual std::string type () const
 Type Information wrapper: must be virtual so that it is polymorphic... More...
 
std::string GetObjectName ()
 
void InstantiateObject (const Initializer &init)
 
virtual std::string Print (const std::string &prepend) const
 
- Public Member Functions inherited from exotica::InstantiableBase
 InstantiableBase ()=default
 
virtual ~InstantiableBase ()=default
 
virtual std::vector< InitializerGetAllTemplates () const =0
 
- Public Member Functions inherited from exotica::Instantiable< QuadrotorDynamicsSolverInitializer >
void InstantiateInternal (const Initializer &init) override
 
Initializer GetInitializerTemplate () override
 
std::vector< InitializerGetAllTemplates () const override
 
virtual void Instantiate (const QuadrotorDynamicsSolverInitializer &init)
 
const QuadrotorDynamicsSolverInitializer & GetParameters () const
 

Private Attributes

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

Additional Inherited Members

- Public Types inherited from exotica::AbstractDynamicsSolver< T, NX, NU >
typedef Eigen::Matrix< T, NX, 1 > StateVector
 Convenience definition for a StateVector containing both position and velocity (dimension NX x 1) More...
 
typedef Eigen::Matrix< T, NU, 1 > ControlVector
 Convenience definition for a ControlVector (dimension NU x 1) More...
 
typedef Eigen::Matrix< T, NX, NX > StateDerivative
 Convenience definition for a StateDerivative. More...
 
typedef Eigen::Matrix< T, NX, NU > ControlDerivative
 Convenience definition for a ControlDerivative. More...
 
- Public Attributes inherited from exotica::Object
std::string ns_
 
std::string object_name_
 
bool debug_
 
- Protected Member Functions inherited from exotica::AbstractDynamicsSolver< T, NX, NU >
virtual StateVector SimulateOneStep (const StateVector &x, const ControlVector &u)
 Integrates the dynamic system from state x with controls u applied for one timestep dt using the selected integrator. More...
 
void InitializeSecondOrderDerivatives ()
 
- Protected Attributes inherited from exotica::AbstractDynamicsSolver< T, NX, NU >
int num_controls_ = -1
 Number of controls in the dynamic system. More...
 
int num_positions_ = -1
 Number of positions in the dynamic system. More...
 
int num_velocities_ = -1
 Number of velocities in the dynamic system. More...
 
int num_state_ = -1
 Size of state space (num_positions + num_velocities) More...
 
int num_state_derivative_ = -1
 Size of the tangent vector to the state space (2 * num_velocities) More...
 
bool has_second_order_derivatives_ = false
 Whether this solver provides second order derivatives. If false (default), assumed to be all zeros. More...
 
bool second_order_derivatives_initialized_ = false
 Whether fxx, fxu and fuu have been initialized to 0. More...
 
bool has_state_limits_ = false
 Whether the solver specifies state limits. More...
 
Eigen::VectorXd state_limits_lower_
 Lower state limits (configuration and velocity) More...
 
Eigen::VectorXd state_limits_upper_
 Upper state limits (configuration and velocity) More...
 
dt_ = 0.01
 Internal timestep used for integration. Defaults to 10ms. More...
 
Integrator integrator_ = Integrator::RK1
 Chosen integrator. Defaults to Euler (RK1). More...
 
Eigen::MatrixXd control_limits_
 ControlLimits. Default is empty vector. More...
 
Eigen::Tensor< T, 3 > fxx_default_
 
Eigen::Tensor< T, 3 > fuu_default_
 
Eigen::Tensor< T, 3 > fxu_default_
 
Eigen::MatrixXd fx_
 Internal storage of differential dynamics partial derivative fx computed by ComputeDerivatives. More...
 
Eigen::MatrixXd fu_
 Internal storage of differential dynamics partial derivative fu computed by ComputeDerivatives. More...
 
Eigen::MatrixXd Fx_
 Internal storage of state transition partial derivative Fx computed by ComputeDerivatives. More...
 
Eigen::MatrixXd Fu_
 Internal storage of state transition partial derivative Fu computed by ComputeDerivatives. More...
 
- 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]

Constructor & Destructor Documentation

◆ QuadrotorDynamicsSolver()

exotica::QuadrotorDynamicsSolver::QuadrotorDynamicsSolver ( )

Member Function Documentation

◆ AssignScene()

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

◆ f()

StateVector exotica::QuadrotorDynamicsSolver::f ( const StateVector x,
const ControlVector u 
)
overridevirtual

Forward dynamics. This computes the differential dynamics.

Implements exotica::AbstractDynamicsSolver< T, NX, NU >.

◆ fu()

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

Derivative of the forward dynamics w.r.t. the control.

Reimplemented from exotica::AbstractDynamicsSolver< T, NX, NU >.

◆ fx()

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

Derivative of the forward dynamics w.r.t. the state.

Reimplemented from exotica::AbstractDynamicsSolver< T, NX, NU >.

Member Data Documentation

◆ g_

double exotica::QuadrotorDynamicsSolver::g_ = 9.81
private

Gravity (m/s^2)

◆ J_

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

Inertia matrix.

◆ J_inv_

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

Inverted inertia matrix.

◆ k_f_

double exotica::QuadrotorDynamicsSolver::k_f_ = 1
private

Thrust coefficient, 6.11*10^-8;.

◆ k_m_

double exotica::QuadrotorDynamicsSolver::k_m_ = 0.0245
private

Moment coefficient.

◆ L_

double exotica::QuadrotorDynamicsSolver::L_ = 0.1750
private

Distance between motors.

◆ mass_

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

Mass.


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