aligator  0.12.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
 
Loading...
Searching...
No Matches
module.cpp
Go to the documentation of this file.
1
4
7
8#include <eigenpy/optional.hpp>
9
10namespace aligator {
11namespace python {
12
14#ifdef ALIGATOR_WITH_CROCODDYL_COMPAT
15void exposeCrocoddylCompat();
16#endif
17
18static void exposeEnums() {
20
21 bp::enum_<MultiplierUpdateMode>(
22 "MultiplierUpdateMode", "Enum for the kind of multiplier update to use.")
23 .value("NEWTON", MultiplierUpdateMode::NEWTON)
24 .value("PRIMAL", MultiplierUpdateMode::PRIMAL)
25 .value("PRIMAL_DUAL", MultiplierUpdateMode::PRIMAL_DUAL);
26
27 bp::enum_<LinesearchMode>("LinesearchMode", "Linesearch mode.")
28 .value("PRIMAL", LinesearchMode::PRIMAL)
29 .value("PRIMAL_DUAL", LinesearchMode::PRIMAL_DUAL);
30
31 bp::enum_<RolloutType>("RolloutType", "Rollout type.")
32 .value("ROLLOUT_LINEAR", RolloutType::LINEAR)
33 .value("ROLLOUT_NONLINEAR", RolloutType::NONLINEAR)
34 .export_values();
35
36 bp::enum_<HessianApprox>("HessianApprox",
37 "Level of approximation for the Hessian.")
38 .value("HESSIAN_EXACT", HessianApprox::EXACT)
39 .value("HESSIAN_GAUSS_NEWTON", HessianApprox::GAUSS_NEWTON)
40 .value("HESSIAN_BFGS", HessianApprox::BFGS)
41 .export_values();
42
43 bp::enum_<StepAcceptanceStrategy>("StepAcceptanceStrategy",
44 "Step acceptance strategy.")
45 .value("SA_LINESEARCH_ARMIJO", StepAcceptanceStrategy::LINESEARCH_ARMIJO)
46 .value("SA_LINESEARCH_NONMONOTONE",
48 .value("SA_FILTER", StepAcceptanceStrategy::FILTER)
49 .export_values();
50}
51
52static void exposeContainers() {
53 StdVectorPythonVisitor<std::vector<long>, true>::expose("StdVec_long");
54 eigenpy::exposeStdVectorEigenSpecificType<context::Vector3s>(
55 "StdVec_Vector3s");
56 StdVectorPythonVisitor<std::vector<bool>, true>::expose("StdVec_bool");
57}
58
59} // namespace python
60} // namespace aligator
61
62BOOST_PYTHON_MODULE(MODULE_NAME) {
63 using namespace aligator::python;
64 using aligator::context::ConstVectorRef;
65
66 bp::docstring_options module_docstring_options(true, true, true);
67
68 bp::scope().attr("__version__") = ALIGATOR_VERSION;
69#ifdef ALIGATOR_MULTITHREADING
70 bp::def("get_available_threads", &aligator::omp::get_available_threads,
71 "Get the number of available threads.");
72 bp::def("get_current_threads", &aligator::omp::get_current_threads,
73 "Get the current number of threads.");
74 bp::def("set_omp_default_options", &aligator::omp::set_default_options,
75 ("num_threads"_a, "dynamic"_a = true));
76#endif
77 eigenpy::enableEigenPy();
78
79 eigenpy::OptionalConverter<ConstVectorRef, std::optional>::registration();
80 eigenpy::detail::NoneToPython<std::nullopt_t>::registration();
81
82 bp::import("warnings");
83 bp::import("proxsuite_nlp");
84
85 bp::def(
86 "has_pinocchio_features",
87 +[]() constexpr -> bool {
88 return
89#ifdef ALIGATOR_WITH_PINOCCHIO
90 true;
91#else
92 false;
93#endif
94 },
95 "Whether Aligator (and its Python bindings) were compiled with support "
96 "for Pinocchio.");
97
99 exposeGAR();
100 exposeEnums();
103 exposeCosts();
105 exposeStage();
107 exposeFilter();
108 {
109 bp::scope dynamics = get_namespace("dynamics");
114 }
115 exposeUtils();
116
120
121#ifdef ALIGATOR_WITH_PINOCCHIO
122 exposePinocchioFeatures();
123#endif
124
125#ifdef ALIGATOR_WITH_CROCODDYL_COMPAT
126 {
127 bp::scope croc_ns = get_namespace("croc");
128 exposeCrocoddylCompat();
129 }
130#endif
131}
BOOST_PYTHON_MODULE(MODULE_NAME)
Definition module.cpp:62
Namespace for modelling system dynamics.
std::size_t get_current_threads()
Get the current number of threads.
Definition threads.hpp:33
void set_default_options(std::size_t, bool=true)
Definition threads.hpp:38
std::size_t get_available_threads()
Definition threads.hpp:30
The Python bindings.
Definition blk-matrix.hpp:5
void exposeGAR()
Expose GAR module.
void exposeConstraint()
Expose constraints.
void exposeStage()
Expose StageModel and StageData.
static void exposeEnums()
Definition module.cpp:18
static void exposeContainers()
Definition module.cpp:52
void exposeCosts()
Expose cost functions.
void exposeSolvers()
Expose solvers.
void exposeDynamics()
Expose discrete dynamics.
void exposeIntegrators()
Expose numerical integrators.
void exposeCallbacks()
Expose solver callbacks.
void exposeProblem()
Expose TrajOptProblem.
void exposeContinuousDynamics()
Expose continuous dynamics.
void exposeAutodiff()
Expose autodiff helpers.
void exposeFunctions()
Expose stagewise function classes.
bool register_enum_symlink(bool export_values)
Definition utils.hpp:14
Main package namespace.
@ LINEAR
Linear rollout.
Definition enums.hpp:7
@ NONLINEAR
Nonlinear rollout, using the full dynamics.
Definition enums.hpp:9
@ GAUSS_NEWTON
Use the Gauss-Newton approximation.
Definition enums.hpp:18
@ BFGS
Use a BFGS-type approximation.
Definition enums.hpp:20
@ EXACT
Use exact Hessian.
Definition enums.hpp:16