hopper_example.cc
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2018, Alexander W. Winkler. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without
5 modification, are permitted provided that the following conditions are met:
6 
7 * Redistributions of source code must retain the above copyright notice, this
8  list of conditions and the following disclaimer.
9 
10 * Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 
14 * Neither the name of the copyright holder nor the names of its
15  contributors may be used to endorse or promote products derived from
16  this software without specific prior written permission.
17 
18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 ******************************************************************************/
29 
30 #include <cmath>
31 #include <iostream>
32 
34 #include <towr/nlp_formulation.h>
35 #include <ifopt/ipopt_solver.h>
36 
37 
38 using namespace towr;
39 
40 // A minimal example how to build a trajectory optimization problem using TOWR.
41 //
42 // The more advanced example that includes ROS integration, GUI, rviz
43 // visualization and plotting can be found here:
44 // towr_ros/src/towr_ros_app.cc
45 int main()
46 {
47  NlpFormulation formulation;
48 
49  // terrain
50  formulation.terrain_ = std::make_shared<FlatGround>(0.0);
51 
52  // Kinematic limits and dynamic parameters of the hopper
53  formulation.model_ = RobotModel(RobotModel::Monoped);
54 
55  // set the initial position of the hopper
56  formulation.initial_base_.lin.at(kPos).z() = 0.5;
57  formulation.initial_ee_W_.push_back(Eigen::Vector3d::Zero());
58 
59  // define the desired goal state of the hopper
60  formulation.final_base_.lin.at(towr::kPos) << 1.0, 0.0, 0.5;
61 
62  // Parameters that define the motion. See c'tor for default values or
63  // other values that can be modified.
64  // First we define the initial phase durations, that can however be changed
65  // by the optimizer. The number of swing and stance phases however is fixed.
66  // alternating stance and swing: ____-----_____-----_____-----_____
67  formulation.params_.ee_phase_durations_.push_back({0.4, 0.2, 0.4, 0.2, 0.4, 0.2, 0.2});
68  formulation.params_.ee_in_contact_at_start_.push_back(true);
69 
70  // Initialize the nonlinear-programming problem with the variables,
71  // constraints and costs.
72  ifopt::Problem nlp;
73  SplineHolder solution;
74  for (auto c : formulation.GetVariableSets(solution))
75  nlp.AddVariableSet(c);
76  for (auto c : formulation.GetConstraints(solution))
77  nlp.AddConstraintSet(c);
78  for (auto c : formulation.GetCosts())
79  nlp.AddCostSet(c);
80 
81  // You can add your own elements to the nlp as well, simply by calling:
82  // nlp.AddVariablesSet(your_custom_variables);
83  // nlp.AddConstraintSet(your_custom_constraints);
84 
85  // Choose ifopt solver (IPOPT or SNOPT), set some parameters and solve.
86  // solver->SetOption("derivative_test", "first-order");
87  auto solver = std::make_shared<ifopt::IpoptSolver>();
88  solver->SetOption("jacobian_approximation", "exact"); // "finite difference-values"
89  solver->SetOption("max_cpu_time", 20.0);
90  solver->Solve(nlp);
91 
92  // Can directly view the optimization variables through:
93  // Eigen::VectorXd x = nlp.GetVariableValues()
94  // However, it's more convenient to access the splines constructed from these
95  // variables and query their values at specific times:
96  using namespace std;
97  cout.precision(2);
98  nlp.PrintCurrent(); // view variable-set, constraint violations, indices,...
99  cout << fixed;
100  cout << "\n====================\nMonoped trajectory:\n====================\n";
101 
102  double t = 0.0;
103  while (t<=solution.base_linear_->GetTotalTime() + 1e-5) {
104  cout << "t=" << t << "\n";
105  cout << "Base linear position x,y,z: \t";
106  cout << solution.base_linear_->GetPoint(t).p().transpose() << "\t[m]" << endl;
107 
108  cout << "Base Euler roll, pitch, yaw: \t";
109  Eigen::Vector3d rad = solution.base_angular_->GetPoint(t).p();
110  cout << (rad/M_PI*180).transpose() << "\t[deg]" << endl;
111 
112  cout << "Foot position x,y,z: \t";
113  cout << solution.ee_motion_.at(0)->GetPoint(t).p().transpose() << "\t[m]" << endl;
114 
115  cout << "Contact force x,y,z: \t";
116  cout << solution.ee_force_.at(0)->GetPoint(t).p().transpose() << "\t[N]" << endl;
117 
118  bool contact = solution.phase_durations_.at(0)->IsContactPhase(t);
119  std::string foot_in_contact = contact? "yes" : "no";
120  cout << "Foot in contact: \t" + foot_in_contact << endl;
121 
122  cout << endl;
123 
124  t += 0.2;
125  }
126 }
one-legged hopper
Definition: robot_model.h:70
void AddCostSet(CostTerm::Ptr cost_set)
const VectorXd at(Dx deriv) const
Read the state value or it&#39;s derivatives by index.
Definition: state.cc:41
Base class for robot specific kinematics and dynamics.
Definition: robot_model.h:63
std::vector< PhaseDurations::Ptr > phase_durations_
Definition: spline_holder.h:76
ContraintPtrVec GetConstraints(const SplineHolder &spline_holder) const
The ifopt constraints that enforce feasible motions.
ContraintPtrVec GetCosts() const
The ifopt costs to tune the motion.
Builds splines from node values (pos/vel) and durations.
Definition: spline_holder.h:47
int main()
NodeSpline::Ptr base_linear_
Definition: spline_holder.h:71
std::vector< VecTimes > ee_phase_durations_
Number and initial duration of each foot&#39;s swing and stance phases.
Definition: parameters.h:168
void PrintCurrent() const
A sample combination of variables, cost and constraints.
std::vector< NodeSpline::Ptr > ee_force_
Definition: spline_holder.h:75
HeightMap::Ptr terrain_
NodeSpline::Ptr base_angular_
Definition: spline_holder.h:72
Node lin
linear position x,y,z and velocities.
Definition: state.h:125
VariablePtrVec GetVariableSets(SplineHolder &spline_holder)
The ifopt variable sets that will be optimized over.
std::vector< bool > ee_in_contact_at_start_
True if the foot is initially in contact with the terrain.
Definition: parameters.h:171
void AddConstraintSet(ConstraintSet::Ptr constraint_set)
void AddVariableSet(VariableSet::Ptr variable_set)
std::vector< NodeSpline::Ptr > ee_motion_
Definition: spline_holder.h:74


towr
Author(s): Alexander W. Winkler
autogenerated on Fri Apr 2 2021 02:14:16