9 #ifndef CROCODDYL_MULTIBODY_ACTUATIONS_MULTICOPTER_BASE_HPP_ 10 #define CROCODDYL_MULTIBODY_ACTUATIONS_MULTICOPTER_BASE_HPP_ 12 #include "crocoddyl/multibody/fwd.hpp" 13 #include "crocoddyl/core/utils/exception.hpp" 14 #include "crocoddyl/core/actuation-base.hpp" 15 #include "crocoddyl/multibody/states/multibody.hpp" 28 template <
typename _Scalar>
31 typedef _Scalar Scalar;
36 typedef typename MathBase::VectorXs VectorXs;
37 typedef typename MathBase::MatrixXs MatrixXs;
40 const Eigen::Ref<const MatrixXs>& tau_f)
41 : Base(state, state->get_nv() - 6 + n_rotors), n_rotors_(n_rotors) {
42 pinocchio::JointModelFreeFlyerTpl<Scalar> ff_joint;
43 if (state->get_pinocchio()->joints[1].shortname() != ff_joint.shortname()) {
44 throw_pretty(
"Invalid argument: " 45 <<
"the first joint has to be free-flyer");
48 tau_f_ = MatrixXs::Zero(state_->get_nv(), nu_);
49 tau_f_.block(0, 0, 6, n_rotors_) = tau_f;
50 if (nu_ > n_rotors_) {
51 tau_f_.bottomRightCorner(nu_ - n_rotors_, nu_ - n_rotors_) =
52 MatrixXs::Identity(nu_ - n_rotors_, nu_ - n_rotors_);
57 virtual void calc(
const boost::shared_ptr<Data>& data,
const Eigen::Ref<const VectorXs>& ,
58 const Eigen::Ref<const VectorXs>& u) {
59 if (static_cast<std::size_t>(u.size()) != nu_) {
60 throw_pretty(
"Invalid argument: " 61 <<
"u has wrong dimension (it should be " + std::to_string(nu_) +
")");
64 data->tau.noalias() = tau_f_ * u;
67 virtual void calcDiff(
const boost::shared_ptr<Data>& ,
const Eigen::Ref<const VectorXs>& ,
68 const Eigen::Ref<const VectorXs>& ) {
72 boost::shared_ptr<Data> createData() {
73 boost::shared_ptr<Data> data = boost::allocate_shared<Data>(Eigen::aligned_allocator<Data>(),
this);
74 data->dtau_du = tau_f_;
78 const std::size_t& get_nrotors()
const {
return n_rotors_; };
79 const MatrixXs& get_tauf()
const {
return tau_f_; };
80 void set_tauf(
const Eigen::Ref<const MatrixXs>& tau_f) { tau_f_ = tau_f; }
85 std::size_t n_rotors_;
93 #endif // CROCODDYL_MULTIBODY_ACTUATIONS_MULTICOPTER_BASE_HPP_