Directory: | ./ |
---|---|
File: | include/crocoddyl/multibody/residuals/frame-placement.hpp |
Date: | 2025-03-26 19:23:43 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 12 | 14 | 85.7% |
Branches: | 10 | 30 | 33.3% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | /////////////////////////////////////////////////////////////////////////////// | ||
2 | // BSD 3-Clause License | ||
3 | // | ||
4 | // Copyright (C) 2021-2025, LAAS-CNRS, University of Edinburgh, | ||
5 | // Heriot-Watt University | ||
6 | // Copyright note valid unless otherwise stated in individual files. | ||
7 | // All rights reserved. | ||
8 | /////////////////////////////////////////////////////////////////////////////// | ||
9 | |||
10 | #ifndef CROCODDYL_MULTIBODY_RESIDUALS_FRAME_PLACEMENT_HPP_ | ||
11 | #define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_PLACEMENT_HPP_ | ||
12 | |||
13 | #include <pinocchio/multibody/fwd.hpp> | ||
14 | #include <pinocchio/spatial/se3.hpp> | ||
15 | |||
16 | #include "crocoddyl/core/residual-base.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 | ✗ | CROCODDYL_DERIVED_CAST(ResidualModelBase, ResidualModelFramePlacementTpl) | |
44 | |||
45 | typedef _Scalar Scalar; | ||
46 | typedef MathBaseTpl<Scalar> MathBase; | ||
47 | typedef ResidualModelAbstractTpl<Scalar> Base; | ||
48 | typedef ResidualDataFramePlacementTpl<Scalar> Data; | ||
49 | typedef StateMultibodyTpl<Scalar> StateMultibody; | ||
50 | typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract; | ||
51 | typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract; | ||
52 | typedef typename MathBase::VectorXs VectorXs; | ||
53 | typedef pinocchio::SE3Tpl<Scalar> SE3; | ||
54 | |||
55 | /** | ||
56 | * @brief Initialize the frame placement residual model | ||
57 | * | ||
58 | * @param[in] state State of the multibody system | ||
59 | * @param[in] id Reference frame id | ||
60 | * @param[in] pref Reference frame placement | ||
61 | * @param[in] nu Dimension of the control vector | ||
62 | */ | ||
63 | ResidualModelFramePlacementTpl(std::shared_ptr<StateMultibody> state, | ||
64 | const pinocchio::FrameIndex id, | ||
65 | const SE3& pref, const std::size_t nu); | ||
66 | |||
67 | /** | ||
68 | * @brief Initialize the frame placement residual model | ||
69 | * | ||
70 | * The default `nu` is obtained from `StateAbstractTpl::get_nv()`. | ||
71 | * | ||
72 | * @param[in] state State of the multibody system | ||
73 | * @param[in] id Reference frame id | ||
74 | * @param[in] pref Reference frame placement | ||
75 | */ | ||
76 | ResidualModelFramePlacementTpl(std::shared_ptr<StateMultibody> state, | ||
77 | const pinocchio::FrameIndex id, | ||
78 | const SE3& pref); | ||
79 | 1806 | virtual ~ResidualModelFramePlacementTpl() = default; | |
80 | |||
81 | /** | ||
82 | * @brief Compute the frame placement residual | ||
83 | * | ||
84 | * @param[in] data Frame placement residual data | ||
85 | * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ | ||
86 | * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$ | ||
87 | */ | ||
88 | virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data, | ||
89 | const Eigen::Ref<const VectorXs>& x, | ||
90 | const Eigen::Ref<const VectorXs>& u) override; | ||
91 | |||
92 | /** | ||
93 | * @brief Compute the derivatives of the frame placement residual | ||
94 | * | ||
95 | * @param[in] data Frame-placement residual data | ||
96 | * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ | ||
97 | * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$ | ||
98 | */ | ||
99 | virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data, | ||
100 | const Eigen::Ref<const VectorXs>& x, | ||
101 | const Eigen::Ref<const VectorXs>& u) override; | ||
102 | |||
103 | /** | ||
104 | * @brief Create the frame placement residual data | ||
105 | */ | ||
106 | virtual std::shared_ptr<ResidualDataAbstract> createData( | ||
107 | DataCollectorAbstract* const data) override; | ||
108 | |||
109 | /** | ||
110 | * @brief Cast the frame-placement residual model to a different scalar type. | ||
111 | * | ||
112 | * It is useful for operations requiring different precision or scalar types. | ||
113 | * | ||
114 | * @tparam NewScalar The new scalar type to cast to. | ||
115 | * @return ResidualModelFramePlacementTpl<NewScalar> A residual model with the | ||
116 | * new scalar type. | ||
117 | */ | ||
118 | template <typename NewScalar> | ||
119 | ResidualModelFramePlacementTpl<NewScalar> cast() const; | ||
120 | |||
121 | /** | ||
122 | * @brief Return the reference frame id | ||
123 | */ | ||
124 | pinocchio::FrameIndex get_id() const; | ||
125 | |||
126 | /** | ||
127 | * @brief Return the reference frame placement | ||
128 | */ | ||
129 | const SE3& get_reference() const; | ||
130 | |||
131 | /** | ||
132 | * @brief Modify the reference frame id | ||
133 | */ | ||
134 | void set_id(const pinocchio::FrameIndex id); | ||
135 | |||
136 | /** | ||
137 | * @brief Modify the reference frame placement | ||
138 | */ | ||
139 | void set_reference(const SE3& reference); | ||
140 | |||
141 | /** | ||
142 | * @brief Print relevant information of the frame-placement residual | ||
143 | * | ||
144 | * @param[out] os Output stream object | ||
145 | */ | ||
146 | virtual void print(std::ostream& os) const override; | ||
147 | |||
148 | protected: | ||
149 | using Base::nu_; | ||
150 | using Base::state_; | ||
151 | using Base::u_dependent_; | ||
152 | using Base::v_dependent_; | ||
153 | |||
154 | private: | ||
155 | pinocchio::FrameIndex id_; //!< Reference frame id | ||
156 | SE3 pref_; //!< Reference frame placement | ||
157 | pinocchio::SE3Tpl<Scalar> oMf_inv_; //!< Inverse reference placement | ||
158 | std::shared_ptr<typename StateMultibody::PinocchioModel> | ||
159 | pin_model_; //!< Pinocchio model | ||
160 | }; | ||
161 | |||
162 | template <typename _Scalar> | ||
163 | struct ResidualDataFramePlacementTpl : public ResidualDataAbstractTpl<_Scalar> { | ||
164 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ||
165 | |||
166 | typedef _Scalar Scalar; | ||
167 | typedef MathBaseTpl<Scalar> MathBase; | ||
168 | typedef ResidualDataAbstractTpl<Scalar> Base; | ||
169 | typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract; | ||
170 | typedef typename MathBase::Matrix6xs Matrix6xs; | ||
171 | typedef typename MathBase::Matrix6s Matrix6s; | ||
172 | typedef typename MathBase::Vector6s Vector6s; | ||
173 | |||
174 | template <template <typename Scalar> class Model> | ||
175 | 46835 | ResidualDataFramePlacementTpl(Model<Scalar>* const model, | |
176 | DataCollectorAbstract* const data) | ||
177 |
5/10✓ Branch 2 taken 46302 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 46302 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 46302 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 46302 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 46302 times.
✗ Branch 16 not taken.
|
46835 | : Base(model, data), rJf(6, 6), fJf(6, model->get_state()->get_nv()) { |
178 |
1/2✓ Branch 1 taken 46302 times.
✗ Branch 2 not taken.
|
46835 | r.setZero(); |
179 |
1/2✓ Branch 1 taken 46302 times.
✗ Branch 2 not taken.
|
46835 | rJf.setZero(); |
180 |
1/2✓ Branch 1 taken 46302 times.
✗ Branch 2 not taken.
|
46835 | fJf.setZero(); |
181 | // Check that proper shared data has been passed | ||
182 | 46835 | DataCollectorMultibodyTpl<Scalar>* d = | |
183 |
1/2✓ Branch 0 taken 46302 times.
✗ Branch 1 not taken.
|
46835 | dynamic_cast<DataCollectorMultibodyTpl<Scalar>*>(shared); |
184 |
1/2✗ Branch 0 not taken.
✓ Branch 1 taken 46302 times.
|
46835 | if (d == NULL) { |
185 | ✗ | throw_pretty( | |
186 | "Invalid argument: the shared data should be derived from " | ||
187 | "DataCollectorMultibody"); | ||
188 | } | ||
189 | |||
190 | // Avoids data casting at runtime | ||
191 | 46835 | pinocchio = d->pinocchio; | |
192 | 46835 | } | |
193 | 92069 | virtual ~ResidualDataFramePlacementTpl() = default; | |
194 | |||
195 | pinocchio::DataTpl<Scalar>* pinocchio; //!< Pinocchio data | ||
196 | pinocchio::SE3Tpl<Scalar> rMf; //!< Error frame placement of the frame | ||
197 | Matrix6s rJf; //!< Error Jacobian of the frame | ||
198 | Matrix6xs fJf; //!< Local Jacobian of the frame | ||
199 | |||
200 | using Base::r; | ||
201 | using Base::Ru; | ||
202 | using Base::Rx; | ||
203 | using Base::shared; | ||
204 | }; | ||
205 | |||
206 | } // namespace crocoddyl | ||
207 | |||
208 | /* --- Details -------------------------------------------------------------- */ | ||
209 | /* --- Details -------------------------------------------------------------- */ | ||
210 | /* --- Details -------------------------------------------------------------- */ | ||
211 | #include "crocoddyl/multibody/residuals/frame-placement.hxx" | ||
212 | |||
213 | CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS( | ||
214 | crocoddyl::ResidualModelFramePlacementTpl) | ||
215 | CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT( | ||
216 | crocoddyl::ResidualDataFramePlacementTpl) | ||
217 | |||
218 | #endif // CROCODDYL_MULTIBODY_RESIDUALS_FRAME_PLACEMENT_HPP_ | ||
219 |