1 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
2 |
|
|
// BSD 3-Clause License |
3 |
|
|
// |
4 |
|
|
// Copyright (C) 2021-2022, University of Edinburgh, LAAS-CNRS |
5 |
|
|
// Copyright note valid unless otherwise stated in individual files. |
6 |
|
|
// All rights reserved. |
7 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
8 |
|
|
|
9 |
|
|
#ifndef CROCODDYL_RESIDUAL_FACTORY_HPP_ |
10 |
|
|
#define CROCODDYL_RESIDUAL_FACTORY_HPP_ |
11 |
|
|
|
12 |
|
|
#include "crocoddyl/core/numdiff/residual.hpp" |
13 |
|
|
#include "crocoddyl/core/residual-base.hpp" |
14 |
|
|
#include "crocoddyl/multibody/states/multibody.hpp" |
15 |
|
|
#include "state.hpp" |
16 |
|
|
|
17 |
|
|
namespace crocoddyl { |
18 |
|
|
namespace unittest { |
19 |
|
|
|
20 |
|
|
struct ResidualModelTypes { |
21 |
|
|
enum Type { |
22 |
|
|
ResidualModelState, |
23 |
|
|
ResidualModelControl, |
24 |
|
|
ResidualModelCoMPosition, |
25 |
|
|
ResidualModelCentroidalMomentum, |
26 |
|
|
ResidualModelFramePlacement, |
27 |
|
|
ResidualModelFrameRotation, |
28 |
|
|
ResidualModelFrameTranslation, |
29 |
|
|
ResidualModelFrameVelocity, |
30 |
|
|
ResidualModelControlGrav, |
31 |
|
|
#ifdef PINOCCHIO_WITH_HPP_FCL |
32 |
|
|
ResidualModelPairCollision, |
33 |
|
|
#endif // PINOCCHIO_WITH_HPP_FCL |
34 |
|
|
NbResidualModelTypes |
35 |
|
|
}; |
36 |
|
23 |
static std::vector<Type> init_all() { |
37 |
|
23 |
std::vector<Type> v; |
38 |
✓✓ |
253 |
for (int i = 0; i < NbResidualModelTypes; ++i) { |
39 |
✓✗ |
230 |
v.push_back((Type)i); |
40 |
|
|
} |
41 |
|
23 |
return v; |
42 |
|
|
} |
43 |
|
|
static const std::vector<Type> all; |
44 |
|
|
}; |
45 |
|
|
|
46 |
|
|
std::ostream& operator<<(std::ostream& os, ResidualModelTypes::Type type); |
47 |
|
|
|
48 |
|
|
class ResidualModelFactory { |
49 |
|
|
public: |
50 |
|
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
51 |
|
|
|
52 |
|
|
typedef crocoddyl::MathBaseTpl<double> MathBase; |
53 |
|
|
typedef typename MathBase::Vector6s Vector6d; |
54 |
|
|
typedef pinocchio::GeometryObject::CollisionGeometryPtr CollisionGeometryPtr; |
55 |
|
|
|
56 |
|
|
explicit ResidualModelFactory(); |
57 |
|
|
~ResidualModelFactory(); |
58 |
|
|
|
59 |
|
|
boost::shared_ptr<crocoddyl::ResidualModelAbstract> create( |
60 |
|
|
ResidualModelTypes::Type residual_type, StateModelTypes::Type state_type, |
61 |
|
|
std::size_t nu = std::numeric_limits<std::size_t>::max()) const; |
62 |
|
|
}; |
63 |
|
|
|
64 |
|
|
boost::shared_ptr<crocoddyl::ResidualModelAbstract> create_random_residual( |
65 |
|
|
StateModelTypes::Type state_type); |
66 |
|
|
|
67 |
|
|
} // namespace unittest |
68 |
|
|
} // namespace crocoddyl |
69 |
|
|
|
70 |
|
|
#endif // CROCODDYL_RESIDUAL_FACTORY_HPP_ |