Crocoddyl
frame-rotation.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2021, LAAS-CNRS, University of Edinburgh
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
8 
9 #ifndef CROCODDYL_MULTIBODY_RESIDUALS_FRAME_ROTATION_HPP_
10 #define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_ROTATION_HPP_
11 
12 #include <pinocchio/multibody/fwd.hpp>
13 
14 #include "crocoddyl/core/residual-base.hpp"
15 #include "crocoddyl/core/utils/exception.hpp"
16 #include "crocoddyl/multibody/data/multibody.hpp"
17 #include "crocoddyl/multibody/fwd.hpp"
18 #include "crocoddyl/multibody/states/multibody.hpp"
19 
20 namespace crocoddyl {
21 
37 template <typename _Scalar>
39  public:
40  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
41 
42  typedef _Scalar Scalar;
49  typedef typename MathBase::VectorXs VectorXs;
50  typedef typename MathBase::Matrix3s Matrix3s;
51 
60  ResidualModelFrameRotationTpl(boost::shared_ptr<StateMultibody> state,
61  const pinocchio::FrameIndex id,
62  const Matrix3s& Rref, const std::size_t nu);
63 
73  ResidualModelFrameRotationTpl(boost::shared_ptr<StateMultibody> state,
74  const pinocchio::FrameIndex id,
75  const Matrix3s& Rref);
77 
85  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
86  const Eigen::Ref<const VectorXs>& x,
87  const Eigen::Ref<const VectorXs>& u);
88 
96  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
97  const Eigen::Ref<const VectorXs>& x,
98  const Eigen::Ref<const VectorXs>& u);
99 
103  virtual boost::shared_ptr<ResidualDataAbstract> createData(
104  DataCollectorAbstract* const data);
105 
109  pinocchio::FrameIndex get_id() const;
110 
114  const Matrix3s& get_reference() const;
115 
119  void set_id(const pinocchio::FrameIndex id);
120 
124  void set_reference(const Matrix3s& reference);
125 
131  virtual void print(std::ostream& os) const;
132 
133  protected:
134  using Base::nu_;
135  using Base::state_;
136  using Base::u_dependent_;
137  using Base::v_dependent_;
138 
139  private:
140  pinocchio::FrameIndex id_;
141  Matrix3s Rref_;
142  Matrix3s oRf_inv_;
143  boost::shared_ptr<typename StateMultibody::PinocchioModel>
144  pin_model_;
145 };
146 
147 template <typename _Scalar>
149  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
150 
151  typedef _Scalar Scalar;
155  typedef typename MathBase::Vector3s Vector3s;
156  typedef typename MathBase::Matrix3s Matrix3s;
157  typedef typename MathBase::Matrix3xs Matrix3xs;
158  typedef typename MathBase::Matrix6xs Matrix6xs;
159 
160  template <template <typename Scalar> class Model>
161  ResidualDataFrameRotationTpl(Model<Scalar>* const model,
162  DataCollectorAbstract* const data)
163  : Base(model, data), rJf(3, 3), fJf(6, model->get_state()->get_nv()) {
164  r.setZero();
165  rRf.setIdentity();
166  rJf.setZero();
167  fJf.setZero();
168  // Check that proper shared data has been passed
171  if (d == NULL) {
172  throw_pretty(
173  "Invalid argument: the shared data should be derived from "
174  "DataCollectorMultibody");
175  }
176 
177  // Avoids data casting at runtime
178  pinocchio = d->pinocchio;
179  }
180 
181  pinocchio::DataTpl<Scalar>* pinocchio;
182  Matrix3s rRf;
183  Matrix3s rJf;
184  Matrix6xs fJf;
185 
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/multibody/residuals/frame-rotation.hxx"
198 
199 #endif // CROCODDYL_MULTIBODY_RESIDUALS_FRAME_ROTATION_HPP_
Abstract class for residual models.
boost::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
virtual void print(std::ostream &os) const
Print relevant information of the frame-rotation residual.
void set_reference(const Matrix3s &reference)
Modify the reference frame rotation.
ResidualModelFrameRotationTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Matrix3s &Rref)
Initialize the frame rotation residual model.
void set_id(const pinocchio::FrameIndex id)
Modify the reference frame id.
virtual void calc(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the frame rotation residual.
pinocchio::FrameIndex get_id() const
Return the reference frame id.
ResidualModelFrameRotationTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Matrix3s &Rref, const std::size_t nu)
Initialize the frame rotation residual model.
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 frame rotation residual.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the frame rotation residual data.
const Matrix3s & get_reference() const
Return the reference frame rotation.
State multibody representation.
Definition: multibody.hpp:35
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.
Matrix3s rRf
Rotation error of the frame.
Matrix3s rJf
Error Jacobian of the frame.
Matrix6xs fJf
Local Jacobian of the frame.
DataCollectorAbstract * shared
Shared data allocated by the action model.
pinocchio::DataTpl< Scalar > * pinocchio
Pinocchio data.