crocoddyl  1.9.0
Contact RObot COntrol by Differential DYnamic programming Library (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/multibody/fwd.hpp"
16 #include "crocoddyl/core/residual-base.hpp"
17 #include "crocoddyl/multibody/states/multibody.hpp"
18 #include "crocoddyl/multibody/data/multibody.hpp"
19 #include "crocoddyl/core/utils/exception.hpp"
20 
21 namespace crocoddyl {
22 
36 template <typename _Scalar>
37 class ResidualModelFramePlacementTpl : public ResidualModelAbstractTpl<_Scalar> {
38  public:
39  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
40 
41  typedef _Scalar Scalar;
42  typedef MathBaseTpl<Scalar> MathBase;
43  typedef ResidualModelAbstractTpl<Scalar> Base;
44  typedef ResidualDataFramePlacementTpl<Scalar> Data;
45  typedef StateMultibodyTpl<Scalar> StateMultibody;
46  typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
47  typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
48  typedef typename MathBase::VectorXs VectorXs;
49  typedef pinocchio::SE3Tpl<Scalar> SE3;
50 
59  ResidualModelFramePlacementTpl(boost::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id,
60  const SE3& pref, const std::size_t nu);
61 
71  ResidualModelFramePlacementTpl(boost::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id,
72  const SE3& pref);
74 
82  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data, const Eigen::Ref<const VectorXs>& x,
83  const Eigen::Ref<const VectorXs>& u);
84 
92  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data, const Eigen::Ref<const VectorXs>& x,
93  const Eigen::Ref<const VectorXs>& u);
94 
98  virtual boost::shared_ptr<ResidualDataAbstract> createData(DataCollectorAbstract* const data);
99 
103  pinocchio::FrameIndex get_id() const;
104 
108  const SE3& get_reference() const;
109 
113  void set_id(const pinocchio::FrameIndex id);
114 
118  void set_reference(const SE3& reference);
119 
125  virtual void print(std::ostream& os) const;
126 
127  protected:
128  using Base::nu_;
129  using Base::state_;
130  using Base::u_dependent_;
131  using Base::unone_;
132  using Base::v_dependent_;
133 
134  private:
135  pinocchio::FrameIndex id_;
136  SE3 pref_;
137  pinocchio::SE3Tpl<Scalar> oMf_inv_;
138  boost::shared_ptr<typename StateMultibody::PinocchioModel> pin_model_;
139 };
140 
141 template <typename _Scalar>
142 struct ResidualDataFramePlacementTpl : public ResidualDataAbstractTpl<_Scalar> {
143  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
144 
145  typedef _Scalar Scalar;
146  typedef MathBaseTpl<Scalar> MathBase;
147  typedef ResidualDataAbstractTpl<Scalar> Base;
148  typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
149  typedef typename MathBase::Matrix6xs Matrix6xs;
150  typedef typename MathBase::Matrix6s Matrix6s;
151  typedef typename MathBase::Vector6s Vector6s;
152 
153  template <template <typename Scalar> class Model>
154  ResidualDataFramePlacementTpl(Model<Scalar>* const model, DataCollectorAbstract* const data)
155  : Base(model, data), rJf(6, 6), fJf(6, model->get_state()->get_nv()) {
156  r.setZero();
157  rJf.setZero();
158  fJf.setZero();
159  // Check that proper shared data has been passed
160  DataCollectorMultibodyTpl<Scalar>* d = dynamic_cast<DataCollectorMultibodyTpl<Scalar>*>(shared);
161  if (d == NULL) {
162  throw_pretty("Invalid argument: the shared data should be derived from DataCollectorMultibody");
163  }
164 
165  // Avoids data casting at runtime
166  pinocchio = d->pinocchio;
167  }
168 
169  pinocchio::DataTpl<Scalar>* pinocchio;
170  pinocchio::SE3Tpl<Scalar> rMf;
171  Matrix6s rJf;
172  Matrix6xs fJf;
173 
174  using Base::r;
175  using Base::Ru;
176  using Base::Rx;
177  using Base::shared;
178 };
179 
180 } // namespace crocoddyl
181 
182 /* --- Details -------------------------------------------------------------- */
183 /* --- Details -------------------------------------------------------------- */
184 /* --- Details -------------------------------------------------------------- */
185 #include "crocoddyl/multibody/residuals/frame-placement.hxx"
186 
187 #endif // CROCODDYL_MULTIBODY_RESIDUALS_FRAME_PLACEMENT_HPP_
crocoddyl::ResidualModelFramePlacementTpl::set_reference
void set_reference(const SE3 &reference)
Modify the reference frame placement.
crocoddyl::ResidualModelFramePlacementTpl::ResidualModelFramePlacementTpl
ResidualModelFramePlacementTpl(boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const SE3 &pref, const std::size_t nu)
Initialize the frame placement residual model.
crocoddyl::ResidualModelAbstractTpl::state_
boost::shared_ptr< StateAbstract > state_
State description.
Definition: residual-base.hpp:179
crocoddyl::ResidualModelFramePlacementTpl::print
virtual void print(std::ostream &os) const
Print relevant information of the frame-placement residual.
crocoddyl::ResidualModelFramePlacementTpl::get_id
pinocchio::FrameIndex get_id() const
Return the reference frame id.
crocoddyl::ResidualDataFramePlacementTpl::pinocchio
pinocchio::DataTpl< Scalar > * pinocchio
Pinocchio data.
Definition: frame-placement.hpp:169
crocoddyl::ResidualModelFramePlacementTpl::createData
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the frame placement residual data.
crocoddyl::ResidualDataFramePlacementTpl::rMf
pinocchio::SE3Tpl< Scalar > rMf
Error frame placement of the frame.
Definition: frame-placement.hpp:170
crocoddyl::ResidualDataFramePlacementTpl::r
VectorXs r
Residual vector.
Definition: residual-base.hpp:211
crocoddyl::ResidualModelAbstractTpl::v_dependent_
bool v_dependent_
Label that indicates if the residual function depends on v.
Definition: residual-base.hpp:184
crocoddyl::ResidualDataFramePlacementTpl::fJf
Matrix6xs fJf
Local Jacobian of the frame.
Definition: frame-placement.hpp:172
crocoddyl::ResidualDataFramePlacementTpl::rJf
Matrix6s rJf
Error Jacobian of the frame.
Definition: frame-placement.hpp:171
crocoddyl::ResidualModelAbstractTpl::unone_
VectorXs unone_
No control vector.
Definition: residual-base.hpp:182
crocoddyl::ResidualDataAbstractTpl::Ru
MatrixXs Ru
Jacobian of the residual vector with respect the control.
Definition: residual-base.hpp:213
crocoddyl::ResidualDataAbstractTpl::Rx
MatrixXs Rx
Jacobian of the residual vector with respect the state.
Definition: residual-base.hpp:212
crocoddyl::ResidualDataFramePlacementTpl::shared
DataCollectorAbstract * shared
Shared data allocated by the action model.
Definition: residual-base.hpp:210
crocoddyl::ResidualDataAbstractTpl::shared
DataCollectorAbstract * shared
Shared data allocated by the action model.
Definition: residual-base.hpp:210
crocoddyl::ResidualModelFramePlacementTpl::calcDiff
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.
crocoddyl::ResidualModelFramePlacementTpl::get_reference
const SE3 & get_reference() const
Return the reference frame placement.
crocoddyl::ResidualDataAbstractTpl::r
VectorXs r
Residual vector.
Definition: residual-base.hpp:211
crocoddyl::ResidualModelFramePlacementTpl::calc
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.
crocoddyl::ResidualModelAbstractTpl::u_dependent_
bool u_dependent_
Label that indicates if the residual function depends on u.
Definition: residual-base.hpp:185
crocoddyl::ResidualModelFramePlacementTpl::set_id
void set_id(const pinocchio::FrameIndex id)
Modify the reference frame id.
crocoddyl::ResidualModelAbstractTpl::nu_
std::size_t nu_
Control dimension.
Definition: residual-base.hpp:181