Skip to content

Commit f5c41a2

Browse files
jorisvEwen Dantec
authored andcommitted
python: Add custodian_and_ward to manage polymorphic lifetime
1 parent ed9754b commit f5c41a2

20 files changed

Lines changed: 155 additions & 87 deletions

bindings/python/src/compat/expose-croco-compat.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -32,15 +32,15 @@ void exposeCrocoddylCompat() {
3232
bp::class_<ActionModelWrapper, bp::bases<context::StageModel>>(
3333
"ActionModelWrapper", "Wrapper for Crocoddyl action models.",
3434
bp::init<boost::xyz::polymorphic<CrocActionModel>>(
35-
bp::args("action_model")))
35+
bp::args("action_model"))[bp::with_custodian_and_ward<1, 2>()])
3636
.def_readonly("action_model", &ActionModelWrapper::action_model_,
3737
"Underlying Crocoddyl ActionModel.");
3838

3939
bp::register_ptr_to_python<shared_ptr<ActionDataWrapper>>();
4040
bp::class_<ActionDataWrapper, bp::bases<context::StageData>>(
4141
"ActionDataWrapper", bp::no_init)
42-
.def(bp::init<const boost::xyz::polymorphic<CrocActionModel> &>(
43-
bp::args("self", "croc_action_model")))
42+
.def(bp::init<const boost::xyz::polymorphic<CrocActionModel> &>(bp::args(
43+
"self", "croc_action_model"))[bp::with_custodian_and_ward<1, 2>()])
4444
.def_readonly("croc_action_data", &ActionDataWrapper::croc_action_data,
4545
"Underlying Crocoddyl action data.");
4646

@@ -51,7 +51,7 @@ void exposeCrocoddylCompat() {
5151
bp::class_<StateWrapper, bp::bases<context::Manifold>>(
5252
"StateWrapper", "Wrapper for a Crocoddyl state.", bp::no_init)
5353
.def(bp::init<boost::xyz::polymorphic<StateAbstract>>(
54-
bp::args("self", "state")))
54+
bp::args("self", "state"))[bp::with_custodian_and_ward<1, 2>()])
5555
.def_readonly("croc_state", &StateWrapper::croc_state);
5656
}
5757

bindings/python/src/expose-constraint.cpp

Lines changed: 11 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -25,15 +25,17 @@ void exposeConstraint() {
2525
"A stage-wise constraint, of the form :math:`c(x,u) \\leq 0 c(x,u)`.\n"
2626
":param f: underlying function\n"
2727
":param cs: constraint set",
28-
bp::no_init)
29-
.def("__init__",
30-
bp::make_constructor(make_constraint_wrap,
31-
bp::default_call_policies(),
32-
("func"_a, "cstr_set")),
33-
"Contruct a StageConstraint from a StageFunction and a constraint "
34-
"set.")
35-
.def_readwrite("func", &StageConstraint::func)
36-
.def_readwrite("set", &StageConstraint::set)
28+
bp::init<const PolyFunc &, const PolySet &>(
29+
("self"_a, "func", "cstr_set"),
30+
"Contruct a StageConstraint from a StageFunction and a constraint "
31+
"set.")[bp::with_custodian_and_ward<
32+
1, 2, bp::with_custodian_and_ward<1, 3>>()])
33+
.add_property("func", bp::make_getter(&StageConstraint::func),
34+
bp::make_setter(&StageConstraint::func,
35+
bp::with_custodian_and_ward<1, 2>()))
36+
.add_property("set", bp::make_getter(&StageConstraint::set),
37+
bp::make_setter(&StageConstraint::set,
38+
bp::with_custodian_and_ward<1, 2>()))
3739
.add_property(
3840
"nr", +[](StageConstraint const &el) { return el.func->nr; },
3941
"Get constraint dimension.");

bindings/python/src/expose-costs.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -30,8 +30,8 @@ void exposeQuadCost() {
3030

3131
bp::class_<ConstantCostTpl<Scalar>, bp::bases<CostAbstract>>(
3232
"ConstantCost", "A constant cost term.",
33-
bp::init<xyz::polymorphic<Manifold>, int, Scalar>(
34-
bp::args("self", "space", "nu", "value")))
33+
bp::init<xyz::polymorphic<Manifold>, int, Scalar>(bp::args(
34+
"self", "space", "nu", "value"))[bp::with_custodian_and_ward<1, 2>()])
3535
.def_readwrite("value", &ConstantCostTpl<Scalar>::value_)
3636
.def(CopyableVisitor<ConstantCostTpl<Scalar>>())
3737
.def(poly_visitor);

