@@ -15,6 +15,8 @@ PYBIND11_MODULE(trajectory_optimization, m) {
15
15
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
16
16
using namespace drake ::systems::trajectory_optimization;
17
17
18
+ using solvers::VectorXDecisionVariable;
19
+
18
20
py::module::import (" pydrake.symbolic" );
19
21
py::module::import (" pydrake.systems.framework" );
20
22
py::module::import (" pydrake.systems.primitives" );
@@ -25,22 +27,35 @@ PYBIND11_MODULE(trajectory_optimization, m) {
25
27
.def (" time" , &MultipleShooting::time )
26
28
.def (" timestep" , &MultipleShooting::timestep)
27
29
.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.
28
33
.def (" state" ,
29
- overload_cast_explicit<const solvers::VectorXDecisionVariable&>(
30
- &MultipleShooting::state))
34
+ [](const MultipleShooting& self) -> VectorXDecisionVariable {
35
+ return self.state ();
36
+ })
31
37
.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
+ })
37
50
.def (" input" ,
38
- overload_cast_explicit<const solvers::VectorXDecisionVariable&>(
39
- &MultipleShooting::input))
51
+ [](const MultipleShooting& self) -> VectorXDecisionVariable {
52
+ return self.input ();
53
+ })
40
54
.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
+ })
44
59
.def (" AddRunningCost" ,
45
60
[](MultipleShooting& prog, const symbolic::Expression& g) {
46
61
prog.AddRunningCost (g);
0 commit comments