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 00035 00036 namespace towr { 00037 00038 enum ConstraintName { Dynamic, EndeffectorRom, TotalTime, Terrain, 00039 Force, Swing, BaseRom, BaseAcc }; 00040 enum CostName { ForcesCostID }; 00041 00045 struct Parameters { 00046 00047 using CostWeights = std::vector<std::pair<CostName, double>>; 00048 using UsedConstraints = std::vector<ConstraintName>; 00049 using VecTimes = std::vector<double>; 00050 using EEID = unsigned int; 00051 00055 Parameters(); 00056 virtual ~Parameters() = default; 00057 00059 UsedConstraints constraints_; 00060 00062 CostWeights costs_; 00063 00065 double t_total_; 00066 00068 double dt_constraint_dynamic_; 00069 00071 double dt_constraint_range_of_motion_; 00072 00074 double dt_constraint_base_motion_; 00075 00077 double duration_base_polynomial_; 00078 00080 std::vector<VecTimes> ee_phase_durations_; 00081 00083 std::vector<bool> ee_in_contact_at_start_; 00084 00086 double min_phase_duration_; 00087 00089 double max_phase_duration_; 00090 00092 int ee_polynomials_per_swing_phase_; 00093 00095 int force_polynomials_per_stance_phase_; 00096 00098 double force_limit_in_norm_; 00099 00100 00101 00103 VecTimes GetBasePolyDurations() const; 00104 00106 int GetPhaseCount(EEID ee) const; 00107 00109 bool OptimizeTimings() const; 00110 00112 int GetEECount() const; 00113 }; 00114 00115 } // namespace towr 00116 00117 #endif /* TOWR_OPTIMIZATION_PARAMETERS_H_ */