GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/core/residuals/joint-effort.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) 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(
62 boost::shared_ptr<StateAbstract> state,
63 boost::shared_ptr<ActuationModelAbstract> actuation, const VectorXs& uref,
64 const std::size_t nu, 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(
76 boost::shared_ptr<StateAbstract> state,
77 boost::shared_ptr<ActuationModelAbstract> actuation,
78 const VectorXs& uref);
79
80 /**
81 * @brief Initialize the joint-effort residual model
82 *
83 * The default reference joint effort is obtained from
84 * `MathBaseTpl<>::VectorXs::Zero(actuation->get_nu())`.
85 *
86 * @param[in] state State description
87 * @param[in] actuation Actuation model
88 * @param[in] nu Dimension of the control vector
89 */
90 ResidualModelJointEffortTpl(
91 boost::shared_ptr<StateAbstract> state,
92 boost::shared_ptr<ActuationModelAbstract> actuation,
93 const std::size_t nu);
94
95 /**
96 * @brief Initialize the joint-effort residual model
97 *
98 * The default reference joint effort is obtained from
99 * `MathBaseTpl<>::VectorXs::Zero(actuation->get_nu())`. The default `nu`
100 * value is obtained from `StateAbstractTpl::get_nv()`.
101 *
102 * @param[in] state State description
103 * @param[in] actuation Actuation model
104 */
105 ResidualModelJointEffortTpl(
106 boost::shared_ptr<StateAbstract> state,
107 boost::shared_ptr<ActuationModelAbstract> actuation);
108
109 virtual ~ResidualModelJointEffortTpl();
110
111 /**
112 * @brief Compute the joint-effort residual
113 *
114 * @param[in] data Joint-effort residual data
115 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
116 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
117 */
118 virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
119 const Eigen::Ref<const VectorXs>& x,
120 const Eigen::Ref<const VectorXs>& u);
121
122 /**
123 * @brief @copydoc Base::calc(const boost::shared_ptr<ResidualDataAbstract>&
124 * data, const Eigen::Ref<const VectorXs>& x)
125 */
126 virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
127 const Eigen::Ref<const VectorXs>& x);
128
129 /**
130 * @brief Compute the derivatives of the joint-effort residual
131 *
132 * @param[in] data Joint-effort residual data
133 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
134 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
135 */
136 virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
137 const Eigen::Ref<const VectorXs>& x,
138 const Eigen::Ref<const VectorXs>& u);
139
140 /**
141 * @brief @copydoc Base::calcDiff(const
142 * boost::shared_ptr<ResidualDataAbstract>& data, const Eigen::Ref<const
143 * VectorXs>& x)
144 */
145 virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
146 const Eigen::Ref<const VectorXs>& x);
147
148 /**
149 * @brief Create the joint-effort residual data
150 */
151 virtual boost::shared_ptr<ResidualDataAbstract> createData(
152 DataCollectorAbstract* const data);
153
154 /**
155 * @brief Return the reference joint-effort vector
156 */
157 const VectorXs& get_reference() const;
158
159 /**
160 * @brief Modify the reference joint-effort vector
161 */
162 void set_reference(const VectorXs& reference);
163
164 /**
165 * @brief Print relevant information of the joint-effort residual
166 *
167 * @param[out] os Output stream object
168 */
169 virtual void print(std::ostream& os) const;
170
171 protected:
172 using Base::nr_;
173 using Base::nu_;
174 using Base::q_dependent_;
175 using Base::state_;
176 using Base::v_dependent_;
177
178 private:
179 VectorXs uref_; //!< Reference joint-effort input
180 bool fwddyn_; //!< True for forward dynamics, False for inverse dynamics
181 };
182
183 template <typename _Scalar>
184 struct ResidualDataJointEffortTpl : public ResidualDataAbstractTpl<_Scalar> {
185 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
186
187 typedef _Scalar Scalar;
188 typedef MathBaseTpl<Scalar> MathBase;
189 typedef ResidualDataAbstractTpl<Scalar> Base;
190 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
191
192 template <template <typename Scalar> class Model>
193 48185 ResidualDataJointEffortTpl(Model<Scalar>* const model,
194 DataCollectorAbstract* const data)
195 48185 : Base(model, data) {
196 // Check that proper shared data has been passed
197 48185 DataCollectorJointTpl<Scalar>* d =
198
1/2
✓ Branch 0 taken 48185 times.
✗ Branch 1 not taken.
48185 dynamic_cast<DataCollectorJointTpl<Scalar>*>(shared);
199
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 48185 times.
48185 if (d == nullptr) {
200 throw_pretty(
201 "Invalid argument: the shared data should be derived from "
202 "DataCollectorJoint");
203 }
204 48185 joint = d->joint;
205 48185 }
206
207 boost::shared_ptr<JointDataAbstractTpl<Scalar> > joint; //!< Joint 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/core/residuals/joint-effort.hxx"
220
221 #endif // CROCODDYL_CORE_RESIDUALS_JOINT_TORQUE_HPP_
222