| 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 | #define BOOST_TEST_NO_MAIN | ||
| 10 | #define BOOST_TEST_ALTERNATIVE_INIT_API | ||
| 11 | |||
| 12 | #include "crocoddyl/core/actions/lqr.hpp" | ||
| 13 | #include "crocoddyl/multibody/data/multibody.hpp" | ||
| 14 | #include "factory/cost.hpp" | ||
| 15 | #include "unittest_common.hpp" | ||
| 16 | |||
| 17 | using namespace boost::unit_test; | ||
| 18 | using namespace crocoddyl::unittest; | ||
| 19 | |||
| 20 | //----------------------------------------------------------------------------// | ||
| 21 | |||
| 22 | ✗ | void test_constructor(StateModelTypes::Type state_type) { | |
| 23 | // Setup the test | ||
| 24 | ✗ | StateModelFactory state_factory; | |
| 25 | ✗ | crocoddyl::CostModelSum model(state_factory.create(state_type)); | |
| 26 | |||
| 27 | // Run the print function | ||
| 28 | ✗ | std::ostringstream tmp; | |
| 29 | ✗ | tmp << model; | |
| 30 | |||
| 31 | // Test the initial size of the map | ||
| 32 | ✗ | BOOST_CHECK(model.get_costs().size() == 0); | |
| 33 | |||
| 34 | // Checking that casted computation is the same | ||
| 35 | #ifdef NDEBUG // Run only in release mode | ||
| 36 | crocoddyl::CostModelSumTpl<float> casted_model = model.cast<float>(); | ||
| 37 | BOOST_CHECK(casted_model.get_costs().size() == 0); | ||
| 38 | #endif | ||
| 39 | ✗ | } | |
| 40 | |||
| 41 | ✗ | void test_addCost(StateModelTypes::Type state_type) { | |
| 42 | // Setup the test | ||
| 43 | ✗ | StateModelFactory state_factory; | |
| 44 | ✗ | crocoddyl::CostModelSum model(state_factory.create(state_type)); | |
| 45 | ✗ | crocoddyl::CostModelSumTpl<float> casted_model = model.cast<float>(); | |
| 46 | |||
| 47 | // add an active cost | ||
| 48 | std::shared_ptr<crocoddyl::CostModelAbstract> rand_cost_1 = | ||
| 49 | ✗ | create_random_cost(state_type); | |
| 50 | ✗ | model.addCost("random_cost_1", rand_cost_1, 1.); | |
| 51 | ✗ | BOOST_CHECK(model.get_nr() == rand_cost_1->get_activation()->get_nr()); | |
| 52 | ✗ | BOOST_CHECK(model.get_nr_total() == rand_cost_1->get_activation()->get_nr()); | |
| 53 | |||
| 54 | // add an inactive cost | ||
| 55 | std::shared_ptr<crocoddyl::CostModelAbstract> rand_cost_2 = | ||
| 56 | ✗ | create_random_cost(state_type); | |
| 57 | ✗ | model.addCost("random_cost_2", rand_cost_2, 1., false); | |
| 58 | ✗ | BOOST_CHECK(model.get_nr() == rand_cost_1->get_activation()->get_nr()); | |
| 59 | ✗ | BOOST_CHECK(model.get_nr_total() == | |
| 60 | rand_cost_1->get_activation()->get_nr() + | ||
| 61 | rand_cost_2->get_activation()->get_nr()); | ||
| 62 | |||
| 63 | // change the random cost 2 status | ||
| 64 | ✗ | model.changeCostStatus("random_cost_2", true); | |
| 65 | ✗ | BOOST_CHECK(model.get_nr() == rand_cost_1->get_activation()->get_nr() + | |
| 66 | rand_cost_2->get_activation()->get_nr()); | ||
| 67 | ✗ | BOOST_CHECK(model.get_nr_total() == | |
| 68 | rand_cost_1->get_activation()->get_nr() + | ||
| 69 | rand_cost_2->get_activation()->get_nr()); | ||
| 70 | |||
| 71 | // change the random cost 1 status | ||
| 72 | ✗ | model.changeCostStatus("random_cost_1", false); | |
| 73 | ✗ | BOOST_CHECK(model.get_nr() == rand_cost_2->get_activation()->get_nr()); | |
| 74 | ✗ | BOOST_CHECK(model.get_nr_total() == | |
| 75 | rand_cost_1->get_activation()->get_nr() + | ||
| 76 | rand_cost_2->get_activation()->get_nr()); | ||
| 77 | |||
| 78 | // Checking that casted computation is the same | ||
| 79 | #ifdef NDEBUG // Run only in release mode | ||
| 80 | std::shared_ptr<crocoddyl::CostModelAbstractTpl<float>> casted_rand_cost_1 = | ||
| 81 | rand_cost_1->cast<float>(); | ||
| 82 | casted_model.addCost("random_cost_1", casted_rand_cost_1, 1.f); | ||
| 83 | BOOST_CHECK(casted_model.get_nr() == | ||
| 84 | casted_rand_cost_1->get_activation()->get_nr()); | ||
| 85 | BOOST_CHECK(casted_model.get_nr_total() == | ||
| 86 | casted_rand_cost_1->get_activation()->get_nr()); | ||
| 87 | std::shared_ptr<crocoddyl::CostModelAbstractTpl<float>> casted_rand_cost_2 = | ||
| 88 | rand_cost_2->cast<float>(); | ||
| 89 | casted_model.addCost("random_cost_2", casted_rand_cost_2, 1.f, false); | ||
| 90 | BOOST_CHECK(casted_model.get_nr() == | ||
| 91 | casted_rand_cost_1->get_activation()->get_nr()); | ||
| 92 | BOOST_CHECK(casted_model.get_nr_total() == | ||
| 93 | casted_rand_cost_1->get_activation()->get_nr() + | ||
| 94 | casted_rand_cost_2->get_activation()->get_nr()); | ||
| 95 | casted_model.changeCostStatus("random_cost_2", true); | ||
| 96 | BOOST_CHECK(casted_model.get_nr() == | ||
| 97 | casted_rand_cost_1->get_activation()->get_nr() + | ||
| 98 | casted_rand_cost_2->get_activation()->get_nr()); | ||
| 99 | BOOST_CHECK(casted_model.get_nr_total() == | ||
| 100 | casted_rand_cost_1->get_activation()->get_nr() + | ||
| 101 | casted_rand_cost_2->get_activation()->get_nr()); | ||
| 102 | casted_model.changeCostStatus("random_cost_1", false); | ||
| 103 | BOOST_CHECK(casted_model.get_nr() == | ||
| 104 | casted_rand_cost_2->get_activation()->get_nr()); | ||
| 105 | BOOST_CHECK(casted_model.get_nr_total() == | ||
| 106 | casted_rand_cost_1->get_activation()->get_nr() + | ||
| 107 | casted_rand_cost_2->get_activation()->get_nr()); | ||
| 108 | #endif | ||
| 109 | ✗ | } | |
| 110 | |||
| 111 | ✗ | void test_addCost_error_message(StateModelTypes::Type state_type) { | |
| 112 | // Setup the test | ||
| 113 | ✗ | StateModelFactory state_factory; | |
| 114 | ✗ | crocoddyl::CostModelSum model(state_factory.create(state_type)); | |
| 115 | |||
| 116 | // create an cost object | ||
| 117 | std::shared_ptr<crocoddyl::CostModelAbstract> rand_cost = | ||
| 118 | ✗ | create_random_cost(state_type); | |
| 119 | |||
| 120 | // add twice the same cost object to the container | ||
| 121 | ✗ | model.addCost("random_cost", rand_cost, 1.); | |
| 122 | |||
| 123 | // test error message when we add a duplicate cost | ||
| 124 | ✗ | CaptureIOStream capture_ios; | |
| 125 | ✗ | capture_ios.beginCapture(); | |
| 126 | ✗ | model.addCost("random_cost", rand_cost, 1.); | |
| 127 | ✗ | capture_ios.endCapture(); | |
| 128 | ✗ | std::stringstream expected_buffer; | |
| 129 | expected_buffer << "Warning: we couldn't add the random_cost cost item, it " | ||
| 130 | ✗ | "already existed." | |
| 131 | ✗ | << std::endl; | |
| 132 | ✗ | BOOST_CHECK(capture_ios.str() == expected_buffer.str()); | |
| 133 | |||
| 134 | // test error message when we change the cost status of an inexistent cost | ||
| 135 | ✗ | capture_ios.beginCapture(); | |
| 136 | ✗ | model.changeCostStatus("no_exist_cost", true); | |
| 137 | ✗ | capture_ios.endCapture(); | |
| 138 | ✗ | expected_buffer.clear(); | |
| 139 | expected_buffer << "Warning: we couldn't change the status of the " | ||
| 140 | ✗ | "no_exist_cost cost item, it doesn't exist." | |
| 141 | ✗ | << std::endl; | |
| 142 | ✗ | BOOST_CHECK(capture_ios.str() == expected_buffer.str()); | |
| 143 | ✗ | } | |
| 144 | |||
| 145 | ✗ | void test_removeCost(StateModelTypes::Type state_type) { | |
| 146 | // Setup the test | ||
| 147 | ✗ | StateModelFactory state_factory; | |
| 148 | ✗ | crocoddyl::CostModelSum model(state_factory.create(state_type)); | |
| 149 | ✗ | crocoddyl::CostModelSumTpl<float> casted_model = model.cast<float>(); | |
| 150 | |||
| 151 | // add an active cost | ||
| 152 | std::shared_ptr<crocoddyl::CostModelAbstract> rand_cost = | ||
| 153 | ✗ | create_random_cost(state_type); | |
| 154 | ✗ | model.addCost("random_cost", rand_cost, 1.); | |
| 155 | ✗ | BOOST_CHECK(model.get_nr() == rand_cost->get_activation()->get_nr()); | |
| 156 | |||
| 157 | // remove the cost | ||
| 158 | ✗ | model.removeCost("random_cost"); | |
| 159 | ✗ | BOOST_CHECK(model.get_nr() == 0); | |
| 160 | ✗ | BOOST_CHECK(model.get_nr_total() == 0); | |
| 161 | |||
| 162 | // Checking that casted computation is the same | ||
| 163 | #ifdef NDEBUG // Run only in release mode | ||
| 164 | std::shared_ptr<crocoddyl::CostModelAbstractTpl<float>> casted_rand_cost = | ||
| 165 | rand_cost->cast<float>(); | ||
| 166 | casted_model.addCost("random_cost", casted_rand_cost, 1.f); | ||
| 167 | BOOST_CHECK(casted_model.get_nr() == | ||
| 168 | casted_rand_cost->get_activation()->get_nr()); | ||
| 169 | casted_model.removeCost("random_cost"); | ||
| 170 | BOOST_CHECK(casted_model.get_nr() == 0); | ||
| 171 | BOOST_CHECK(casted_model.get_nr_total() == 0); | ||
| 172 | #endif | ||
| 173 | ✗ | } | |
| 174 | |||
| 175 | ✗ | void test_removeCost_error_message(StateModelTypes::Type state_type) { | |
| 176 | // Setup the test | ||
| 177 | ✗ | StateModelFactory state_factory; | |
| 178 | ✗ | crocoddyl::CostModelSum model(state_factory.create(state_type)); | |
| 179 | |||
| 180 | // remove a none existing cost form the container, we expect a cout message | ||
| 181 | // here | ||
| 182 | ✗ | CaptureIOStream capture_ios; | |
| 183 | ✗ | capture_ios.beginCapture(); | |
| 184 | ✗ | model.removeCost("random_cost"); | |
| 185 | ✗ | capture_ios.endCapture(); | |
| 186 | |||
| 187 | // Test that the error message is sent. | ||
| 188 | ✗ | std::stringstream expected_buffer; | |
| 189 | expected_buffer << "Warning: we couldn't remove the random_cost cost item, " | ||
| 190 | ✗ | "it doesn't exist." | |
| 191 | ✗ | << std::endl; | |
| 192 | ✗ | BOOST_CHECK(capture_ios.str() == expected_buffer.str()); | |
| 193 | ✗ | } | |
| 194 | |||
| 195 | ✗ | void test_calc(StateModelTypes::Type state_type) { | |
| 196 | // setup the test | ||
| 197 | ✗ | StateModelFactory state_factory; | |
| 198 | ✗ | crocoddyl::CostModelSum model(state_factory.create(state_type)); | |
| 199 | // create the corresponding data object | ||
| 200 | const std::shared_ptr<crocoddyl::StateMultibody>& state = | ||
| 201 | ✗ | std::static_pointer_cast<crocoddyl::StateMultibody>(model.get_state()); | |
| 202 | ✗ | pinocchio::Model& pinocchio_model = *state->get_pinocchio().get(); | |
| 203 | ✗ | pinocchio::Data pinocchio_data(pinocchio_model); | |
| 204 | ✗ | crocoddyl::DataCollectorMultibody shared_data(&pinocchio_data); | |
| 205 | |||
| 206 | // create and add some cost objects | ||
| 207 | ✗ | std::vector<std::shared_ptr<crocoddyl::CostModelAbstract>> models; | |
| 208 | ✗ | std::vector<std::shared_ptr<crocoddyl::CostDataAbstract>> datas; | |
| 209 | ✗ | for (std::size_t i = 0; i < 5; ++i) { | |
| 210 | ✗ | std::ostringstream os; | |
| 211 | ✗ | os << "random_cost_" << i; | |
| 212 | const std::shared_ptr<crocoddyl::CostModelAbstract>& m = | ||
| 213 | ✗ | create_random_cost(state_type); | |
| 214 | ✗ | model.addCost(os.str(), m, 1.); | |
| 215 | ✗ | models.push_back(m); | |
| 216 | ✗ | datas.push_back(m->createData(&shared_data)); | |
| 217 | ✗ | } | |
| 218 | |||
| 219 | // create the data of the cost sum | ||
| 220 | const std::shared_ptr<crocoddyl::CostDataSum>& data = | ||
| 221 | ✗ | model.createData(&shared_data); | |
| 222 | |||
| 223 | // compute the cost sum data for the case when all costs are defined as active | ||
| 224 | ✗ | const Eigen::VectorXd x1 = state->rand(); | |
| 225 | ✗ | const Eigen::VectorXd u1 = Eigen::VectorXd::Random(model.get_nu()); | |
| 226 | ✗ | crocoddyl::unittest::updateAllPinocchio(&pinocchio_model, &pinocchio_data, | |
| 227 | x1); | ||
| 228 | ✗ | model.calc(data, x1, u1); | |
| 229 | |||
| 230 | // check that the cost has been filled | ||
| 231 | ✗ | BOOST_CHECK(data->cost > 0.); | |
| 232 | |||
| 233 | // check the cost against single cost computations | ||
| 234 | ✗ | double cost = 0; | |
| 235 | ✗ | for (std::size_t i = 0; i < 5; ++i) { | |
| 236 | ✗ | models[i]->calc(datas[i], x1, u1); | |
| 237 | ✗ | cost += datas[i]->cost; | |
| 238 | } | ||
| 239 | ✗ | BOOST_CHECK(data->cost == cost); | |
| 240 | |||
| 241 | // compute the cost sum data for the case when the first three costs are | ||
| 242 | // defined as active | ||
| 243 | ✗ | model.changeCostStatus("random_cost_3", false); | |
| 244 | ✗ | model.changeCostStatus("random_cost_4", false); | |
| 245 | ✗ | const Eigen::VectorXd x2 = state->rand(); | |
| 246 | ✗ | const Eigen::VectorXd u2 = Eigen::VectorXd::Random(model.get_nu()); | |
| 247 | ✗ | crocoddyl::unittest::updateAllPinocchio(&pinocchio_model, &pinocchio_data, | |
| 248 | x1); | ||
| 249 | ✗ | model.calc(data, x2, u2); | |
| 250 | ✗ | cost = 0; | |
| 251 | ✗ | for (std::size_t i = 0; i < 3; | |
| 252 | ++i) { // we need to update data because this costs are active | ||
| 253 | ✗ | models[i]->calc(datas[i], x2, u2); | |
| 254 | ✗ | cost += datas[i]->cost; | |
| 255 | } | ||
| 256 | ✗ | BOOST_CHECK(data->cost == cost); | |
| 257 | |||
| 258 | // Checking that casted computation is the same | ||
| 259 | #ifdef NDEBUG // Run only in release mode | ||
| 260 | model.changeCostStatus("random_cost_3", true); | ||
| 261 | model.changeCostStatus("random_cost_4", true); | ||
| 262 | crocoddyl::CostModelSumTpl<float> casted_model = model.cast<float>(); | ||
| 263 | const std::shared_ptr<crocoddyl::StateMultibodyTpl<float>>& casted_state = | ||
| 264 | std::static_pointer_cast<crocoddyl::StateMultibodyTpl<float>>( | ||
| 265 | casted_model.get_state()); | ||
| 266 | pinocchio::ModelTpl<float>& casted_pinocchio_model = | ||
| 267 | *casted_state->get_pinocchio().get(); | ||
| 268 | pinocchio::DataTpl<float> casted_pinocchio_data(casted_pinocchio_model); | ||
| 269 | crocoddyl::DataCollectorMultibodyTpl<float> casted_shared_data( | ||
| 270 | &casted_pinocchio_data); | ||
| 271 | std::vector<std::shared_ptr<crocoddyl::CostModelAbstractTpl<float>>> | ||
| 272 | casted_models; | ||
| 273 | std::vector<std::shared_ptr<crocoddyl::CostDataAbstractTpl<float>>> | ||
| 274 | casted_datas; | ||
| 275 | for (std::size_t i = 0; i < 5; ++i) { | ||
| 276 | casted_models.push_back(models[i]->cast<float>()); | ||
| 277 | casted_datas.push_back(casted_models[i]->createData(&casted_shared_data)); | ||
| 278 | } | ||
| 279 | const std::shared_ptr<crocoddyl::CostDataSumTpl<float>>& casted_data = | ||
| 280 | casted_model.createData(&casted_shared_data); | ||
| 281 | const Eigen::VectorXf x1_f = x1.cast<float>(); | ||
| 282 | const Eigen::VectorXf u1_f = u1.cast<float>(); | ||
| 283 | crocoddyl::unittest::updateAllPinocchio(&pinocchio_model, &pinocchio_data, | ||
| 284 | x1); | ||
| 285 | crocoddyl::unittest::updateAllPinocchio(&casted_pinocchio_model, | ||
| 286 | &casted_pinocchio_data, x1_f); | ||
| 287 | model.calc(data, x1, u1); | ||
| 288 | casted_model.calc(casted_data, x1_f, u1_f); | ||
| 289 | BOOST_CHECK(casted_data->cost > 0.f); | ||
| 290 | float tol_f = std::sqrt(2.0f * std::numeric_limits<float>::epsilon()); | ||
| 291 | BOOST_CHECK(std::abs(float(data->cost) - casted_data->cost) <= tol_f); | ||
| 292 | float cost_f = 0.f; | ||
| 293 | for (std::size_t i = 0; i < 5; ++i) { | ||
| 294 | casted_models[i]->calc(casted_datas[i], x1_f, u1_f); | ||
| 295 | cost_f += casted_datas[i]->cost; | ||
| 296 | } | ||
| 297 | BOOST_CHECK(casted_data->cost == cost_f); | ||
| 298 | #endif | ||
| 299 | ✗ | } | |
| 300 | |||
| 301 | ✗ | void test_calcDiff(StateModelTypes::Type state_type) { | |
| 302 | // setup the test | ||
| 303 | ✗ | StateModelFactory state_factory; | |
| 304 | ✗ | crocoddyl::CostModelSum model(state_factory.create(state_type)); | |
| 305 | // create the corresponding data object | ||
| 306 | const std::shared_ptr<crocoddyl::StateMultibody>& state = | ||
| 307 | ✗ | std::static_pointer_cast<crocoddyl::StateMultibody>(model.get_state()); | |
| 308 | ✗ | pinocchio::Model& pinocchio_model = *state->get_pinocchio().get(); | |
| 309 | ✗ | pinocchio::Data pinocchio_data(pinocchio_model); | |
| 310 | ✗ | crocoddyl::DataCollectorMultibody shared_data(&pinocchio_data); | |
| 311 | |||
| 312 | // create and add some cost objects | ||
| 313 | ✗ | std::vector<std::shared_ptr<crocoddyl::CostModelAbstract>> models; | |
| 314 | ✗ | std::vector<std::shared_ptr<crocoddyl::CostDataAbstract>> datas; | |
| 315 | ✗ | for (std::size_t i = 0; i < 5; ++i) { | |
| 316 | ✗ | std::ostringstream os; | |
| 317 | ✗ | os << "random_cost_" << i; | |
| 318 | const std::shared_ptr<crocoddyl::CostModelAbstract>& m = | ||
| 319 | ✗ | create_random_cost(state_type); | |
| 320 | ✗ | model.addCost(os.str(), m, 1.); | |
| 321 | ✗ | models.push_back(m); | |
| 322 | ✗ | datas.push_back(m->createData(&shared_data)); | |
| 323 | ✗ | } | |
| 324 | |||
| 325 | // create the data of the cost sum | ||
| 326 | const std::shared_ptr<crocoddyl::CostDataSum>& data = | ||
| 327 | ✗ | model.createData(&shared_data); | |
| 328 | |||
| 329 | // compute the cost sum data for the case when all costs are defined as active | ||
| 330 | ✗ | Eigen::VectorXd x1 = state->rand(); | |
| 331 | ✗ | const Eigen::VectorXd u1 = Eigen::VectorXd::Random(model.get_nu()); | |
| 332 | ✗ | crocoddyl::unittest::updateAllPinocchio(&pinocchio_model, &pinocchio_data, | |
| 333 | x1); | ||
| 334 | ✗ | model.calc(data, x1, u1); | |
| 335 | ✗ | model.calcDiff(data, x1, u1); | |
| 336 | |||
| 337 | // check that the cost has been filled | ||
| 338 | ✗ | BOOST_CHECK(data->cost > 0.); | |
| 339 | |||
| 340 | // check the cost against single cost computations | ||
| 341 | ✗ | double cost = 0; | |
| 342 | ✗ | Eigen::VectorXd Lx = Eigen::VectorXd::Zero(state->get_ndx()); | |
| 343 | ✗ | Eigen::VectorXd Lu = Eigen::VectorXd::Zero(model.get_nu()); | |
| 344 | Eigen::MatrixXd Lxx = | ||
| 345 | ✗ | Eigen::MatrixXd::Zero(state->get_ndx(), state->get_ndx()); | |
| 346 | ✗ | Eigen::MatrixXd Lxu = Eigen::MatrixXd::Zero(state->get_ndx(), model.get_nu()); | |
| 347 | ✗ | Eigen::MatrixXd Luu = Eigen::MatrixXd::Zero(model.get_nu(), model.get_nu()); | |
| 348 | ✗ | for (std::size_t i = 0; i < 5; ++i) { | |
| 349 | ✗ | models[i]->calc(datas[i], x1, u1); | |
| 350 | ✗ | models[i]->calcDiff(datas[i], x1, u1); | |
| 351 | ✗ | cost += datas[i]->cost; | |
| 352 | ✗ | Lx += datas[i]->Lx; | |
| 353 | ✗ | Lu += datas[i]->Lu; | |
| 354 | ✗ | Lxx += datas[i]->Lxx; | |
| 355 | ✗ | Lxu += datas[i]->Lxu; | |
| 356 | ✗ | Luu += datas[i]->Luu; | |
| 357 | } | ||
| 358 | ✗ | BOOST_CHECK(data->cost == cost); | |
| 359 | ✗ | BOOST_CHECK(data->Lx == Lx); | |
| 360 | ✗ | BOOST_CHECK(data->Lu == Lu); | |
| 361 | ✗ | BOOST_CHECK(data->Lxx == Lxx); | |
| 362 | ✗ | BOOST_CHECK(data->Lxu == Lxu); | |
| 363 | ✗ | BOOST_CHECK(data->Luu == Luu); | |
| 364 | |||
| 365 | ✗ | x1 = state->rand(); | |
| 366 | ✗ | crocoddyl::unittest::updateAllPinocchio(&pinocchio_model, &pinocchio_data, | |
| 367 | x1); | ||
| 368 | ✗ | model.calc(data, x1); | |
| 369 | ✗ | model.calcDiff(data, x1); | |
| 370 | ✗ | cost = 0.; | |
| 371 | ✗ | Lx.setZero(); | |
| 372 | ✗ | Lxx.setZero(); | |
| 373 | ✗ | for (std::size_t i = 0; i < 5; ++i) { | |
| 374 | ✗ | models[i]->calc(datas[i], x1); | |
| 375 | ✗ | models[i]->calcDiff(datas[i], x1); | |
| 376 | ✗ | cost += datas[i]->cost; | |
| 377 | ✗ | Lx += datas[i]->Lx; | |
| 378 | ✗ | Lxx += datas[i]->Lxx; | |
| 379 | } | ||
| 380 | ✗ | BOOST_CHECK(data->cost == cost); | |
| 381 | ✗ | BOOST_CHECK(data->Lx == Lx); | |
| 382 | ✗ | BOOST_CHECK(data->Lxx == Lxx); | |
| 383 | |||
| 384 | // compute the cost sum data for the case when the first three costs are | ||
| 385 | // defined as active | ||
| 386 | ✗ | model.changeCostStatus("random_cost_3", false); | |
| 387 | ✗ | model.changeCostStatus("random_cost_4", false); | |
| 388 | ✗ | Eigen::VectorXd x2 = state->rand(); | |
| 389 | ✗ | const Eigen::VectorXd u2 = Eigen::VectorXd::Random(model.get_nu()); | |
| 390 | ✗ | crocoddyl::unittest::updateAllPinocchio(&pinocchio_model, &pinocchio_data, | |
| 391 | x2); | ||
| 392 | ✗ | model.calc(data, x2, u2); | |
| 393 | ✗ | model.calcDiff(data, x2, u2); | |
| 394 | ✗ | cost = 0; | |
| 395 | ✗ | Lx.setZero(); | |
| 396 | ✗ | Lu.setZero(); | |
| 397 | ✗ | Lxx.setZero(); | |
| 398 | ✗ | Lxu.setZero(); | |
| 399 | ✗ | Luu.setZero(); | |
| 400 | ✗ | for (std::size_t i = 0; i < 3; | |
| 401 | ++i) { // we need to update data because this costs are active | ||
| 402 | ✗ | models[i]->calc(datas[i], x2, u2); | |
| 403 | ✗ | models[i]->calcDiff(datas[i], x2, u2); | |
| 404 | ✗ | cost += datas[i]->cost; | |
| 405 | ✗ | Lx += datas[i]->Lx; | |
| 406 | ✗ | Lu += datas[i]->Lu; | |
| 407 | ✗ | Lxx += datas[i]->Lxx; | |
| 408 | ✗ | Lxu += datas[i]->Lxu; | |
| 409 | ✗ | Luu += datas[i]->Luu; | |
| 410 | } | ||
| 411 | ✗ | BOOST_CHECK(data->cost == cost); | |
| 412 | ✗ | BOOST_CHECK(data->Lx == Lx); | |
| 413 | ✗ | BOOST_CHECK(data->Lu == Lu); | |
| 414 | ✗ | BOOST_CHECK(data->Lxx == Lxx); | |
| 415 | ✗ | BOOST_CHECK(data->Lxu == Lxu); | |
| 416 | ✗ | BOOST_CHECK(data->Luu == Luu); | |
| 417 | |||
| 418 | ✗ | x2 = state->rand(); | |
| 419 | ✗ | crocoddyl::unittest::updateAllPinocchio(&pinocchio_model, &pinocchio_data, | |
| 420 | x2); | ||
| 421 | ✗ | model.calc(data, x2); | |
| 422 | ✗ | model.calcDiff(data, x2); | |
| 423 | ✗ | cost = 0.; | |
| 424 | ✗ | Lx.setZero(); | |
| 425 | ✗ | Lxx.setZero(); | |
| 426 | ✗ | for (std::size_t i = 0; i < 3; ++i) { | |
| 427 | ✗ | models[i]->calc(datas[i], x2); | |
| 428 | ✗ | models[i]->calcDiff(datas[i], x2); | |
| 429 | ✗ | cost += datas[i]->cost; | |
| 430 | ✗ | Lx += datas[i]->Lx; | |
| 431 | ✗ | Lxx += datas[i]->Lxx; | |
| 432 | } | ||
| 433 | ✗ | BOOST_CHECK(data->cost == cost); | |
| 434 | ✗ | BOOST_CHECK(data->Lx == Lx); | |
| 435 | ✗ | BOOST_CHECK(data->Lxx == Lxx); | |
| 436 | |||
| 437 | // Checking that casted computation is the same | ||
| 438 | #ifdef NDEBUG // Run only in release mode | ||
| 439 | model.changeCostStatus("random_cost_3", true); | ||
| 440 | model.changeCostStatus("random_cost_4", true); | ||
| 441 | crocoddyl::CostModelSumTpl<float> casted_model = model.cast<float>(); | ||
| 442 | const std::shared_ptr<crocoddyl::StateMultibodyTpl<float>>& casted_state = | ||
| 443 | std::static_pointer_cast<crocoddyl::StateMultibodyTpl<float>>( | ||
| 444 | casted_model.get_state()); | ||
| 445 | pinocchio::ModelTpl<float>& casted_pinocchio_model = | ||
| 446 | *casted_state->get_pinocchio().get(); | ||
| 447 | pinocchio::DataTpl<float> casted_pinocchio_data(casted_pinocchio_model); | ||
| 448 | crocoddyl::DataCollectorMultibodyTpl<float> casted_shared_data( | ||
| 449 | &casted_pinocchio_data); | ||
| 450 | std::vector<std::shared_ptr<crocoddyl::CostModelAbstractTpl<float>>> | ||
| 451 | casted_models; | ||
| 452 | std::vector<std::shared_ptr<crocoddyl::CostDataAbstractTpl<float>>> | ||
| 453 | casted_datas; | ||
| 454 | for (std::size_t i = 0; i < 5; ++i) { | ||
| 455 | casted_models.push_back(models[i]->cast<float>()); | ||
| 456 | casted_datas.push_back(casted_models[i]->createData(&casted_shared_data)); | ||
| 457 | } | ||
| 458 | const std::shared_ptr<crocoddyl::CostDataSumTpl<float>>& casted_data = | ||
| 459 | casted_model.createData(&casted_shared_data); | ||
| 460 | const Eigen::VectorXf x1_f = x1.cast<float>(); | ||
| 461 | const Eigen::VectorXf u1_f = u1.cast<float>(); | ||
| 462 | crocoddyl::unittest::updateAllPinocchio(&pinocchio_model, &pinocchio_data, | ||
| 463 | x1); | ||
| 464 | crocoddyl::unittest::updateAllPinocchio(&casted_pinocchio_model, | ||
| 465 | &casted_pinocchio_data, x1_f); | ||
| 466 | model.calc(data, x1, u1); | ||
| 467 | model.calcDiff(data, x1, u1); | ||
| 468 | casted_model.calc(casted_data, x1_f, u1_f); | ||
| 469 | casted_model.calcDiff(casted_data, x1_f, u1_f); | ||
| 470 | Lx.setZero(); | ||
| 471 | Lu.setZero(); | ||
| 472 | Lxx.setZero(); | ||
| 473 | Lxu.setZero(); | ||
| 474 | Luu.setZero(); | ||
| 475 | float cost_f = 0.f; | ||
| 476 | Eigen::VectorXf Lx_f = Lx.cast<float>(); | ||
| 477 | Eigen::VectorXf Lu_f = Lu.cast<float>(); | ||
| 478 | Eigen::MatrixXf Lxx_f = Lxx.cast<float>(); | ||
| 479 | Eigen::MatrixXf Lxu_f = Lxu.cast<float>(); | ||
| 480 | Eigen::MatrixXf Luu_f = Luu.cast<float>(); | ||
| 481 | for (std::size_t i = 0; i < 5; | ||
| 482 | ++i) { // we need to update data because this costs are active | ||
| 483 | casted_models[i]->calc(casted_datas[i], x1_f, u1_f); | ||
| 484 | casted_models[i]->calcDiff(casted_datas[i], x1_f, u1_f); | ||
| 485 | cost_f += casted_datas[i]->cost; | ||
| 486 | Lx_f += casted_datas[i]->Lx; | ||
| 487 | Lu_f += casted_datas[i]->Lu; | ||
| 488 | Lxx_f += casted_datas[i]->Lxx; | ||
| 489 | Lxu_f += casted_datas[i]->Lxu; | ||
| 490 | Luu_f += casted_datas[i]->Luu; | ||
| 491 | } | ||
| 492 | BOOST_CHECK(casted_data->cost == cost_f); | ||
| 493 | BOOST_CHECK(casted_data->Lx == Lx_f); | ||
| 494 | BOOST_CHECK(casted_data->Lu == Lu_f); | ||
| 495 | BOOST_CHECK(casted_data->Lxx == Lxx_f); | ||
| 496 | BOOST_CHECK(casted_data->Lxu == Lxu_f); | ||
| 497 | BOOST_CHECK(casted_data->Luu == Luu_f); | ||
| 498 | #endif | ||
| 499 | ✗ | } | |
| 500 | |||
| 501 | ✗ | void test_get_costs(StateModelTypes::Type state_type) { | |
| 502 | // setup the test | ||
| 503 | ✗ | StateModelFactory state_factory; | |
| 504 | ✗ | crocoddyl::CostModelSum model(state_factory.create(state_type)); | |
| 505 | // create the corresponding data object | ||
| 506 | const std::shared_ptr<crocoddyl::StateMultibody>& state = | ||
| 507 | ✗ | std::static_pointer_cast<crocoddyl::StateMultibody>(model.get_state()); | |
| 508 | ✗ | pinocchio::Data pinocchio_data(*state->get_pinocchio().get()); | |
| 509 | |||
| 510 | // create and add some contact objects | ||
| 511 | ✗ | for (unsigned i = 0; i < 5; ++i) { | |
| 512 | ✗ | std::ostringstream os; | |
| 513 | ✗ | os << "random_cost_" << i; | |
| 514 | ✗ | model.addCost(os.str(), create_random_cost(state_type), 1.); | |
| 515 | ✗ | } | |
| 516 | |||
| 517 | // get the contacts | ||
| 518 | ✗ | const crocoddyl::CostModelSum::CostModelContainer& costs = model.get_costs(); | |
| 519 | |||
| 520 | // test | ||
| 521 | ✗ | crocoddyl::CostModelSum::CostModelContainer::const_iterator it_m, end_m; | |
| 522 | unsigned i; | ||
| 523 | ✗ | for (i = 0, it_m = costs.begin(), end_m = costs.end(); it_m != end_m; | |
| 524 | ✗ | ++it_m, ++i) { | |
| 525 | ✗ | std::ostringstream os; | |
| 526 | ✗ | os << "random_cost_" << i; | |
| 527 | ✗ | BOOST_CHECK(it_m->first == os.str()); | |
| 528 | ✗ | } | |
| 529 | ✗ | } | |
| 530 | |||
| 531 | ✗ | void test_get_nr(StateModelTypes::Type state_type) { | |
| 532 | // Setup the test | ||
| 533 | ✗ | StateModelFactory state_factory; | |
| 534 | ✗ | crocoddyl::CostModelSum model(state_factory.create(state_type)); | |
| 535 | |||
| 536 | // create the corresponding data object | ||
| 537 | const std::shared_ptr<crocoddyl::StateMultibody>& state = | ||
| 538 | ✗ | std::static_pointer_cast<crocoddyl::StateMultibody>(model.get_state()); | |
| 539 | ✗ | pinocchio::Data pinocchio_data(*state->get_pinocchio().get()); | |
| 540 | |||
| 541 | // create and add some contact objects | ||
| 542 | ✗ | for (unsigned i = 0; i < 5; ++i) { | |
| 543 | ✗ | std::ostringstream os; | |
| 544 | ✗ | os << "random_cost_" << i; | |
| 545 | ✗ | model.addCost(os.str(), create_random_cost(state_type), 1.); | |
| 546 | ✗ | } | |
| 547 | |||
| 548 | // compute ni | ||
| 549 | ✗ | std::size_t nr = 0; | |
| 550 | ✗ | crocoddyl::CostModelSum::CostModelContainer::const_iterator it_m, end_m; | |
| 551 | ✗ | for (it_m = model.get_costs().begin(), end_m = model.get_costs().end(); | |
| 552 | ✗ | it_m != end_m; ++it_m) { | |
| 553 | ✗ | nr += it_m->second->cost->get_activation()->get_nr(); | |
| 554 | } | ||
| 555 | |||
| 556 | ✗ | BOOST_CHECK(nr == model.get_nr()); | |
| 557 | ✗ | } | |
| 558 | |||
| 559 | ✗ | void test_shareMemory(StateModelTypes::Type state_type) { | |
| 560 | // setup the test | ||
| 561 | ✗ | StateModelFactory state_factory; | |
| 562 | const std::shared_ptr<crocoddyl::StateAbstract> state = | ||
| 563 | ✗ | state_factory.create(state_type); | |
| 564 | ✗ | crocoddyl::CostModelSum cost_model(state); | |
| 565 | ✗ | crocoddyl::DataCollectorAbstract shared_data; | |
| 566 | const std::shared_ptr<crocoddyl::CostDataSum>& cost_data = | ||
| 567 | ✗ | cost_model.createData(&shared_data); | |
| 568 | |||
| 569 | ✗ | const std::size_t ndx = state->get_ndx(); | |
| 570 | ✗ | const std::size_t nu = cost_model.get_nu(); | |
| 571 | ✗ | crocoddyl::ActionModelLQR action_model(ndx, nu); | |
| 572 | const std::shared_ptr<crocoddyl::ActionDataAbstract>& action_data = | ||
| 573 | ✗ | action_model.createData(); | |
| 574 | |||
| 575 | ✗ | cost_data->shareMemory(action_data.get()); | |
| 576 | ✗ | cost_data->Lx = Eigen::VectorXd::Random(ndx); | |
| 577 | ✗ | cost_data->Lu = Eigen::VectorXd::Random(nu); | |
| 578 | ✗ | cost_data->Lxx = Eigen::MatrixXd::Random(ndx, ndx); | |
| 579 | ✗ | cost_data->Luu = Eigen::MatrixXd::Random(nu, nu); | |
| 580 | ✗ | cost_data->Lxu = Eigen::MatrixXd::Random(ndx, nu); | |
| 581 | |||
| 582 | // check that the data has been shared | ||
| 583 | ✗ | BOOST_CHECK(action_data->Lx.isApprox(cost_data->Lx, 1e-9)); | |
| 584 | ✗ | BOOST_CHECK(action_data->Lu.isApprox(cost_data->Lu, 1e-9)); | |
| 585 | ✗ | BOOST_CHECK(action_data->Lxx.isApprox(cost_data->Lxx, 1e-9)); | |
| 586 | ✗ | BOOST_CHECK(action_data->Luu.isApprox(cost_data->Luu, 1e-9)); | |
| 587 | ✗ | BOOST_CHECK(action_data->Lxu.isApprox(cost_data->Lxu, 1e-9)); | |
| 588 | ✗ | } | |
| 589 | |||
| 590 | //----------------------------------------------------------------------------// | ||
| 591 | |||
| 592 | ✗ | void register_unit_tests(StateModelTypes::Type state_type) { | |
| 593 | ✗ | boost::test_tools::output_test_stream test_name; | |
| 594 | test_name << "test_CostModelSum" | ||
| 595 | ✗ | << "_" << state_type; | |
| 596 | ✗ | std::cout << "Running " << test_name.str() << std::endl; | |
| 597 | ✗ | test_suite* ts = BOOST_TEST_SUITE(test_name.str()); | |
| 598 | ✗ | ts->add(BOOST_TEST_CASE(boost::bind(&test_constructor, state_type))); | |
| 599 | ✗ | ts->add(BOOST_TEST_CASE(boost::bind(&test_addCost, state_type))); | |
| 600 | ✗ | ts->add( | |
| 601 | ✗ | BOOST_TEST_CASE(boost::bind(&test_addCost_error_message, state_type))); | |
| 602 | ✗ | ts->add(BOOST_TEST_CASE(boost::bind(&test_removeCost, state_type))); | |
| 603 | ✗ | ts->add( | |
| 604 | ✗ | BOOST_TEST_CASE(boost::bind(&test_removeCost_error_message, state_type))); | |
| 605 | ✗ | ts->add(BOOST_TEST_CASE(boost::bind(&test_calc, state_type))); | |
| 606 | ✗ | ts->add(BOOST_TEST_CASE(boost::bind(&test_calcDiff, state_type))); | |
| 607 | ✗ | ts->add(BOOST_TEST_CASE(boost::bind(&test_get_costs, state_type))); | |
| 608 | ✗ | ts->add(BOOST_TEST_CASE(boost::bind(&test_get_nr, state_type))); | |
| 609 | ✗ | ts->add(BOOST_TEST_CASE(boost::bind(&test_shareMemory, state_type))); | |
| 610 | ✗ | framework::master_test_suite().add(ts); | |
| 611 | ✗ | } | |
| 612 | |||
| 613 | ✗ | bool init_function() { | |
| 614 | ✗ | register_unit_tests(StateModelTypes::StateMultibody_TalosArm); | |
| 615 | ✗ | register_unit_tests(StateModelTypes::StateMultibody_HyQ); | |
| 616 | ✗ | register_unit_tests(StateModelTypes::StateMultibody_Talos); | |
| 617 | ✗ | return true; | |
| 618 | } | ||
| 619 | |||
| 620 | ✗ | int main(int argc, char** argv) { | |
| 621 | ✗ | return ::boost::unit_test::unit_test_main(&init_function, argc, argv); | |
| 622 | } | ||
| 623 |