GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/multibody/residuals/frame-velocity.hpp
Date: 2025-01-16 08:47:40
Exec Total Coverage
Lines: 7 8 87.5%
Branches: 2 12 16.7%

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_VELOCITY_HPP_
10 #define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_VELOCITY_HPP_
11
12 #include <pinocchio/multibody/fwd.hpp>
13 #include <pinocchio/spatial/motion.hpp>
14
15 #include "crocoddyl/core/residual-base.hpp"
16 #include "crocoddyl/core/utils/exception.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
44 typedef _Scalar Scalar;
45 typedef MathBaseTpl<Scalar> MathBase;
46 typedef ResidualModelAbstractTpl<Scalar> Base;
47 typedef ResidualDataFrameVelocityTpl<Scalar> Data;
48 typedef StateMultibodyTpl<Scalar> StateMultibody;
49 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
50 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
51 typedef pinocchio::MotionTpl<Scalar> Motion;
52 typedef typename MathBase::VectorXs VectorXs;
53
54 /**
55 * @brief Initialize the frame velocity residual model
56 *
57 * @param[in] state State of the multibody system
58 * @param[in] id Reference frame id
59 * @param[in] velocity Reference velocity
60 * @param[in] type Reference type of velocity (WORLD, LOCAL,
61 * LOCAL_WORLD_ALIGNED)
62 * @param[in] nu Dimension of the control vector
63 */
64 ResidualModelFrameVelocityTpl(boost::shared_ptr<StateMultibody> state,
65 const pinocchio::FrameIndex id,
66 const Motion& velocity,
67 const pinocchio::ReferenceFrame type,
68 const std::size_t nu);
69
70 /**
71 * @brief Initialize the frame velocity residual model
72 *
73 * The default `nu` value is obtained from `StateAbstractTpl::get_nv()`.
74 *
75 * @param[in] state State of the multibody system
76 * @param[in] id Reference frame id
77 * @param[in] velocity Reference velocity
78 * @param[in] type Reference type of velocity (WORLD, LOCAL,
79 * LOCAL_WORLD_ALIGNED)
80 */
81 ResidualModelFrameVelocityTpl(boost::shared_ptr<StateMultibody> state,
82 const pinocchio::FrameIndex id,
83 const Motion& velocity,
84 const pinocchio::ReferenceFrame type);
85 virtual ~ResidualModelFrameVelocityTpl();
86
87 /**
88 * @brief Compute the frame velocity residual vector
89 *
90 * @param[in] data Frame velocity residual data
91 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
92 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
93 */
94 virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
95 const Eigen::Ref<const VectorXs>& x,
96 const Eigen::Ref<const VectorXs>& u);
97
98 /**
99 * @brief Compute the Jacobians of the frame velocity residual
100 *
101 * @param[in] data Frame velocity residual data
102 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
103 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
104 */
105 virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
106 const Eigen::Ref<const VectorXs>& x,
107 const Eigen::Ref<const VectorXs>& u);
108
109 /**
110 * @brief Create the frame velocity residual data
111 */
112 virtual boost::shared_ptr<ResidualDataAbstract> createData(
113 DataCollectorAbstract* const data);
114
115 /**
116 * @brief Return the reference frame id
117 */
118 pinocchio::FrameIndex get_id() const;
119
120 /**
121 * @brief Return the reference velocity
122 */
123 const Motion& get_reference() const;
124
125 /**
126 * @brief Return the reference type of velocity
127 */
128 pinocchio::ReferenceFrame get_type() const;
129
130 /**
131 * @brief Modify reference frame id
132 */
133 void set_id(const pinocchio::FrameIndex id);
134
135 /**
136 * @brief Modify reference velocity
137 */
138 void set_reference(const Motion& velocity);
139
140 /**
141 * @brief Modify reference type of velocity
142 */
143 void set_type(const pinocchio::ReferenceFrame type);
144
145 /**
146 * @brief Print relevant information of the frame-velocity residual
147 *
148 * @param[out] os Output stream object
149 */
150 virtual void print(std::ostream& os) const;
151
152 protected:
153 using Base::nr_;
154 using Base::nu_;
155 using Base::state_;
156 using Base::u_dependent_;
157
158 private:
159 pinocchio::FrameIndex id_; //!< Reference frame id
160 Motion vref_; //!< Reference velocity
161 pinocchio::ReferenceFrame type_; //!< Reference type of velocity
162 boost::shared_ptr<typename StateMultibody::PinocchioModel>
163 pin_model_; //!< Pinocchio model
164 };
165
166 template <typename _Scalar>
167 struct ResidualDataFrameVelocityTpl : public ResidualDataAbstractTpl<_Scalar> {
168 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
169
170 typedef _Scalar Scalar;
171 typedef MathBaseTpl<Scalar> MathBase;
172 typedef ResidualDataAbstractTpl<Scalar> Base;
173 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
174 typedef typename MathBase::Matrix6xs Matrix6xs;
175
176 template <template <typename Scalar> class Model>
177 26099 ResidualDataFrameVelocityTpl(Model<Scalar>* const model,
178 DataCollectorAbstract* const data)
179 26099 : Base(model, data) {
180 // Check that proper shared data has been passed
181 26099 DataCollectorMultibodyTpl<Scalar>* d =
182
1/2
✓ Branch 0 taken 26099 times.
✗ Branch 1 not taken.
26099 dynamic_cast<DataCollectorMultibodyTpl<Scalar>*>(shared);
183
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 26099 times.
26099 if (d == NULL) {
184 throw_pretty(
185 "Invalid argument: the shared data should be derived from "
186 "DataCollectorMultibody");
187 }
188
189 // Avoids data casting at runtime
190 26099 pinocchio = d->pinocchio;
191 26099 }
192
193 pinocchio::DataTpl<Scalar>* pinocchio; //!< Pinocchio data
194 using Base::r;
195 using Base::Ru;
196 using Base::Rx;
197 using Base::shared;
198 };
199
200 } // namespace crocoddyl
201
202 /* --- Details -------------------------------------------------------------- */
203 /* --- Details -------------------------------------------------------------- */
204 /* --- Details -------------------------------------------------------------- */
205 #include "crocoddyl/multibody/residuals/frame-velocity.hxx"
206
207 #endif // CROCODDYL_MULTIBODY_RESIDUALS_FRAME_VELOCITY_HPP_
208