Skip to content

Commit daedecb

Browse files
pybind11: Remove any usages of Ref<> with dtype=object
1 parent 370e53c commit daedecb

File tree

3 files changed

+31
-15
lines changed

3 files changed

+31
-15
lines changed

bindings/pydrake/solvers/mathematicalprogram_py.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -258,7 +258,7 @@ PYBIND11_MODULE(_mathematicalprogram_py, m) {
258258
&MathematicalProgram::AddBoundingBoxConstraint))
259259
.def("AddBoundingBoxConstraint",
260260
[](MathematicalProgram* self, double lb, double ub,
261-
const Eigen::Ref<MatrixX<symbolic::Variable>>& vars) {
261+
const Eigen::Ref<const MatrixX<symbolic::Variable>>& vars) {
262262
return self->AddBoundingBoxConstraint(lb, ub, vars);
263263
})
264264
.def("AddConstraint",

bindings/pydrake/systems/trajectory_optimization_py.cc

+27-12
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@ PYBIND11_MODULE(trajectory_optimization, m) {
1515
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
1616
using namespace drake::systems::trajectory_optimization;
1717

18+
using solvers::VectorXDecisionVariable;
19+
1820
py::module::import("pydrake.symbolic");
1921
py::module::import("pydrake.systems.framework");
2022
py::module::import("pydrake.systems.primitives");
@@ -25,22 +27,35 @@ PYBIND11_MODULE(trajectory_optimization, m) {
2527
.def("time", &MultipleShooting::time)
2628
.def("timestep", &MultipleShooting::timestep)
2729
.def("fixed_timestep", &MultipleShooting::fixed_timestep)
30+
// TODO(eric.cousineau): The original bindings returned references
31+
// instead of copies using VectorXBlock. Restore this once dtype=custom
32+
// is resolved.
2833
.def("state",
29-
overload_cast_explicit<const solvers::VectorXDecisionVariable&>(
30-
&MultipleShooting::state))
34+
[](const MultipleShooting& self) -> VectorXDecisionVariable {
35+
return self.state();
36+
})
3137
.def("state",
32-
overload_cast_explicit<
33-
Eigen::VectorBlock<const solvers::VectorXDecisionVariable>, int>(
34-
&MultipleShooting::state))
35-
.def("initial_state", &MultipleShooting::initial_state)
36-
.def("final_state", &MultipleShooting::final_state)
38+
[](const MultipleShooting& self, int index) ->
39+
VectorXDecisionVariable {
40+
return self.state(index);
41+
})
42+
.def("initial_state",
43+
[](const MultipleShooting& self) -> VectorXDecisionVariable {
44+
return self.initial_state();
45+
})
46+
.def("final_state",
47+
[](const MultipleShooting& self) -> VectorXDecisionVariable {
48+
return self.final_state();
49+
})
3750
.def("input",
38-
overload_cast_explicit<const solvers::VectorXDecisionVariable&>(
39-
&MultipleShooting::input))
51+
[](const MultipleShooting& self) -> VectorXDecisionVariable {
52+
return self.input();
53+
})
4054
.def("input",
41-
overload_cast_explicit<
42-
Eigen::VectorBlock<const solvers::VectorXDecisionVariable>, int>(
43-
&MultipleShooting::input))
55+
[](const MultipleShooting& self, int index) ->
56+
VectorXDecisionVariable {
57+
return self.input(index);
58+
})
4459
.def("AddRunningCost",
4560
[](MultipleShooting& prog, const symbolic::Expression& g) {
4661
prog.AddRunningCost(g);

tools/workspace/pybind11/repository.bzl

+3-2
Original file line numberDiff line numberDiff line change
@@ -5,9 +5,10 @@ load("@drake//tools/workspace:github.bzl", "github_archive")
55

66
_REPOSITORY = "RobotLocomotion/pybind11"
77

8-
_COMMIT = "77211dfa6933858bdad00a77867ee4ca4b80cfd0"
8+
# PR DRAFT(eric.cousineau): Change this once RobotLocomotion/pybind11#17 lands.
9+
_COMMIT = "f8d6b820a30936d21f261e2162464f1cabe4ceda"
910

10-
_SHA256 = "bbc405fbe4225f8a6e86bc6a21372957f11db2953b601d98eb7ef12c9f6473b6"
11+
_SHA256 = "86a155960e9fc585e31c750c315c2ea0ae8b5b2bcbff21dea1898c0331fd4e0b"
1112

1213
def pybind11_repository(
1314
name,

0 commit comments

Comments
 (0)