Skip to content
This repository was archived by the owner on Sep 26, 2025. It is now read-only.

Commit 14a9635

Browse files
committed
Merge pull request #90 from Simple-Robotics/topic/manifold-polymorphic-value
[API breaking] Use polymorphic value type holder for manifolds and constraint sets
2 parents 7773970 + 4e321aa commit 14a9635

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

53 files changed

+1560
-397
lines changed

CHANGELOG.md

Lines changed: 21 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -8,15 +8,33 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
88
## [Unreleased]
99

1010
### Added
11-
- Allow use of installed jrl-cmakemodules & eigenrand ([#106](https://github.com/Simple-Robotics/proxsuite-nlp/pull/106))
11+
12+
* Add compatibility with jrl-cmakemodules workspace ([#99](https://github.com/Simple-Robotics/proxsuite-nlp/pull/99))
13+
* Add the `polymorphic_cxx14.hpp` header from [jbcoe/value_types](https://github.com/jbcoe/value_types/blob/main/polymorphic_cxx14.h), [#90](https://github.com/Simple-Robotics/proxsuite-nlp/pull/90)
14+
* **Python:** add conversions (for values, versions) for the `polymorphic<T,A>` types in new `<proxsuite-nlp/python/polymorphic.hpp>` header
15+
* **Python:** add `PolymorphicVisitor` visitor and `register_polymorphic_to_python<T>()` template function to register conversions from/to the `polymorphic<T, A>` type
16+
* Allow use of installed jrl-cmakemodules & eigenrand ([#106](https://github.com/Simple-Robotics/proxsuite-nlp/pull/106))
17+
18+
### Changed
19+
20+
* Change from `shared_ptr<T>` to `polymorphic<T>` for manifolds and constraint sets
21+
* Remove use of `std::make_shared` for manifolds in examples [#90](https://github.com/Simple-Robotics/proxsuite-nlp/pull/90), instead plass pain types
22+
* `ConstraintObjectTpl` now holds the constraint set through a `polymorphic<ConstraintSet>`
23+
* Changed ctors of `ProblemTpl` and `CostAbstractTpl` to template which takes the concrete manifold type
24+
* **Python:** pull all wrapper classes (inheriting from `bp::wrapper<U>`) out of the `aligator::python::internal` namespace
25+
* **Python:** fix abstract classes exposed as subclasses of `bp::wrapper<U>` not registering their owning `PyObject*` properly
26+
* Removed function template `allocate_shared_eigen_aligned` since we now use C++17 and Eigen::aligned_allocator is no longer needed.
27+
* Remove redundant macro `PROXSUITE_NLP_DEFINE_MANIFOLD_TYPES` and `PointType/TangentVectorType` typedefs in manifold API
1228

1329
## [0.7.1] - 2024-09-04
1430

1531
### Added
16-
- Add compatibility with jrl-cmakemodules workspace ([#99](https://github.com/Simple-Robotics/proxsuite-nlp/pull/99))
32+
* Add compatibility with jrl-cmakemodules workspace ([#99](https://github.com/Simple-Robotics/proxsuite-nlp/pull/99))
1733

1834
### Fixed
19-
- Remove CMake CMP0167 and CMP0169 warnings ([#100](https://github.com/Simple-Robotics/proxsuite-nlp/pull/100))
35+
36+
* Remove CMake CMP0167 and CMP0169 warnings ([#100](https://github.com/Simple-Robotics/proxsuite-nlp/pull/100))
37+
2038

2139
## [0.7.0] - 2024-05-14
2240

bindings/python/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
#
2-
# Copyright (C) 2022 LAAS-CNRS, INRIA
2+
# Copyright (C) 2022-2024 LAAS-CNRS, INRIA
33
#
44

55
# use underscore for Python to parse module name

bindings/python/expose-cartesian-product.cpp

Lines changed: 21 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,15 @@
11
#include "proxsuite-nlp/modelling/spaces/cartesian-product.hpp"
22

33
#include "proxsuite-nlp/python/fwd.hpp"
4+
#include "proxsuite-nlp/python/polymorphic.hpp"
45

56
namespace proxsuite {
67
namespace nlp {
78
namespace python {
89

910
using context::Manifold;
1011
using context::Scalar;
11-
using ManifoldPtr = shared_ptr<Manifold>;
12+
using PolymorphicManifold = polymorphic<Manifold>;
1213
using context::ConstVectorRef;
1314
using context::VectorRef;
1415
using context::VectorXs;
@@ -31,12 +32,14 @@ void exposeCartesianProduct() {
3132
using MutSplitSig =
3233
std::vector<VectorRef> (CartesianProduct::*)(VectorRef) const;
3334

34-
bp::class_<CartesianProduct, bp::bases<Manifold>,
35-
shared_ptr<CartesianProduct>>(
35+
bp::class_<CartesianProduct, bp::bases<Manifold>>(
3636
"CartesianProduct", "Cartesian product of two or more manifolds.",
37-
bp::init<const std::vector<ManifoldPtr> &>(bp::args("self", "spaces")))
38-
.def(
39-
bp::init<ManifoldPtr, ManifoldPtr>(bp::args("self", "left", "right")))
37+
bp::no_init)
38+
.def(bp::init<>("self"_a))
39+
.def(bp::init<const std::vector<PolymorphicManifold> &>(
40+
("self"_a, "spaces")))
41+
.def(bp::init<PolymorphicManifold, PolymorphicManifold>(
42+
("self"_a, "left", "right")))
4043
.def(
4144
"getComponent",
4245
+[](CartesianProduct const &m, std::size_t i) -> const Manifold & {
@@ -46,28 +49,20 @@ void exposeCartesianProduct() {
4649
}
4750
return m.getComponent(i);
4851
},
49-
bp::return_internal_reference<>(), bp::args("self", "i"),
52+
bp::return_internal_reference<>(), ("self"_a, "i"),
5053
"Get the i-th component of the Cartesian product.")
51-
.def(
52-
"addComponent",
53-
+[](CartesianProduct &m, ManifoldPtr const &p) { m.addComponent(p); },
54-
bp::args("self", "c"), "Add a component to the Cartesian product.")
55-
.def(
56-
"addComponent",
57-
+[](CartesianProduct &m, shared_ptr<CartesianProduct> const &p) {
58-
m.addComponent(p);
59-
},
60-
bp::args("self", "c"), "Add a component to the Cartesian product.")
54+
.def("addComponent", &CartesianProduct::addComponent<PolymorphicManifold>,
55+
("self"_a, "c"), "Add a component to the Cartesian product.")
6156
.add_property("num_components", &CartesianProduct::numComponents,
6257
"Get the number of components in the Cartesian product.")
6358
.def(
6459
"split",
6560
+[](CartesianProduct const &m, const ConstVectorRef &x) {
6661
return copy_vec_constref(m.split(x));
6762
},
68-
bp::args("self", "x"), split_doc.c_str())
63+
("self"_a, "x"), split_doc.c_str())
6964
.def<MutSplitSig>(
70-
"split", &CartesianProduct::split, bp::args("self", "x"),
65+
"split", &CartesianProduct::split, ("self"_a, "x"),
7166
(split_doc +
7267
" This returns a list of mutable references to each component.")
7368
.c_str())
@@ -76,23 +71,22 @@ void exposeCartesianProduct() {
7671
+[](CartesianProduct const &m, const ConstVectorRef &x) {
7772
return copy_vec_constref(m.split_vector(x));
7873
},
79-
bp::args("self", "v"), split_vec_doc.c_str())
74+
("self"_a, "v"), split_vec_doc.c_str())
8075
.def<MutSplitSig>(
81-
"split_vector", &CartesianProduct::split_vector,
82-
bp::args("self", "v"),
76+
"split_vector", &CartesianProduct::split_vector, ("self"_a, "v"),
8377
(split_vec_doc +
8478
" This returns a list of mutable references to each component.")
8579
.c_str())
86-
.def("merge", &CartesianProduct::merge, bp::args("self", "xs"),
80+
.def("merge", &CartesianProduct::merge, ("self"_a, "xs"),
8781
"Define a point on the manifold by merging points from each "
8882
"component.")
89-
.def("merge_vector", &CartesianProduct::merge_vector,
90-
bp::args("self", "vs"),
83+
.def("merge_vector", &CartesianProduct::merge_vector, ("self"_a, "vs"),
9184
"Define a tangent vector on the manifold by merging vectors from "
9285
"each component.")
9386
.def(
94-
"__mul__", +[](const shared_ptr<CartesianProduct> &a,
95-
const ManifoldPtr &b) { return a * b; });
87+
"__mul__", +[](const CartesianProduct &a,
88+
const CartesianProduct &b) { return a * b; })
89+
.def(PolymorphicVisitor<PolymorphicManifold>());
9690
}
9791

9892
} // namespace python

bindings/python/expose-constraint.cpp

Lines changed: 28 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,12 @@
11
/// @copyright Copyright (C) 2022 LAAS-CNRS, INRIA
2-
#include "proxsuite-nlp/python/fwd.hpp"
3-
42
#include "proxsuite-nlp/modelling/constraints.hpp"
53

4+
#include "proxsuite-nlp/python/polymorphic.hpp"
5+
66
#include <eigenpy/std-vector.hpp>
77

8+
#include <vector>
9+
810
namespace proxsuite {
911
namespace nlp {
1012
namespace python {
@@ -21,67 +23,66 @@ using BoxConstraint = BoxConstraintTpl<Scalar>;
2123

2224
template <typename T>
2325
auto exposeSpecificConstraintSet(const char *name, const char *docstring) {
24-
return bp::class_<T, bp::bases<context::ConstraintSet>>(name, docstring,
25-
bp::no_init);
26+
return bp::class_<T, bp::bases<ConstraintSet>>(name, docstring, bp::no_init)
27+
.def(PolymorphicVisitor<polymorphic<ConstraintSet>>());
2628
}
2729

28-
template <typename T>
30+
template <typename ConstraintType>
2931
context::Constraint make_constraint(const shared_ptr<context::C2Function> &f) {
30-
return context::Constraint(f, std::make_shared<T>());
32+
return context::Constraint(f, ConstraintType{});
3133
}
3234

3335
static void exposeConstraintTypes();
3436

3537
/// @todo Expose properly using pure_virtual, to allow overriding from Python
3638
void exposeConstraints() {
3739

38-
bp::register_ptr_to_python<shared_ptr<ConstraintSet>>();
40+
register_polymorphic_to_python<polymorphic<ConstraintSet>>();
3941
bp::class_<ConstraintSet, boost::noncopyable>(
4042
"ConstraintSetBase",
4143
"Base class for constraint sets or nonsmooth penalties.", bp::no_init)
42-
.def("evaluate", &ConstraintSet::evaluate, bp::args("self", "z"),
44+
.def("evaluate", &ConstraintSet::evaluate, ("self"_a, "z"),
4345
"Evaluate the constraint indicator function or nonsmooth penalty "
4446
"on the projection/prox map of :math:`z`.")
45-
.def("projection", &ConstraintSet::projection,
46-
bp::args("self", "z", "zout"))
47+
.def("projection", &ConstraintSet::projection, ("self"_a, "z", "zout"))
4748
.def(
4849
"projection",
4950
+[](const ConstraintSet &c, const ConstVectorRef &z) {
5051
context::VectorXs zout(z.size());
5152
c.projection(z, zout);
5253
return zout;
5354
},
54-
bp::args("self", "z"))
55+
("self"_a, "z"))
5556
.def("normalConeProjection", &ConstraintSet::normalConeProjection,
56-
bp::args("self", "z", "zout"))
57+
("self"_a, "z", "zout"))
5758
.def(
5859
"normalConeProjection",
5960
+[](const ConstraintSet &c, const ConstVectorRef &z) {
6061
context::VectorXs zout(z.size());
6162
c.normalConeProjection(z, zout);
6263
return zout;
6364
},
64-
bp::args("self", "z"))
65+
("self"_a, "z"))
6566
.def("applyProjectionJacobian", &ConstraintSet::applyProjectionJacobian,
66-
bp::args("self", "z", "Jout"), "Apply the projection Jacobian.")
67+
("self"_a, "z", "Jout"), "Apply the projection Jacobian.")
6768
.def("applyNormalProjectionJacobian",
6869
&ConstraintSet::applyNormalConeProjectionJacobian,
69-
bp::args("self", "z", "Jout"),
70+
("self"_a, "z", "Jout"),
7071
"Apply the normal cone projection Jacobian.")
7172
.def("computeActiveSet", &ConstraintSet::computeActiveSet,
72-
bp::args("self", "z", "out"))
73+
("self"_a, "z", "out"))
7374
.def("evaluateMoreauEnvelope", &ConstraintSet::evaluateMoreauEnvelope,
74-
bp::args("self", "zin", "zproj"),
75+
("self"_a, "zin", "zproj"),
7576
"Evaluate the Moreau envelope with parameter :math:`\\mu`.")
7677
.def("setProxParameter", &ConstraintSet::setProxParameter,
77-
bp::args("self", "mu"), "Set proximal parameter.")
78+
("self"_a, "mu"), "Set proximal parameter.")
7879
.add_property("mu", &ConstraintSet::mu, "Current proximal parameter.")
7980
.def(bp::self == bp::self);
8081

8182
bp::class_<Constraint>(
8283
"ConstraintObject", "Packs a constraint set together with a function.",
83-
bp::init<shared_ptr<C2Function>, shared_ptr<ConstraintSet>>(
84-
bp::args("self", "func", "set")))
84+
bp::init<shared_ptr<C2Function>, const polymorphic<ConstraintSet> &>(
85+
("self"_a, "func", "constraint_set")))
8586
.add_property("nr", &Constraint::nr, "Constraint dimension.")
8687
.def_readonly("func", &Constraint::func_, "Underlying function.")
8788
.def_readonly("set", &Constraint::set_, "Constraint set.");
@@ -125,7 +126,8 @@ static void exposeConstraintTypes() {
125126

126127
exposeSpecificConstraintSet<ConstraintSetProduct>(
127128
"ConstraintSetProduct", "Cartesian product of constraint sets.")
128-
.def(bp::init<std::vector<ConstraintSet *>, std::vector<Eigen::Index>>(
129+
.def(bp::init<std::vector<polymorphic<ConstraintSet>>,
130+
std::vector<Eigen::Index>>(
129131
("self"_a, "components", "blockSizes")))
130132
.add_property("components",
131133
bp::make_function(&ConstraintSetProduct::components,
@@ -134,6 +136,11 @@ static void exposeConstraintTypes() {
134136
bp::make_function(&ConstraintSetProduct::blockSizes,
135137
bp::return_internal_reference<>()),
136138
"Dimensions of each component of the cartesian product.");
139+
140+
StdVectorPythonVisitor<std::vector<polymorphic<ConstraintSet>>>::expose(
141+
"StdVec_ConstraintObject",
142+
eigenpy::details::overload_base_get_item_for_std_vector<
143+
std::vector<polymorphic<ConstraintSet>>>());
137144
}
138145

139146
} // namespace python

bindings/python/expose-ldlt.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,4 @@
11
#include "proxsuite-nlp/python/fwd.hpp"
2-
#include "proxsuite-nlp/python/policies.hpp"
32

43
#include "proxsuite-nlp/ldlt-allocator.hpp"
54

@@ -29,13 +28,13 @@ struct LDLTVisitor : bp::def_visitor<LDLTVisitor<LDLTtype>> {
2928
}
3029

3130
template <typename... Args> void visit(bp::class_<Args...> &cl) const {
32-
cl.def("compute", compute_proxy, policies::return_internal_reference,
31+
cl.def("compute", compute_proxy, bp::return_internal_reference<>(),
3332
("self"_a, "mat"))
3433
.def("solveInPlace", solveInPlace_proxy, ("self"_a, "rhsAndX"))
3534
.def("solve", solve<Eigen::Ref<const VectorXs>>, ("self"_a, "rhs"))
3635
.def("solve", solve<Eigen::Ref<const MatrixXs>>, ("self"_a, "rhs"))
37-
.def("matrixLDLT", &LDLTtype::matrixLDLT, policies::return_by_value,
38-
"self"_a,
36+
.def("matrixLDLT", &LDLTtype::matrixLDLT,
37+
bp::return_value_policy<bp::return_by_value>(), "self"_a,
3938
"Get the current value of the decomposition matrix. This makes a "
4039
"copy.");
4140
}

0 commit comments

Comments
 (0)