bindings/python/src/expose-functions.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -146,7 +146,8 @@ void exposeFunctions() {
146146
"StateErrorResidual",
147147
bp::init<const xyz::polymorphic<context::Manifold> &, const int,
148148
const context::VectorXs &>(
149-
bp::args("self", "space", "nu", "target")))
149+
bp::args("self", "space", "nu",
150+
"target"))[bp::with_custodian_and_ward<1, 2>()])
150151
.def_readonly("space", &StateErrorResidual::space_)
151152
.def_readwrite("target", &StateErrorResidual::target_)
152153
.def(PolymorphicMultiBaseVisitor<UnaryFunction, StageFunction>());
@@ -155,7 +156,8 @@ void exposeFunctions() {
155156
"ControlErrorResidual",
156157
bp::init<const int, const xyz::polymorphic<context::Manifold> &,
157158
const context::VectorXs &>(
158-
bp::args("self", "ndx", "uspace", "target")))
159+
bp::args("self", "ndx", "uspace",
160+
"target"))[bp::with_custodian_and_ward<1, 3>()])
159161
.def(bp::init<const int, const context::VectorXs &>(
160162
bp::args("self", "ndx", "target")))
161163
.def(bp::init<int, int>(bp::args("self", "ndx", "nu")))

bindings/python/src/expose-problem.cpp

Lines changed: 32 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,8 @@
55
#include "aligator/core/traj-opt-data.hpp"
66
#include "aligator/core/cost-abstract.hpp"
77

8+
#include "proxsuite-nlp/python/polymorphic.hpp"
9+
810
namespace aligator {
911
namespace python {
1012
void exposeProblem() {
@@ -18,6 +20,7 @@ void exposeProblem() {
1820
using context::TrajOptProblem;
1921
using context::UnaryFunction;
2022

23+
using proxsuite::nlp::python::with_custodian_and_ward_list_content;
2124
using PolyFunction = xyz::polymorphic<UnaryFunction>;
2225
using PolyStage = xyz::polymorphic<StageModel>;
2326
using PolyCost = xyz::polymorphic<CostAbstract>;
@@ -27,21 +30,37 @@ void exposeProblem() {
2730
bp::no_init)
2831
.def(bp::init<PolyFunction, const std::vector<PolyStage> &, PolyCost>(
2932
"Constructor adding the initial constraint explicitly.",
30-
("self"_a, "init_constraint", "stages", "term_cost")))
33+
("self"_a, "init_constraint", "stages", "term_cost"))
34+
[bp::with_custodian_and_ward<
35+
1, 2,
36+
with_custodian_and_ward_list_content<
37+
1, 3, bp::with_custodian_and_ward<1, 4>>>()])
3138
.def(bp::init<ConstVectorRef, const std::vector<PolyStage> &, PolyCost>(
3239
"Constructor for an initial value problem.",
33-
("self"_a, "x0", "stages", "term_cost")))
34-
.def(bp::init<PolyFunction, PolyCost>(
35-
"Constructor adding the initial constraint explicitly (without "
36-
"stages).",
37-
("self"_a, "init_constraint", "term_cost")))
38-
.def(bp::init<ConstVectorRef, const int, PolyManifold, PolyCost>(
39-
"Constructor for an initial value problem (without pre-allocated "
40-
"stages).",
41-
("self"_a, "x0", "nu", "space", "term_cost")))
40+
("self"_a, "x0", "stages", "term_cost"))
41+
[with_custodian_and_ward_list_content<
42+
1, 3, bp::with_custodian_and_ward<1, 4>>()])
43+
.def(
44+
bp::init<PolyFunction, PolyCost>(
45+
"Constructor adding the initial constraint explicitly (without "
46+
"stages).",
47+
("self"_a, "init_constraint", "term_cost"))
48+
[bp::with_custodian_and_ward<1, 2,
49+
bp::with_custodian_and_ward<1, 3>>()]
50+
51+
)
52+
.def(
53+
bp::init<ConstVectorRef, const int, PolyManifold, PolyCost>(
54+
"Constructor for an initial value problem (without pre-allocated "
55+
"stages).",
56+
("self"_a, "x0", "nu", "space", "term_cost"))
57+
[bp::with_custodian_and_ward<1, 3,
58+
bp::with_custodian_and_ward<1, 4>>()]
59+
60+
)
4261
.def<void (TrajOptProblem::*)(const PolyStage &)>(
4362
"addStage", &TrajOptProblem::addStage, ("self"_a, "new_stage"),
44-
"Add a stage to the problem.")
63+
"Add a stage to the problem.", bp::with_custodian_and_ward<1, 2>())
4564
.def_readonly("stages", &TrajOptProblem::stages_,
4665
"Stages of the shooting problem.")
4766
.def_readwrite("term_cost", &TrajOptProblem::term_cost_,
@@ -55,7 +74,8 @@ void exposeProblem() {
5574
.add_property("init_constraint", &TrajOptProblem::init_condition_,
5675
"Get initial state constraint.")
5776
.def("addTerminalConstraint", &TrajOptProblem::addTerminalConstraint,
58-
("self"_a, "constraint"), "Add a terminal constraint.")
77+
("self"_a, "constraint"), "Add a terminal constraint.",
78+
bp::with_custodian_and_ward<1, 2>())
5979
.def("removeTerminalConstraint",
6080
&TrajOptProblem::removeTerminalConstraints, "self"_a,
6181
"Remove all terminal constraints.")

bindings/python/src/expose-stage.cpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -41,15 +41,19 @@ void exposeStage() {
4141
"A stage of the control problem. Holds costs, dynamics, and constraints.",
4242
bp::no_init)
4343
.def(bp::init<const PolyCost &, const PolyDynamics &>(
44-
("self"_a, "cost", "dynamics")))
44+
("self"_a, "cost", "dynamics"))[bp::with_custodian_and_ward<
45+
1, 2, bp::with_custodian_and_ward<1, 3>>()])
4546
.def<void (StageModel::*)(const context::StageConstraint &)>(
4647
"addConstraint", &StageModel::addConstraint, ("self"_a, "constraint"),
47-
"Add an existing constraint to the stage.")
48+
"Add an existing constraint to the stage.",
49+
bp::with_custodian_and_ward<1, 2>())
4850
.def<void (StageModel::*)(const PolyFunction &, const PolyCstrSet &)>(
4951
"addConstraint", &StageModel::addConstraint,
5052
("self"_a, "func", "cstr_set"),
5153
"Constructs a new constraint (from the underlying function and set) "
52-
"and adds it to the stage.")
54+
"and adds it to the stage.",
55+
bp::with_custodian_and_ward<1, 2,
56+
bp::with_custodian_and_ward<1, 3>>())
5357
.def_readonly("constraints", &StageModel::constraints_,
5458
"Get the set of constraints.")
5559
.def_readonly("dynamics", &StageModel::dynamics_, "Stage dynamics.")

