parameters.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 <towr/parameters.h>
31 
32 #include <algorithm>
33 
34 namespace towr {
35 
37 {
38  t_total_ = 3.0; // [s]
39 
41 
42  // 2 also works quite well. Remember that in between the nodes, forces
43  // could still be violating unilateral and friction constraints by
44  // polynomial interpolation
45  force_polynomials_per_stance_phase_ = 3; // this makes it a lot bigger
46  ee_polynomials_per_swing_phase_ = 2; // should always be 2 if i want to use swing constraint!
47 
48 
52 
53 
54  min_phase_duration_ = 0.1;
55  double max_time = 2.0; // this helps convergence
56  max_phase_duration_ = max_time>t_total_? t_total_ : max_time;
57 // max_phase_duration_ = GetTotalTime()/contact_timings_.size();
58 
59 
60  force_limit_in_norm_ = 1000; // [N] this affects convergence when optimizing gait
61 
62  constraints_ = {
63  BaseAcc,
65  Dynamic,
66  Terrain,
67  Force,
68 // TotalTime, // Attention: this causes segfault in SNOPT
69  Swing, // remove this at some point -> hacky
70 // BaseRom, // CAREFUL: restricts the base to be in a specific range->very limiting
71  };
72 
73  costs_ = {
74 // {ForcesCostID, 1.0},
75  };
76 }
77 
78 bool
80 {
82  auto v = constraints_; // shorthand
83  return std::find(v.begin(), v.end(), c) != v.end();
84 }
85 
88 {
89  std::vector<double> base_spline_timings_;
90  double dt = duration_base_polynomial_;
91  double t_left = t_total_;
92 
93  double eps = 1e-10; // since repeated subtraction causes inaccuracies
94  while (t_left > eps) {
95  double duration = t_left>dt? dt : t_left;
96  base_spline_timings_.push_back(duration);
97 
98  t_left -= dt;
99  }
100 
101  return base_spline_timings_;
102 }
103 
104 int
106 {
107  return ee_phase_durations_.at(ee).size();
108 }
109 
110 int
112 {
113  return ee_in_contact_at_start_.size();
114 }
115 
116 } // namespace towr
117 
int ee_polynomials_per_swing_phase_
Number of polynomials to parameterize foot movement during swing phases.
Definition: parameters.h:92
double dt_constraint_base_motion_
Interval at which the base motion constraint is enforced.
Definition: parameters.h:74
UsedConstraints constraints_
Which constraints should be used in the optimization problem.
Definition: parameters.h:59
double min_phase_duration_
When optimizing over phase duration, this is the minimum allowed.
Definition: parameters.h:86
std::vector< bool > ee_in_contact_at_start_
True if the foot is initially in contact with the terrain.
Definition: parameters.h:83
CostWeights costs_
Which costs should be used in the optimiation problem.
Definition: parameters.h:62
double max_phase_duration_
When optimizing over phase duration, this is is maximum allowed.
Definition: parameters.h:89
int GetPhaseCount(EEID ee) const
The number of phases allowed for endeffector ee.
Definition: parameters.cc:105
int GetEECount() const
The number of endeffectors.
Definition: parameters.cc:111
int force_polynomials_per_stance_phase_
Number of polynomials to parameterize each contact force during stance phase.
Definition: parameters.h:95
Parameters()
Default parameters to use.
Definition: parameters.cc:36
std::vector< VecTimes > ee_phase_durations_
Number and initial duration of each foot&#39;s swing and stance phases.
Definition: parameters.h:80
VecTimes GetBasePolyDurations() const
The durations of each base polynomial in the spline (lin+ang).
Definition: parameters.cc:87
double dt_constraint_dynamic_
Interval at which the dynamic constraint is enforced.
Definition: parameters.h:68
ConstraintName
Definition: parameters.h:38
double force_limit_in_norm_
The maximum allowable force [N] in normal direction.
Definition: parameters.h:98
bool OptimizeTimings() const
True if the phase durations should be optimized over.
Definition: parameters.cc:79
double dt_constraint_range_of_motion_
Interval at which the range of motion constraint is enforced.
Definition: parameters.h:71
double t_total_
Total duration [s] of the walking motion.
Definition: parameters.h:65
unsigned int EEID
Definition: parameters.h:50
double duration_base_polynomial_
Fixed duration of each cubic polynomial describing the base motion.
Definition: parameters.h:77
std::vector< double > VecTimes
Definition: parameters.h:49


towr_core
Author(s): Alexander W. Winkler
autogenerated on Sat Apr 7 2018 02:15:57