crocoddyl  1.9.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
ActuationModelMultiCopterBaseTpl< _Scalar > Class Template Reference

Multicopter actuation model. More...

#include <crocoddyl/multibody/actuations/multicopter-base.hpp>

Inheritance diagram for ActuationModelMultiCopterBaseTpl< _Scalar >:
Collaboration diagram for ActuationModelMultiCopterBaseTpl< _Scalar >:

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
 
- Public Types inherited from ActuationModelAbstractTpl< _Scalar >
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)
 Compute the actuation signal from the state point \(\mathbf{x}\in\mathbb{R}^{ndx}\) and control input \(\mathbf{u}\in\mathbb{R}^{nu}\). More...
 
virtual void calcDiff (const boost::shared_ptr< Data > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &)
 Compute the Jacobians of the actuation function. More...
 
boost::shared_ptr< DatacreateData ()
 Create the actuation data. More...
 
 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)
 
- Public Member Functions inherited from ActuationModelAbstractTpl< _Scalar >
 ActuationModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nu)
 Initialize the actuation model. More...
 
void calc (const boost::shared_ptr< ActuationDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 Ignore the computation of the actuation signal. More...
 
void calcDiff (const boost::shared_ptr< ActuationDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 Ignore the computation of the Jacobians of the actuation function. More...
 
std::size_t get_nu () const
 Return the dimension of the control input.
 
const boost::shared_ptr< StateAbstract > & get_state () const
 Return the state.
 
virtual void print (std::ostream &os) const
 Print relevant information of the residual model. More...
 

Protected Attributes

std::size_t n_rotors_
 
std::size_t nu_
 Control dimension.
 
boost::shared_ptr< StateAbstractstate_
 Model of the state.
 
MatrixXs tau_f_
 
- Protected Attributes inherited from ActuationModelAbstractTpl< _Scalar >
std::size_t nu_
 Control dimension.
 
boost::shared_ptr< StateAbstractstate_
 Model of the state.
 

Additional Inherited Members

- Public Attributes inherited from ActuationModelAbstractTpl< _Scalar >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 

Detailed Description

template<typename _Scalar>
class crocoddyl::ActuationModelMultiCopterBaseTpl< _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.

See also
ActuationModelAbstractTpl, calc(), calcDiff(), createData()

Definition at line 39 of file multicopter-base.hpp.

Constructor & Destructor Documentation

◆ ActuationModelMultiCopterBaseTpl()

ActuationModelMultiCopterBaseTpl ( boost::shared_ptr< StateMultibody state,
const Eigen::Ref< const Matrix6xs > &  tau_f 
)
inline

Initialize the multicopter actuation model.

Parameters
[in]stateState of the dynamical system
[in]tau_fMatrix that maps the thrust of each propeller to the net force and torque

Definition at line 56 of file multicopter-base.hpp.

Member Function Documentation

◆ calc()

virtual void calc ( const boost::shared_ptr< Data > &  data,
const Eigen::Ref< const VectorXs > &  x,
const Eigen::Ref< const VectorXs > &  u 
)
inlinevirtual

Compute the actuation signal from the state point \(\mathbf{x}\in\mathbb{R}^{ndx}\) and control input \(\mathbf{u}\in\mathbb{R}^{nu}\).

Parameters
[in]dataActuation data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
[in]uControl input \(\mathbf{u}\in\mathbb{R}^{nu}\)

Implements ActuationModelAbstractTpl< _Scalar >.

Definition at line 76 of file multicopter-base.hpp.

◆ calcDiff()

virtual void calcDiff ( const boost::shared_ptr< Data > &  data,
const Eigen::Ref< const VectorXs > &  x,
const Eigen::Ref< const VectorXs > &  u 
)
inlinevirtual

Compute the Jacobians of the actuation function.

Parameters
[in]dataActuation data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
[in]uControl input \(\mathbf{u}\in\mathbb{R}^{nu}\)

Implements ActuationModelAbstractTpl< _Scalar >.

Definition at line 87 of file multicopter-base.hpp.

◆ createData()

boost::shared_ptr<Data> createData ( )
inlinevirtual

Create the actuation data.

Returns
the actuation data

Reimplemented from ActuationModelAbstractTpl< _Scalar >.

Definition at line 97 of file multicopter-base.hpp.


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