bindings/python/src/modelling/expose-autodiff.cpp

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,9 @@ void exposeAutodiff() {
2323
"Make a function into a differentiable function/dynamics using"
2424
" finite differences.",
2525
bp::init<xyz::polymorphic<Manifold>, xyz::polymorphic<StageFunction>,
26-
const Scalar>(bp::args("self", "space", "func", "eps")));
26+
const Scalar>(bp::args("self", "space", "func", "eps"))
27+
[bp::with_custodian_and_ward<1, 2,
28+
bp::with_custodian_and_ward<1, 3>>()]);
2729
bp::class_<FiniteDiffType::Data, bp::bases<StageFunctionData>>("Data",
2830
bp::no_init);
2931
}
@@ -33,7 +35,9 @@ void exposeAutodiff() {
3335
bp::scope _ = bp::class_<DynFiniteDiffType, bp::bases<DynamicsModel>>(
3436
"DynamicsFiniteDifferenceHelper",
3537
bp::init<xyz::polymorphic<Manifold>, xyz::polymorphic<DynamicsModel>,
36-
const Scalar>(bp::args("self", "space", "dyn", "eps")));
38+
const Scalar>(bp::args("self", "space", "dyn", "eps"))
39+
[bp::with_custodian_and_ward<1, 2,
40+
bp::with_custodian_and_ward<1, 3>>()]);
3741
bp::class_<DynFiniteDiffType::Data>("Data", bp::no_init);
3842
}
3943

@@ -45,7 +49,8 @@ void exposeAutodiff() {
4549
"Define a cost function's derivatives using finite differences.",
4650
bp::no_init)
4751
.def(bp::init<xyz::polymorphic<CostAbstract>, Scalar>(
48-
bp::args("self", "cost", "fd_eps")));
52+
bp::args("self", "cost",
53+
"fd_eps"))[bp::with_custodian_and_ward<1, 2>()]);
4954
bp::class_<CostFiniteDiffType::Data, bp::bases<CostData>>("Data",
5055
bp::no_init)
5156
.def_readonly("c1", &CostFiniteDiffType::Data::c1)

bindings/python/src/modelling/expose-centroidal.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -181,7 +181,8 @@ void exposeCentroidalFunctions() {
181181
bp::class_<CentroidalWrapperResidual, bp::bases<UnaryFunction>>(
182182
"CentroidalWrapperResidual",
183183
"A wrapper for centroidal cost with smooth control",
184-
bp::init<xyz::polymorphic<StageFunction>>(("self"_a, "centroidal_cost")))
184+
bp::init<xyz::polymorphic<StageFunction>>(
185+
("self"_a, "centroidal_cost"))[bp::with_custodian_and_ward<1, 2>()])
185186
.def_readwrite("centroidal_cost",
186187
&CentroidalWrapperResidual::centroidal_cost_)
187188
.def(CreateDataPythonVisitor<CentroidalWrapperResidual>())

