GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/multibody/residuals/frame-rotation.hpp
Date: 2025-03-26 19:23:43
Exec Total Coverage
Lines: 13 15 86.7%
Branches: 11 32 34.4%

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_ROTATION_HPP_
11 #define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_ROTATION_HPP_
12
13 #include <pinocchio/multibody/fwd.hpp>
14
15 #include "crocoddyl/core/residual-base.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
22 /**
23 * @brief Frame rotation residual
24 *
25 * This residual function is defined as
26 * \f$\mathbf{r}=\mathbf{R}\ominus\mathbf{R}^*\f$, where
27 * \f$\mathbf{R},\mathbf{R}^*\in~\mathbb{SO(3)}\f$ are the current and reference
28 * frame rotations, respectively. Note that the dimension of the residual vector
29 * is 3. Furthermore, the Jacobians of the residual function are computed
30 * analytically.
31 *
32 * As described in `ResidualModelAbstractTpl()`, the residual value and its
33 * Jacobians are calculated by `calc` and `calcDiff`, respectively.
34 *
35 * \sa `ResidualModelAbstractTpl`, `calc()`, `calcDiff()`, `createData()`
36 */
37 template <typename _Scalar>
38 class ResidualModelFrameRotationTpl : public ResidualModelAbstractTpl<_Scalar> {
39 public:
40 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
41 CROCODDYL_DERIVED_CAST(ResidualModelBase, ResidualModelFrameRotationTpl)
42
43 typedef _Scalar Scalar;
44 typedef MathBaseTpl<Scalar> MathBase;
45 typedef ResidualModelAbstractTpl<Scalar> Base;
46 typedef ResidualDataFrameRotationTpl<Scalar> Data;
47 typedef StateMultibodyTpl<Scalar> StateMultibody;
48 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
49 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
50 typedef typename MathBase::VectorXs VectorXs;
51 typedef typename MathBase::Matrix3s Matrix3s;
52
53 /**
54 * @brief Initialize the frame rotation residual model
55 *
56 * @param[in] state State of the multibody system
57 * @param[in] id Reference frame id
58 * @param[in] Rref Reference frame rotation
59 * @param[in] nu Dimension of the control vector
60 */
61 ResidualModelFrameRotationTpl(std::shared_ptr<StateMultibody> state,
62 const pinocchio::FrameIndex id,
63 const Matrix3s& Rref, const std::size_t nu);
64
65 /**
66 * @brief Initialize the frame rotation residual model
67 *
68 * The default `nu` is equals to StateAbstractTpl::get_nv().
69 *
70 * @param[in] state State of the multibody system
71 * @param[in] id Reference frame id
72 * @param[in] Rref Reference frame rotation
73 */
74 ResidualModelFrameRotationTpl(std::shared_ptr<StateMultibody> state,
75 const pinocchio::FrameIndex id,
76 const Matrix3s& Rref);
77 716 virtual ~ResidualModelFrameRotationTpl() = default;
78
79 /**
80 * @brief Compute the frame rotation residual
81 *
82 * @param[in] data Frame rotation residual data
83 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
84 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
85 */
86 virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
87 const Eigen::Ref<const VectorXs>& x,
88 const Eigen::Ref<const VectorXs>& u) override;
89
90 /**
91 * @brief Compute the derivatives of the frame rotation residual
92 *
93 * @param[in] data Frame rotation residual data
94 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
95 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
96 */
97 virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
98 const Eigen::Ref<const VectorXs>& x,
99 const Eigen::Ref<const VectorXs>& u) override;
100
101 /**
102 * @brief Create the frame rotation residual data
103 */
104 virtual std::shared_ptr<ResidualDataAbstract> createData(
105 DataCollectorAbstract* const data) override;
106
107 /**
108 * @brief Cast the frame-rotation residual model to a different scalar type.
109 *
110 * It is useful for operations requiring different precision or scalar types.
111 *
112 * @tparam NewScalar The new scalar type to cast to.
113 * @return ResidualModelFrameRotationTpl<NewScalar> A residual model with the
114 * new scalar type.
115 */
116 template <typename NewScalar>
117 ResidualModelFrameRotationTpl<NewScalar> cast() const;
118
119 /**
120 * @brief Return the reference frame id
121 */
122 pinocchio::FrameIndex get_id() const;
123
124 /**
125 * @brief Return the reference frame rotation
126 */
127 const Matrix3s& get_reference() const;
128
129 /**
130 * @brief Modify the reference frame id
131 */
132 void set_id(const pinocchio::FrameIndex id);
133
134 /**
135 * @brief Modify the reference frame rotation
136 */
137 void set_reference(const Matrix3s& reference);
138
139 /**
140 * @brief Print relevant information of the frame-rotation residual
141 *
142 * @param[out] os Output stream object
143 */
144 virtual void print(std::ostream& os) const override;
145
146 protected:
147 using Base::nu_;
148 using Base::state_;
149 using Base::u_dependent_;
150 using Base::v_dependent_;
151
152 private:
153 pinocchio::FrameIndex id_; //!< Reference frame id
154 Matrix3s Rref_; //!< Reference frame rotation
155 Matrix3s oRf_inv_; //!< Inverse reference rotation
156 std::shared_ptr<typename StateMultibody::PinocchioModel>
157 pin_model_; //!< Pinocchio model
158 };
159
160 template <typename _Scalar>
161 struct ResidualDataFrameRotationTpl : public ResidualDataAbstractTpl<_Scalar> {
162 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
163
164 typedef _Scalar Scalar;
165 typedef MathBaseTpl<Scalar> MathBase;
166 typedef ResidualDataAbstractTpl<Scalar> Base;
167 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
168 typedef typename MathBase::Vector3s Vector3s;
169 typedef typename MathBase::Matrix3s Matrix3s;
170 typedef typename MathBase::Matrix3xs Matrix3xs;
171 typedef typename MathBase::Matrix6xs Matrix6xs;
172
173 template <template <typename Scalar> class Model>
174 9571 ResidualDataFrameRotationTpl(Model<Scalar>* const model,
175 DataCollectorAbstract* const data)
176
5/10
✓ Branch 2 taken 9556 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 9556 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 9556 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 9556 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 9556 times.
✗ Branch 16 not taken.
9571 : Base(model, data), rJf(3, 3), fJf(6, model->get_state()->get_nv()) {
177
1/2
✓ Branch 1 taken 9556 times.
✗ Branch 2 not taken.
9571 r.setZero();
178
1/2
✓ Branch 1 taken 9556 times.
✗ Branch 2 not taken.
9571 rRf.setIdentity();
179
1/2
✓ Branch 1 taken 9556 times.
✗ Branch 2 not taken.
9571 rJf.setZero();
180
1/2
✓ Branch 1 taken 9556 times.
✗ Branch 2 not taken.
9571 fJf.setZero();
181 // Check that proper shared data has been passed
182 9571 DataCollectorMultibodyTpl<Scalar>* d =
183
1/2
✓ Branch 0 taken 9556 times.
✗ Branch 1 not taken.
9571 dynamic_cast<DataCollectorMultibodyTpl<Scalar>*>(shared);
184
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 9556 times.
9571 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 9571 pinocchio = d->pinocchio;
192 9571 }
193 19099 virtual ~ResidualDataFrameRotationTpl() = default;
194
195 pinocchio::DataTpl<Scalar>* pinocchio; //!< Pinocchio data
196 Matrix3s rRf; //!< Rotation error of the frame
197 Matrix3s 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-rotation.hxx"
212
213 CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
214 crocoddyl::ResidualModelFrameRotationTpl)
215 CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
216 crocoddyl::ResidualDataFrameRotationTpl)
217
218 #endif // CROCODDYL_MULTIBODY_RESIDUALS_FRAME_ROTATION_HPP_
219