Public Types | Public Member Functions | Public Attributes | Private Member Functions | List of all members
towr::NlpFormulation Class Reference

A sample combination of variables, cost and constraints. More...

#include <nlp_formulation.h>

Public Types

using ContraintPtrVec = std::vector< ifopt::ConstraintSet::Ptr >
 
using CostPtrVec = std::vector< ifopt::CostTerm::Ptr >
 
using EEPos = std::vector< Eigen::Vector3d >
 
using VariablePtrVec = std::vector< ifopt::VariableSet::Ptr >
 
using Vector3d = Eigen::Vector3d
 

Public Member Functions

ContraintPtrVec GetConstraints (const SplineHolder &spline_holder) const
 The ifopt constraints that enforce feasible motions. More...
 
ContraintPtrVec GetCosts () const
 The ifopt costs to tune the motion. More...
 
VariablePtrVec GetVariableSets (SplineHolder &spline_holder)
 The ifopt variable sets that will be optimized over. More...
 
 NlpFormulation ()
 
virtual ~NlpFormulation ()=default
 

Public Attributes

BaseState final_base_
 
BaseState initial_base_
 
EEPos initial_ee_W_
 
RobotModel model_
 
Parameters params_
 
HeightMap::Ptr terrain_
 

Private Member Functions

ContraintPtrVec GetConstraint (Parameters::ConstraintName name, const SplineHolder &splines) const
 
CostPtrVec GetCost (const Parameters::CostName &id, double weight) const
 
ContraintPtrVec MakeBaseAccConstraint (const SplineHolder &s) const
 
ContraintPtrVec MakeBaseRangeOfMotionConstraint (const SplineHolder &s) const
 
std::vector< NodesVariables::PtrMakeBaseVariables () const
 
std::vector< PhaseDurations::PtrMakeContactScheduleVariables () const
 
ContraintPtrVec MakeDynamicConstraint (const SplineHolder &s) const
 
CostPtrVec MakeEEMotionCost (double weight) const
 
std::vector< NodesVariablesPhaseBased::PtrMakeEndeffectorVariables () const
 
ContraintPtrVec MakeForceConstraint () const
 
CostPtrVec MakeForcesCost (double weight) const
 
std::vector< NodesVariablesPhaseBased::PtrMakeForceVariables () const
 
ContraintPtrVec MakeRangeOfMotionBoxConstraint (const SplineHolder &s) const
 
ContraintPtrVec MakeSwingConstraint () const
 
ContraintPtrVec MakeTerrainConstraint () const
 
ContraintPtrVec MakeTotalTimeConstraint () const
 

Detailed Description

A sample combination of variables, cost and constraints.

This is one example of how to combine the variables, constraints and costs provided by this library. Additional variables or constraints can be added to the NLP, or existing elements replaced to find a more powerful/general formulation. This formulation was used to generate the motions described in this paper: https://ieeexplore.ieee.org/document/8283570/

Definition at line 73 of file nlp_formulation.h.

Member Typedef Documentation

Definition at line 76 of file nlp_formulation.h.

Definition at line 77 of file nlp_formulation.h.

using towr::NlpFormulation::EEPos = std::vector<Eigen::Vector3d>

Definition at line 78 of file nlp_formulation.h.

Definition at line 75 of file nlp_formulation.h.

using towr::NlpFormulation::Vector3d = Eigen::Vector3d

Definition at line 79 of file nlp_formulation.h.

Constructor & Destructor Documentation

towr::NlpFormulation::NlpFormulation ( )

Definition at line 51 of file nlp_formulation.cc.

virtual towr::NlpFormulation::~NlpFormulation ( )
virtualdefault

Member Function Documentation

NlpFormulation::ContraintPtrVec towr::NlpFormulation::GetConstraint ( Parameters::ConstraintName  name,
const SplineHolder splines 
) const
private

Definition at line 212 of file nlp_formulation.cc.

NlpFormulation::ContraintPtrVec towr::NlpFormulation::GetConstraints ( const SplineHolder spline_holder) const

The ifopt constraints that enforce feasible motions.

