|
aligator
0.16.0
A versatile and efficient C++ library for real-time constrained trajectory optimization.
|
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 | NoOpDynamics |
| struct | StateWrapperTpl |
| Wraps a crocoddyl::StateAbstractTpl to a manifold (aligator::ManifoldAbstractTpl). More... | |
Functions | |
| template<typename Scalar> | |
| TrajOptProblemTpl< Scalar > | convertCrocoddylProblem (const shared_ptr< crocoddyl::ShootingProblemTpl< Scalar > > &croc_problem) |
| This function converts a crocoddyl::ShootingProblemTpl to an aligator::TrajOptProblemTpl. | |
Headers for the Crocoddyl compatibility module.
| TrajOptProblemTpl< Scalar > aligator::compat::croc::convertCrocoddylProblem | ( | const shared_ptr< crocoddyl::ShootingProblemTpl< Scalar > > & | croc_problem | ) |
This function converts a crocoddyl::ShootingProblemTpl to an aligator::TrajOptProblemTpl.