Multicopter actuation model. More...
#include <crocoddyl/multibody/actuations/multicopter-base.hpp>
Public Types | |
typedef ActuationModelAbstractTpl< Scalar > | Base |
typedef ActuationDataAbstractTpl< Scalar > | Data |
typedef MathBaseTpl< Scalar > | MathBase |
typedef MathBase::Matrix6xs | Matrix6xs |
typedef MathBase::MatrixXs | MatrixXs |
typedef _Scalar | Scalar |
typedef StateMultibodyTpl< Scalar > | StateMultibody |
typedef MathBase::VectorXs | VectorXs |
![]() | |
typedef ActuationDataAbstractTpl< Scalar > | ActuationDataAbstract |
typedef MathBaseTpl< Scalar > | MathBase |
typedef MathBase::MatrixXs | MatrixXs |
typedef StateAbstractTpl< Scalar > | StateAbstract |
typedef MathBase::VectorXs | VectorXs |
Public Member Functions | |
ActuationModelMultiCopterBaseTpl (boost::shared_ptr< StateMultibody > state, const Eigen::Ref< const Matrix6xs > &tau_f) | |
Initialize the multicopter actuation model. More... | |
virtual void | calc (const boost::shared_ptr< Data > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &u) |
virtual void | calcDiff (const boost::shared_ptr< Data > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &) |
boost::shared_ptr< Data > | createData () |
DEPRECATED ("Use constructor without n_rotors", ActuationModelMultiCopterBaseTpl(boost::shared_ptr< StateMultibody > state, const std::size_t n_rotors, const Eigen::Ref< const Matrix6xs > &tau_f)) | |
std::size_t | get_nrotors () const |
const MatrixXs & | get_tauf () const |
void | set_tauf (const Eigen::Ref< const MatrixXs > &tau_f) |
![]() | |
ActuationModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nu) | |
std::size_t | get_nu () const |
const boost::shared_ptr< StateAbstract > & | get_state () const |
Protected Attributes | |
std::size_t | n_rotors_ |
MatrixXs | tau_f_ |
![]() | |
std::size_t | nu_ |
boost::shared_ptr< StateAbstract > | state_ |
Additional Inherited Members | |
![]() | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar | Scalar |
Multicopter actuation model.
This actuation model is aimed for those robots whose base_link is actuated using a propulsion system, e.g., a multicopter or an aerial manipulator (multicopter with a robotic arm attached). Control input: the thrust (force) created by each propeller. tau_f matrix: this matrix relates the thrust of each propeller to the net force and torque that it causes to the base_link. For a simple quadrotor: tau_f.nrows = 6, tau_f.ncols = 4
Both actuation and Jacobians are computed analytically by calc
and calcDiff
, respectively.
Reference: M. Geisert and N. Mansard, "Trajectory generation for quadrotor based systems using numerical optimal control," 2016 IEEE International Conference on Robotics and Automation (ICRA), Stockholm, 2016, pp. 2958-2964. See Section III.C.
ActuationModelAbstractTpl
, calc()
, calcDiff()
, createData()
Definition at line 39 of file multicopter-base.hpp.
|
inline |
Initialize the multicopter actuation model.
[in] | state | State of the dynamical system |
[in] | tau_f | Matrix that maps the thrust of each propeller to the net force and torque |
Definition at line 56 of file multicopter-base.hpp.