hopper_example.cc
Go to the documentation of this file.
00001 /******************************************************************************
00002 Copyright (c) 2018, Alexander W. Winkler. All rights reserved.
00003 
00004 Redistribution and use in source and binary forms, with or without
00005 modification, are permitted provided that the following conditions are met:
00006 
00007 * Redistributions of source code must retain the above copyright notice, this
00008   list of conditions and the following disclaimer.
00009 
00010 * Redistributions in binary form must reproduce the above copyright notice,
00011   this list of conditions and the following disclaimer in the documentation
00012   and/or other materials provided with the distribution.
00013 
00014 * Neither the name of the copyright holder nor the names of its
00015   contributors may be used to endorse or promote products derived from
00016   this software without specific prior written permission.
00017 
00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00022 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00023 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00024 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00025 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00026 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00027 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 ******************************************************************************/
00029 
00030 #include <cmath>
00031 #include <iostream>
00032 
00033 #include <towr/terrain/examples/height_map_examples.h>
00034 #include <towr/nlp_formulation.h>
00035 #include <ifopt/ipopt_solver.h>
00036 
00037 
00038 using namespace towr;
00039 
00040 // A minimal example how to build a trajectory optimization problem using TOWR.
00041 //
00042 // The more advanced example that includes ROS integration, GUI, rviz
00043 // visualization and plotting can be found here:
00044 // towr_ros/src/towr_ros_app.cc
00045 int main()
00046 {
00047   NlpFormulation formulation;
00048 
00049   // terrain
00050   formulation.terrain_ = std::make_shared<FlatGround>(0.0);
00051 
00052   // Kinematic limits and dynamic parameters of the hopper
00053   formulation.model_ = RobotModel(RobotModel::Monoped);
00054 
00055   // set the initial position of the hopper
00056   formulation.initial_base_.lin.at(kPos).z() = 0.5;
00057   formulation.initial_ee_W_.push_back(Eigen::Vector3d::Zero());
00058 
00059   // define the desired goal state of the hopper
00060   formulation.final_base_.lin.at(towr::kPos) << 1.0, 0.0, 0.5;
00061 
00062   // Parameters that define the motion. See c'tor for default values or
00063   // other values that can be modified.
00064   // First we define the initial phase durations, that can however be changed
00065   // by the optimizer. The number of swing and stance phases however is fixed.
00066   // alternating stance and swing:     ____-----_____-----_____-----_____
00067   formulation.params_.ee_phase_durations_.push_back({0.4, 0.2, 0.4, 0.2, 0.4, 0.2, 0.2});
00068   formulation.params_.ee_in_contact_at_start_.push_back(true);
00069 
00070   // Initialize the nonlinear-programming problem with the variables,
00071   // constraints and costs.
00072   ifopt::Problem nlp;
00073   SplineHolder solution;
00074   for (auto c : formulation.GetVariableSets(solution))
00075     nlp.AddVariableSet(c);
00076   for (auto c : formulation.GetConstraints(solution))
00077     nlp.AddConstraintSet(c);
00078   for (auto c : formulation.GetCosts())
00079     nlp.AddCostSet(c);
00080 
00081   // You can add your own elements to the nlp as well, simply by calling:
00082   // nlp.AddVariablesSet(your_custom_variables);
00083   // nlp.AddConstraintSet(your_custom_constraints);
00084 
00085   // Choose ifopt solver (IPOPT or SNOPT), set some parameters and solve.
00086   // solver->SetOption("derivative_test", "first-order");
00087   auto solver = std::make_shared<ifopt::IpoptSolver>();
00088   solver->SetOption("jacobian_approximation", "exact"); // "finite difference-values"
00089   solver->SetOption("max_cpu_time", 20.0);
00090   solver->Solve(nlp);
00091 
00092   // Can directly view the optimization variables through:
00093   // Eigen::VectorXd x = nlp.GetVariableValues()
00094   // However, it's more convenient to access the splines constructed from these
00095   // variables and query their values at specific times:
00096   using namespace std;
00097   cout.precision(2);
00098   nlp.PrintCurrent(); // view variable-set, constraint violations, indices,...
00099   cout << fixed;
00100   cout << "\n====================\nMonoped trajectory:\n====================\n";
00101 
00102   double t = 0.0;
00103   while (t<=solution.base_linear_->GetTotalTime() + 1e-5) {
00104     cout << "t=" << t << "\n";
00105     cout << "Base linear position x,y,z:   \t";
00106     cout << solution.base_linear_->GetPoint(t).p().transpose() << "\t[m]" << endl;
00107 
00108     cout << "Base Euler roll, pitch, yaw:  \t";
00109     Eigen::Vector3d rad = solution.base_angular_->GetPoint(t).p();
00110     cout << (rad/M_PI*180).transpose() << "\t[deg]" << endl;
00111 
00112     cout << "Foot position x,y,z:          \t";
00113     cout << solution.ee_motion_.at(0)->GetPoint(t).p().transpose() << "\t[m]" << endl;
00114 
00115     cout << "Contact force x,y,z:          \t";
00116     cout << solution.ee_force_.at(0)->GetPoint(t).p().transpose() << "\t[N]" << endl;
00117 
00118     bool contact = solution.phase_durations_.at(0)->IsContactPhase(t);
00119     std::string foot_in_contact = contact? "yes" : "no";
00120     cout << "Foot in contact:              \t" + foot_in_contact << endl;
00121 
00122     cout << endl;
00123 
00124     t += 0.2;
00125   }
00126 }


towr
Author(s): Alexander W. Winkler
autogenerated on Mon Apr 15 2019 02:42:32