Crocoddyl
joint-acceleration.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2022-2023, Heriot-Watt University
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
8 
9 #ifndef CROCODDYL_CORE_RESIDUALS_JOINT_ACCELERATION_HPP_
10 #define CROCODDYL_CORE_RESIDUALS_JOINT_ACCELERATION_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 
36 template <typename _Scalar>
38  : public ResidualModelAbstractTpl<_Scalar> {
39  public:
40  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
41 
42  typedef _Scalar Scalar;
50  typedef typename MathBase::VectorXs VectorXs;
51  typedef typename MathBase::MatrixXs MatrixXs;
52 
60  ResidualModelJointAccelerationTpl(boost::shared_ptr<StateAbstract> state,
61  const VectorXs& aref, const std::size_t nu);
62 
71  ResidualModelJointAccelerationTpl(boost::shared_ptr<StateAbstract> state,
72  const VectorXs& aref);
73 
83  ResidualModelJointAccelerationTpl(boost::shared_ptr<StateAbstract> state,
84  const std::size_t nu);
85 
95  ResidualModelJointAccelerationTpl(boost::shared_ptr<StateAbstract> state);
96 
98 
106  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
107  const Eigen::Ref<const VectorXs>& x,
108  const Eigen::Ref<const VectorXs>& u);
109 
114  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
115  const Eigen::Ref<const VectorXs>& x);
116 
124  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
125  const Eigen::Ref<const VectorXs>& x,
126  const Eigen::Ref<const VectorXs>& u);
127 
131  virtual boost::shared_ptr<ResidualDataAbstract> createData(
132  DataCollectorAbstract* const data);
133 
137  const VectorXs& get_reference() const;
138 
142  void set_reference(const VectorXs& reference);
143 
149  virtual void print(std::ostream& os) const;
150 
151  protected:
152  using Base::nr_;
153  using Base::nu_;
154  using Base::state_;
155 
156  private:
157  VectorXs aref_;
158 };
159 
160 template <typename _Scalar>
162  : public ResidualDataAbstractTpl<_Scalar> {
163  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
164 
165  typedef _Scalar Scalar;
169 
170  template <template <typename Scalar> class Model>
171  ResidualDataJointAccelerationTpl(Model<Scalar>* const model,
172  DataCollectorAbstract* const data)
173  : Base(model, data) {
174  // Check that proper shared data has been passed
176  dynamic_cast<DataCollectorJointTpl<Scalar>*>(shared);
177  if (d == nullptr) {
178  throw_pretty(
179  "Invalid argument: the shared data should be derived from "
180  "DataCollectorJoint");
181  }
182  joint = d->joint;
183  }
184 
185  boost::shared_ptr<JointDataAbstractTpl<Scalar> > joint;
186  using Base::r;
187  using Base::Ru;
188  using Base::Rx;
189  using Base::shared;
190 };
191 
192 } // namespace crocoddyl
193 
194 /* --- Details -------------------------------------------------------------- */
195 /* --- Details -------------------------------------------------------------- */
196 /* --- Details -------------------------------------------------------------- */
197 #include "crocoddyl/core/residuals/joint-acceleration.hxx"
198 
199 #endif // CROCODDYL_CORE_RESIDUALS_JOINT_ACCELERATION_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-acceleration residual.
ResidualModelJointAccelerationTpl(boost::shared_ptr< StateAbstract > state, const VectorXs &aref)
Initialize the joint-acceleration residual model.
virtual void calc(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
ResidualModelJointAccelerationTpl(boost::shared_ptr< StateAbstract > state, const std::size_t nu)
Initialize the joint-acceleration residual model.
virtual void print(std::ostream &os) const
Print relevant information of the joint-acceleration residual.
ResidualModelJointAccelerationTpl(boost::shared_ptr< StateAbstract > state, const VectorXs &aref, const std::size_t nu)
Initialize the joint-acceleration 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-acceleration residual.
void set_reference(const VectorXs &reference)
Modify the reference joint-acceleration 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-acceleration residual.
const VectorXs & get_reference() const
Return the reference joint-acceleration vector.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the joint-acceleration residual data.
ResidualModelJointAccelerationTpl(boost::shared_ptr< StateAbstract > state)
Initialize the joint-acceleration 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.