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 
32 #include <towr/towr.h>
34 
35 
36 using namespace towr;
37 
38 
39 // Generate even ground.
40 class FlatGround : public HeightMap {
41 public:
42  virtual double GetHeight(double x, double y) const override { return 0.0; };
43 };
44 
45 
46 // The kinematic limits of a one-legged hopper
48 public:
50  {
51  nominal_stance_.at(0) = Eigen::Vector3d( 0.0, 0.0, -0.58);
52  max_dev_from_nominal_ << 0.25, 0.15, 0.2;
53  }
54 };
55 
56 
57 // The Centroidal dynamics of a one-legged hopper
59 public:
61  : CentroidalModel(20, // mass of the robot
62  1.2, 5.5, 6.0, 0.0, -0.2, -0.01, // base inertia
63  1) {} // number of endeffectors
64 };
65 
66 
67 int main()
68 {
69  // Kinematic limits and dynamic parameters of the hopper
70  RobotModel model;
71  model.dynamic_model_ = std::make_shared<MonopedDynamicModel>();
72  model.kinematic_model_ = std::make_shared<MonopedKinematicModel>();
73 
74 
75  // set the initial position of the hopper
76  BaseState initial_base;
77  initial_base.lin.at(kPos).z() = 0.5;
78  Eigen::Vector3d initial_foot_pos_W = Eigen::Vector3d::Zero();
79 
80 
81  // define the desired goal state of the hopper
82  BaseState goal;
83  goal.lin.at(towr::kPos) << 1.0, 0.0, 0.5;
84 
85 
86  // Parameters that define the motion. See c'tor for default values or
87  // other values that can be modified.
88  Parameters params;
89  params.t_total_ = 1.6; // [s] time to reach goal state
90  // here we define the initial phase durations, that can however be changed
91  // by the optimizer. The number of swing and stance phases however is fixed.
92  // alternating stance and swing: ____-----_____-----_____-----_____
93  params.ee_phase_durations_.push_back({0.4, 0.2, 0.4, 0.2, 0.4, 0.2, 0.2});
94  params.ee_in_contact_at_start_.push_back(true);
95 
96 
97  // Pass this information to the actual solver
98  TOWR towr;
99  towr.SetInitialState(initial_base, {initial_foot_pos_W});
100  towr.SetParameters(goal, params, model, std::make_shared<FlatGround>());
101 
102  towr.SolveNLP();
103  auto x = towr.GetSolution();
104 
105 
106  // Print out the trajecetory at discrete time samples
107  using namespace std;
108  cout.precision(2);
109  cout << fixed;
110  cout << "\n====================\nMonoped trajectory:\n====================\n";
111 
112  double t = 0.0;
113  while (t<=params.t_total_+1e-5) {
114 
115  cout << "t=" << t << "\n";
116  cout << "Base linear position x,y,z: \t";
117  cout << x.base_linear_->GetPoint(t).p().transpose() << "\t[m]" << endl;
118 
119  cout << "Base Euler roll, pitch, yaw: \t";
120  Eigen::Vector3d rad = x.base_angular_->GetPoint(t).p();
121  cout << (rad/M_PI*180).transpose() << "\t[deg]" << endl;
122 
123  cout << "Foot position x,y,z: \t";
124  cout << x.ee_motion_.at(0)->GetPoint(t).p().transpose() << "\t[m]" << endl;
125 
126  cout << "Contact force x,y,z: \t";
127  cout << x.ee_force_.at(0)->GetPoint(t).p().transpose() << "\t[N]" << endl;
128 
129  bool contact = x.phase_durations_.at(0)->IsContactPhase(t);
130  std::string foot_in_contact = contact? "yes" : "no";
131  cout << "Foot in contact: \t" + foot_in_contact << endl;
132 
133  cout << endl;
134 
135  t += 0.2;
136  }
137 }
DynamicModel::Ptr dynamic_model_
virtual double GetHeight(double x, double y) const override
Definition: example.cc:42
const VectorXd at(Dx deriv) const
std::vector< bool > ee_in_contact_at_start_
void SetInitialState(const BaseState &base, const FeetPos &feet)
void SetParameters(const BaseState &final_base, const Parameters &params, const RobotModel &model, HeightMap::Ptr terrain)
NodeSpline::Ptr base_linear_
std::vector< VecTimes > ee_phase_durations_
int main()
Definition: example.cc:67
void SolveNLP()
SplineHolder GetSolution() const
KinematicModel::Ptr kinematic_model_


towr_examples
Author(s): Alexander W. Winkler
autogenerated on Sat Apr 7 2018 02:16:00