crocoddyl  1.9.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
multicopter-base.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-2021, LAAS-CNRS, IRI: CSIC-UPC, University of Edinburgh
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
8 
9 #ifndef CROCODDYL_MULTIBODY_ACTUATIONS_MULTICOPTER_BASE_HPP_
10 #define CROCODDYL_MULTIBODY_ACTUATIONS_MULTICOPTER_BASE_HPP_
11 
12 #include <iostream>
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"
18 
19 namespace crocoddyl {
20 
38 template <typename _Scalar>
40  public:
41  typedef _Scalar Scalar;
46  typedef typename MathBase::VectorXs VectorXs;
47  typedef typename MathBase::MatrixXs MatrixXs;
48  typedef typename MathBase::Matrix6xs Matrix6xs;
49 
56  ActuationModelMultiCopterBaseTpl(boost::shared_ptr<StateMultibody> state, const Eigen::Ref<const Matrix6xs>& tau_f)
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");
62  }
63 
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();
68  }
69  }
70 
71  DEPRECATED("Use constructor without n_rotors",
72  ActuationModelMultiCopterBaseTpl(boost::shared_ptr<StateMultibody> state, const std::size_t n_rotors,
73  const Eigen::Ref<const Matrix6xs>& tau_f));
75 
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_) + ")");
81  }
82 
83  data->tau.noalias() = tau_f_ * u;
84  }
85 
86 #ifndef NDEBUG
87  virtual void calcDiff(const boost::shared_ptr<Data>& data, const Eigen::Ref<const VectorXs>&,
88  const Eigen::Ref<const VectorXs>&) {
89 #else
90  virtual void calcDiff(const boost::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&,
91  const Eigen::Ref<const VectorXs>&) {
92 #endif
93  // The derivatives has constant values which were set in createData.
94  assert_pretty(MatrixXs(data->dtau_du).isApprox(tau_f_), "dtau_du has wrong value");
95  }
96 
97  boost::shared_ptr<Data> createData() {
98  boost::shared_ptr<Data> data = boost::allocate_shared<Data>(Eigen::aligned_allocator<Data>(), this);
99  data->dtau_du = tau_f_;
100  return data;
101  }
102 
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; }
106 
107  protected:
108  // Specific of multicopter
109  MatrixXs tau_f_; // Matrix from rotors thrust to body force/moments
110  std::size_t n_rotors_;
111 
112  using Base::nu_;
113  using Base::state_;
114 };
115 
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");
125  }
126 
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();
131  }
132  std::cerr << "Deprecated ActuationModelMultiCopterBase: Use constructor without n_rotors." << std::endl;
133 }
134 
135 } // namespace crocoddyl
136 
137 #endif // CROCODDYL_MULTIBODY_ACTUATIONS_MULTICOPTER_BASE_HPP_
crocoddyl::ActuationModelAbstractTpl
Abstract class for the actuation-mapping model.
Definition: actuation-base.hpp:39
crocoddyl::MathBaseTpl< Scalar >
crocoddyl::ActuationModelMultiCopterBaseTpl
Multicopter actuation model.
Definition: multicopter-base.hpp:39
crocoddyl::ActuationModelMultiCopterBaseTpl::calc
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 and control input .
Definition: multicopter-base.hpp:76
crocoddyl::ActuationModelAbstractTpl::nu_
std::size_t nu_
Control dimension.
Definition: actuation-base.hpp:133
crocoddyl::StateMultibodyTpl
State multibody representation.
Definition: fwd.hpp:305
crocoddyl::ActuationModelAbstractTpl::state_
boost::shared_ptr< StateAbstract > state_
Model of the state.
Definition: actuation-base.hpp:134
crocoddyl::ActuationModelMultiCopterBaseTpl::calcDiff
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.
Definition: multicopter-base.hpp:87
crocoddyl::ActuationDataAbstractTpl
Definition: actuation-base.hpp:138
crocoddyl::ActuationModelMultiCopterBaseTpl::ActuationModelMultiCopterBaseTpl
ActuationModelMultiCopterBaseTpl(boost::shared_ptr< StateMultibody > state, const Eigen::Ref< const Matrix6xs > &tau_f)
Initialize the multicopter actuation model.
Definition: multicopter-base.hpp:56
crocoddyl::ActuationModelMultiCopterBaseTpl::createData
boost::shared_ptr< Data > createData()
Create the actuation data.
Definition: multicopter-base.hpp:97