bindings/python/src/modelling/expose-composite-costs.cpp

Lines changed: 16 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,9 @@ void exposeComposites() {
3030
bp::class_<QuadResCost, bp::bases<CostAbstract>>(
3131
"QuadraticResidualCost", "Weighted 2-norm of a given residual function.",
3232
bp::init<ManifoldPtr, PolyFunction, const ConstMatrixRef &>(
33-
bp::args("self", "space", "function", "weights")))
33+
bp::args("self", "space", "function", "weights"))
34+
[bp::with_custodian_and_ward<1, 2,
35+
bp::with_custodian_and_ward<1, 3>>()])
3436
.def_readwrite("residual", &QuadResCost::residual_)
3537
.def_readwrite("weights", &QuadResCost::weights_)
3638
.def(CopyableVisitor<QuadResCost>())
@@ -39,9 +41,12 @@ void exposeComposites() {
3941
bp::class_<LogResCost, bp::bases<CostAbstract>>(
4042
"LogResidualCost", "Weighted log-cost composite cost.",
4143
bp::init<ManifoldPtr, PolyFunction, const ConstVectorRef &>(
42-
bp::args("self", "space", "function", "barrier_weights")))
44+
bp::args("self", "space", "function", "barrier_weights"))
45+
[bp::with_custodian_and_ward<1, 2,
46+
bp::with_custodian_and_ward<1, 3>>()])
4347
.def(bp::init<ManifoldPtr, PolyFunction, Scalar>(
44-
bp::args("self", "function", "scale")))
48+
bp::args("self", "function", "scale"))[bp::with_custodian_and_ward<
49+
1, 2, bp::with_custodian_and_ward<1, 3>>()])
4550
.def_readwrite("residual", &LogResCost::residual_)
4651
.def_readwrite("weights", &LogResCost::barrier_weights_)
4752
.def(CopyableVisitor<LogResCost>())
@@ -62,20 +67,22 @@ void exposeComposites() {
6267
bp::args("self", "resdl", "weights")))
6368
.def(bp::init<ManifoldPtr, const int, const ConstVectorRef &,
6469
const MatrixXs &>(
65-
bp::args("self", "space", "nu", "target", "weights")))
70+
bp::args("self", "space", "nu", "target",
71+
"weights"))[bp::with_custodian_and_ward<1, 2>()])
6672
.add_property("target", &QuadStateCost::getTarget,
6773
&QuadStateCost::setTarget,
6874
"Target of the quadratic distance.")
6975
.def(visitor);
7076

7177
bp::class_<QuadControlCost, bp::bases<QuadResCost>>(
7278
"QuadraticControlCost", "Quadratic control cost.", bp::no_init)
73-
.def(bp::init<ManifoldPtr, ConstVectorRef, const MatrixXs &>(
74-
bp::args("space", "target", "weights")))
79+
.def(bp::init<ManifoldPtr, ConstVectorRef, const MatrixXs &>(bp::args(
80+
"space", "target", "weights"))[bp::with_custodian_and_ward<1, 2>()])
7581
.def(bp::init<ManifoldPtr, QuadControlCost::Error, const MatrixXs &>(
76-
bp::args("self", "space", "resdl", "weights")))
77-
.def(bp::init<ManifoldPtr, int, const MatrixXs &>(
78-
bp::args("space", "nu", "weights")))
82+
bp::args("self", "space", "resdl",
83+
"weights"))[bp::with_custodian_and_ward<1, 2>()])
84+
.def(bp::init<ManifoldPtr, int, const MatrixXs &>(bp::args(
85+
"space", "nu", "weights"))[bp::with_custodian_and_ward<1, 2>()])
7986
.add_property("target", &QuadControlCost::getTarget,
8087
&QuadControlCost::setTarget,
8188
"Reference of the control cost.")

bindings/python/src/modelling/expose-continuous-dynamics.cpp

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -33,10 +33,11 @@ void exposeContinuousDynamics() {
3333
bp::class_<PyContinuousDynamics<>, boost::noncopyable>(
3434
"ContinuousDynamicsAbstract",
3535
"Base class for continuous-time dynamical models (DAEs and ODEs).",
36-
bp::init<ManifoldPtr, int>("Default constructor: provide the working "
37-
"manifold and control space "
38-
"dimension.",
39-
bp::args("self", "space", "nu")))
36+
bp::init<ManifoldPtr, int>(
37+
"Default constructor: provide the working "
38+
"manifold and control space "
39+
"dimension.",
40+
bp::args("self", "space", "nu"))[bp::with_custodian_and_ward<1, 2>()])
4041
.add_property("ndx", &ContinuousDynamicsAbstract::ndx,
4142
"State space dimension.")
4243
.add_property("nu", &ContinuousDynamicsAbstract::nu,

0 commit comments

Comments
 (0)