| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | /////////////////////////////////////////////////////////////////////////////// | ||
| 2 | // BSD 3-Clause License | ||
| 3 | // | ||
| 4 | // Copyright (C) 2021-2022, University of Edinburgh, Heriot-Watt University | ||
| 5 | // Copyright note valid unless otherwise stated in individual files. | ||
| 6 | // All rights reserved. | ||
| 7 | /////////////////////////////////////////////////////////////////////////////// | ||
| 8 | |||
| 9 | #include "contact_cost.hpp" | ||
| 10 | |||
| 11 | #include "crocoddyl/core/costs/residual.hpp" | ||
| 12 | #include "crocoddyl/multibody/residuals/contact-control-gravity.hpp" | ||
| 13 | #include "crocoddyl/multibody/residuals/contact-cop-position.hpp" | ||
| 14 | #include "crocoddyl/multibody/residuals/contact-force.hpp" | ||
| 15 | #include "crocoddyl/multibody/residuals/contact-friction-cone.hpp" | ||
| 16 | #include "crocoddyl/multibody/residuals/contact-wrench-cone.hpp" | ||
| 17 | #include "diff_action.hpp" | ||
| 18 | |||
| 19 | namespace crocoddyl { | ||
| 20 | namespace unittest { | ||
| 21 | |||
| 22 | const std::vector<ContactCostModelTypes::Type> ContactCostModelTypes::all( | ||
| 23 | ContactCostModelTypes::init_all()); | ||
| 24 | |||
| 25 | ✗ | std::ostream& operator<<(std::ostream& os, ContactCostModelTypes::Type type) { | |
| 26 | ✗ | switch (type) { | |
| 27 | ✗ | case ContactCostModelTypes::CostModelResidualContactForce: | |
| 28 | ✗ | os << "CostModelResidualContactForce"; | |
| 29 | ✗ | break; | |
| 30 | ✗ | case ContactCostModelTypes::CostModelResidualContactCoPPosition: | |
| 31 | ✗ | os << "CostModelResidualContactCoPPosition"; | |
| 32 | ✗ | break; | |
| 33 | ✗ | case ContactCostModelTypes::CostModelResidualContactFrictionCone: | |
| 34 | ✗ | os << "CostModelResidualContactFrictionCone"; | |
| 35 | ✗ | break; | |
| 36 | ✗ | case ContactCostModelTypes::CostModelResidualContactWrenchCone: | |
| 37 | ✗ | os << "CostModelResidualContactWrenchCone"; | |
| 38 | ✗ | break; | |
| 39 | ✗ | case ContactCostModelTypes::CostModelResidualContactControlGrav: | |
| 40 | ✗ | os << "CostModelResidualContactControlGrav"; | |
| 41 | ✗ | break; | |
| 42 | ✗ | case ContactCostModelTypes::NbContactCostModelTypes: | |
| 43 | ✗ | os << "NbContactCostModelTypes"; | |
| 44 | ✗ | break; | |
| 45 | ✗ | default: | |
| 46 | ✗ | break; | |
| 47 | } | ||
| 48 | ✗ | return os; | |
| 49 | } | ||
| 50 | |||
| 51 | ✗ | ContactCostModelFactory::ContactCostModelFactory() {} | |
| 52 | ✗ | ContactCostModelFactory::~ContactCostModelFactory() {} | |
| 53 | |||
| 54 | std::shared_ptr<crocoddyl::DifferentialActionModelAbstract> | ||
| 55 | ✗ | ContactCostModelFactory::create( | |
| 56 | ContactCostModelTypes::Type cost_type, PinocchioModelTypes::Type model_type, | ||
| 57 | ActivationModelTypes::Type activation_type, | ||
| 58 | ActuationModelTypes::Type actuation_type) const { | ||
| 59 | // Create contact action model with no cost | ||
| 60 | ✗ | std::shared_ptr<crocoddyl::DifferentialActionModelContactFwdDynamics> action; | |
| 61 | ✗ | switch (model_type) { | |
| 62 | ✗ | case PinocchioModelTypes::Talos: | |
| 63 | ✗ | action = DifferentialActionModelFactory().create_contactFwdDynamics( | |
| 64 | ✗ | StateModelTypes::StateMultibody_Talos, actuation_type, false); | |
| 65 | ✗ | break; | |
| 66 | ✗ | case PinocchioModelTypes::HyQ: | |
| 67 | ✗ | action = DifferentialActionModelFactory().create_contactFwdDynamics( | |
| 68 | ✗ | StateModelTypes::StateMultibody_HyQ, actuation_type, false); | |
| 69 | ✗ | break; | |
| 70 | ✗ | default: | |
| 71 | ✗ | throw_pretty(__FILE__ ": Wrong PinocchioModelTypes::Type given"); | |
| 72 | break; | ||
| 73 | } | ||
| 74 | ✗ | action->get_costs()->removeCost("state"); | |
| 75 | ✗ | action->get_costs()->removeCost("control"); | |
| 76 | |||
| 77 | // Create cost | ||
| 78 | ✗ | std::shared_ptr<crocoddyl::CostModelAbstract> cost; | |
| 79 | ✗ | PinocchioModelFactory model_factory(model_type); | |
| 80 | std::shared_ptr<crocoddyl::StateMultibody> state = | ||
| 81 | ✗ | std::static_pointer_cast<crocoddyl::StateMultibody>(action->get_state()); | |
| 82 | ✗ | const std::size_t nu = action->get_actuation()->get_nu(); | |
| 83 | ✗ | Eigen::Matrix3d R = Eigen::Matrix3d::Identity(); | |
| 84 | ✗ | std::vector<std::size_t> frame_ids = model_factory.get_frame_ids(); | |
| 85 | ✗ | switch (cost_type) { | |
| 86 | ✗ | case ContactCostModelTypes::CostModelResidualContactForce: | |
| 87 | ✗ | for (std::size_t i = 0; i < frame_ids.size(); ++i) { | |
| 88 | ✗ | cost = std::make_shared<crocoddyl::CostModelResidual>( | |
| 89 | state, | ||
| 90 | ✗ | ActivationModelFactory().create(activation_type, | |
| 91 | model_factory.get_contact_nc()), | ||
| 92 | ✗ | std::make_shared<crocoddyl::ResidualModelContactForce>( | |
| 93 | ✗ | state, frame_ids[i], pinocchio::Force::Random(), | |
| 94 | ✗ | model_factory.get_contact_nc(), nu)); | |
| 95 | ✗ | action->get_costs()->addCost("cost_" + std::to_string(i), cost, 0.001); | |
| 96 | } | ||
| 97 | ✗ | break; | |
| 98 | ✗ | case ContactCostModelTypes::CostModelResidualContactCoPPosition: | |
| 99 | ✗ | for (std::size_t i = 0; i < frame_ids.size(); ++i) { | |
| 100 | ✗ | cost = std::make_shared<crocoddyl::CostModelResidual>( | |
| 101 | ✗ | state, ActivationModelFactory().create(activation_type, 4), | |
| 102 | ✗ | std::make_shared<crocoddyl::ResidualModelContactCoPPosition>( | |
| 103 | ✗ | state, frame_ids[i], | |
| 104 | ✗ | crocoddyl::CoPSupport(R, Eigen::Vector2d(0.1, 0.1)), nu)); | |
| 105 | ✗ | action->get_costs()->addCost("cost_" + std::to_string(i), cost, 0.001); | |
| 106 | } | ||
| 107 | ✗ | break; | |
| 108 | ✗ | case ContactCostModelTypes::CostModelResidualContactFrictionCone: | |
| 109 | ✗ | for (std::size_t i = 0; i < frame_ids.size(); ++i) { | |
| 110 | ✗ | cost = std::make_shared<crocoddyl::CostModelResidual>( | |
| 111 | ✗ | state, ActivationModelFactory().create(activation_type, 5), | |
| 112 | ✗ | std::make_shared<crocoddyl::ResidualModelContactFrictionCone>( | |
| 113 | ✗ | state, frame_ids[i], crocoddyl::FrictionCone(R, 1.), nu)); | |
| 114 | ✗ | action->get_costs()->addCost("cost_" + std::to_string(i), cost, 0.001); | |
| 115 | } | ||
| 116 | ✗ | break; | |
| 117 | ✗ | case ContactCostModelTypes::CostModelResidualContactWrenchCone: | |
| 118 | ✗ | for (std::size_t i = 0; i < frame_ids.size(); ++i) { | |
| 119 | ✗ | cost = std::make_shared<crocoddyl::CostModelResidual>( | |
| 120 | ✗ | state, ActivationModelFactory().create(activation_type, 17), | |
| 121 | ✗ | std::make_shared<crocoddyl::ResidualModelContactWrenchCone>( | |
| 122 | ✗ | state, frame_ids[i], | |
| 123 | ✗ | crocoddyl::WrenchCone(R, 1., Eigen::Vector2d(0.1, 0.1)), nu)); | |
| 124 | ✗ | action->get_costs()->addCost("cost_" + std::to_string(i), cost, 0.001); | |
| 125 | } | ||
| 126 | ✗ | break; | |
| 127 | ✗ | case ContactCostModelTypes::CostModelResidualContactControlGrav: | |
| 128 | ✗ | for (std::size_t i = 0; i < frame_ids.size(); ++i) { | |
| 129 | ✗ | cost = std::make_shared<crocoddyl::CostModelResidual>( | |
| 130 | state, | ||
| 131 | ✗ | ActivationModelFactory().create(activation_type, state->get_nv()), | |
| 132 | ✗ | std::make_shared<crocoddyl::ResidualModelContactControlGrav>(state, | |
| 133 | ✗ | nu)); | |
| 134 | ✗ | action->get_costs()->addCost("cost_" + std::to_string(i), cost, 0.001); | |
| 135 | } | ||
| 136 | ✗ | break; | |
| 137 | ✗ | default: | |
| 138 | ✗ | throw_pretty(__FILE__ ": Wrong ContactCostModelTypes::Type given"); | |
| 139 | break; | ||
| 140 | } | ||
| 141 | // Include the cost in the contact model | ||
| 142 | ✗ | return action; | |
| 143 | ✗ | } | |
| 144 | |||
| 145 | } // namespace unittest | ||
| 146 | } // namespace crocoddyl | ||
| 147 |