Directory: | ./ |
---|---|
File: | include/crocoddyl/multibody/residuals/frame-placement.hpp |
Date: | 2025-01-16 08:47:40 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 10 | 11 | 90.9% |
Branches: | 8 | 24 | 33.3% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | /////////////////////////////////////////////////////////////////////////////// | ||
2 | // 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. | ||
7 | /////////////////////////////////////////////////////////////////////////////// | ||
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 | |||
23 | /** | ||
24 | * @brief Frame placement residual | ||
25 | * | ||
26 | * This residual function defines the frame placement tracking as | ||
27 | * \f$\mathbf{r}=\mathbf{p}\ominus\mathbf{p}^*\f$, where | ||
28 | * \f$\mathbf{p},\mathbf{p}^*\in~\mathbb{SE(3)}\f$ are the current and reference | ||
29 | * frame placements, respectively. Note that the dimension of the residual | ||
30 | * vector is 6. Furthermore, the Jacobians of the residual function are computed | ||
31 | * analytically. | ||
32 | * | ||
33 | * As described in `ResidualModelAbstractTpl()`, the residual value and its | ||
34 | * Jacobians are calculated by `calc` and `calcDiff`, respectively. | ||
35 | * | ||
36 | * \sa `ResidualModelAbstractTpl`, `calc()`, `calcDiff()`, `createData()` | ||
37 | */ | ||
38 | template <typename _Scalar> | ||
39 | class ResidualModelFramePlacementTpl | ||
40 | : public ResidualModelAbstractTpl<_Scalar> { | ||
41 | public: | ||
42 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ||
43 | |||
44 | typedef _Scalar Scalar; | ||
45 | typedef MathBaseTpl<Scalar> MathBase; | ||
46 | typedef ResidualModelAbstractTpl<Scalar> Base; | ||
47 | typedef ResidualDataFramePlacementTpl<Scalar> Data; | ||
48 | typedef StateMultibodyTpl<Scalar> StateMultibody; | ||
49 | typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract; | ||
50 | typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract; | ||
51 | typedef typename MathBase::VectorXs VectorXs; | ||
52 | typedef pinocchio::SE3Tpl<Scalar> SE3; | ||
53 | |||
54 | /** | ||
55 | * @brief Initialize the frame placement residual model | ||
56 | * | ||
57 | * @param[in] state State of the multibody system | ||
58 | * @param[in] id Reference frame id | ||
59 | * @param[in] pref Reference frame placement | ||
60 | * @param[in] nu Dimension of the control vector | ||
61 | */ | ||
62 | ResidualModelFramePlacementTpl(boost::shared_ptr<StateMultibody> state, | ||
63 | const pinocchio::FrameIndex id, | ||
64 | const SE3& pref, const std::size_t nu); | ||
65 | |||
66 | /** | ||
67 | * @brief Initialize the frame placement residual model | ||
68 | * | ||
69 | * The default `nu` is obtained from `StateAbstractTpl::get_nv()`. | ||
70 | * | ||
71 | * @param[in] state State of the multibody system | ||
72 | * @param[in] id Reference frame id | ||
73 | * @param[in] pref Reference frame placement | ||
74 | */ | ||
75 | ResidualModelFramePlacementTpl(boost::shared_ptr<StateMultibody> state, | ||
76 | const pinocchio::FrameIndex id, | ||
77 | const SE3& pref); | ||
78 | virtual ~ResidualModelFramePlacementTpl(); | ||
79 | |||
80 | /** | ||
81 | * @brief Compute the frame placement residual | ||
82 | * | ||
83 | * @param[in] data Frame placement residual data | ||
84 | * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ | ||
85 | * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$ | ||
86 | */ | ||
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 | |||
91 | /** | ||
92 | * @brief Compute the derivatives of the frame placement residual | ||
93 | * | ||
94 | * @param[in] data Frame-placement residual data | ||
95 | * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ | ||
96 | * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$ | ||
97 | */ | ||
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 | |||
102 | /** | ||
103 | * @brief Create the frame placement residual data | ||
104 | */ | ||
105 | virtual boost::shared_ptr<ResidualDataAbstract> createData( | ||
106 | DataCollectorAbstract* const data); | ||
107 | |||
108 | /** | ||
109 | * @brief Return the reference frame id | ||
110 | */ | ||
111 | pinocchio::FrameIndex get_id() const; | ||
112 | |||
113 | /** | ||
114 | * @brief Return the reference frame placement | ||
115 | */ | ||
116 | const SE3& get_reference() const; | ||
117 | |||
118 | /** | ||
119 | * @brief Modify the reference frame id | ||
120 | */ | ||
121 | void set_id(const pinocchio::FrameIndex id); | ||
122 | |||
123 | /** | ||
124 | * @brief Modify the reference frame placement | ||
125 | */ | ||
126 | void set_reference(const SE3& reference); | ||
127 | |||
128 | /** | ||
129 | * @brief Print relevant information of the frame-placement residual | ||
130 | * | ||
131 | * @param[out] os Output stream object | ||
132 | */ | ||
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_; //!< Reference frame id | ||
143 | SE3 pref_; //!< Reference frame placement | ||
144 | pinocchio::SE3Tpl<Scalar> oMf_inv_; //!< Inverse reference placement | ||
145 | boost::shared_ptr<typename StateMultibody::PinocchioModel> | ||
146 | pin_model_; //!< Pinocchio model | ||
147 | }; | ||
148 | |||
149 | template <typename _Scalar> | ||
150 | struct ResidualDataFramePlacementTpl : public ResidualDataAbstractTpl<_Scalar> { | ||
151 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ||
152 | |||
153 | typedef _Scalar Scalar; | ||
154 | typedef MathBaseTpl<Scalar> MathBase; | ||
155 | typedef ResidualDataAbstractTpl<Scalar> Base; | ||
156 | typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract; | ||
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 | 46652 | ResidualDataFramePlacementTpl(Model<Scalar>* const model, | |
163 | DataCollectorAbstract* const data) | ||
164 |
3/6✓ Branch 2 taken 46652 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 46652 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 46652 times.
✗ Branch 12 not taken.
|
46652 | : Base(model, data), rJf(6, 6), fJf(6, model->get_state()->get_nv()) { |
165 |
1/2✓ Branch 1 taken 46652 times.
✗ Branch 2 not taken.
|
46652 | r.setZero(); |
166 |
1/2✓ Branch 1 taken 46652 times.
✗ Branch 2 not taken.
|
46652 | rJf.setZero(); |
167 |
1/2✓ Branch 1 taken 46652 times.
✗ Branch 2 not taken.
|
46652 | fJf.setZero(); |
168 | // Check that proper shared data has been passed | ||
169 | 46652 | DataCollectorMultibodyTpl<Scalar>* d = | |
170 |
1/2✓ Branch 0 taken 46652 times.
✗ Branch 1 not taken.
|
46652 | dynamic_cast<DataCollectorMultibodyTpl<Scalar>*>(shared); |
171 |
1/2✗ Branch 0 not taken.
✓ Branch 1 taken 46652 times.
|
46652 | 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 | 46652 | pinocchio = d->pinocchio; | |
179 | 46652 | } | |
180 | |||
181 | pinocchio::DataTpl<Scalar>* pinocchio; //!< Pinocchio data | ||
182 | pinocchio::SE3Tpl<Scalar> rMf; //!< Error frame placement of the frame | ||
183 | Matrix6s rJf; //!< Error Jacobian of the frame | ||
184 | Matrix6xs fJf; //!< Local Jacobian of the frame | ||
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_ | ||
200 |