Line |
Branch |
Exec |
Source |
1 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
2 |
|
|
// BSD 3-Clause License |
3 |
|
|
// |
4 |
|
|
// Copyright (C) 2019-2025, University of Edinburgh, Heriot-Watt University |
5 |
|
|
// Copyright note valid unless otherwise stated in individual files. |
6 |
|
|
// All rights reserved. |
7 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
8 |
|
|
|
9 |
|
|
#ifndef CROCODDYL_ACTUATION_FACTORY_HPP_ |
10 |
|
|
#define CROCODDYL_ACTUATION_FACTORY_HPP_ |
11 |
|
|
|
12 |
|
|
#include "crocoddyl/core/actuation-base.hpp" |
13 |
|
|
#include "crocoddyl/core/numdiff/actuation.hpp" |
14 |
|
|
#include "state.hpp" |
15 |
|
|
|
16 |
|
|
namespace crocoddyl { |
17 |
|
|
namespace unittest { |
18 |
|
|
|
19 |
|
|
struct ActuationModelTypes { |
20 |
|
|
enum Type { |
21 |
|
|
ActuationModelFull, |
22 |
|
|
ActuationModelFloatingBase, |
23 |
|
|
ActuationModelFloatingBaseThrusters, |
24 |
|
|
ActuationModelSquashingFull, |
25 |
|
|
NbActuationModelTypes |
26 |
|
|
}; |
27 |
|
✗ |
static std::vector<Type> init_all() { |
28 |
|
✗ |
std::vector<Type> v; |
29 |
|
✗ |
v.reserve(NbActuationModelTypes); |
30 |
|
✗ |
for (int i = 0; i < NbActuationModelTypes; ++i) { |
31 |
|
✗ |
v.push_back((Type)i); |
32 |
|
|
} |
33 |
|
✗ |
return v; |
34 |
|
|
} |
35 |
|
|
static const std::vector<Type> all; |
36 |
|
|
}; |
37 |
|
|
|
38 |
|
|
std::ostream& operator<<(std::ostream& os, ActuationModelTypes::Type type); |
39 |
|
|
|
40 |
|
|
class ActuationModelFactory { |
41 |
|
|
public: |
42 |
|
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
43 |
|
|
|
44 |
|
|
explicit ActuationModelFactory(); |
45 |
|
|
~ActuationModelFactory(); |
46 |
|
|
|
47 |
|
|
std::shared_ptr<crocoddyl::ActuationModelAbstract> create( |
48 |
|
|
ActuationModelTypes::Type actuation_type, |
49 |
|
|
StateModelTypes::Type state_type) const; |
50 |
|
|
}; |
51 |
|
|
|
52 |
|
|
/** |
53 |
|
|
* @brief Update the actuation model needed for numerical differentiation. |
54 |
|
|
* We use the address of the object to avoid a copy from the |
55 |
|
|
* "boost::bind". |
56 |
|
|
* |
57 |
|
|
* @param model[in] Pinocchio model |
58 |
|
|
* @param data[out] Pinocchio data |
59 |
|
|
* @param x[in] State vector |
60 |
|
|
* @param u[in] Control vector |
61 |
|
|
*/ |
62 |
|
|
template <typename Scalar> |
63 |
|
|
void updateActuation( |
64 |
|
|
const std::shared_ptr<crocoddyl::ActuationModelAbstractTpl<Scalar>>& model, |
65 |
|
|
const std::shared_ptr<crocoddyl::ActuationDataAbstractTpl<Scalar>>& data, |
66 |
|
|
const Eigen::Matrix<Scalar, Eigen::Dynamic, 1>& x, |
67 |
|
|
const Eigen::Matrix<Scalar, Eigen::Dynamic, 1>& u); |
68 |
|
|
|
69 |
|
|
} // namespace unittest |
70 |
|
|
} // namespace crocoddyl |
71 |
|
|
|
72 |
|
|
/* --- Details -------------------------------------------------------------- */ |
73 |
|
|
/* --- Details -------------------------------------------------------------- */ |
74 |
|
|
/* --- Details -------------------------------------------------------------- */ |
75 |
|
|
#include "actuation.hxx" |
76 |
|
|
|
77 |
|
|
#endif // CROCODDYL_ACTUATION_FACTORY_HPP_ |
78 |
|
|
|