GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/multibody/residuals/frame-translation.hpp
Date: 2025-01-16 08:47:40
Exec Total Coverage
Lines: 8 9 88.9%
Branches: 4 16 25.0%

Line Branch Exec Source
1
2 ///////////////////////////////////////////////////////////////////////////////
3 // BSD 3-Clause License
4 //
5 // Copyright (C) 2021, LAAS-CNRS, University of Edinburgh
6 // Copyright note valid unless otherwise stated in individual files.
7 // All rights reserved.
8 ///////////////////////////////////////////////////////////////////////////////
9
10 #ifndef CROCODDYL_MULTIBODY_RESIDUALS_FRAME_TRANSLATION_HPP_
11 #define CROCODDYL_MULTIBODY_RESIDUALS_FRAME_TRANSLATION_HPP_
12
13 #include <pinocchio/multibody/fwd.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 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
44 typedef _Scalar Scalar;
45 typedef MathBaseTpl<Scalar> MathBase;
46 typedef ResidualModelAbstractTpl<Scalar> Base;
47 typedef ResidualDataFrameTranslationTpl<Scalar> Data;
48 typedef StateMultibodyTpl<Scalar> StateMultibody;
49 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
50 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
51 typedef typename MathBase::VectorXs VectorXs;
52 typedef typename MathBase::Vector3s Vector3s;
53
54 /**
55 * @brief Initialize the frame translation residual model
56 *
57 * @param[in] state State of the multibody system
58 * @param[in] id Reference frame id
59 * @param[in] xref Reference frame translation
60 * @param[in] nu Dimension of the control vector
61 */
62 ResidualModelFrameTranslationTpl(boost::shared_ptr<StateMultibody> state,
63 const pinocchio::FrameIndex,
64 const Vector3s& xref, const std::size_t nu);
65
66 /**
67 * @brief Initialize the frame translation residual model
68 *
69 * The default `nu` is equals to StateAbstractTpl::get_nv().
70 *
71 * @param[in] state State of the multibody system
72 * @param[in] id Reference frame id
73 * @param[in] xref Reference frame translation
74 */
75 ResidualModelFrameTranslationTpl(boost::shared_ptr<StateMultibody> state,
76 const pinocchio::FrameIndex id,
77 const Vector3s& xref);
78 virtual ~ResidualModelFrameTranslationTpl();
79
80 /**
81 * @brief Compute the frame translation residual
82 *
83 * @param[in] data Frame translation residual data
84 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
85 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
86 */
87 virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
88 const Eigen::Ref<const VectorXs>& x,
89 const Eigen::Ref<const VectorXs>& u);
90
91 /**
92 * @brief Compute the derivatives of the frame translation residual
93 *
94 * @param[in] data Frame translation residual data
95 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
96 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
97 */
98 virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
99 const Eigen::Ref<const VectorXs>& x,
100 const Eigen::Ref<const VectorXs>& u);
101
102 /**
103 * @brief Create the frame translation residual data
104 */
105 virtual boost::shared_ptr<ResidualDataAbstract> createData(
106 DataCollectorAbstract* const data);
107
108 /**
109 * @brief Return the reference frame id
110 */
111 pinocchio::FrameIndex get_id() const;
112
113 /**
114 * @brief Return the reference frame translation
115 */
116 const Vector3s& get_reference() const;
117
118 /**
119 * @brief Modify the reference frame id
120 */
121 void set_id(const pinocchio::FrameIndex id);
122
123 /**
124 * @brief Modify the reference frame translation reference
125 */
126 void set_reference(const Vector3s& reference);
127
128 /**
129 * @brief Print relevant information of the frame-translation residual
130 *
131 * @param[out] os Output stream object
132 */
133 virtual void print(std::ostream& os) const;
134
135 protected:
136 using Base::nu_;
137 using Base::state_;
138 using Base::u_dependent_;
139 using Base::v_dependent_;
140
141 private:
142 pinocchio::FrameIndex id_; //!< Reference frame id
143 Vector3s xref_; //!< Reference frame translation
144 boost::shared_ptr<typename StateMultibody::PinocchioModel>
145 pin_model_; //!< Pinocchio model
146 };
147
148 template <typename _Scalar>
149 struct ResidualDataFrameTranslationTpl
150 : public ResidualDataAbstractTpl<_Scalar> {
151 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
152
153 typedef _Scalar Scalar;
154 typedef MathBaseTpl<Scalar> MathBase;
155 typedef ResidualDataAbstractTpl<Scalar> Base;
156 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
157 typedef typename MathBase::Matrix6xs Matrix6xs;
158
159 template <template <typename Scalar> class Model>
160 9554 ResidualDataFrameTranslationTpl(Model<Scalar>* const model,
161 DataCollectorAbstract* const data)
162
1/2
✓ Branch 5 taken 9554 times.
✗ Branch 6 not taken.
9554 : Base(model, data), fJf(6, model->get_state()->get_nv()) {
163
1/2
✓ Branch 1 taken 9554 times.
✗ Branch 2 not taken.
9554 fJf.setZero();
164 // Check that proper shared data has been passed
165 9554 DataCollectorMultibodyTpl<Scalar>* d =
166
1/2
✓ Branch 0 taken 9554 times.
✗ Branch 1 not taken.
9554 dynamic_cast<DataCollectorMultibodyTpl<Scalar>*>(shared);
167
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 9554 times.
9554 if (d == NULL) {
168 throw_pretty(
169 "Invalid argument: the shared data should be derived from "
170 "DataCollectorMultibody");
171 }
172
173 // Avoids data casting at runtime
174 9554 pinocchio = d->pinocchio;
175 9554 }
176
177 pinocchio::DataTpl<Scalar>* pinocchio; //!< Pinocchio data
178 Matrix6xs fJf; //!< Local Jacobian of the frame
179
180 using Base::r;
181 using Base::Ru;
182 using Base::Rx;
183 using Base::shared;
184 };
185
186 } // namespace crocoddyl
187
188 /* --- Details -------------------------------------------------------------- */
189 /* --- Details -------------------------------------------------------------- */
190 /* --- Details -------------------------------------------------------------- */
191 #include "crocoddyl/multibody/residuals/frame-translation.hxx"
192
193 #endif // CROCODDYL_MULTIBODY_RESIDUALS_FRAME_TRANSLATION_HPP_
194