Parameters
[in]usesthe fully-constructed splines for initialization of constraints.

Definition at line 201 of file nlp_formulation.cc.

NlpFormulation::CostPtrVec towr::NlpFormulation::GetCost ( const Parameters::CostName id,
double  weight 
) const
private

Definition at line 345 of file nlp_formulation.cc.

NlpFormulation::ContraintPtrVec towr::NlpFormulation::GetCosts ( ) const

The ifopt costs to tune the motion.

Definition at line 334 of file nlp_formulation.cc.

NlpFormulation::VariablePtrVec towr::NlpFormulation::GetVariableSets ( SplineHolder spline_holder)

The ifopt variable sets that will be optimized over.

Parameters

Definition at line 64 of file nlp_formulation.cc.

NlpFormulation::ContraintPtrVec towr::NlpFormulation::MakeBaseAccConstraint ( const SplineHolder s) const
private

Definition at line 320 of file nlp_formulation.cc.

NlpFormulation::ContraintPtrVec towr::NlpFormulation::MakeBaseRangeOfMotionConstraint ( const SplineHolder s) const
private

Definition at line 230 of file nlp_formulation.cc.

std::vector< NodesVariables::Ptr > towr::NlpFormulation::MakeBaseVariables ( ) const
private

Definition at line 96 of file nlp_formulation.cc.

std::vector< PhaseDurations::Ptr > towr::NlpFormulation::MakeContactScheduleVariables ( ) const
private

Definition at line 184 of file nlp_formulation.cc.

NlpFormulation::ContraintPtrVec towr::NlpFormulation::MakeDynamicConstraint ( const SplineHolder s) const
private

Definition at line 238 of file nlp_formulation.cc.

NlpFormulation::CostPtrVec towr::NlpFormulation::MakeEEMotionCost ( double  weight) const
private

Definition at line 366 of file nlp_formulation.cc.

std::vector< NodesVariablesPhaseBased::Ptr > towr::NlpFormulation::MakeEndeffectorVariables ( ) const
private

Definition at line 128 of file nlp_formulation.cc.

NlpFormulation::ContraintPtrVec towr::NlpFormulation::MakeForceConstraint ( ) const
private

Definition at line 292 of file nlp_formulation.cc.

NlpFormulation::CostPtrVec towr::NlpFormulation::MakeForcesCost ( double  weight) const
private

Definition at line 355 of file nlp_formulation.cc.

std::vector< NodesVariablesPhaseBased::Ptr > towr::NlpFormulation::MakeForceVariables ( ) const
private

Definition at line 159 of file nlp_formulation.cc.

NlpFormulation::ContraintPtrVec towr::NlpFormulation::MakeRangeOfMotionBoxConstraint ( const SplineHolder s) const
private

Definition at line 248 of file nlp_formulation.cc.

NlpFormulation::ContraintPtrVec towr::NlpFormulation::MakeSwingConstraint ( ) const
private

Definition at line 307 of file nlp_formulation.cc.

NlpFormulation::ContraintPtrVec towr::NlpFormulation::MakeTerrainConstraint ( ) const
private

Definition at line 279 of file nlp_formulation.cc.

NlpFormulation::ContraintPtrVec towr::NlpFormulation::MakeTotalTimeConstraint ( ) const
private

Definition at line 265 of file nlp_formulation.cc.

Member Data Documentation

BaseState towr::NlpFormulation::final_base_

Definition at line 101 of file nlp_formulation.h.

BaseState towr::NlpFormulation::initial_base_

Definition at line 100 of file nlp_formulation.h.

EEPos towr::NlpFormulation::initial_ee_W_

Definition at line 102 of file nlp_formulation.h.

RobotModel towr::NlpFormulation::model_

Definition at line 103 of file nlp_formulation.h.

Parameters towr::NlpFormulation::params_

Definition at line 105 of file nlp_formulation.h.

HeightMap::Ptr towr::NlpFormulation::terrain_

Definition at line 104 of file nlp_formulation.h.


The documentation for this class was generated from the following files:


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