GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/multibody/residuals/frame-translation.hpp
Date: 2025-03-26 19:23:43
Exec Total Coverage
Lines: 10 12 83.3%
Branches: 6 22 27.3%

Line Branch Exec Source
1
2 ///////////////////////////////////////////////////////////////////////////////
3 // BSD 3-Clause License
4 //
5 // Copyright (C) 2021-2025, LAAS-CNRS, University of Edinburgh,
6 // Heriot-Watt University
7 // Copyright note valid unless otherwise stated in individual files.
8 // All rights reserved.
9 ///////////////////////////////////////////////////////////////////////////////
10
11 #ifndef CROCODDYL_MULTIBODY_RESIDUALS_FRAME_TRANSLATION_HPP_
12 #define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_TRANSLATION_HPP_
13
14 #include <pinocchio/multibody/fwd.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 translation residual
25 *
26 * This residual function defines the tracking of a frame translation as
27 * \f$\mathbf{r}=\mathbf{t}-\mathbf{t}^*\f$, where
28 * \f$\mathbf{t},\mathbf{t}^*\in~\mathbb{R}^3\f$ are the current and reference
29 * frame translations, respectively. Note that the dimension of the residual
30 * vector is 3. 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 ResidualModelFrameTranslationTpl
40 : public ResidualModelAbstractTpl<_Scalar> {
41 public:
42 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
43 CROCODDYL_DERIVED_CAST(ResidualModelBase, ResidualModelFrameTranslationTpl)
44
45 typedef _Scalar Scalar;
46 typedef MathBaseTpl<Scalar> MathBase;
47 typedef ResidualModelAbstractTpl<Scalar> Base;
48 typedef ResidualDataFrameTranslationTpl<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 typename MathBase::Vector3s Vector3s;
54
55 /**
56 * @brief Initialize the frame translation residual model
57 *
58 * @param[in] state State of the multibody system
59 * @param[in] id Reference frame id
60 * @param[in] xref Reference frame translation
61 * @param[in] nu Dimension of the control vector
62 */
63 ResidualModelFrameTranslationTpl(std::shared_ptr<StateMultibody> state,
64 const pinocchio::FrameIndex id,
65 const Vector3s& xref, const std::size_t nu);
66
67 /**
68 * @brief Initialize the frame translation residual model
69 *
70 * The default `nu` is equals to StateAbstractTpl::get_nv().
71 *
72 * @param[in] state State of the multibody system
73 * @param[in] id Reference frame id
74 * @param[in] xref Reference frame translation
75 */
76 ResidualModelFrameTranslationTpl(std::shared_ptr<StateMultibody> state,
77 const pinocchio::FrameIndex id,
78 const Vector3s& xref);
79 698 virtual ~ResidualModelFrameTranslationTpl() = default;
80
81 /**
82 * @brief Compute the frame translation residual
83 *
84 * @param[in] data Frame translation 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 translation residual
94 *
95 * @param[in] data Frame translation 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 translation residual data
105 */
106 virtual std::shared_ptr<ResidualDataAbstract> createData(
107 DataCollectorAbstract* const data) override;
108
109 /**
110 * @brief Cast the frame-translation residual model to a different scalar
111 * type.
112 *
113 * It is useful for operations requiring different precision or scalar types.
114 *
115 * @tparam NewScalar The new scalar type to cast to.
116 * @return ResidualModelFrameTranslationTpl<NewScalar> A residual model with
117 * the new scalar type.
118 */
119 template <typename NewScalar>
120 ResidualModelFrameTranslationTpl<NewScalar> cast() const;
121
122 /**
123 * @brief Return the reference frame id
124 */
125 pinocchio::FrameIndex get_id() const;
126
127 /**
128 * @brief Return the reference frame translation
129 */
130 const Vector3s& get_reference() const;
131
132 /**
133 * @brief Modify the reference frame id
134 */
135 void set_id(const pinocchio::FrameIndex id);
136
137 /**
138 * @brief Modify the reference frame translation reference
139 */
140 void set_reference(const Vector3s& reference);
141
142 /**
143 * @brief Print relevant information of the frame-translation residual
144 *
145 * @param[out] os Output stream object
146 */
147 virtual void print(std::ostream& os) const override;
148
149 protected:
150 using Base::nu_;
151 using Base::state_;
152 using Base::u_dependent_;
153 using Base::v_dependent_;
154
155 private:
156 pinocchio::FrameIndex id_; //!< Reference frame id
157 Vector3s xref_; //!< Reference frame translation
158 std::shared_ptr<typename StateMultibody::PinocchioModel>
159 pin_model_; //!< Pinocchio model
160 };
161
162 template <typename _Scalar>
163 struct ResidualDataFrameTranslationTpl
164 : public ResidualDataAbstractTpl<_Scalar> {
165 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
166
167 typedef _Scalar Scalar;
168 typedef MathBaseTpl<Scalar> MathBase;
169 typedef ResidualDataAbstractTpl<Scalar> Base;
170 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
171 typedef typename MathBase::Matrix6xs Matrix6xs;
172
173 template <template <typename Scalar> class Model>
174 9565 ResidualDataFrameTranslationTpl(Model<Scalar>* const model,
175 DataCollectorAbstract* const data)
176
3/6
✓ Branch 2 taken 9550 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 9550 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 9550 times.
✗ Branch 10 not taken.
9565 : Base(model, data), fJf(6, model->get_state()->get_nv()) {
177
1/2
✓ Branch 1 taken 9550 times.
✗ Branch 2 not taken.
9565 fJf.setZero();
178 // Check that proper shared data has been passed
179 9565 DataCollectorMultibodyTpl<Scalar>* d =
180
1/2
✓ Branch 0 taken 9550 times.
✗ Branch 1 not taken.
9565 dynamic_cast<DataCollectorMultibodyTpl<Scalar>*>(shared);
181
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 9550 times.
9565 if (d == NULL) {
182 throw_pretty(
183 "Invalid argument: the shared data should be derived from "
184 "DataCollectorMultibody");
185 }
186
187 // Avoids data casting at runtime
188 9565 pinocchio = d->pinocchio;
189 9565 }
190 19087 virtual ~ResidualDataFrameTranslationTpl() = default;
191
192 pinocchio::DataTpl<Scalar>* pinocchio; //!< Pinocchio data
193 Matrix6xs fJf; //!< Local Jacobian of the frame
194
195 using Base::r;
196 using Base::Ru;
197 using Base::Rx;
198 using Base::shared;
199 };
200
201 } // namespace crocoddyl
202
203 /* --- Details -------------------------------------------------------------- */
204 /* --- Details -------------------------------------------------------------- */
205 /* --- Details -------------------------------------------------------------- */
206 #include "crocoddyl/multibody/residuals/frame-translation.hxx"
207
208 CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
209 crocoddyl::ResidualModelFrameTranslationTpl)
210 CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
211 crocoddyl::ResidualDataFrameTranslationTpl)
212
213 #endif // CROCODDYL_MULTIBODY_RESIDUALS_FRAME_TRANSLATION_HPP_
214