Crocoddyl
frame-placement.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_PLACEMENT_HPP_
10 #define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_PLACEMENT_HPP_
11 
12 #include <pinocchio/multibody/fwd.hpp>
13 #include <pinocchio/spatial/se3.hpp>
14 
15 #include "crocoddyl/core/residual-base.hpp"
16 #include "crocoddyl/core/utils/exception.hpp"
17 #include "crocoddyl/multibody/data/multibody.hpp"
18 #include "crocoddyl/multibody/fwd.hpp"
19 #include "crocoddyl/multibody/states/multibody.hpp"
20 
21 namespace crocoddyl {
22 
38 template <typename _Scalar>
40  : public ResidualModelAbstractTpl<_Scalar> {
41  public:
42  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
43 
44  typedef _Scalar Scalar;
51  typedef typename MathBase::VectorXs VectorXs;
52  typedef pinocchio::SE3Tpl<Scalar> SE3;
53 
62  ResidualModelFramePlacementTpl(boost::shared_ptr<StateMultibody> state,
63  const pinocchio::FrameIndex id,
64  const SE3& pref, const std::size_t nu);
65 
75  ResidualModelFramePlacementTpl(boost::shared_ptr<StateMultibody> state,
76  const pinocchio::FrameIndex id,
77  const SE3& pref);
79 
87  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
88  const Eigen::Ref<const VectorXs>& x,
89  const Eigen::Ref<const VectorXs>& u);
90 
98  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
99  const Eigen::Ref<const VectorXs>& x,
100  const Eigen::Ref<const VectorXs>& u);
101 
105  virtual boost::shared_ptr<ResidualDataAbstract> createData(
106  DataCollectorAbstract* const data);
107 
111  pinocchio::FrameIndex get_id() const;
112 
116  const SE3& get_reference() const;
117 
121  void set_id(const pinocchio::FrameIndex id);
122 
126  void set_reference(const SE3& reference);
127 
133  virtual void print(std::ostream& os) const;
134 
135  protected:
136  using Base::nu_;
137  using Base::state_;
138  using Base::u_dependent_;
139  using Base::v_dependent_;
140 
141  private:
142  pinocchio::FrameIndex id_;
143  SE3 pref_;
144  pinocchio::SE3Tpl<Scalar> oMf_inv_;
145  boost::shared_ptr<typename StateMultibody::PinocchioModel>
146  pin_model_;
147 };
148 
149 template <typename _Scalar>
151  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
152 
153  typedef _Scalar Scalar;
157  typedef typename MathBase::Matrix6xs Matrix6xs;
158  typedef typename MathBase::Matrix6s Matrix6s;
159  typedef typename MathBase::Vector6s Vector6s;
160 
161  template <template <typename Scalar> class Model>
162  ResidualDataFramePlacementTpl(Model<Scalar>* const model,
163  DataCollectorAbstract* const data)
164  : Base(model, data), rJf(6, 6), fJf(6, model->get_state()->get_nv()) {
165  r.setZero();
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  pinocchio::SE3Tpl<Scalar> rMf;
183  Matrix6s 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-placement.hxx"
198 
199 #endif // CROCODDYL_MULTIBODY_RESIDUALS_FRAME_PLACEMENT_HPP_
Abstract class for residual models.
boost::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
ResidualModelFramePlacementTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const SE3 &pref, const std::size_t nu)
Initialize the frame placement residual model.
ResidualModelFramePlacementTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const SE3 &pref)
Initialize the frame placement residual model.
const SE3 & get_reference() const
Return the reference frame placement.
virtual void print(std::ostream &os) const
Print relevant information of the frame-placement residual.
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 placement residual.
pinocchio::FrameIndex get_id() const
Return the reference frame id.
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 placement residual.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the frame placement residual data.
void set_reference(const SE3 &reference)
Modify the reference frame placement.
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.
pinocchio::SE3Tpl< Scalar > rMf
Error frame placement of the frame.
Matrix6s 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.