towr_ros_app.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 <towr/initialization/gait_generator.h>
00031 #include <towr_ros/towr_ros_interface.h>
00032 
00033 
00034 namespace towr {
00035 
00042 class TowrRosApp : public TowrRosInterface {
00043 public:
00047   void SetTowrInitialState() override
00048   {
00049     auto nominal_stance_B = formulation_.model_.kinematic_model_->GetNominalStanceInBase();
00050 
00051     double z_ground = 0.0;
00052     formulation_.initial_ee_W_ =  nominal_stance_B;
00053     std::for_each(formulation_.initial_ee_W_.begin(), formulation_.initial_ee_W_.end(),
00054                   [&](Vector3d& p){ p.z() = z_ground; } // feet at 0 height
00055     );
00056 
00057     formulation_.initial_base_.lin.at(kPos).z() = - nominal_stance_B.front().z() + z_ground;
00058   }
00059 
00063   Parameters GetTowrParameters(int n_ee, const TowrCommandMsg& msg) const override
00064   {
00065     Parameters params;
00066 
00067     // Instead of manually defining the initial durations for each foot and
00068     // step, for convenience we use a GaitGenerator with some predefined gaits
00069     // for a variety of robots (walk, trot, pace, ...).
00070     auto gait_gen_ = GaitGenerator::MakeGaitGenerator(n_ee);
00071     auto id_gait   = static_cast<GaitGenerator::Combos>(msg.gait);
00072     gait_gen_->SetCombo(id_gait);
00073     for (int ee=0; ee<n_ee; ++ee) {
00074       params.ee_phase_durations_.push_back(gait_gen_->GetPhaseDurations(msg.total_duration, ee));
00075       params.ee_in_contact_at_start_.push_back(gait_gen_->IsInContactAtStart(ee));
00076     }
00077 
00078     // Here you can also add other constraints or change parameters
00079     // params.constraints_.push_back(Parameters::BaseRom);
00080 
00081     // increases optimization time, but sometimes helps find a solution for
00082     // more difficult terrain.
00083     if (msg.optimize_phase_durations)
00084       params.OptimizePhaseDurations();
00085 
00086     return params;
00087   }
00088 
00092   void SetIpoptParameters(const TowrCommandMsg& msg) override
00093   {
00094     // the HA-L solvers are alot faster, so consider installing and using
00095     solver_->SetOption("linear_solver", "mumps"); // ma27, ma57
00096 
00097     // Analytically defining the derivatives in IFOPT as we do it, makes the
00098     // problem a lot faster. However, if this becomes too difficult, we can also
00099     // tell IPOPT to just approximate them using finite differences. However,
00100     // this uses numerical derivatives for ALL constraints, there doesn't yet
00101     // exist an option to turn on numerical derivatives for only some constraint
00102     // sets.
00103     solver_->SetOption("jacobian_approximation", "exact"); // finite difference-values
00104 
00105     // This is a great to test if the analytical derivatives implemented in are
00106     // correct. Some derivatives that are correct are still flagged, showing a
00107     // deviation of 10e-4, which is fine. What to watch out for is deviations > 10e-2.
00108     // solver_->SetOption("derivative_test", "first-order");
00109 
00110     solver_->SetOption("max_cpu_time", 40.0);
00111     solver_->SetOption("print_level", 5);
00112 
00113     if (msg.play_initialization)
00114       solver_->SetOption("max_iter", 0);
00115     else
00116       solver_->SetOption("max_iter", 3000);
00117   }
00118 };
00119 
00120 } // namespace towr
00121 
00122 
00123 int main(int argc, char *argv[])
00124 {
00125   ros::init(argc, argv, "my_towr_ros_app");
00126   towr::TowrRosApp towr_app;
00127   ros::spin();
00128 
00129   return 1;
00130 }


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