aligator  0.6.1
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
aligator::compat::croc Namespace Reference

Headers for the Crocoddyl compatibility module. More...

Namespaces

namespace  context
 

Classes

struct  ActionDataWrapperTpl
 A complicated child class to StageDataTpl which pipes Crocoddyl's data to the right places. More...
 
struct  ActionModelWrapperTpl
 Wraps a crocoddyl::ActionModelAbstract. More...
 
struct  CrocCostDataWrapperTpl
 
struct  CrocCostModelWrapperTpl
 
struct  DynamicsDataWrapperTpl
 
struct  StateWrapperTpl
 Wraps a crocoddyl::StateAbstractTpl to a manifold (proxsuite::nlp::ManifoldAbstractTpl). More...
 

Functions

template<typename Scalar >
TrajOptProblemTpl< Scalar > convertCrocoddylProblem (const boost::shared_ptr< crocoddyl::ShootingProblemTpl< Scalar > > &croc_problem)
 This function converts a crocoddyl::ShootingProblemTpl to an aligator::TrajOptProblemTpl.
 

Detailed Description

Headers for the Crocoddyl compatibility module.

Function Documentation

◆ convertCrocoddylProblem()

template<typename Scalar >
TrajOptProblemTpl< Scalar > aligator::compat::croc::convertCrocoddylProblem ( const boost::shared_ptr< crocoddyl::ShootingProblemTpl< Scalar > > & croc_problem)

This function converts a crocoddyl::ShootingProblemTpl to an aligator::TrajOptProblemTpl.

Definition at line 19 of file problem-wrap.hpp.