| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | /////////////////////////////////////////////////////////////////////////////// | ||
| 2 | // BSD 3-Clause License | ||
| 3 | // | ||
| 4 | // Copyright (C) 2019-2022, LAAS-CNRS, University of Edinburgh | ||
| 5 | // Copyright note valid unless otherwise stated in individual files. | ||
| 6 | // All rights reserved. | ||
| 7 | /////////////////////////////////////////////////////////////////////////////// | ||
| 8 | |||
| 9 | #ifndef CROCODDYL_COST_FACTORY_HPP_ | ||
| 10 | #define CROCODDYL_COST_FACTORY_HPP_ | ||
| 11 | |||
| 12 | #include "activation.hpp" | ||
| 13 | #include "crocoddyl/core/cost-base.hpp" | ||
| 14 | #include "crocoddyl/core/costs/cost-sum.hpp" | ||
| 15 | #include "crocoddyl/core/numdiff/cost.hpp" | ||
| 16 | #include "crocoddyl/multibody/states/multibody.hpp" | ||
| 17 | #include "state.hpp" | ||
| 18 | |||
| 19 | namespace crocoddyl { | ||
| 20 | namespace unittest { | ||
| 21 | |||
| 22 | struct CostModelTypes { | ||
| 23 | enum Type { | ||
| 24 | CostModelResidualState, | ||
| 25 | CostModelResidualControl, | ||
| 26 | CostModelResidualCoMPosition, | ||
| 27 | // CostModelResidualCentroidalMomentum, // @todo Figure out the pinocchio | ||
| 28 | // callbacks. | ||
| 29 | CostModelResidualFramePlacement, | ||
| 30 | CostModelResidualFrameRotation, | ||
| 31 | CostModelResidualFrameTranslation, | ||
| 32 | CostModelResidualFrameVelocity, | ||
| 33 | NbCostModelTypes | ||
| 34 | }; | ||
| 35 | ✗ | static std::vector<Type> init_all() { | |
| 36 | ✗ | std::vector<Type> v; | |
| 37 | ✗ | v.reserve(NbCostModelTypes); | |
| 38 | ✗ | for (int i = 0; i < NbCostModelTypes; ++i) { | |
| 39 | ✗ | v.push_back((Type)i); | |
| 40 | } | ||
| 41 | ✗ | return v; | |
| 42 | ✗ | } | |
| 43 | static const std::vector<Type> all; | ||
| 44 | }; | ||
| 45 | |||
| 46 | struct CostModelNoFFTypes { | ||
| 47 | enum Type { CostModelResidualControlGrav, NbCostModelNoFFTypes }; | ||
| 48 | ✗ | static std::vector<Type> init_all() { | |
| 49 | ✗ | std::vector<Type> v; | |
| 50 | ✗ | v.clear(); | |
| 51 | ✗ | for (int i = 0; i < NbCostModelNoFFTypes; ++i) { | |
| 52 | ✗ | v.push_back((Type)i); | |
| 53 | } | ||
| 54 | ✗ | return v; | |
| 55 | ✗ | } | |
| 56 | static const std::vector<Type> all; | ||
| 57 | }; | ||
| 58 | |||
| 59 | #ifdef PINOCCHIO_WITH_HPP_FCL | ||
| 60 | struct CostModelCollisionTypes { | ||
| 61 | enum Type { CostModelResidualPairCollision, NbCostModelCollisionTypes }; | ||
| 62 | static std::vector<Type> init_all() { | ||
| 63 | std::vector<Type> v; | ||
| 64 | v.clear(); | ||
| 65 | for (int i = 0; i < NbCostModelCollisionTypes; ++i) { | ||
| 66 | v.push_back((Type)i); | ||
| 67 | } | ||
| 68 | return v; | ||
| 69 | } | ||
| 70 | static const std::vector<Type> all; | ||
| 71 | }; | ||
| 72 | #endif // PINOCCHIO_WITH_HPP_FCL | ||
| 73 | |||
| 74 | std::ostream& operator<<(std::ostream& os, CostModelTypes::Type type); | ||
| 75 | std::ostream& operator<<(std::ostream& os, CostModelNoFFTypes::Type type); | ||
| 76 | #ifdef PINOCCHIO_WITH_HPP_FCL | ||
| 77 | std::ostream& operator<<(std::ostream& os, CostModelCollisionTypes::Type type); | ||
| 78 | #endif // PINOCCHIO_WITH_HPP_FCL | ||
| 79 | |||
| 80 | class CostModelFactory { | ||
| 81 | public: | ||
| 82 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ||
| 83 | |||
| 84 | typedef crocoddyl::MathBaseTpl<double> MathBase; | ||
| 85 | typedef typename MathBase::Vector6s Vector6d; | ||
| 86 | typedef pinocchio::GeometryObject::CollisionGeometryPtr CollisionGeometryPtr; | ||
| 87 | |||
| 88 | explicit CostModelFactory(); | ||
| 89 | ~CostModelFactory(); | ||
| 90 | |||
| 91 | std::shared_ptr<crocoddyl::CostModelAbstract> create( | ||
| 92 | CostModelTypes::Type cost_type, StateModelTypes::Type state_type, | ||
| 93 | ActivationModelTypes::Type activation_type, | ||
| 94 | std::size_t nu = std::numeric_limits<std::size_t>::max()) const; | ||
| 95 | std::shared_ptr<crocoddyl::CostModelAbstract> create( | ||
| 96 | CostModelNoFFTypes::Type cost_type, | ||
| 97 | ActivationModelTypes::Type activation_type, | ||
| 98 | std::size_t nu = std::numeric_limits<std::size_t>::max()) const; | ||
| 99 | |||
| 100 | #ifdef PINOCCHIO_WITH_HPP_FCL | ||
| 101 | std::shared_ptr<crocoddyl::CostModelAbstract> create( | ||
| 102 | CostModelCollisionTypes::Type cost_type, StateModelTypes::Type state_type, | ||
| 103 | std::size_t nu = std::numeric_limits<std::size_t>::max()) const; | ||
| 104 | #endif // PINOCCHIO_WITH_HPP_FCL | ||
| 105 | }; | ||
| 106 | |||
| 107 | std::shared_ptr<crocoddyl::CostModelAbstract> create_random_cost( | ||
| 108 | StateModelTypes::Type state_type, | ||
| 109 | std::size_t nu = std::numeric_limits<std::size_t>::max()); | ||
| 110 | } // namespace unittest | ||
| 111 | } // namespace crocoddyl | ||
| 112 | |||
| 113 | #endif // CROCODDYL_COST_FACTORY_HPP_ | ||
| 114 |