parameters.h
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 #ifndef TOWR_OPTIMIZATION_PARAMETERS_H_
00031 #define TOWR_OPTIMIZATION_PARAMETERS_H_
00032 
00033 #include <vector>
00034 #include <array>
00035 #include <utility> // std::pair, std::make_pair
00036 
00037 namespace towr {
00038 
00133 class Parameters {
00134 public:
00139   enum ConstraintName { Dynamic,        
00140                         EndeffectorRom, 
00141                         TotalTime,      
00142                         Terrain,        
00143                         Force,          
00144                         Swing,          
00145                         BaseRom,        
00146                         BaseAcc         
00147   };
00152   enum CostName       { ForcesCostID,    
00153                         EEMotionCostID   
00154   };
00155 
00156   using CostWeights      = std::vector<std::pair<CostName, double>>;
00157   using UsedConstraints  = std::vector<ConstraintName>;
00158   using VecTimes         = std::vector<double>;
00159   using EEID             = unsigned int;
00160 
00164   Parameters();
00165   virtual ~Parameters() = default;
00166 
00168   std::vector<VecTimes> ee_phase_durations_;
00169 
00171   std::vector<bool> ee_in_contact_at_start_;
00172 
00174   UsedConstraints constraints_;
00175 
00177   CostWeights costs_;
00178 
00180   double dt_constraint_dynamic_;
00181 
00183   double dt_constraint_range_of_motion_;
00184 
00186   double dt_constraint_base_motion_;
00187 
00189   double duration_base_polynomial_;
00190 
00192   int ee_polynomials_per_swing_phase_;
00193 
00195   int force_polynomials_per_stance_phase_;
00196 
00198   double force_limit_in_normal_direction_;
00199 
00201   std::vector<int> bounds_final_lin_pos_,
00202                    bounds_final_lin_vel_,
00203                    bounds_final_ang_pos_,
00204                    bounds_final_ang_vel_;
00205 
00212   std::pair<double,double> bound_phase_duration_;
00213 
00215   void OptimizePhaseDurations();
00216 
00218   VecTimes GetBasePolyDurations() const;
00219 
00221   int GetPhaseCount(EEID ee) const;
00222 
00224   bool IsOptimizeTimings() const;
00225 
00227   int GetEECount() const;
00228 
00230   double GetTotalTime() const;
00231 };
00232 
00233 } // namespace towr
00234 
00235 #endif /* TOWR_OPTIMIZATION_PARAMETERS_H_ */


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