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

TOWR - Trajectory Optimizer for Walking Robots. More...

#include <towr.h>

Public Types

using FeetPos = std::vector< Eigen::Vector3d >
 

Public Member Functions

int GetIterationCount () const
 
SplineHolder GetSolution () const
 
void SetInitialState (const BaseState &base, const FeetPos &feet)
 The current state of the robot where the optimization starts from. More...
 
void SetParameters (const BaseState &final_base, const Parameters &params, const RobotModel &model, HeightMap::Ptr terrain)
 The parameters that determine the type of motion produced. More...
 
void SetSolution (int solver_iteration)
 Sets the solution to a previous iteration of solver. More...
 
void SolveNLP ()
 Constructs the problem and solves it with IPOPT. More...
 
 TOWR ()
 
virtual ~TOWR ()=default
 

Private Member Functions

ifopt::Problem BuildNLP ()
 

Private Attributes

NlpFactory factory_
 
ifopt::Problem nlp_
 The solver independent optimization problem formulation. More...
 

Detailed Description

TOWR - Trajectory Optimizer for Walking Robots.

Facade to the motion optimization framework. The user sets the initial state and the desired motion parameters, then and NLP is constructed and solved with the chosen solver and finally the solution splines can be retrieved.

Attention
To build this file into an executable, the solver IPOPT must be installed and linked against its ifopt interface via "find_package(ifopt_ipopt)

Definition at line 63 of file towr.h.

Member Typedef Documentation

using towr::TOWR::FeetPos = std::vector<Eigen::Vector3d>

Definition at line 65 of file towr.h.

Constructor & Destructor Documentation

towr::TOWR::TOWR ( )
inline

Definition at line 67 of file towr.h.

virtual towr::TOWR::~TOWR ( )
virtualdefault

Member Function Documentation

ifopt::Problem towr::TOWR::BuildNLP ( )
inlineprivate
Returns
the solver independent optimization problem.

Definition at line 173 of file towr.h.

int towr::TOWR::GetIterationCount ( ) const
inline
Returns
The number of iterations the solver took to find the solution.

Definition at line 154 of file towr.h.

SplineHolder towr::TOWR::GetSolution ( ) const
inline
Returns
the optimized motion for base, feet and force as splines.

The can then be queried at specific times to get the positions, velocities, or forces.

Definition at line 133 of file towr.h.

void towr::TOWR::SetInitialState ( const BaseState base,
const FeetPos feet 
)
inline

The current state of the robot where the optimization starts from.

Parameters
baseThe linear and angular position and velocity of the 6D- base.
feetThe current position of the end-effectors.

Definition at line 86 of file towr.h.

void towr::TOWR::SetParameters ( const BaseState final_base,
const Parameters params,
const RobotModel model,
HeightMap::Ptr  terrain 
)
inline

The parameters that determine the type of motion produced.

Parameters
final_baseThe desired final position and velocity of the base.
paramsThe parameters defining the optimization problem.
modelThe kinematic and dynamic model of the system.
terrainThe height map of the terrain to walk over.

Definition at line 100 of file towr.h.

void towr::TOWR::SetSolution ( int  solver_iteration)
inline

Sets the solution to a previous iteration of solver.

Parameters
solver_iterationThe iteration to be inspected.

This can be helpful when trying to understand how the NLP solver reached a particular solution. The initialization of the NLP can also be inspected by setting the iteration to zero.

Definition at line 146 of file towr.h.

void towr::TOWR::SolveNLP ( )
inline

Constructs the problem and solves it with IPOPT.

Could use any ifopt solver interface, see (http://wiki.ros.org/ifopt). Currently IPOPT and SNOPT are implemented.

Definition at line 117 of file towr.h.

Member Data Documentation

NlpFactory towr::TOWR::factory_
private

Definition at line 168 of file towr.h.

ifopt::Problem towr::TOWR::nlp_
private

The solver independent optimization problem formulation.

This object holds ownership of the optimization variables, so must exist to query the solution values.

Definition at line 166 of file towr.h.


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


towr_core
Author(s): Alexander W. Winkler
autogenerated on Sat Apr 7 2018 02:15:58