GCC Code Coverage Report


Directory: ./
File: benchmark/quadrupedal_gaits_optctrl.cpp
Date: 2025-01-16 08:47:40
Exec Total Coverage
Lines: 0 56 0.0%
Branches: 0 148 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 <example-robot-data/path.hpp>
10 #include <pinocchio/parsers/srdf.hpp>
11 #include <pinocchio/parsers/urdf.hpp>
12
13 #include "crocoddyl/core/solvers/fddp.hpp"
14 #include "crocoddyl/core/utils/callbacks.hpp"
15 #include "crocoddyl/core/utils/timer.hpp"
16 #include "crocoddyl/multibody/utils/quadruped-gaits.hpp"
17
18 int main(int argc, char* argv[]) {
19 bool CALLBACKS = false;
20 unsigned int T = 5e3; // number of trials
21 unsigned int MAXITER = 1;
22 if (argc > 1) {
23 T = atoi(argv[1]);
24 }
25
26 pinocchio::Model model;
27 pinocchio::urdf::buildModel(EXAMPLE_ROBOT_DATA_MODEL_DIR
28 "/hyq_description/robots/hyq_no_sensors.urdf",
29 pinocchio::JointModelFreeFlyer(), model);
30 pinocchio::srdf::loadReferenceConfigurations(
31 model, EXAMPLE_ROBOT_DATA_MODEL_DIR "/hyq_description/srdf/hyq.srdf",
32 false);
33
34 crocoddyl::SimpleQuadrupedGaitProblem gait(model, "lf_foot", "rf_foot",
35 "lh_foot", "rh_foot");
36
37 const Eigen::VectorXd& x0 = gait.get_defaultState();
38
39 // Walking gait_phase
40 const double stepLength(0.25), stepHeight(0.25), timeStep(1e-2);
41 const unsigned int stepKnots(25), supportKnots(2);
42
43 // DDP Solver
44 boost::shared_ptr<crocoddyl::ShootingProblem> problem =
45 gait.createWalkingProblem(x0, stepLength, stepHeight, timeStep, stepKnots,
46 supportKnots);
47 crocoddyl::SolverFDDP solver(problem);
48 if (CALLBACKS) {
49 std::vector<boost::shared_ptr<crocoddyl::CallbackAbstract> > cbs;
50 cbs.push_back(boost::make_shared<crocoddyl::CallbackVerbose>());
51 solver.setCallbacks(cbs);
52 }
53
54 // Initial State
55 const std::size_t N = solver.get_problem()->get_T();
56 std::vector<Eigen::VectorXd> xs(N, x0);
57 std::vector<Eigen::VectorXd> us = problem->quasiStatic_xs(xs);
58 xs.push_back(x0);
59
60 std::cout << "NQ: "
61 << solver.get_problem()->get_terminalModel()->get_state()->get_nq()
62 << std::endl;
63 std::cout << "Number of nodes: " << N << std::endl;
64
65 // Solving the optimal control problem
66 Eigen::ArrayXd duration(T);
67 for (unsigned int i = 0; i < T; ++i) {
68 crocoddyl::Timer timer;
69 solver.solve(xs, us, MAXITER, false, 0.1);
70 duration[i] = timer.get_duration();
71 }
72
73 double avrg_duration = duration.mean();
74 double min_duration = duration.minCoeff();
75 double max_duration = duration.maxCoeff();
76 std::cout << " FDDP.solve [ms]: " << avrg_duration << " (" << min_duration
77 << "-" << max_duration << ")" << std::endl;
78
79 // Running calc
80 for (unsigned int i = 0; i < T; ++i) {
81 crocoddyl::Timer timer;
82 problem->calc(xs, us);
83 duration[i] = timer.get_duration();
84 }
85
86 avrg_duration = duration.sum() / T;
87 min_duration = duration.minCoeff();
88 max_duration = duration.maxCoeff();
89 std::cout << " ShootingProblem.calc [ms]: " << avrg_duration << " ("
90 << min_duration << "-" << max_duration << ")" << std::endl;
91
92 // Running calcDiff
93 for (unsigned int i = 0; i < T; ++i) {
94 crocoddyl::Timer timer;
95 problem->calcDiff(xs, us);
96 duration[i] = timer.get_duration();
97 }
98
99 avrg_duration = duration.sum() / T;
100 min_duration = duration.minCoeff();
101 max_duration = duration.maxCoeff();
102 std::cout << " ShootingProblem.calcDiff [ms]: " << avrg_duration << " ("
103 << min_duration << "-" << max_duration << ")" << std::endl;
104 }
105