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 
61  ResidualModelJointEffortTpl(std::shared_ptr<StateAbstract> state,
62  std::shared_ptr<ActuationModelAbstract> actuation,
63  const VectorXs& uref, const std::size_t nu,
64  const bool fwddyn = false);
65 
75  ResidualModelJointEffortTpl(std::shared_ptr<StateAbstract> state,
76  std::shared_ptr<ActuationModelAbstract> actuation,
77  const VectorXs& uref);
78 
89  ResidualModelJointEffortTpl(std::shared_ptr<StateAbstract> state,
90  std::shared_ptr<ActuationModelAbstract> actuation,
91  const std::size_t nu);
92 
104  std::shared_ptr<StateAbstract> state,
105  std::shared_ptr<ActuationModelAbstract> actuation);
106 
107  virtual ~ResidualModelJointEffortTpl();
108 
116  virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
117  const Eigen::Ref<const VectorXs>& x,
118  const Eigen::Ref<const VectorXs>& u);
119 
124  virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
125  const Eigen::Ref<const VectorXs>& x);
126 
134  virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
135  const Eigen::Ref<const VectorXs>& x,
136  const Eigen::Ref<const VectorXs>& u);
137 
143  virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
144  const Eigen::Ref<const VectorXs>& x);
145 
149  virtual std::shared_ptr<ResidualDataAbstract> createData(
150  DataCollectorAbstract* const data);
151 
155  const VectorXs& get_reference() const;
156 
160  void set_reference(const VectorXs& reference);
161 
167  virtual void print(std::ostream& os) const;
168 
169  protected:
170  using Base::nr_;
171  using Base::nu_;
172  using Base::q_dependent_;
173  using Base::state_;
174  using Base::v_dependent_;
175 
176  private:
177  VectorXs uref_;
178  bool fwddyn_;
179 };
180 
181 template <typename _Scalar>
183  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
184 
185  typedef _Scalar Scalar;
189 
190  template <template <typename Scalar> class Model>
191  ResidualDataJointEffortTpl(Model<Scalar>* const model,
192  DataCollectorAbstract* const data)
193  : Base(model, data) {
194  // Check that proper shared data has been passed
196  dynamic_cast<DataCollectorJointTpl<Scalar>*>(shared);
197  if (d == nullptr) {
198  throw_pretty(
199  "Invalid argument: the shared data should be derived from "
200  "DataCollectorJoint");
201  }
202  joint = d->joint;
203  }
204 
205  std::shared_ptr<JointDataAbstractTpl<Scalar> > joint;
206  using Base::r;
207  using Base::Ru;
208  using Base::Rx;
209  using Base::shared;
210 };
211 
212 } // namespace crocoddyl
213 
214 /* --- Details -------------------------------------------------------------- */
215 /* --- Details -------------------------------------------------------------- */
216 /* --- Details -------------------------------------------------------------- */
217 #include "crocoddyl/core/residuals/joint-effort.hxx"
218 
219 #endif // CROCODDYL_CORE_RESIDUALS_JOINT_TORQUE_HPP_
Abstract class for the actuation-mapping model.
Abstract class for residual models.
std::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
std::size_t nr_
Residual vector dimension.
Define a joint-effort residual.
virtual void calcDiff(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the derivatives of the joint-effort residual.
ResidualModelJointEffortTpl(std::shared_ptr< StateAbstract > state, std::shared_ptr< ActuationModelAbstract > actuation, const VectorXs &uref)
Initialize the joint-effort residual model.
virtual void print(std::ostream &os) const
Print relevant information of the joint-effort residual.
virtual void calcDiff(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
ResidualModelJointEffortTpl(std::shared_ptr< StateAbstract > state, std::shared_ptr< ActuationModelAbstract > actuation)
Initialize the joint-effort residual model.
virtual void calc(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the joint-effort residual.
virtual void calc(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
void set_reference(const VectorXs &reference)
Modify the reference joint-effort vector.
virtual std::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the joint-effort residual data.
const VectorXs & get_reference() const
Return the reference joint-effort vector.
ResidualModelJointEffortTpl(std::shared_ptr< StateAbstract > state, std::shared_ptr< ActuationModelAbstract > actuation, const std::size_t nu)
Initialize the joint-effort residual model.
ResidualModelJointEffortTpl(std::shared_ptr< StateAbstract > state, std::shared_ptr< ActuationModelAbstract > actuation, const VectorXs &uref, const std::size_t nu, const bool fwddyn=false)
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.
std::shared_ptr< JointDataAbstractTpl< Scalar > > joint
Joint data.
DataCollectorAbstract * shared
Shared data allocated by the action model.