GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/multibody/residuals/frame-velocity.hpp
Date: 2025-03-26 19:23:43
Exec Total Coverage
Lines: 9 11 81.8%
Branches: 2 14 14.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_VELOCITY_HPP_
11 #define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_VELOCITY_HPP_
12
13 #include <pinocchio/multibody/fwd.hpp>
14 #include <pinocchio/spatial/motion.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 velocity residual
25 *
26 * This residual function defines a tracking of frame velocity as
27 * \f$\mathbf{r}=\mathbf{v}-\mathbf{v}^*\f$, where
28 * \f$\mathbf{v},\mathbf{v}^*\in~T_{\mathbf{p}}~\mathbb{SE(3)}\f$ are the
29 * current and reference frame velocities, respectively. Note that the tangent
30 * vector is described by the frame placement \f$\mathbf{p}\f$, and the
31 * dimension of the residual vector is 6. Furthermore, the Jacobians of the
32 * residual function are computed analytically.
33 *
34 * As described in `ResidualModelAbstractTpl`, the residual vector and its
35 * Jacobians are calculated by `calc` and `calcDiff`, respectively.
36 *
37 * \sa `ResidualModelAbstractTpl`, `calc()`, `calcDiff()`, `createData()`
38 */
39 template <typename _Scalar>
40 class ResidualModelFrameVelocityTpl : public ResidualModelAbstractTpl<_Scalar> {
41 public:
42 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
43 CROCODDYL_DERIVED_CAST(ResidualModelBase, ResidualModelFrameVelocityTpl)
44
45 typedef _Scalar Scalar;
46 typedef MathBaseTpl<Scalar> MathBase;
47 typedef ResidualModelAbstractTpl<Scalar> Base;
48 typedef ResidualDataFrameVelocityTpl<Scalar> Data;
49 typedef StateMultibodyTpl<Scalar> StateMultibody;
50 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
51 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
52 typedef pinocchio::MotionTpl<Scalar> Motion;
53 typedef typename MathBase::VectorXs VectorXs;
54
55 /**
56 * @brief Initialize the frame velocity residual model
57 *
58 * @param[in] state State of the multibody system
59 * @param[in] id Reference frame id
60 * @param[in] vref Reference velocity
61 * @param[in] type Reference type of velocity (WORLD, LOCAL,
62 * LOCAL_WORLD_ALIGNED)
63 * @param[in] nu Dimension of the control vector
64 */
65 ResidualModelFrameVelocityTpl(std::shared_ptr<StateMultibody> state,
66 const pinocchio::FrameIndex id,
67 const Motion& vref,
68 const pinocchio::ReferenceFrame type,
69 const std::size_t nu);
70
71 /**
72 * @brief Initialize the frame velocity residual model
73 *
74 * The default `nu` value is obtained from `StateAbstractTpl::get_nv()`.
75 *
76 * @param[in] state State of the multibody system
77 * @param[in] id Reference frame id
78 * @param[in] vref Reference velocity
79 * @param[in] type Reference type of velocity (WORLD, LOCAL,
80 * LOCAL_WORLD_ALIGNED)
81 */
82 ResidualModelFrameVelocityTpl(std::shared_ptr<StateMultibody> state,
83 const pinocchio::FrameIndex id,
84 const Motion& vref,
85 const pinocchio::ReferenceFrame type);
86 1200 virtual ~ResidualModelFrameVelocityTpl() = default;
87
88 /**
89 * @brief Compute the frame velocity residual vector
90 *
91 * @param[in] data Frame velocity residual data
92 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
93 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
94 */
95 virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
96 const Eigen::Ref<const VectorXs>& x,
97 const Eigen::Ref<const VectorXs>& u) override;
98
99 /**
100 * @brief Compute the Jacobians of the frame velocity residual
101 *
102 * @param[in] data Frame velocity residual data
103 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
104 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
105 */
106 virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
107 const Eigen::Ref<const VectorXs>& x,
108 const Eigen::Ref<const VectorXs>& u) override;
109
110 /**
111 * @brief Create the frame velocity residual data
112 */
113 virtual std::shared_ptr<ResidualDataAbstract> createData(
114 DataCollectorAbstract* const data) override;
115
116 /**
117 * @brief Cast the frame-velocity residual model to a different scalar type.
118 *
119 * It is useful for operations requiring different precision or scalar types.
120 *
121 * @tparam NewScalar The new scalar type to cast to.
122 * @return ResidualModelFrameVelocityTpl<NewScalar> A residual model with the
123 * new scalar type.
124 */
125 template <typename NewScalar>
126 ResidualModelFrameVelocityTpl<NewScalar> cast() const;
127
128 /**
129 * @brief Return the reference frame id
130 */
131 pinocchio::FrameIndex get_id() const;
132
133 /**
134 * @brief Return the reference velocity
135 */
136 const Motion& get_reference() const;
137
138 /**
139 * @brief Return the reference type of velocity
140 */
141 pinocchio::ReferenceFrame get_type() const;
142
143 /**
144 * @brief Modify reference frame id
145 */
146 void set_id(const pinocchio::FrameIndex id);
147
148 /**
149 * @brief Modify reference velocity
150 */
151 void set_reference(const Motion& velocity);
152
153 /**
154 * @brief Modify reference type of velocity
155 */
156 void set_type(const pinocchio::ReferenceFrame type);
157
158 /**
159 * @brief Print relevant information of the frame-velocity residual
160 *
161 * @param[out] os Output stream object
162 */
163 virtual void print(std::ostream& os) const override;
164
165 protected:
166 using Base::nr_;
167 using Base::nu_;
168 using Base::state_;
169 using Base::u_dependent_;
170
171 private:
172 pinocchio::FrameIndex id_; //!< Reference frame id
173 Motion vref_; //!< Reference velocity
174 pinocchio::ReferenceFrame type_; //!< Reference type of velocity
175 std::shared_ptr<typename StateMultibody::PinocchioModel>
176 pin_model_; //!< Pinocchio model
177 };
178
179 template <typename _Scalar>
180 struct ResidualDataFrameVelocityTpl : public ResidualDataAbstractTpl<_Scalar> {
181 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
182
183 typedef _Scalar Scalar;
184 typedef MathBaseTpl<Scalar> MathBase;
185 typedef ResidualDataAbstractTpl<Scalar> Base;
186 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
187 typedef typename MathBase::Matrix6xs Matrix6xs;
188
189 template <template <typename Scalar> class Model>
190 26126 ResidualDataFrameVelocityTpl(Model<Scalar>* const model,
191 DataCollectorAbstract* const data)
192 26126 : Base(model, data) {
193 // Check that proper shared data has been passed
194 26126 DataCollectorMultibodyTpl<Scalar>* d =
195
1/2
✓ Branch 0 taken 26111 times.
✗ Branch 1 not taken.
26126 dynamic_cast<DataCollectorMultibodyTpl<Scalar>*>(shared);
196
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 26111 times.
26126 if (d == NULL) {
197 throw_pretty(
198 "Invalid argument: the shared data should be derived from "
199 "DataCollectorMultibody");
200 }
201
202 // Avoids data casting at runtime
203 26126 pinocchio = d->pinocchio;
204 26126 }
205 52209 virtual ~ResidualDataFrameVelocityTpl() = default;
206
207 pinocchio::DataTpl<Scalar>* pinocchio; //!< Pinocchio data
208 using Base::r;
209 using Base::Ru;
210 using Base::Rx;
211 using Base::shared;
212 };
213
214 } // namespace crocoddyl
215
216 /* --- Details -------------------------------------------------------------- */
217 /* --- Details -------------------------------------------------------------- */
218 /* --- Details -------------------------------------------------------------- */
219 #include "crocoddyl/multibody/residuals/frame-velocity.hxx"
220
221 CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
222 crocoddyl::ResidualModelFrameVelocityTpl)
223 CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
224 crocoddyl::ResidualDataFrameVelocityTpl)
225
226 #endif // CROCODDYL_MULTIBODY_RESIDUALS_FRAME_VELOCITY_HPP_
227