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_PINOCCHIO_MODEL_FACTORY_HPP_ |
10 |
|
|
#define CROCODDYL_PINOCCHIO_MODEL_FACTORY_HPP_ |
11 |
|
|
|
12 |
|
|
#include <pinocchio/fwd.hpp> |
13 |
|
|
#include <pinocchio/multibody/data.hpp> |
14 |
|
|
#include <pinocchio/multibody/model.hpp> |
15 |
|
|
|
16 |
|
|
#include "crocoddyl/core/utils/exception.hpp" |
17 |
|
|
|
18 |
|
|
namespace crocoddyl { |
19 |
|
|
namespace unittest { |
20 |
|
|
|
21 |
|
|
struct PinocchioModelTypes { |
22 |
|
|
enum Type { |
23 |
|
|
Hector, |
24 |
|
|
TalosArm, |
25 |
|
|
HyQ, |
26 |
|
|
Talos, |
27 |
|
|
RandomHumanoid, |
28 |
|
|
NbPinocchioModelTypes |
29 |
|
|
}; |
30 |
|
✗ |
static std::vector<Type> init_all() { |
31 |
|
✗ |
std::vector<Type> v; |
32 |
|
✗ |
v.reserve(NbPinocchioModelTypes); |
33 |
|
✗ |
for (int i = 0; i < NbPinocchioModelTypes; ++i) { |
34 |
|
✗ |
v.push_back((Type)i); |
35 |
|
|
} |
36 |
|
✗ |
return v; |
37 |
|
|
} |
38 |
|
|
static const std::vector<Type> all; |
39 |
|
|
}; |
40 |
|
|
|
41 |
|
|
std::ostream& operator<<(std::ostream& os, PinocchioModelTypes::Type type); |
42 |
|
|
|
43 |
|
|
class PinocchioModelFactory { |
44 |
|
|
public: |
45 |
|
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
46 |
|
|
|
47 |
|
|
PinocchioModelFactory(PinocchioModelTypes::Type type); |
48 |
|
|
~PinocchioModelFactory(); |
49 |
|
|
|
50 |
|
|
void construct_model(const std::string& urdf_file = "", |
51 |
|
|
const std::string& srdf_file = "", |
52 |
|
|
bool free_flyer = true); |
53 |
|
|
|
54 |
|
|
std::shared_ptr<pinocchio::Model> create() const; |
55 |
|
|
std::vector<std::string> get_frame_names() const; |
56 |
|
|
std::vector<std::size_t> get_frame_ids() const; |
57 |
|
|
std::size_t get_contact_nc() const; |
58 |
|
|
|
59 |
|
|
private: |
60 |
|
|
std::shared_ptr<pinocchio::Model> |
61 |
|
|
model_; //!< The pointer to the state in testing |
62 |
|
|
std::vector<std::string> frame_name_; //!< Frame name for unittesting |
63 |
|
|
std::vector<std::size_t> frame_id_; //!< Frame id for unittesting |
64 |
|
|
std::size_t contact_nc_; //!< Dimension of the contact |
65 |
|
|
}; |
66 |
|
|
|
67 |
|
|
/** |
68 |
|
|
* @brief Compute all the pinocchio data needed for the numerical |
69 |
|
|
* differentiation. We use the address of the object to avoid a copy from the |
70 |
|
|
* "boost::bind". |
71 |
|
|
* |
72 |
|
|
* @param model[in] Pinocchio model |
73 |
|
|
* @param data[out] Pinocchio data |
74 |
|
|
* @param x[in] State vector |
75 |
|
|
* @param u[in] Control vector |
76 |
|
|
*/ |
77 |
|
|
template <typename Scalar, int Options, |
78 |
|
|
template <typename, int> class JointCollectionTpl> |
79 |
|
|
void updateAllPinocchio( |
80 |
|
|
pinocchio::ModelTpl<Scalar, Options, JointCollectionTpl>* const model, |
81 |
|
|
pinocchio::DataTpl<Scalar, Options, JointCollectionTpl>* data, |
82 |
|
|
const Eigen::Matrix<Scalar, Eigen::Dynamic, 1>& x, |
83 |
|
|
const Eigen::Matrix<Scalar, Eigen::Dynamic, 1>& u = |
84 |
|
|
Eigen::Matrix<Scalar, Eigen::Dynamic, 1>()); |
85 |
|
|
|
86 |
|
|
} // namespace unittest |
87 |
|
|
} // namespace crocoddyl |
88 |
|
|
|
89 |
|
|
/* --- Details -------------------------------------------------------------- */ |
90 |
|
|
/* --- Details -------------------------------------------------------------- */ |
91 |
|
|
/* --- Details -------------------------------------------------------------- */ |
92 |
|
|
#include "pinocchio_model.hxx" |
93 |
|
|
|
94 |
|
|
#endif // CROCODDYL_PINOCCHIO_MODEL_FACTORY_HPP_ |
95 |
|
|
|