9 #ifndef CROCODDYL_MULTIBODY_ACTUATIONS_MULTICOPTER_BASE_HPP_
10 #define CROCODDYL_MULTIBODY_ACTUATIONS_MULTICOPTER_BASE_HPP_
13 #include "crocoddyl/multibody/fwd.hpp"
14 #include "crocoddyl/core/utils/exception.hpp"
15 #include "crocoddyl/core/actuation-base.hpp"
16 #include "crocoddyl/multibody/states/multibody.hpp"
17 #include "crocoddyl/core/utils/deprecate.hpp"
38 template <
typename _Scalar>
41 typedef _Scalar Scalar;
46 typedef typename MathBase::VectorXs VectorXs;
47 typedef typename MathBase::MatrixXs MatrixXs;
48 typedef typename MathBase::Matrix6xs Matrix6xs;
57 :
Base(state, state->get_nv() - 6 + tau_f.cols()), n_rotors_(tau_f.cols()) {
58 pinocchio::JointModelFreeFlyerTpl<Scalar> ff_joint;
59 if (state->get_pinocchio()->joints[1].shortname() != ff_joint.shortname()) {
60 throw_pretty(
"Invalid argument: "
61 <<
"the first joint has to be free-flyer");
64 tau_f_ = MatrixXs::Zero(
state_->get_nv(),
nu_);
65 tau_f_.block(0, 0, 6, n_rotors_) = tau_f;
66 if (
nu_ > n_rotors_) {
67 tau_f_.bottomRightCorner(
nu_ - n_rotors_,
nu_ - n_rotors_).diagonal().setOnes();
71 DEPRECATED(
"Use constructor without n_rotors",
73 const Eigen::Ref<const Matrix6xs>& tau_f));
76 virtual void calc(
const boost::shared_ptr<Data>& data,
const Eigen::Ref<const VectorXs>&,
77 const Eigen::Ref<const VectorXs>& u) {
78 if (
static_cast<std::size_t
>(u.size()) !=
nu_) {
79 throw_pretty(
"Invalid argument: "
80 <<
"u has wrong dimension (it should be " + std::to_string(
nu_) +
")");
83 data->tau.noalias() = tau_f_ * u;
87 virtual void calcDiff(
const boost::shared_ptr<Data>& data,
const Eigen::Ref<const VectorXs>&,
88 const Eigen::Ref<const VectorXs>&) {
90 virtual void calcDiff(
const boost::shared_ptr<Data>&,
const Eigen::Ref<const VectorXs>&,
91 const Eigen::Ref<const VectorXs>&) {
94 assert_pretty(MatrixXs(data->dtau_du).isApprox(tau_f_),
"dtau_du has wrong value");
98 boost::shared_ptr<Data> data = boost::allocate_shared<Data>(Eigen::aligned_allocator<Data>(),
this);
99 data->dtau_du = tau_f_;
103 std::size_t get_nrotors()
const {
return n_rotors_; };
104 const MatrixXs& get_tauf()
const {
return tau_f_; };
105 void set_tauf(
const Eigen::Ref<const MatrixXs>& tau_f) { tau_f_ = tau_f; }
110 std::size_t n_rotors_;
116 template <
typename Scalar>
118 const std::size_t n_rotors,
119 const Eigen::Ref<const Matrix6xs>& tau_f)
120 : Base(state, state->get_nv() - 6 + n_rotors), n_rotors_(n_rotors) {
121 pinocchio::JointModelFreeFlyerTpl<Scalar> ff_joint;
122 if (state->get_pinocchio()->joints[1].shortname() != ff_joint.shortname()) {
123 throw_pretty(
"Invalid argument: "
124 <<
"the first joint has to be free-flyer");
127 tau_f_ = MatrixXs::Zero(
state_->get_nv(),
nu_);
128 tau_f_.block(0, 0, 6, n_rotors_) = tau_f;
129 if (
nu_ > n_rotors_) {
130 tau_f_.bottomRightCorner(
nu_ - n_rotors_,
nu_ - n_rotors_).diagonal().setOnes();
132 std::cerr <<
"Deprecated ActuationModelMultiCopterBase: Use constructor without n_rotors." << std::endl;
137 #endif // CROCODDYL_MULTIBODY_ACTUATIONS_MULTICOPTER_BASE_HPP_