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 ¶ms, 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... | |
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.
using towr::TOWR::FeetPos = std::vector<Eigen::Vector3d> |
|
virtualdefault |
|
inlineprivate |
|
inline |
|
inline |
|
inline |
The parameters that determine the type of motion produced.
final_base | The desired final position and velocity of the base. |
params | The parameters defining the optimization problem. |
model | The kinematic and dynamic model of the system. |
terrain | The height map of the terrain to walk over. |
|
inline |
Sets the solution to a previous iteration of solver.
solver_iteration | The 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.
|
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.
|
private |
|
private |