15 using context::ConstVectorRef;
19 using context::VectorRef;
22 eigenpy::register_symbolic_link_to_registered_type<
23 Linesearch<Scalar>::Options>();
24 eigenpy::register_symbolic_link_to_registered_type<LinesearchStrategy>();
25 eigenpy::register_symbolic_link_to_registered_type<
26 proxsuite::nlp::LSInterpolation>();
28 bp::enum_<LQSolverChoice>(
"LQSolverChoice")
34 bp::class_<Workspace, bp::bases<WorkspaceBaseTpl<Scalar>>,
36 "Workspace",
"Workspace for ProxDDP.",
37 bp::init<const TrajOptProblem &>((
"self"_a,
"problem")))
38 .def_readonly(
"lqr_problem", &Workspace::lqr_problem,
39 "Buffers for the LQ subproblem.")
40 .def_readonly(
"Lxs", &Workspace::Lxs)
41 .def_readonly(
"Lus", &Workspace::Lus)
42 .def_readonly(
"Lds", &Workspace::Lds)
43 .def_readonly(
"Lvs", &Workspace::Lvs)
44 .def_readonly(
"dxs", &Workspace::dxs)
45 .def_readonly(
"dus", &Workspace::dus)
46 .def_readonly(
"dvs", &Workspace::dvs)
47 .def_readonly(
"dlams", &Workspace::dlams)
48 .def_readonly(
"trial_vs", &Workspace::trial_vs)
49 .def_readonly(
"trial_lams", &Workspace::trial_lams)
50 .def_readonly(
"lams_plus", &Workspace::lams_plus)
51 .def_readonly(
"lams_pdal", &Workspace::lams_pdal)
52 .def_readonly(
"vs_plus", &Workspace::vs_plus)
53 .def_readonly(
"vs_pdal", &Workspace::vs_pdal)
54 .def_readonly(
"shifted_constraints", &Workspace::shifted_constraints)
55 .def_readonly(
"cstr_proj_jacs", &Workspace::cstr_proj_jacs)
56 .def_readonly(
"inner_crit", &Workspace::inner_criterion)
57 .def_readonly(
"active_constraints", &Workspace::active_constraints)
58 .def_readonly(
"prev_xs", &Workspace::prev_xs)
59 .def_readonly(
"prev_us", &Workspace::prev_us)
60 .def_readonly(
"prev_lams", &Workspace::prev_lams)
61 .def_readonly(
"prev_vs", &Workspace::prev_vs)
62 .def_readonly(
"stage_infeasibilities", &Workspace::stage_infeasibilities)
63 .def_readonly(
"state_dual_infeas", &Workspace::state_dual_infeas)
64 .def_readonly(
"control_dual_infeas", &Workspace::control_dual_infeas)
67 bp::class_<Results, bp::bases<ResultsBaseTpl<Scalar>>, boost::noncopyable>(
68 "Results",
"Results struct for proxDDP.",
69 bp::init<const TrajOptProblem &>((
"self"_a,
"problem")))
70 .def(
"cycleAppend", &Results::cycleAppend, (
"self"_a,
"problem",
"x0"),
72 .def_readonly(
"al_iter", &Results::al_iter)
73 .def_readonly(
"lams", &Results::lams)
79 bp::class_<SolverType, boost::noncopyable>(
81 "A proximal, augmented Lagrangian solver, using a DDP-type scheme to "
83 "search directions and feedforward, feedback gains."
84 " The solver instance initializes both a Workspace and a Results "
86 bp::init<
const Scalar,
const Scalar, std::size_t, VerboseLevel,
88 (
"self"_a,
"tol",
"mu_init"_a = 1e-2,
"max_iters"_a = 1000,
89 "verbose"_a = VerboseLevel::QUIET,
91 .def(
"cycleProblem", &SolverType::cycleProblem,
92 (
"self"_a,
"problem",
"data"),
93 "Cycle the problem data (for MPC applications).")
94 .def_readwrite(
"bcl_params", &SolverType::bcl_params,
96 .def_readwrite(
"max_refinement_steps",
97 &SolverType::max_refinement_steps_)
98 .def_readwrite(
"refinement_threshold",
99 &SolverType::refinement_threshold_)
100 .def_readwrite(
"linear_solver_choice",
101 &SolverType::linear_solver_choice)
102 .def_readwrite(
"multiplier_update_mode",
103 &SolverType::multiplier_update_mode)
104 .def_readwrite(
"mu_init", &SolverType::mu_init,
105 "Initial AL penalty parameter.")
106 .add_property(
"mu", &SolverType::mu)
108 "rollout_max_iters", &SolverType::rollout_max_iters,
109 "Maximum number of iterations when solving the forward dynamics.")
110 .def_readwrite(
"max_al_iters", &SolverType::max_al_iters,
111 "Maximum number of AL iterations.")
112 .def_readwrite(
"ls_mode", &SolverType::ls_mode,
"Linesearch mode.")
113 .def_readwrite(
"sa_strategy", &SolverType::sa_strategy,
114 "StepAcceptance strategy.")
115 .def_readwrite(
"rollout_type", &SolverType::rollout_type_,
117 .def_readwrite(
"dual_weight", &SolverType::dual_weight,
118 "Dual penalty weight.")
119 .def_readwrite(
"reg_min", &SolverType::reg_min,
120 "Minimum regularization value.")
121 .def_readwrite(
"reg_max", &SolverType::reg_max,
122 "Maximum regularization value.")
123 .def_readwrite(
"lq_print_detailed", &SolverType::lq_print_detailed)
124 .def(
"updateLQSubproblem", &SolverType::updateLQSubproblem,
"self"_a)
125 .def(
"computeCriterion", &SolverType::computeCriterion,
"self"_a,
126 "Compute problem stationarity.")
127 .add_property(
"linearSolver",
128 bp::make_getter(&SolverType::linearSolver_,
129 eigenpy::ReturnInternalStdUniquePtr{}),
130 "Linear solver for the semismooth Newton method.")
131 .def_readwrite(
"filter", &SolverType::filter_,
132 "Pair filter used to accept a step.")
133 .def(
"computeInfeasibilities", &SolverType::computeInfeasibilities,
134 (
"self"_a,
"problem"),
"Compute problem infeasibilities.")
135 .add_property(
"num_threads", &SolverType::getNumThreads)
136 .def(
"setNumThreads", &SolverType::setNumThreads,
137 (
"self"_a,
"num_threads"))
138 .add_property(
"target_dual_tol", &SolverType::getDualTolerance)
139 .def(
"setDualTolerance", &SolverType::setDualTolerance,
141 "Manually set the solver's dual infeasibility tolerance. Once "
142 "this method is called, the dual tolerance and primal tolerance "
143 "(target_tol) will not be synced when the latter changes and "
144 "`solver.run()` is called.")
146 .def(
"run", &SolverType::run,
147 (
"self"_a,
"problem",
"xs_init"_a = bp::list(),
148 "us_init"_a = bp::list(),
"vs_init"_a = bp::list(),
149 "lams_init"_a = bp::list()),
150 "Run the algorithm. Can receive initial guess for "
151 "multiplier trajectory.");
154 using AlmParams = SolverType::AlmParams;
155 bp::scope scope{cls};
156#define _c(name) def_readwrite(#name, &AlmParams::name)
157 bp::class_<AlmParams>(
"AlmParams",
"Parameters for the ALM algorithm",
158 bp::init<>(
"self"_a))
163 ._c(mu_update_factor)