GCC Code Coverage Report | |||||||||||||||||||||
|
|||||||||||||||||||||
Line | Branch | Exec | Source |
1 |
/////////////////////////////////////////////////////////////////////////////// |
||
2 |
// BSD 3-Clause License |
||
3 |
// |
||
4 |
// Copyright (C) 2019-2023, LAAS-CNRS, University of Edinburgh, |
||
5 |
// University of Oxford, Heriot-Watt University |
||
6 |
// Copyright note valid unless otherwise stated in individual files. |
||
7 |
// All rights reserved. |
||
8 |
/////////////////////////////////////////////////////////////////////////////// |
||
9 |
|||
10 |
#ifndef CROCODDYL_CORE_DIFF_ACTION_BASE_HPP_ |
||
11 |
#define CROCODDYL_CORE_DIFF_ACTION_BASE_HPP_ |
||
12 |
|||
13 |
#include <boost/make_shared.hpp> |
||
14 |
#include <boost/shared_ptr.hpp> |
||
15 |
#include <stdexcept> |
||
16 |
|||
17 |
#include "crocoddyl/core/fwd.hpp" |
||
18 |
#include "crocoddyl/core/state-base.hpp" |
||
19 |
#include "crocoddyl/core/utils/math.hpp" |
||
20 |
|||
21 |
namespace crocoddyl { |
||
22 |
|||
23 |
/** |
||
24 |
* @brief Abstract class for differential action model |
||
25 |
* |
||
26 |
* A differential action model combines dynamics, cost and constraints models. |
||
27 |
* We can use it in each node of our optimal control problem thanks to dedicated |
||
28 |
* integration rules (e.g., `IntegratedActionModelEulerTpl` or |
||
29 |
* `IntegratedActionModelRK4Tpl`). These integrated action models produce action |
||
30 |
* models (`ActionModelAbstractTpl`). Thus, every time that we want to describe |
||
31 |
* a problem, we need to provide ways of computing the dynamics, cost, |
||
32 |
* constraints functions and their derivatives. All these are described inside |
||
33 |
* the differential action model. |
||
34 |
* |
||
35 |
* Concretely speaking, the differential action model is the time-continuous |
||
36 |
* version of an action model, i.e., \f[ \begin{aligned} |
||
37 |
* &\dot{\mathbf{v}} = \mathbf{f}(\mathbf{q}, \mathbf{v}, \mathbf{u}), |
||
38 |
* &\textrm{(dynamics)}\\ |
||
39 |
* &\ell(\mathbf{q}, \mathbf{v},\mathbf{u}) = \int_0^{\delta t} |
||
40 |
* a(\mathbf{r}(\mathbf{q}, \mathbf{v},\mathbf{u}))\,dt, |
||
41 |
* &\textrm{(cost)}\\ |
||
42 |
* &\mathbf{g}(\mathbf{q}, \mathbf{v},\mathbf{u})<\mathbf{0}, |
||
43 |
* &\textrm{(inequality constraint)}\\ |
||
44 |
* &\mathbf{h}(\mathbf{q}, \mathbf{v},\mathbf{u})=\mathbf{0}, &\textrm{(equality |
||
45 |
* constraint)} \end{aligned} \f] where |
||
46 |
* - the configuration \f$\mathbf{q}\in\mathcal{Q}\f$ lies in the configuration |
||
47 |
* manifold described with a `nq`-tuple, |
||
48 |
* - the velocity \f$\mathbf{v}\in T_{\mathbf{q}}\mathcal{Q}\f$ is the tangent |
||
49 |
* vector to the configuration manifold with `nv` dimension, |
||
50 |
* - the control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$ is an Euclidean |
||
51 |
* vector, |
||
52 |
* - \f$\mathbf{r}(\cdot)\f$ and \f$a(\cdot)\f$ are the residual and activation |
||
53 |
* functions (see `ResidualModelAbstractTpl` and `ActivationModelAbstractTpl`, |
||
54 |
* respectively), |
||
55 |
* - \f$\mathbf{g}(\cdot)\in\mathbb{R}^{ng}\f$ and |
||
56 |
* \f$\mathbf{h}(\cdot)\in\mathbb{R}^{nh}\f$ are the inequality and equality |
||
57 |
* vector functions, respectively. |
||
58 |
* |
||
59 |
* Both configuration and velocity describe the system space |
||
60 |
* \f$\mathbf{x}=(\mathbf{q}, \mathbf{v})\in\mathcal{X}\f$ which lies in the |
||
61 |
* state manifold. Note that the acceleration \f$\dot{\mathbf{v}}\in |
||
62 |
* T_{\mathbf{q}}\mathcal{Q}\f$ lies also in the tangent space of the |
||
63 |
* configuration manifold. The computation of these equations are carried out |
||
64 |
* inside `calc()` function. In short, this function computes the system |
||
65 |
* acceleration, cost and constraints values (also called constraints |
||
66 |
* violations). This procedure is equivalent to running a forward pass of the |
||
67 |
* action model. |
||
68 |
* |
||
69 |
* However, during numerical optimization, we also need to run backward passes |
||
70 |
* of the differential action model. These calculations are performed by |
||
71 |
* `calcDiff()`. In short, this function builds a linear-quadratic approximation |
||
72 |
* of the differential action model, i.e., \f[ \begin{aligned} |
||
73 |
* &\delta\dot{\mathbf{v}} = |
||
74 |
* \mathbf{f_{q}}\delta\mathbf{q}+\mathbf{f_{v}}\delta\mathbf{v}+\mathbf{f_{u}}\delta\mathbf{u}, |
||
75 |
* &\textrm{(dynamics)}\\ |
||
76 |
* &\ell(\delta\mathbf{q},\delta\mathbf{v},\delta\mathbf{u}) = \begin{bmatrix}1 |
||
77 |
* \\ \delta\mathbf{q} \\ \delta\mathbf{v} |
||
78 |
* \\ \delta\mathbf{u}\end{bmatrix}^T \begin{bmatrix}0 & \mathbf{\ell_q}^T & |
||
79 |
* \mathbf{\ell_v}^T & \mathbf{\ell_u}^T \\ \mathbf{\ell_q} & \mathbf{\ell_{qq}} |
||
80 |
* & |
||
81 |
* \mathbf{\ell_{qv}} & \mathbf{\ell_{uq}}^T \\ |
||
82 |
* \mathbf{\ell_v} & \mathbf{\ell_{vq}} & \mathbf{\ell_{vv}} & |
||
83 |
* \mathbf{\ell_{uv}}^T \\ |
||
84 |
* \mathbf{\ell_u} & \mathbf{\ell_{uq}} & \mathbf{\ell_{uv}} & |
||
85 |
* \mathbf{\ell_{uu}}\end{bmatrix} \begin{bmatrix}1 \\ \delta\mathbf{q} |
||
86 |
* \\ \delta\mathbf{v} \\ |
||
87 |
* \delta\mathbf{u}\end{bmatrix}, &\textrm{(cost)}\\ |
||
88 |
* &\mathbf{g_q}\delta\mathbf{q}+\mathbf{g_v}\delta\mathbf{v}+\mathbf{g_u}\delta\mathbf{u}\leq\mathbf{0}, |
||
89 |
* &\textrm{(inequality constraints)}\\ |
||
90 |
* &\mathbf{h_q}\delta\mathbf{q}+\mathbf{h_v}\delta\mathbf{v}+\mathbf{h_u}\delta\mathbf{u}=\mathbf{0}, |
||
91 |
* &\textrm{(equality constraints)} \end{aligned} \f] where |
||
92 |
* - \f$\mathbf{f_x}=(\mathbf{f_q};\,\, \mathbf{f_v})\in\mathbb{R}^{nv\times |
||
93 |
* ndx}\f$ and \f$\mathbf{f_u}\in\mathbb{R}^{nv\times nu}\f$ are the Jacobians |
||
94 |
* of the dynamics, |
||
95 |
* - \f$\mathbf{\ell_x}=(\mathbf{\ell_q};\,\, |
||
96 |
* \mathbf{\ell_v})\in\mathbb{R}^{ndx}\f$ and |
||
97 |
* \f$\mathbf{\ell_u}\in\mathbb{R}^{nu}\f$ are the Jacobians of the cost |
||
98 |
* function, |
||
99 |
* - \f$\mathbf{\ell_{xx}}=(\mathbf{\ell_{qq}}\,\, \mathbf{\ell_{qv}};\,\, |
||
100 |
* \mathbf{\ell_{vq}}\, \mathbf{\ell_{vv}})\in\mathbb{R}^{ndx\times ndx}\f$, |
||
101 |
* \f$\mathbf{\ell_{xu}}=(\mathbf{\ell_q};\,\, |
||
102 |
* \mathbf{\ell_v})\in\mathbb{R}^{ndx\times nu}\f$ and |
||
103 |
* \f$\mathbf{\ell_{uu}}\in\mathbb{R}^{nu\times nu}\f$ are the Hessians of the |
||
104 |
* cost function, |
||
105 |
* - \f$\mathbf{g_x}=(\mathbf{g_q};\,\, \mathbf{g_v})\in\mathbb{R}^{ng\times |
||
106 |
* ndx}\f$ and \f$\mathbf{g_u}\in\mathbb{R}^{ng\times nu}\f$ are the Jacobians |
||
107 |
* of the inequality constraints, and |
||
108 |
* - \f$\mathbf{h_x}=(\mathbf{h_q};\,\, \mathbf{h_v})\in\mathbb{R}^{nh\times |
||
109 |
* ndx}\f$ and \f$\mathbf{h_u}\in\mathbb{R}^{nh\times nu}\f$ are the Jacobians |
||
110 |
* of the equality constraints. |
||
111 |
* |
||
112 |
* Additionally, it is important to note that `calcDiff()` computes the |
||
113 |
* derivatives using the latest stored values by `calc()`. Thus, we need to |
||
114 |
* first run `calc()`. |
||
115 |
* |
||
116 |
* \sa `ActionModelAbstractTpl`, `calc()`, `calcDiff()`, `createData()` |
||
117 |
*/ |
||
118 |
template <typename _Scalar> |
||
119 |
class DifferentialActionModelAbstractTpl { |
||
120 |
public: |
||
121 |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
||
122 |
|||
123 |
typedef _Scalar Scalar; |
||
124 |
typedef MathBaseTpl<Scalar> MathBase; |
||
125 |
typedef DifferentialActionDataAbstractTpl<Scalar> |
||
126 |
DifferentialActionDataAbstract; |
||
127 |
typedef StateAbstractTpl<Scalar> StateAbstract; |
||
128 |
typedef typename MathBase::VectorXs VectorXs; |
||
129 |
typedef typename MathBase::MatrixXs MatrixXs; |
||
130 |
|||
131 |
/** |
||
132 |
* @brief Initialize the differential action model |
||
133 |
* |
||
134 |
* @param[in] state State description |
||
135 |
* @param[in] nu Dimension of control vector |
||
136 |
* @param[in] nr Dimension of cost-residual vector |
||
137 |
* @param[in] ng Number of inequality constraints |
||
138 |
* @param[in] nh Number of equality constraints |
||
139 |
*/ |
||
140 |
DifferentialActionModelAbstractTpl(boost::shared_ptr<StateAbstract> state, |
||
141 |
const std::size_t nu, |
||
142 |
const std::size_t nr = 0, |
||
143 |
const std::size_t ng = 0, |
||
144 |
const std::size_t nh = 0); |
||
145 |
virtual ~DifferentialActionModelAbstractTpl(); |
||
146 |
|||
147 |
/** |
||
148 |
* @brief Compute the system acceleration and cost value |
||
149 |
* |
||
150 |
* @param[in] data Differential action data |
||
151 |
* @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ |
||
152 |
* @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$ |
||
153 |
*/ |
||
154 |
virtual void calc( |
||
155 |
const boost::shared_ptr<DifferentialActionDataAbstract>& data, |
||
156 |
const Eigen::Ref<const VectorXs>& x, |
||
157 |
const Eigen::Ref<const VectorXs>& u) = 0; |
||
158 |
|||
159 |
/** |
||
160 |
* @brief Compute the total cost value for nodes that depends only on the |
||
161 |
* state |
||
162 |
* |
||
163 |
* It updates the total cost and the system acceleration is not updated as the |
||
164 |
* control input is undefined. This function is used in the terminal nodes of |
||
165 |
* an optimal control problem. |
||
166 |
* |
||
167 |
* @param[in] data Differential action data |
||
168 |
* @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ |
||
169 |
*/ |
||
170 |
virtual void calc( |
||
171 |
const boost::shared_ptr<DifferentialActionDataAbstract>& data, |
||
172 |
const Eigen::Ref<const VectorXs>& x); |
||
173 |
|||
174 |
/** |
||
175 |
* @brief Compute the derivatives of the dynamics and cost functions |
||
176 |
* |
||
177 |
* It computes the partial derivatives of the dynamical system and the cost |
||
178 |
* function. It assumes that `calc()` has been run first. This function builds |
||
179 |
* a quadratic approximation of the time-continuous action model (i.e. |
||
180 |
* dynamical system and cost function). |
||
181 |
* |
||
182 |
* @param[in] data Differential action data |
||
183 |
* @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ |
||
184 |
* @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$ |
||
185 |
*/ |
||
186 |
virtual void calcDiff( |
||
187 |
const boost::shared_ptr<DifferentialActionDataAbstract>& data, |
||
188 |
const Eigen::Ref<const VectorXs>& x, |
||
189 |
const Eigen::Ref<const VectorXs>& u) = 0; |
||
190 |
|||
191 |
/** |
||
192 |
* @brief Compute the derivatives of the cost functions with respect to the |
||
193 |
* state only |
||
194 |
* |
||
195 |
* It updates the derivatives of the cost function with respect to the state |
||
196 |
* only. This function is used in the terminal nodes of an optimal control |
||
197 |
* problem. |
||
198 |
* |
||
199 |
* @param[in] data Differential action data |
||
200 |
* @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ |
||
201 |
*/ |
||
202 |
virtual void calcDiff( |
||
203 |
const boost::shared_ptr<DifferentialActionDataAbstract>& data, |
||
204 |
const Eigen::Ref<const VectorXs>& x); |
||
205 |
|||
206 |
/** |
||
207 |
* @brief Create the differential action data |
||
208 |
* |
||
209 |
* @return the differential action data |
||
210 |
*/ |
||
211 |
virtual boost::shared_ptr<DifferentialActionDataAbstract> createData(); |
||
212 |
|||
213 |
/** |
||
214 |
* @brief Checks that a specific data belongs to this model |
||
215 |
*/ |
||
216 |
virtual bool checkData( |
||
217 |
const boost::shared_ptr<DifferentialActionDataAbstract>& data); |
||
218 |
|||
219 |
/** |
||
220 |
* @brief Computes the quasic static commands |
||
221 |
* |
||
222 |
* The quasic static commands are the ones produced for a the reference |
||
223 |
* posture as an equilibrium point, i.e. for |
||
224 |
* \f$\mathbf{f}(\mathbf{q},\mathbf{v}=\mathbf{0},\mathbf{u})=\mathbf{0}\f$ |
||
225 |
* |
||
226 |
* @param[in] data Differential action data |
||
227 |
* @param[out] u Quasic static commands |
||
228 |
* @param[in] x State point (velocity has to be zero) |
||
229 |
* @param[in] maxiter Maximum allowed number of iterations |
||
230 |
* @param[in] tol Tolerance |
||
231 |
*/ |
||
232 |
virtual void quasiStatic( |
||
233 |
const boost::shared_ptr<DifferentialActionDataAbstract>& data, |
||
234 |
Eigen::Ref<VectorXs> u, const Eigen::Ref<const VectorXs>& x, |
||
235 |
const std::size_t maxiter = 100, const Scalar tol = Scalar(1e-9)); |
||
236 |
|||
237 |
/** |
||
238 |
* @copybrief quasicStatic() |
||
239 |
* |
||
240 |
* @copydetails quasicStatic() |
||
241 |
* |
||
242 |
* @param[in] data Differential action data |
||
243 |
* @param[in] x State point (velocity has to be zero) |
||
244 |
* @param[in] maxiter Maximum allowed number of iterations |
||
245 |
* @param[in] tol Tolerance |
||
246 |
* @return Quasic static commands |
||
247 |
*/ |
||
248 |
VectorXs quasiStatic_x( |
||
249 |
const boost::shared_ptr<DifferentialActionDataAbstract>& data, |
||
250 |
const VectorXs& x, const std::size_t maxiter = 100, |
||
251 |
const Scalar tol = Scalar(1e-9)); |
||
252 |
|||
253 |
/** |
||
254 |
* @brief Return the dimension of the control input |
||
255 |
*/ |
||
256 |
std::size_t get_nu() const; |
||
257 |
|||
258 |
/** |
||
259 |
* @brief Return the dimension of the cost-residual vector |
||
260 |
*/ |
||
261 |
std::size_t get_nr() const; |
||
262 |
|||
263 |
/** |
||
264 |
* @brief Return the number of inequality constraints |
||
265 |
*/ |
||
266 |
virtual std::size_t get_ng() const; |
||
267 |
|||
268 |
/** |
||
269 |
* @brief Return the number of equality constraints |
||
270 |
*/ |
||
271 |
virtual std::size_t get_nh() const; |
||
272 |
|||
273 |
/** |
||
274 |
* @brief Return the state |
||
275 |
*/ |
||
276 |
const boost::shared_ptr<StateAbstract>& get_state() const; |
||
277 |
|||
278 |
/** |
||
279 |
* @brief Return the lower bound of the inequality constraints |
||
280 |
*/ |
||
281 |
virtual const VectorXs& get_g_lb() const; |
||
282 |
|||
283 |
/** |
||
284 |
* @brief Return the upper bound of the inequality constraints |
||
285 |
*/ |
||
286 |
virtual const VectorXs& get_g_ub() const; |
||
287 |
|||
288 |
/** |
||
289 |
* @brief Return the control lower bound |
||
290 |
*/ |
||
291 |
const VectorXs& get_u_lb() const; |
||
292 |
|||
293 |
/** |
||
294 |
* @brief Return the control upper bound |
||
295 |
*/ |
||
296 |
const VectorXs& get_u_ub() const; |
||
297 |
|||
298 |
/** |
||
299 |
* @brief Indicates if there are defined control limits |
||
300 |
*/ |
||
301 |
bool get_has_control_limits() const; |
||
302 |
|||
303 |
/** |
||
304 |
* @brief Modify the lower bound of the inequality constraints |
||
305 |
*/ |
||
306 |
void set_g_lb(const VectorXs& g_lb); |
||
307 |
|||
308 |
/** |
||
309 |
* @brief Modify the upper bound of the inequality constraints |
||
310 |
*/ |
||
311 |
void set_g_ub(const VectorXs& g_ub); |
||
312 |
|||
313 |
/** |
||
314 |
* @brief Modify the control lower bounds |
||
315 |
*/ |
||
316 |
void set_u_lb(const VectorXs& u_lb); |
||
317 |
|||
318 |
/** |
||
319 |
* @brief Modify the control upper bounds |
||
320 |
*/ |
||
321 |
void set_u_ub(const VectorXs& u_ub); |
||
322 |
|||
323 |
/** |
||
324 |
* @brief Print information on the differential action model |
||
325 |
*/ |
||
326 |
template <class Scalar> |
||
327 |
friend std::ostream& operator<<( |
||
328 |
std::ostream& os, |
||
329 |
const DifferentialActionModelAbstractTpl<Scalar>& model); |
||
330 |
|||
331 |
/** |
||
332 |
* @brief Print relevant information of the differential action model |
||
333 |
* |
||
334 |
* @param[out] os Output stream object |
||
335 |
*/ |
||
336 |
virtual void print(std::ostream& os) const; |
||
337 |
|||
338 |
private: |
||
339 |
std::size_t ng_internal_; //!< Internal object for storing the number of |
||
340 |
//!< inequality constraints |
||
341 |
std::size_t nh_internal_; //!< Internal object for storing the number of |
||
342 |
//!< equality constraints |
||
343 |
|||
344 |
protected: |
||
345 |
std::size_t nu_; //!< Control dimension |
||
346 |
std::size_t nr_; //!< Dimension of the cost residual |
||
347 |
std::size_t ng_; //!< Number of inequality constraints |
||
348 |
std::size_t nh_; //!< Number of equality constraints |
||
349 |
boost::shared_ptr<StateAbstract> state_; //!< Model of the state |
||
350 |
VectorXs unone_; //!< Neutral state |
||
351 |
VectorXs g_lb_; //!< Lower bound of the inequality constraints |
||
352 |
VectorXs g_ub_; //!< Lower bound of the inequality constraints |
||
353 |
VectorXs u_lb_; //!< Lower control limits |
||
354 |
VectorXs u_ub_; //!< Upper control limits |
||
355 |
bool has_control_limits_; //!< Indicates whether any of the control limits is |
||
356 |
//!< finite |
||
357 |
|||
358 |
/** |
||
359 |
* @brief Update the status of the control limits (i.e. if there are defined |
||
360 |
* limits) |
||
361 |
*/ |
||
362 |
void update_has_control_limits(); |
||
363 |
|||
364 |
template <class Scalar> |
||
365 |
friend class IntegratedActionModelAbstractTpl; |
||
366 |
template <class Scalar> |
||
367 |
friend class ConstraintModelManagerTpl; |
||
368 |
}; |
||
369 |
|||
370 |
template <typename _Scalar> |
||
371 |
struct DifferentialActionDataAbstractTpl { |
||
372 |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
||
373 |
|||
374 |
typedef _Scalar Scalar; |
||
375 |
typedef MathBaseTpl<Scalar> MathBase; |
||
376 |
typedef typename MathBase::VectorXs VectorXs; |
||
377 |
typedef typename MathBase::MatrixXs MatrixXs; |
||
378 |
|||
379 |
template <template <typename Scalar> class Model> |
||
380 |
210012 |
explicit DifferentialActionDataAbstractTpl(Model<Scalar>* const model) |
|
381 |
: cost(Scalar(0.)), |
||
382 |
210012 |
xout(model->get_state()->get_nv()), |
|
383 |
420024 |
Fx(model->get_state()->get_nv(), model->get_state()->get_ndx()), |
|
384 |
210012 |
Fu(model->get_state()->get_nv(), model->get_nu()), |
|
385 |
r(model->get_nr()), |
||
386 |
210012 |
Lx(model->get_state()->get_ndx()), |
|
387 |
Lu(model->get_nu()), |
||
388 |
420024 |
Lxx(model->get_state()->get_ndx(), model->get_state()->get_ndx()), |
|
389 |
210012 |
Lxu(model->get_state()->get_ndx(), model->get_nu()), |
|
390 |
Luu(model->get_nu(), model->get_nu()), |
||
391 |
g(model->get_ng()), |
||
392 |
210012 |
Gx(model->get_ng(), model->get_state()->get_ndx()), |
|
393 |
Gu(model->get_ng(), model->get_nu()), |
||
394 |
h(model->get_nh()), |
||
395 |
210012 |
Hx(model->get_nh(), model->get_state()->get_ndx()), |
|
396 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
210012 |
Hu(model->get_nh(), model->get_nu()) { |
397 |
✓✗ | 210012 |
xout.setZero(); |
398 |
✓✗ | 210012 |
Fx.setZero(); |
399 |
✓✗ | 210012 |
Fu.setZero(); |
400 |
✓✗ | 210012 |
r.setZero(); |
401 |
✓✗ | 210012 |
Lx.setZero(); |
402 |
✓✗ | 210012 |
Lu.setZero(); |
403 |
✓✗ | 210012 |
Lxx.setZero(); |
404 |
✓✗ | 210012 |
Lxu.setZero(); |
405 |
✓✗ | 210012 |
Luu.setZero(); |
406 |
✓✗ | 210012 |
g.setZero(); |
407 |
✓✗ | 210012 |
Gx.setZero(); |
408 |
✓✗ | 210012 |
Gu.setZero(); |
409 |
✓✗ | 210012 |
h.setZero(); |
410 |
✓✗ | 210012 |
Hx.setZero(); |
411 |
✓✗ | 210012 |
Hu.setZero(); |
412 |
210012 |
} |
|
413 |
105006 |
virtual ~DifferentialActionDataAbstractTpl() {} |
|
414 |
|||
415 |
Scalar cost; //!< cost value |
||
416 |
VectorXs xout; //!< evolution state |
||
417 |
MatrixXs Fx; //!< Jacobian of the dynamics w.r.t. the state \f$\mathbf{x}\f$ |
||
418 |
MatrixXs |
||
419 |
Fu; //!< Jacobian of the dynamics w.r.t. the control \f$\mathbf{u}\f$ |
||
420 |
VectorXs r; //!< Cost residual |
||
421 |
VectorXs Lx; //!< Jacobian of the cost w.r.t. the state \f$\mathbf{x}\f$ |
||
422 |
VectorXs Lu; //!< Jacobian of the cost w.r.t. the control \f$\mathbf{u}\f$ |
||
423 |
MatrixXs Lxx; //!< Hessian of the cost w.r.t. the state \f$\mathbf{x}\f$ |
||
424 |
MatrixXs Lxu; //!< Hessian of the cost w.r.t. the state \f$\mathbf{x}\f$ and |
||
425 |
//!< control u |
||
426 |
MatrixXs Luu; //!< Hessian of the cost w.r.t. the control \f$\mathbf{u}\f$ |
||
427 |
VectorXs g; //!< Inequality constraint values |
||
428 |
MatrixXs Gx; //!< Jacobian of the inequality constraint w.r.t. the state |
||
429 |
//!< \f$\mathbf{x}\f$ |
||
430 |
MatrixXs Gu; //!< Jacobian of the inequality constraint w.r.t. the control |
||
431 |
//!< \f$\mathbf{u}\f$ |
||
432 |
VectorXs h; //!< Equality constraint values |
||
433 |
MatrixXs Hx; //!< Jacobian of the equality constraint w.r.t. the state |
||
434 |
//!< \f$\mathbf{x}\f$ |
||
435 |
MatrixXs Hu; //!< Jacobian of the equality constraint w.r.t the control |
||
436 |
//!< \f$\mathbf{u}\f$ |
||
437 |
}; |
||
438 |
|||
439 |
} // namespace crocoddyl |
||
440 |
|||
441 |
/* --- Details -------------------------------------------------------------- */ |
||
442 |
/* --- Details -------------------------------------------------------------- */ |
||
443 |
/* --- Details -------------------------------------------------------------- */ |
||
444 |
#include "crocoddyl/core/diff-action-base.hxx" |
||
445 |
|||
446 |
#endif // CROCODDYL_CORE_DIFF_ACTION_BASE_HPP_ |
Generated by: GCOVR (Version 4.2) |