GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/core/residuals/joint-effort.hpp
Date: 2025-02-24 23:41:29
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) 2022-2023, Heriot-Watt University, University of Edinburgh
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
7 ///////////////////////////////////////////////////////////////////////////////
8
9 #ifndef CROCODDYL_CORE_RESIDUALS_JOINT_TORQUE_HPP_
10 #define CROCODDYL_CORE_RESIDUALS_JOINT_TORQUE_HPP_
11
12 #include "crocoddyl/core/actuation-base.hpp"
13 #include "crocoddyl/core/data/joint.hpp"
14 #include "crocoddyl/core/fwd.hpp"
15 #include "crocoddyl/core/residual-base.hpp"
16
17 namespace crocoddyl {
18
19 /**
20 * @brief Define a joint-effort residual
21 *
22 * This residual function is defined as
23 * \f$\mathbf{r}=\mathbf{u}-\mathbf{u}^*\f$, where
24 * \f$\mathbf{u},\mathbf{u}^*\in~\mathbb{R}^{nu}\f$ are the current and
25 * reference joint effort inputs, respectively. Note that the dimension of the
26 * residual vector is obtained from `ActuationModelAbstract::nu`.
27 *
28 * Both residual and residual Jacobians are computed analytically.
29 *
30 * As described in ResidualModelAbstractTpl(), the residual value and its
31 * Jacobians are calculated by `calc` and `calcDiff`, respectively.
32 *
33 * \sa `ResidualModelAbstractTpl`, `calc()`, `calcDiff()`, `createData()`
34 */
35 template <typename _Scalar>
36 class ResidualModelJointEffortTpl : public ResidualModelAbstractTpl<_Scalar> {
37 public:
38 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
39
40 typedef _Scalar Scalar;
41 typedef MathBaseTpl<Scalar> MathBase;
42 typedef ResidualModelAbstractTpl<Scalar> Base;
43 typedef ResidualDataJointEffortTpl<Scalar> Data;
44 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
45 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
46 typedef StateAbstractTpl<Scalar> StateAbstract;
47 typedef ActuationModelAbstractTpl<Scalar> ActuationModelAbstract;
48 typedef typename MathBase::VectorXs VectorXs;
49 typedef typename MathBase::MatrixXs MatrixXs;
50
51 /**
52 * @brief Initialize the joint-effort residual model
53 *
54 * @param[in] state State description
55 * @param[in] actuation Actuation model
56 * @param[in] uref Reference joint effort
57 * @param[in] nu Dimension of the control vector
58 * @param[in] fwddyn Indicates that we have a forward dynamics problem
59 * (true) or inverse dynamics (false) (default false)
60 */
61 ResidualModelJointEffortTpl(std::shared_ptr<StateAbstract> state,
62 std::shared_ptr<ActuationModelAbstract> actuation,
63 const VectorXs& uref, const std::size_t nu,
64 const bool fwddyn = false);
65
66 /**
67 * @brief Initialize the joint-effort residual model
68 *
69 * The default `nu` value is obtained from `StateAbstractTpl::get_nv()`.
70 *
71 * @param[in] state State description
72 * @param[in] actuation Actuation model
73 * @param[in] uref Reference joint effort
74 */
75 ResidualModelJointEffortTpl(std::shared_ptr<StateAbstract> state,
76 std::shared_ptr<ActuationModelAbstract> actuation,
77 const VectorXs& uref);
78
79 /**
80 * @brief Initialize the joint-effort residual model
81 *
82 * The default reference joint effort is obtained from
83 * `MathBaseTpl<>::VectorXs::Zero(actuation->get_nu())`.
84 *
85 * @param[in] state State description
86 * @param[in] actuation Actuation model
87 * @param[in] nu Dimension of the control vector
88 */
89 ResidualModelJointEffortTpl(std::shared_ptr<StateAbstract> state,
90 std::shared_ptr<ActuationModelAbstract> actuation,
91 const std::size_t nu);
92
93 /**
94 * @brief Initialize the joint-effort residual model
95 *
96 * The default reference joint effort is obtained from
97 * `MathBaseTpl<>::VectorXs::Zero(actuation->get_nu())`. The default `nu`
98 * value is obtained from `StateAbstractTpl::get_nv()`.
99 *
100 * @param[in] state State description
101 * @param[in] actuation Actuation model
102 */
103 ResidualModelJointEffortTpl(
104 std::shared_ptr<StateAbstract> state,
105 std::shared_ptr<ActuationModelAbstract> actuation);
106
107 virtual ~ResidualModelJointEffortTpl();
108
109 /**
110 * @brief Compute the joint-effort residual
111 *
112 * @param[in] data Joint-effort residual data
113 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
114 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
115 */
116 virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
117 const Eigen::Ref<const VectorXs>& x,
118 const Eigen::Ref<const VectorXs>& u);
119
120 /**
121 * @brief @copydoc Base::calc(const std::shared_ptr<ResidualDataAbstract>&
122 * data, const Eigen::Ref<const VectorXs>& x)
123 */
124 virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
125 const Eigen::Ref<const VectorXs>& x);
126
127 /**
128 * @brief Compute the derivatives of the joint-effort residual
129 *
130 * @param[in] data Joint-effort residual data
131 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
132 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
133 */
134 virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
135 const Eigen::Ref<const VectorXs>& x,
136 const Eigen::Ref<const VectorXs>& u);
137
138 /**
139 * @brief @copydoc Base::calcDiff(const
140 * std::shared_ptr<ResidualDataAbstract>& data, const Eigen::Ref<const
141 * VectorXs>& x)
142 */
143 virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
144 const Eigen::Ref<const VectorXs>& x);
145
146 /**
147 * @brief Create the joint-effort residual data
148 */
149 virtual std::shared_ptr<ResidualDataAbstract> createData(
150 DataCollectorAbstract* const data);
151
152 /**
153 * @brief Return the reference joint-effort vector
154 */
155 const VectorXs& get_reference() const;
156
157 /**
158 * @brief Modify the reference joint-effort vector
159 */
160 void set_reference(const VectorXs& reference);
161
162 /**
163 * @brief Print relevant information of the joint-effort residual
164 *
165 * @param[out] os Output stream object
166 */
167 virtual void print(std::ostream& os) const;
168
169 protected:
170 using Base::nr_;
171 using Base::nu_;
172 using Base::q_dependent_;
173 using Base::state_;
174 using Base::v_dependent_;
175
176 private:
177 VectorXs uref_; //!< Reference joint-effort input
178 bool fwddyn_; //!< True for forward dynamics, False for inverse dynamics
179 };
180
181 template <typename _Scalar>
182 struct ResidualDataJointEffortTpl : public ResidualDataAbstractTpl<_Scalar> {
183 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
184
185 typedef _Scalar Scalar;
186 typedef MathBaseTpl<Scalar> MathBase;
187 typedef ResidualDataAbstractTpl<Scalar> Base;
188 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
189
190 template <template <typename Scalar> class Model>
191 48185 ResidualDataJointEffortTpl(Model<Scalar>* const model,
192 DataCollectorAbstract* const data)
193 48185 : Base(model, data) {
194 // Check that proper shared data has been passed
195 48185 DataCollectorJointTpl<Scalar>* d =
196
1/2
✓ Branch 0 taken 48185 times.
✗ Branch 1 not taken.
48185 dynamic_cast<DataCollectorJointTpl<Scalar>*>(shared);
197
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 48185 times.
48185 if (d == nullptr) {
198 throw_pretty(
199 "Invalid argument: the shared data should be derived from "
200 "DataCollectorJoint");
201 }
202 48185 joint = d->joint;
203 48185 }
204
205 std::shared_ptr<JointDataAbstractTpl<Scalar> > joint; //!< Joint data
206 using Base::r;
207 using Base::Ru;
208 using Base::Rx;
209 using Base::shared;
210 };
211
212 } // namespace crocoddyl
213
214 /* --- Details -------------------------------------------------------------- */
215 /* --- Details -------------------------------------------------------------- */
216 /* --- Details -------------------------------------------------------------- */
217 #include "crocoddyl/core/residuals/joint-effort.hxx"
218
219 #endif // CROCODDYL_CORE_RESIDUALS_JOINT_TORQUE_HPP_
220