Skip to content

Commit

Permalink
[py examples] Fix signatures to use Python types (not C++) (#21918)
Browse files Browse the repository at this point in the history
Adjust bindings to follow topological order, so that function
signatures can look up their requisite python types.
  • Loading branch information
jwnimmer-tri authored Oct 1, 2024
1 parent b31b995 commit 3b46257
Show file tree
Hide file tree
Showing 3 changed files with 90 additions and 90 deletions.
106 changes: 53 additions & 53 deletions bindings/pydrake/examples/examples_py_acrobot.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,59 +29,6 @@ void DefineExamplesAcrobot(py::module m) {
// conversion. Issue #7660.
using T = double;

py::class_<AcrobotPlant<T>, LeafSystem<T>>(
m, "AcrobotPlant", doc.AcrobotPlant.doc)
.def(py::init<>(), doc.AcrobotPlant.ctor.doc)
.def("DynamicsBiasTerm", &AcrobotPlant<T>::DynamicsBiasTerm,
doc.AcrobotPlant.DynamicsBiasTerm.doc)
.def("SetMitAcrobotParameters", &AcrobotPlant<T>::SetMitAcrobotParameters,
doc.AcrobotPlant.SetMitAcrobotParameters.doc)
.def("MassMatrix", &AcrobotPlant<T>::MassMatrix,
doc.AcrobotPlant.MassMatrix.doc)
.def_static("get_state",
py::overload_cast<const Context<T>&>(&AcrobotPlant<T>::get_state),
py::arg("context"),
// Keey alive, ownership: `return` keeps `context` alive
py::keep_alive<0, 1>(), doc.AcrobotPlant.get_state.doc)
.def_static("get_mutable_state",
py::overload_cast<Context<T>*>(&AcrobotPlant<T>::get_mutable_state),
py::arg("context"),
// Keep alive, ownership: `return` keeps `context` alive
py::keep_alive<0, 1>(), doc.AcrobotPlant.get_mutable_state.doc)
.def("get_parameters", &AcrobotPlant<T>::get_parameters,
py_rvp::reference_internal, py::arg("context"),
doc.AcrobotPlant.get_parameters.doc)
.def("get_mutable_parameters", &AcrobotPlant<T>::get_mutable_parameters,
py_rvp::reference_internal, py::arg("context"),
doc.AcrobotPlant.get_mutable_parameters.doc);

py::class_<AcrobotWEncoder<T>, Diagram<T>>(
m, "AcrobotWEncoder", doc.AcrobotWEncoder.doc)
.def(py::init<bool>(), py::arg("acrobot_state_as_second_output") = false,
doc.AcrobotWEncoder.ctor.doc)
.def("acrobot_plant", &AcrobotWEncoder<T>::acrobot_plant,
py_rvp::reference_internal, doc.AcrobotWEncoder.acrobot_plant.doc)
.def("get_mutable_acrobot_state",
&AcrobotWEncoder<T>::get_mutable_acrobot_state,
py_rvp::reference_internal, py::arg("context"),
// Keep alive, ownership: `return` keeps `context` alive.
py::keep_alive<0, 1>(),
doc.AcrobotWEncoder.get_mutable_acrobot_state.doc);

py::class_<AcrobotSpongController<T>, LeafSystem<T>>(
m, "AcrobotSpongController", doc.AcrobotSpongController.doc)
.def(py::init<>(), doc.AcrobotSpongController.ctor.doc)
.def("get_parameters", &AcrobotSpongController<T>::get_parameters,
py_rvp::reference, py::arg("context"),
// Keep alive, ownership: `return` keeps `context` alive.
py::keep_alive<0, 2>(), doc.AcrobotSpongController.get_parameters.doc)
.def("get_mutable_parameters",
&AcrobotSpongController<T>::get_mutable_parameters, py_rvp::reference,
py::arg("context"),
// Keep alive, ownership: `return` keeps `context` alive.
py::keep_alive<0, 2>(),
doc.AcrobotSpongController.get_mutable_parameters.doc);

py::class_<AcrobotInput<T>, BasicVector<T>>(
m, "AcrobotInput", doc.AcrobotInput.doc)
.def(py::init<>(), doc.AcrobotInput.ctor.doc)
Expand Down Expand Up @@ -153,6 +100,59 @@ void DefineExamplesAcrobot(py::module m) {
&SpongControllerParams<T>::set_balancing_threshold,
doc.SpongControllerParams.set_balancing_threshold.doc);

py::class_<AcrobotPlant<T>, LeafSystem<T>>(
m, "AcrobotPlant", doc.AcrobotPlant.doc)
.def(py::init<>(), doc.AcrobotPlant.ctor.doc)
.def("DynamicsBiasTerm", &AcrobotPlant<T>::DynamicsBiasTerm,
doc.AcrobotPlant.DynamicsBiasTerm.doc)
.def("SetMitAcrobotParameters", &AcrobotPlant<T>::SetMitAcrobotParameters,
doc.AcrobotPlant.SetMitAcrobotParameters.doc)
.def("MassMatrix", &AcrobotPlant<T>::MassMatrix,
doc.AcrobotPlant.MassMatrix.doc)
.def_static("get_state",
py::overload_cast<const Context<T>&>(&AcrobotPlant<T>::get_state),
py::arg("context"),
// Keey alive, ownership: `return` keeps `context` alive
py::keep_alive<0, 1>(), doc.AcrobotPlant.get_state.doc)
.def_static("get_mutable_state",
py::overload_cast<Context<T>*>(&AcrobotPlant<T>::get_mutable_state),
py::arg("context"),
// Keep alive, ownership: `return` keeps `context` alive
py::keep_alive<0, 1>(), doc.AcrobotPlant.get_mutable_state.doc)
.def("get_parameters", &AcrobotPlant<T>::get_parameters,
py_rvp::reference_internal, py::arg("context"),
doc.AcrobotPlant.get_parameters.doc)
.def("get_mutable_parameters", &AcrobotPlant<T>::get_mutable_parameters,
py_rvp::reference_internal, py::arg("context"),
doc.AcrobotPlant.get_mutable_parameters.doc);

py::class_<AcrobotWEncoder<T>, Diagram<T>>(
m, "AcrobotWEncoder", doc.AcrobotWEncoder.doc)
.def(py::init<bool>(), py::arg("acrobot_state_as_second_output") = false,
doc.AcrobotWEncoder.ctor.doc)
.def("acrobot_plant", &AcrobotWEncoder<T>::acrobot_plant,
py_rvp::reference_internal, doc.AcrobotWEncoder.acrobot_plant.doc)
.def("get_mutable_acrobot_state",
&AcrobotWEncoder<T>::get_mutable_acrobot_state,
py_rvp::reference_internal, py::arg("context"),
// Keep alive, ownership: `return` keeps `context` alive.
py::keep_alive<0, 1>(),
doc.AcrobotWEncoder.get_mutable_acrobot_state.doc);

py::class_<AcrobotSpongController<T>, LeafSystem<T>>(
m, "AcrobotSpongController", doc.AcrobotSpongController.doc)
.def(py::init<>(), doc.AcrobotSpongController.ctor.doc)
.def("get_parameters", &AcrobotSpongController<T>::get_parameters,
py_rvp::reference, py::arg("context"),
// Keep alive, ownership: `return` keeps `context` alive.
py::keep_alive<0, 2>(), doc.AcrobotSpongController.get_parameters.doc)
.def("get_mutable_parameters",
&AcrobotSpongController<T>::get_mutable_parameters, py_rvp::reference,
py::arg("context"),
// Keep alive, ownership: `return` keeps `context` alive.
py::keep_alive<0, 2>(),
doc.AcrobotSpongController.get_mutable_parameters.doc);

py::class_<AcrobotGeometry, LeafSystem<double>>(
m, "AcrobotGeometry", doc.AcrobotGeometry.doc)
.def_static("AddToBuilder",
Expand Down
46 changes: 23 additions & 23 deletions bindings/pydrake/examples/examples_py_pendulum.cc
Original file line number Diff line number Diff line change
Expand Up @@ -27,29 +27,6 @@ void DefineExamplesPendulum(py::module m) {
// conversion.
using T = double;

py::class_<PendulumPlant<T>, LeafSystem<T>>(
m, "PendulumPlant", doc.PendulumPlant.doc)
.def(py::init<>(), doc.PendulumPlant.ctor.doc)
.def("get_state_output_port", &PendulumPlant<T>::get_state_output_port,
py_rvp::reference_internal,
doc.PendulumPlant.get_state_output_port.doc)
.def_static("get_state",
py::overload_cast<const Context<T>&>(&PendulumPlant<T>::get_state),
py::arg("context"),
// Keey alive, ownership: `return` keeps `context` alive
py::keep_alive<0, 1>(), doc.PendulumPlant.get_state.doc)
.def_static("get_mutable_state",
py::overload_cast<Context<T>*>(&PendulumPlant<T>::get_mutable_state),
py::arg("context"),
// Keey alive, ownership: `return` keeps `context` alive
py::keep_alive<0, 1>(), doc.PendulumPlant.get_mutable_state.doc)
.def("get_parameters", &PendulumPlant<T>::get_parameters,
py_rvp::reference_internal, py::arg("context"),
doc.PendulumPlant.get_parameters.doc)
.def("get_mutable_parameters", &PendulumPlant<T>::get_mutable_parameters,
py_rvp::reference_internal, py::arg("context"),
doc.PendulumPlant.get_mutable_parameters.doc);

py::class_<PendulumInput<T>, BasicVector<T>>(
m, "PendulumInput", doc.PendulumInput.doc)
.def(py::init<>(), doc.PendulumInput.ctor.doc)
Expand Down Expand Up @@ -100,6 +77,29 @@ void DefineExamplesPendulum(py::module m) {
.def("with_thetadot", &PendulumState<T>::with_thetadot,
py::arg("thetadot"), doc.PendulumState.with_thetadot.doc);

py::class_<PendulumPlant<T>, LeafSystem<T>>(
m, "PendulumPlant", doc.PendulumPlant.doc)
.def(py::init<>(), doc.PendulumPlant.ctor.doc)
.def("get_state_output_port", &PendulumPlant<T>::get_state_output_port,
py_rvp::reference_internal,
doc.PendulumPlant.get_state_output_port.doc)
.def_static("get_state",
py::overload_cast<const Context<T>&>(&PendulumPlant<T>::get_state),
py::arg("context"),
// Keey alive, ownership: `return` keeps `context` alive
py::keep_alive<0, 1>(), doc.PendulumPlant.get_state.doc)
.def_static("get_mutable_state",
py::overload_cast<Context<T>*>(&PendulumPlant<T>::get_mutable_state),
py::arg("context"),
// Keey alive, ownership: `return` keeps `context` alive
py::keep_alive<0, 1>(), doc.PendulumPlant.get_mutable_state.doc)
.def("get_parameters", &PendulumPlant<T>::get_parameters,
py_rvp::reference_internal, py::arg("context"),
doc.PendulumPlant.get_parameters.doc)
.def("get_mutable_parameters", &PendulumPlant<T>::get_mutable_parameters,
py_rvp::reference_internal, py::arg("context"),
doc.PendulumPlant.get_mutable_parameters.doc);

py::class_<PendulumGeometry, LeafSystem<double>>(
m, "PendulumGeometry", doc.PendulumGeometry.doc)
.def_static("AddToBuilder", &PendulumGeometry::AddToBuilder,
Expand Down
28 changes: 14 additions & 14 deletions bindings/pydrake/examples/examples_py_rimless_wheel.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,20 +22,6 @@ void DefineExamplesRimlessWheel(py::module m) {
// conversion.
using T = double;

py::class_<RimlessWheel<T>, LeafSystem<T>>(
m, "RimlessWheel", doc.RimlessWheel.doc)
.def(py::init<>(), doc.RimlessWheel.ctor.doc)
.def("get_minimal_state_output_port",
&RimlessWheel<T>::get_minimal_state_output_port,
py_rvp::reference_internal,
doc.RimlessWheel.get_minimal_state_output_port.doc)
.def("get_floating_base_state_output_port",
&RimlessWheel<T>::get_floating_base_state_output_port,
py_rvp::reference_internal,
doc.RimlessWheel.get_floating_base_state_output_port.doc)
.def_static("calc_alpha", &RimlessWheel<T>::calc_alpha, py::arg("params"),
doc.RimlessWheel.calc_alpha.doc);

py::class_<RimlessWheelParams<T>, BasicVector<T>>(
m, "RimlessWheelParams", doc.RimlessWheelParams.doc)
.def(py::init<>(), doc.RimlessWheelParams.ctor.doc)
Expand Down Expand Up @@ -72,6 +58,20 @@ void DefineExamplesRimlessWheel(py::module m) {
.def("set_thetadot", &RimlessWheelContinuousState<T>::set_thetadot,
doc.RimlessWheelContinuousState.set_thetadot.doc);

py::class_<RimlessWheel<T>, LeafSystem<T>>(
m, "RimlessWheel", doc.RimlessWheel.doc)
.def(py::init<>(), doc.RimlessWheel.ctor.doc)
.def("get_minimal_state_output_port",
&RimlessWheel<T>::get_minimal_state_output_port,
py_rvp::reference_internal,
doc.RimlessWheel.get_minimal_state_output_port.doc)
.def("get_floating_base_state_output_port",
&RimlessWheel<T>::get_floating_base_state_output_port,
py_rvp::reference_internal,
doc.RimlessWheel.get_floating_base_state_output_port.doc)
.def_static("calc_alpha", &RimlessWheel<T>::calc_alpha, py::arg("params"),
doc.RimlessWheel.calc_alpha.doc);

py::class_<RimlessWheelGeometry, LeafSystem<double>>(
m, "RimlessWheelGeometry", doc.RimlessWheelGeometry.doc)
.def_static("AddToBuilder",
Expand Down

0 comments on commit 3b46257

Please sign in to comment.