GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/multibody/residuals/frame-rotation.hpp
Date: 2025-01-16 08:47:40
Exec Total Coverage
Lines: 11 12 91.7%
Branches: 9 26 34.6%

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_ROTATION_HPP_
10 #define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_ROTATION_HPP_
11
12 #include <pinocchio/multibody/fwd.hpp>
13
14 #include "crocoddyl/core/residual-base.hpp"
15 #include "crocoddyl/core/utils/exception.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
42 typedef _Scalar Scalar;
43 typedef MathBaseTpl<Scalar> MathBase;
44 typedef ResidualModelAbstractTpl<Scalar> Base;
45 typedef ResidualDataFrameRotationTpl<Scalar> Data;
46 typedef StateMultibodyTpl<Scalar> StateMultibody;
47 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
48 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
49 typedef typename MathBase::VectorXs VectorXs;
50 typedef typename MathBase::Matrix3s Matrix3s;
51
52 /**
53 * @brief Initialize the frame rotation residual model
54 *
55 * @param[in] state State of the multibody system
56 * @param[in] id Reference frame id
57 * @param[in] Rref Reference frame rotation
58 * @param[in] nu Dimension of the control vector
59 */
60 ResidualModelFrameRotationTpl(boost::shared_ptr<StateMultibody> state,
61 const pinocchio::FrameIndex id,
62 const Matrix3s& Rref, const std::size_t nu);
63
64 /**
65 * @brief Initialize the frame rotation residual model
66 *
67 * The default `nu` is equals to StateAbstractTpl::get_nv().
68 *
69 * @param[in] state State of the multibody system
70 * @param[in] id Reference frame id
71 * @param[in] Rref Reference frame rotation
72 */
73 ResidualModelFrameRotationTpl(boost::shared_ptr<StateMultibody> state,
74 const pinocchio::FrameIndex id,
75 const Matrix3s& Rref);
76 virtual ~ResidualModelFrameRotationTpl();
77
78 /**
79 * @brief Compute the frame rotation residual
80 *
81 * @param[in] data Frame rotation residual data
82 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
83 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
84 */
85 virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
86 const Eigen::Ref<const VectorXs>& x,
87 const Eigen::Ref<const VectorXs>& u);
88
89 /**
90 * @brief Compute the derivatives of the frame rotation residual
91 *
92 * @param[in] data Frame rotation residual data
93 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
94 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
95 */
96 virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
97 const Eigen::Ref<const VectorXs>& x,
98 const Eigen::Ref<const VectorXs>& u);
99
100 /**
101 * @brief Create the frame rotation residual data
102 */
103 virtual boost::shared_ptr<ResidualDataAbstract> createData(
104 DataCollectorAbstract* const data);
105
106 /**
107 * @brief Return the reference frame id
108 */
109 pinocchio::FrameIndex get_id() const;
110
111 /**
112 * @brief Return the reference frame rotation
113 */
114 const Matrix3s& get_reference() const;
115
116 /**
117 * @brief Modify the reference frame id
118 */
119 void set_id(const pinocchio::FrameIndex id);
120
121 /**
122 * @brief Modify the reference frame rotation
123 */
124 void set_reference(const Matrix3s& reference);
125
126 /**
127 * @brief Print relevant information of the frame-rotation residual
128 *
129 * @param[out] os Output stream object
130 */
131 virtual void print(std::ostream& os) const;
132
133 protected:
134 using Base::nu_;
135 using Base::state_;
136 using Base::u_dependent_;
137 using Base::v_dependent_;
138
139 private:
140 pinocchio::FrameIndex id_; //!< Reference frame id
141 Matrix3s Rref_; //!< Reference frame rotation
142 Matrix3s oRf_inv_; //!< Inverse reference rotation
143 boost::shared_ptr<typename StateMultibody::PinocchioModel>
144 pin_model_; //!< Pinocchio model
145 };
146
147 template <typename _Scalar>
148 struct ResidualDataFrameRotationTpl : public ResidualDataAbstractTpl<_Scalar> {
149 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
150
151 typedef _Scalar Scalar;
152 typedef MathBaseTpl<Scalar> MathBase;
153 typedef ResidualDataAbstractTpl<Scalar> Base;
154 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
155 typedef typename MathBase::Vector3s Vector3s;
156 typedef typename MathBase::Matrix3s Matrix3s;
157 typedef typename MathBase::Matrix3xs Matrix3xs;
158 typedef typename MathBase::Matrix6xs Matrix6xs;
159
160 template <template <typename Scalar> class Model>
161 9556 ResidualDataFrameRotationTpl(Model<Scalar>* const model,
162 DataCollectorAbstract* const data)
163
3/6
✓ Branch 2 taken 9556 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 9556 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 9556 times.
✗ Branch 12 not taken.
9556 : Base(model, data), rJf(3, 3), fJf(6, model->get_state()->get_nv()) {
164
1/2
✓ Branch 1 taken 9556 times.
✗ Branch 2 not taken.
9556 r.setZero();
165
1/2
✓ Branch 1 taken 9556 times.
✗ Branch 2 not taken.
9556 rRf.setIdentity();
166
1/2
✓ Branch 1 taken 9556 times.
✗ Branch 2 not taken.
9556 rJf.setZero();
167
1/2
✓ Branch 1 taken 9556 times.
✗ Branch 2 not taken.
9556 fJf.setZero();
168 // Check that proper shared data has been passed
169 9556 DataCollectorMultibodyTpl<Scalar>* d =
170
1/2
✓ Branch 0 taken 9556 times.
✗ Branch 1 not taken.
9556 dynamic_cast<DataCollectorMultibodyTpl<Scalar>*>(shared);
171
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 9556 times.
9556 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 9556 pinocchio = d->pinocchio;
179 9556 }
180
181 pinocchio::DataTpl<Scalar>* pinocchio; //!< Pinocchio data
182 Matrix3s rRf; //!< Rotation error of the frame
183 Matrix3s 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-rotation.hxx"
198
199 #endif // CROCODDYL_MULTIBODY_RESIDUALS_FRAME_ROTATION_HPP_
200