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

#include <nlp_factory.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
 
ContraintPtrVec GetCosts () const
 
VariablePtrVec GetVariableSets ()
 
 NlpFactory ()=default
 
virtual ~NlpFactory ()=default
 

Public Attributes

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

Private Member Functions

ContraintPtrVec GetConstraint (ConstraintName name) const
 
CostPtrVec GetCost (const CostName &id, double weight) const
 
ContraintPtrVec MakeBaseAccConstraint () const
 
ContraintPtrVec MakeBaseRangeOfMotionConstraint () const
 
std::vector< Nodes::PtrMakeBaseVariables () const
 
std::vector< PhaseDurations::PtrMakeContactScheduleVariables () const
 
ContraintPtrVec MakeDynamicConstraint () const
 
std::vector< PhaseNodes::PtrMakeEndeffectorVariables () const
 
ContraintPtrVec MakeForceConstraint () const
 
CostPtrVec MakeForcesCost (double weight) const
 
std::vector< PhaseNodes::PtrMakeForceVariables () const
 
ContraintPtrVec MakeRangeOfMotionBoxConstraint () const
 
ContraintPtrVec MakeSwingConstraint () const
 
ContraintPtrVec MakeTerrainConstraint () const
 
ContraintPtrVec MakeTotalTimeConstraint () const
 

Detailed Description

Builds variables, cost and constraints for the legged locomotion problem.

Abstracts the entire problem of Trajectory Optimization for walking robots into the formulation of variables, constraints and cost, solvable by any NLP solver.

Definition at line 51 of file nlp_factory.h.

Member Typedef Documentation

using towr::NlpFactory::ContraintPtrVec = std::vector<ifopt::ConstraintSet::Ptr>

Definition at line 54 of file nlp_factory.h.

using towr::NlpFactory::CostPtrVec = std::vector<ifopt::CostTerm::Ptr>

Definition at line 55 of file nlp_factory.h.

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

Definition at line 56 of file nlp_factory.h.

using towr::NlpFactory::VariablePtrVec = std::vector<ifopt::VariableSet::Ptr>

Definition at line 53 of file nlp_factory.h.

using towr::NlpFactory::Vector3d = Eigen::Vector3d

Definition at line 57 of file nlp_factory.h.

Constructor & Destructor Documentation

towr::NlpFactory::NlpFactory ( )
default
virtual towr::NlpFactory::~NlpFactory ( )
virtualdefault

Member Function Documentation

NlpFactory::ContraintPtrVec towr::NlpFactory::GetConstraint ( ConstraintName  name) const
private

Definition at line 206 of file nlp_factory.cc.

NlpFactory::ContraintPtrVec towr::NlpFactory::GetConstraints ( ) const
Returns
The ifopt constraints that enforce feasible motions.

Definition at line 195 of file nlp_factory.cc.

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

Definition at line 334 of file nlp_factory.cc.

NlpFactory::ContraintPtrVec towr::NlpFactory::GetCosts ( ) const
Returns
The ifopt costs to tune the motion.

Definition at line 323 of file nlp_factory.cc.

NlpFactory::VariablePtrVec towr::NlpFactory::GetVariableSets ( )
Returns
The ifopt variable sets that will be optimized over.

Definition at line 51 of file nlp_factory.cc.

NlpFactory::ContraintPtrVec towr::NlpFactory::MakeBaseAccConstraint ( ) const
private

Definition at line 309 of file nlp_factory.cc.

NlpFactory::ContraintPtrVec towr::NlpFactory::MakeBaseRangeOfMotionConstraint ( ) const
private

Definition at line 223 of file nlp_factory.cc.

std::vector< Nodes::Ptr > towr::NlpFactory::MakeBaseVariables ( ) const
private

Definition at line 82 of file nlp_factory.cc.

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

Definition at line 177 of file nlp_factory.cc.

NlpFactory::ContraintPtrVec towr::NlpFactory::MakeDynamicConstraint ( ) const
private

Definition at line 229 of file nlp_factory.cc.

std::vector< PhaseNodes::Ptr > towr::NlpFactory::MakeEndeffectorVariables ( ) const
private

Definition at line 108 of file nlp_factory.cc.

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

Definition at line 281 of file nlp_factory.cc.

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

Definition at line 343 of file nlp_factory.cc.

std::vector< PhaseNodes::Ptr > towr::NlpFactory::MakeForceVariables ( ) const
private

Definition at line 150 of file nlp_factory.cc.

NlpFactory::ContraintPtrVec towr::NlpFactory::MakeRangeOfMotionBoxConstraint ( ) const
private

Definition at line 238 of file nlp_factory.cc.

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

Definition at line 296 of file nlp_factory.cc.

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

Definition at line 268 of file nlp_factory.cc.

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

Definition at line 254 of file nlp_factory.cc.

Member Data Documentation

BaseState towr::NlpFactory::final_base_

Definition at line 79 of file nlp_factory.h.

BaseState towr::NlpFactory::initial_base_

Definition at line 78 of file nlp_factory.h.

EEPos towr::NlpFactory::initial_ee_W_

Definition at line 80 of file nlp_factory.h.

RobotModel towr::NlpFactory::model_

Definition at line 81 of file nlp_factory.h.

Parameters towr::NlpFactory::params_

Definition at line 83 of file nlp_factory.h.

SplineHolder towr::NlpFactory::spline_holder_

Definition at line 85 of file nlp_factory.h.

HeightMap::Ptr towr::NlpFactory::terrain_

Definition at line 82 of file nlp_factory.h.


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


towr_core
Author(s): Alexander W. Winkler
autogenerated on Sun Apr 8 2018 02:18:53