towr_ros_app.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 
32 
33 
34 namespace towr {
35 
42 class TowrRosApp : public TowrRosInterface {
43 public:
47  void SetTowrInitialState() override
48  {
49  auto nominal_stance_B = formulation_.model_.kinematic_model_->GetNominalStanceInBase();
50 
51  double z_ground = 0.0;
52  formulation_.initial_ee_W_ = nominal_stance_B;
53  std::for_each(formulation_.initial_ee_W_.begin(), formulation_.initial_ee_W_.end(),
54  [&](Vector3d& p){ p.z() = z_ground; } // feet at 0 height
55  );
56 
57  formulation_.initial_base_.lin.at(kPos).z() = - nominal_stance_B.front().z() + z_ground;
58  }
59 
63  Parameters GetTowrParameters(int n_ee, const TowrCommandMsg& msg) const override
64  {
65  Parameters params;
66 
67  // Instead of manually defining the initial durations for each foot and
68  // step, for convenience we use a GaitGenerator with some predefined gaits
69  // for a variety of robots (walk, trot, pace, ...).
70  auto gait_gen_ = GaitGenerator::MakeGaitGenerator(n_ee);
71  auto id_gait = static_cast<GaitGenerator::Combos>(msg.gait);
72  gait_gen_->SetCombo(id_gait);
73  for (int ee=0; ee<n_ee; ++ee) {
74  params.ee_phase_durations_.push_back(gait_gen_->GetPhaseDurations(msg.total_duration, ee));
75  params.ee_in_contact_at_start_.push_back(gait_gen_->IsInContactAtStart(ee));
76  }
77 
78  // Here you can also add other constraints or change parameters
79  // params.constraints_.push_back(Parameters::BaseRom);
80 
81  // increases optimization time, but sometimes helps find a solution for
82  // more difficult terrain.
83  if (msg.optimize_phase_durations)
84  params.OptimizePhaseDurations();
85 
86  return params;
87  }
88 
92  void SetIpoptParameters(const TowrCommandMsg& msg) override
93  {
94  // the HA-L solvers are alot faster, so consider installing and using
95  solver_->SetOption("linear_solver", "mumps"); // ma27, ma57
96 
97  // Analytically defining the derivatives in IFOPT as we do it, makes the
98  // problem a lot faster. However, if this becomes too difficult, we can also
99  // tell IPOPT to just approximate them using finite differences. However,
100  // this uses numerical derivatives for ALL constraints, there doesn't yet
101  // exist an option to turn on numerical derivatives for only some constraint
102  // sets.
103  solver_->SetOption("jacobian_approximation", "exact"); // finite difference-values
104 
105  // This is a great to test if the analytical derivatives implemented in are
106  // correct. Some derivatives that are correct are still flagged, showing a
107  // deviation of 10e-4, which is fine. What to watch out for is deviations > 10e-2.
108  // solver_->SetOption("derivative_test", "first-order");
109 
110  solver_->SetOption("max_cpu_time", 40.0);
111  solver_->SetOption("print_level", 5);
112 
113  if (msg.play_initialization)
114  solver_->SetOption("max_iter", 0);
115  else
116  solver_->SetOption("max_iter", 3000);
117  }
118 };
119 
120 } // namespace towr
121 
122 
123 int main(int argc, char *argv[])
124 {
125  ros::init(argc, argv, "my_towr_ros_app");
126  towr::TowrRosApp towr_app;
127  ros::spin();
128 
129  return 1;
130 }
Parameters GetTowrParameters(int n_ee, const TowrCommandMsg &msg) const override
Sets the parameters required to formulate the TOWR problem.
Definition: towr_ros_app.cc:63
towr_ros::TowrCommand TowrCommandMsg
const VectorXd at(Dx deriv) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ifopt::IpoptSolver::Ptr solver_
NLP solver, could also use SNOPT.
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char *argv[])
void SetTowrInitialState() override
Sets the feet to nominal position on flat ground and base above.
Definition: towr_ros_app.cc:47
Base class to interface TOWR with a ROS GUI and RVIZ.
std::vector< VecTimes > ee_phase_durations_
void OptimizePhaseDurations()
An example application of using TOWR together with ROS.
Definition: towr_ros_app.cc:42
std::vector< bool > ee_in_contact_at_start_
static Ptr MakeGaitGenerator(int leg_count)
KinematicModel::Ptr kinematic_model_
void SetIpoptParameters(const TowrCommandMsg &msg) override
Sets the paramters for IPOPT.
Definition: towr_ros_app.cc:92
NlpFormulation formulation_
the default formulation, can be adapted


towr_ros
Author(s): Alexander W. Winkler
autogenerated on Sat Apr 13 2019 02:28:05