GCC Code Coverage Report


Directory: ./
File: benchmark/unicycle_optctrl.cpp
Date: 2025-01-30 11:01:55
Exec Total Coverage
Lines: 0 50 0.0%
Branches: 0 130 0.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-2023, LAAS-CNRS, Heriot-Watt University
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
7 ///////////////////////////////////////////////////////////////////////////////
8
9 #include "crocoddyl/core/actions/unicycle.hpp"
10 #include "crocoddyl/core/solvers/fddp.hpp"
11 #include "crocoddyl/core/utils/callbacks.hpp"
12 #include "crocoddyl/core/utils/timer.hpp"
13
14 int main(int argc, char* argv[]) {
15 bool CALLBACKS = false;
16 unsigned int N = 200; // number of nodes
17 unsigned int T = 5e3; // number of trials
18 unsigned int MAXITER = 1;
19 if (argc > 1) {
20 T = atoi(argv[1]);
21 }
22
23 // Creating the action models and warm point for the unicycle system
24 Eigen::VectorXd x0 = Eigen::Vector3d(1., 0., 0.);
25 std::shared_ptr<crocoddyl::ActionModelAbstract> model =
26 std::make_shared<crocoddyl::ActionModelUnicycle>();
27 std::vector<Eigen::VectorXd> xs(N + 1, x0);
28 std::vector<Eigen::VectorXd> us(N, Eigen::Vector2d::Zero());
29 std::vector<std::shared_ptr<crocoddyl::ActionModelAbstract> > runningModels(
30 N, model);
31
32 // Formulating the optimal control problem
33 std::shared_ptr<crocoddyl::ShootingProblem> problem =
34 std::make_shared<crocoddyl::ShootingProblem>(x0, runningModels, model);
35 crocoddyl::SolverDDP solver(problem);
36 if (CALLBACKS) {
37 std::vector<std::shared_ptr<crocoddyl::CallbackAbstract> > cbs;
38 cbs.push_back(std::make_shared<crocoddyl::CallbackVerbose>());
39 solver.setCallbacks(cbs);
40 }
41
42 std::cout << "NQ: "
43 << solver.get_problem()->get_terminalModel()->get_state()->get_nq()
44 << std::endl;
45 std::cout << "Number of nodes: " << N << std::endl;
46
47 // Solving the optimal control problem
48 Eigen::ArrayXd duration(T);
49 for (unsigned int i = 0; i < T; ++i) {
50 crocoddyl::Timer timer;
51 solver.solve(xs, us, MAXITER);
52 duration[i] = timer.get_duration();
53 }
54
55 double avrg_duration = duration.sum() / T;
56 double min_duration = duration.minCoeff();
57 double max_duration = duration.maxCoeff();
58 std::cout << " FDDP.solve [ms]: " << avrg_duration << " (" << min_duration
59 << "-" << max_duration << ")" << std::endl;
60
61 // Running calc
62 for (unsigned int i = 0; i < T; ++i) {
63 crocoddyl::Timer timer;
64 problem->calc(xs, us);
65 duration[i] = timer.get_duration();
66 }
67
68 avrg_duration = duration.sum() / T;
69 min_duration = duration.minCoeff();
70 max_duration = duration.maxCoeff();
71 std::cout << " ShootingProblem.calc [ms]: " << avrg_duration << " ("
72 << min_duration << "-" << max_duration << ")" << std::endl;
73
74 // Running calcDiff
75 for (unsigned int i = 0; i < T; ++i) {
76 crocoddyl::Timer timer;
77 problem->calcDiff(xs, us);
78 duration[i] = timer.get_duration();
79 }
80
81 avrg_duration = duration.sum() / T;
82 min_duration = duration.minCoeff();
83 max_duration = duration.maxCoeff();
84 std::cout << " ShootingProblem.calcDiff [ms]: " << avrg_duration << " ("
85 << min_duration << "-" << max_duration << ")" << std::endl;
86 }
87