GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: benchmark/arm_manipulation_optctrl.cpp Lines: 0 56 0.0 %
Date: 2024-02-13 11:12:33 Branches: 0 146 0.0 %

Line Branch Exec Source
1
///////////////////////////////////////////////////////////////////////////////
2
// BSD 3-Clause License
3
//
4
// Copyright (C) 2019-2023, LAAS-CNRS, University of Edinburgh
5
//                          Heriot-Watt University
6
// Copyright note valid unless otherwise stated in individual files.
7
// All rights reserved.
8
///////////////////////////////////////////////////////////////////////////////
9
10
#include "crocoddyl/core/solvers/fddp.hpp"
11
#include "crocoddyl/core/utils/callbacks.hpp"
12
#include "crocoddyl/core/utils/timer.hpp"
13
#include "factory/arm.hpp"
14
15
int main(int argc, char* argv[]) {
16
  bool CALLBACKS = false;
17
  unsigned int N = 100;  // number of nodes
18
  unsigned int T = 5e3;  // number of trials
19
  unsigned int MAXITER = 1;
20
  if (argc > 1) {
21
    T = atoi(argv[1]);
22
  }
23
24
  // Building the running and terminal models
25
  boost::shared_ptr<crocoddyl::ActionModelAbstract> runningModel, terminalModel;
26
  crocoddyl::benchmark::build_arm_action_models(runningModel, terminalModel);
27
28
  // Get the initial state
29
  boost::shared_ptr<crocoddyl::StateMultibody> state =
30
      boost::static_pointer_cast<crocoddyl::StateMultibody>(
31
          runningModel->get_state());
32
  std::cout << "NQ: " << state->get_nq() << std::endl;
33
  std::cout << "Number of nodes: " << N << std::endl;
34
  Eigen::VectorXd q0 =
35
      state->get_pinocchio()->referenceConfigurations["arm_up"];
36
  Eigen::VectorXd x0(state->get_nx());
37
  x0 << q0, Eigen::VectorXd::Random(state->get_nv());
38
39
  // For this optimal control problem, we define 100 knots (or running action
40
  // models) plus a terminal knot
41
  std::vector<boost::shared_ptr<crocoddyl::ActionModelAbstract> > runningModels(
42
      N, runningModel);
43
  boost::shared_ptr<crocoddyl::ShootingProblem> problem =
44
      boost::make_shared<crocoddyl::ShootingProblem>(x0, runningModels,
45
                                                     terminalModel);
46
  std::vector<Eigen::VectorXd> xs(N + 1, x0);
47
  std::vector<Eigen::VectorXd> us(
48
      N, Eigen::VectorXd::Zero(runningModel->get_nu()));
49
  for (unsigned int i = 0; i < N; ++i) {
50
    const boost::shared_ptr<crocoddyl::ActionModelAbstract>& model =
51
        problem->get_runningModels()[i];
52
    const boost::shared_ptr<crocoddyl::ActionDataAbstract>& data =
53
        problem->get_runningDatas()[i];
54
    model->quasiStatic(data, us[i], x0);
55
  }
56
57
  // Formulating the optimal control problem
58
  crocoddyl::SolverFDDP solver(problem);
59
  if (CALLBACKS) {
60
    std::vector<boost::shared_ptr<crocoddyl::CallbackAbstract> > cbs;
61
    cbs.push_back(boost::make_shared<crocoddyl::CallbackVerbose>());
62
    solver.setCallbacks(cbs);
63
  }
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.sum() / T;
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
}