nlp_formulation.h
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 #ifndef TOWR_NLP_FACTORY_H_
31 #define TOWR_NLP_FACTORY_H_
32 
33 #include <ifopt/variable_set.h>
34 #include <ifopt/constraint_set.h>
35 #include <ifopt/cost_term.h>
36 
40 #include <towr/parameters.h>
41 
42 namespace towr {
43 
74 public:
75  using VariablePtrVec = std::vector<ifopt::VariableSet::Ptr>;
76  using ContraintPtrVec = std::vector<ifopt::ConstraintSet::Ptr>;
77  using CostPtrVec = std::vector<ifopt::CostTerm::Ptr>;
78  using EEPos = std::vector<Eigen::Vector3d>;
79  using Vector3d = Eigen::Vector3d;
80 
81  NlpFormulation ();
82  virtual ~NlpFormulation () = default;
83 
89 
94  ContraintPtrVec GetConstraints(const SplineHolder& spline_holder) const;
95 
97  ContraintPtrVec GetCosts() const;
98 
99 
106 
107 private:
108  // variables
109  std::vector<NodesVariables::Ptr> MakeBaseVariables() const;
110  std::vector<NodesVariablesPhaseBased::Ptr> MakeEndeffectorVariables() const;
111  std::vector<NodesVariablesPhaseBased::Ptr> MakeForceVariables() const;
112  std::vector<PhaseDurations::Ptr> MakeContactScheduleVariables() const;
113 
114  // constraints
116  const SplineHolder& splines) const;
125 
126  // costs
127  CostPtrVec GetCost(const Parameters::CostName& id, double weight) const;
128  CostPtrVec MakeForcesCost(double weight) const;
129  CostPtrVec MakeEEMotionCost(double weight) const;
130 };
131 
132 } /* namespace towr */
133 
134 #endif /* TOWR_NLP_FACTORY_H_ */
The parameters to tune the optimization problem.
Definition: parameters.h:133
ContraintPtrVec MakeTerrainConstraint() const
std::vector< NodesVariablesPhaseBased::Ptr > MakeEndeffectorVariables() const
std::vector< ifopt::ConstraintSet::Ptr > ContraintPtrVec
ConstraintName
Identifiers to be used to add certain constraints to the optimization problem.
Definition: parameters.h:139
ContraintPtrVec GetConstraint(Parameters::ConstraintName name, const SplineHolder &splines) const
Base class for robot specific kinematics and dynamics.
Definition: robot_model.h:63
CostPtrVec GetCost(const Parameters::CostName &id, double weight) const
ContraintPtrVec GetConstraints(const SplineHolder &spline_holder) const
The ifopt constraints that enforce feasible motions.
ContraintPtrVec MakeBaseRangeOfMotionConstraint(const SplineHolder &s) const
CostName
Indentifiers to be used to add certain costs to the optimization problem.
Definition: parameters.h:152
std::vector< ifopt::VariableSet::Ptr > VariablePtrVec
std::vector< PhaseDurations::Ptr > MakeContactScheduleVariables() const
ContraintPtrVec MakeForceConstraint() const
ContraintPtrVec GetCosts() const
The ifopt costs to tune the motion.
Builds splines from node values (pos/vel) and durations.
Definition: spline_holder.h:47
std::vector< NodesVariablesPhaseBased::Ptr > MakeForceVariables() const
ContraintPtrVec MakeDynamicConstraint(const SplineHolder &s) const
CostPtrVec MakeForcesCost(double weight) const
Can represent the 6Degree-of-Freedom floating base of a robot.
Definition: state.h:122
std::vector< Eigen::Vector3d > EEPos
A sample combination of variables, cost and constraints.
ContraintPtrVec MakeTotalTimeConstraint() const
HeightMap::Ptr terrain_
std::vector< NodesVariables::Ptr > MakeBaseVariables() const
ContraintPtrVec MakeBaseAccConstraint(const SplineHolder &s) const
VariablePtrVec GetVariableSets(SplineHolder &spline_holder)
The ifopt variable sets that will be optimized over.
Eigen::Vector3d Vector3d
std::vector< ifopt::CostTerm::Ptr > CostPtrVec
ContraintPtrVec MakeSwingConstraint() const
ContraintPtrVec MakeRangeOfMotionBoxConstraint(const SplineHolder &s) const
std::shared_ptr< HeightMap > Ptr
Definition: height_map.h:73
CostPtrVec MakeEEMotionCost(double weight) const
virtual ~NlpFormulation()=default


towr
Author(s): Alexander W. Winkler
autogenerated on Fri Apr 2 2021 02:14:16