30 #ifndef EXOTICA_QUADROTOR_DYNAMICS_SOLVER_QUADROTOR_DYNAMICS_SOLVER_H_ 31 #define EXOTICA_QUADROTOR_DYNAMICS_SOLVER_QUADROTOR_DYNAMICS_SOLVER_H_ 36 #include <exotica_quadrotor_dynamics_solver/quadrotor_dynamics_solver_initializer.h> 78 #endif // EXOTICA_QUADROTOR_DYNAMICS_SOLVER_QUADROTOR_DYNAMICS_SOLVER_H_ QuadrotorDynamicsSolver()
Eigen::Matrix3d J_inv_
Inverted inertia matrix.
std::shared_ptr< Scene > ScenePtr
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.
double L_
Distance between motors.
StateVector f(const StateVector &x, const ControlVector &u) override
Eigen::Matrix< T, NU, 1 > ControlVector
Eigen::MatrixXd fu(const StateVector &x, const ControlVector &u) override
Eigen::MatrixXd fx(const StateVector &x, const ControlVector &u) override
double k_f_
Thrust coefficient, 6.11*10^-8;.
void AssignScene(ScenePtr scene_in) override
Eigen::Matrix3d J_
Inertia matrix.
double k_m_
Moment coefficient.
Eigen::Matrix< T, NX, 1 > StateVector