Crocoddyl
joint-effort.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2022-2023, Heriot-Watt University, University of Edinburgh
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
8 
9 #ifndef CROCODDYL_CORE_RESIDUALS_JOINT_TORQUE_HPP_
10 #define CROCODDYL_CORE_RESIDUALS_JOINT_TORQUE_HPP_
11 
12 #include "crocoddyl/core/actuation-base.hpp"
13 #include "crocoddyl/core/data/joint.hpp"
14 #include "crocoddyl/core/fwd.hpp"
15 #include "crocoddyl/core/residual-base.hpp"
16 
17 namespace crocoddyl {
18 
35 template <typename _Scalar>
37  public:
38  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
39 
40  typedef _Scalar Scalar;
48  typedef typename MathBase::VectorXs VectorXs;
49  typedef typename MathBase::MatrixXs MatrixXs;
50 
62  boost::shared_ptr<StateAbstract> state,
63  boost::shared_ptr<ActuationModelAbstract> actuation, const VectorXs& uref,
64  const std::size_t nu, const bool fwddyn = false);
65 
76  boost::shared_ptr<StateAbstract> state,
77  boost::shared_ptr<ActuationModelAbstract> actuation,
78  const VectorXs& uref);
79 
91  boost::shared_ptr<StateAbstract> state,
92  boost::shared_ptr<ActuationModelAbstract> actuation,
93  const std::size_t nu);
94 
106  boost::shared_ptr<StateAbstract> state,
107  boost::shared_ptr<ActuationModelAbstract> actuation);
108 
109  virtual ~ResidualModelJointEffortTpl();
110 
118  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
119  const Eigen::Ref<const VectorXs>& x,
120  const Eigen::Ref<const VectorXs>& u);
121 
126  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
127  const Eigen::Ref<const VectorXs>& x);
128 
136  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
137  const Eigen::Ref<const VectorXs>& x,
138  const Eigen::Ref<const VectorXs>& u);
139 
145  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
146  const Eigen::Ref<const VectorXs>& x);
147 
151  virtual boost::shared_ptr<ResidualDataAbstract> createData(
152  DataCollectorAbstract* const data);
153 
157  const VectorXs& get_reference() const;
158 
162  void set_reference(const VectorXs& reference);
163 
169  virtual void print(std::ostream& os) const;
170 
171  protected:
172  using Base::nr_;
173  using Base::nu_;
174  using Base::q_dependent_;
175  using Base::state_;
176  using Base::v_dependent_;
177 
178  private:
179  VectorXs uref_;
180  bool fwddyn_;
181 };
182 
183 template <typename _Scalar>
185  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
186 
187  typedef _Scalar Scalar;
191 
192  template <template <typename Scalar> class Model>
193  ResidualDataJointEffortTpl(Model<Scalar>* const model,
194  DataCollectorAbstract* const data)
195  : Base(model, data) {
196  // Check that proper shared data has been passed
198  dynamic_cast<DataCollectorJointTpl<Scalar>*>(shared);
199  if (d == nullptr) {
200  throw_pretty(
201  "Invalid argument: the shared data should be derived from "
202  "DataCollectorJoint");
203  }
204  joint = d->joint;
205  }
206 
207  boost::shared_ptr<JointDataAbstractTpl<Scalar> > joint;
208  using Base::r;
209  using Base::Ru;
210  using Base::Rx;
211  using Base::shared;
212 };
213 
214 } // namespace crocoddyl
215 
216 /* --- Details -------------------------------------------------------------- */
217 /* --- Details -------------------------------------------------------------- */
218 /* --- Details -------------------------------------------------------------- */
219 #include "crocoddyl/core/residuals/joint-effort.hxx"
220 
221 #endif // CROCODDYL_CORE_RESIDUALS_JOINT_TORQUE_HPP_
Abstract class for the actuation-mapping model.
Abstract class for residual models.
boost::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
std::size_t nr_
Residual vector dimension.
Define a joint-effort residual.
ResidualModelJointEffortTpl(boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ActuationModelAbstract > actuation, const VectorXs &uref, const std::size_t nu, const bool fwddyn=false)
Initialize the joint-effort residual model.
virtual void calc(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
virtual void calcDiff(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
virtual void print(std::ostream &os) const
Print relevant information of the joint-effort residual.
ResidualModelJointEffortTpl(boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ActuationModelAbstract > actuation, const VectorXs &uref)
Initialize the joint-effort residual model.
virtual void calc(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the joint-effort residual.
ResidualModelJointEffortTpl(boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ActuationModelAbstract > actuation)
Initialize the joint-effort residual model.
void set_reference(const VectorXs &reference)
Modify the reference joint-effort vector.
virtual void calcDiff(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the derivatives of the joint-effort residual.
const VectorXs & get_reference() const
Return the reference joint-effort vector.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the joint-effort residual data.
ResidualModelJointEffortTpl(boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ActuationModelAbstract > actuation, const std::size_t nu)
Initialize the joint-effort residual model.
Abstract class for the state representation.
Definition: state-base.hpp:46
MatrixXs Ru
Jacobian of the residual vector with respect the control.
MatrixXs Rx
Jacobian of the residual vector with respect the state.
DataCollectorAbstract * shared
Shared data allocated by the action model.
DataCollectorAbstract * shared
Shared data allocated by the action model.
boost::shared_ptr< JointDataAbstractTpl< Scalar > > joint
Joint data.