diff --git a/bindings/pydrake/examples/examples_py_acrobot.cc b/bindings/pydrake/examples/examples_py_acrobot.cc index 4dcbbbf8b1cd..8aacf38247fe 100644 --- a/bindings/pydrake/examples/examples_py_acrobot.cc +++ b/bindings/pydrake/examples/examples_py_acrobot.cc @@ -29,59 +29,6 @@ void DefineExamplesAcrobot(py::module m) { // conversion. Issue #7660. using T = double; - py::class_, LeafSystem>( - m, "AcrobotPlant", doc.AcrobotPlant.doc) - .def(py::init<>(), doc.AcrobotPlant.ctor.doc) - .def("DynamicsBiasTerm", &AcrobotPlant::DynamicsBiasTerm, - doc.AcrobotPlant.DynamicsBiasTerm.doc) - .def("SetMitAcrobotParameters", &AcrobotPlant::SetMitAcrobotParameters, - doc.AcrobotPlant.SetMitAcrobotParameters.doc) - .def("MassMatrix", &AcrobotPlant::MassMatrix, - doc.AcrobotPlant.MassMatrix.doc) - .def_static("get_state", - py::overload_cast&>(&AcrobotPlant::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*>(&AcrobotPlant::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::get_parameters, - py_rvp::reference_internal, py::arg("context"), - doc.AcrobotPlant.get_parameters.doc) - .def("get_mutable_parameters", &AcrobotPlant::get_mutable_parameters, - py_rvp::reference_internal, py::arg("context"), - doc.AcrobotPlant.get_mutable_parameters.doc); - - py::class_, Diagram>( - m, "AcrobotWEncoder", doc.AcrobotWEncoder.doc) - .def(py::init(), py::arg("acrobot_state_as_second_output") = false, - doc.AcrobotWEncoder.ctor.doc) - .def("acrobot_plant", &AcrobotWEncoder::acrobot_plant, - py_rvp::reference_internal, doc.AcrobotWEncoder.acrobot_plant.doc) - .def("get_mutable_acrobot_state", - &AcrobotWEncoder::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_, LeafSystem>( - m, "AcrobotSpongController", doc.AcrobotSpongController.doc) - .def(py::init<>(), doc.AcrobotSpongController.ctor.doc) - .def("get_parameters", &AcrobotSpongController::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::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_, BasicVector>( m, "AcrobotInput", doc.AcrobotInput.doc) .def(py::init<>(), doc.AcrobotInput.ctor.doc) @@ -153,6 +100,59 @@ void DefineExamplesAcrobot(py::module m) { &SpongControllerParams::set_balancing_threshold, doc.SpongControllerParams.set_balancing_threshold.doc); + py::class_, LeafSystem>( + m, "AcrobotPlant", doc.AcrobotPlant.doc) + .def(py::init<>(), doc.AcrobotPlant.ctor.doc) + .def("DynamicsBiasTerm", &AcrobotPlant::DynamicsBiasTerm, + doc.AcrobotPlant.DynamicsBiasTerm.doc) + .def("SetMitAcrobotParameters", &AcrobotPlant::SetMitAcrobotParameters, + doc.AcrobotPlant.SetMitAcrobotParameters.doc) + .def("MassMatrix", &AcrobotPlant::MassMatrix, + doc.AcrobotPlant.MassMatrix.doc) + .def_static("get_state", + py::overload_cast&>(&AcrobotPlant::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*>(&AcrobotPlant::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::get_parameters, + py_rvp::reference_internal, py::arg("context"), + doc.AcrobotPlant.get_parameters.doc) + .def("get_mutable_parameters", &AcrobotPlant::get_mutable_parameters, + py_rvp::reference_internal, py::arg("context"), + doc.AcrobotPlant.get_mutable_parameters.doc); + + py::class_, Diagram>( + m, "AcrobotWEncoder", doc.AcrobotWEncoder.doc) + .def(py::init(), py::arg("acrobot_state_as_second_output") = false, + doc.AcrobotWEncoder.ctor.doc) + .def("acrobot_plant", &AcrobotWEncoder::acrobot_plant, + py_rvp::reference_internal, doc.AcrobotWEncoder.acrobot_plant.doc) + .def("get_mutable_acrobot_state", + &AcrobotWEncoder::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_, LeafSystem>( + m, "AcrobotSpongController", doc.AcrobotSpongController.doc) + .def(py::init<>(), doc.AcrobotSpongController.ctor.doc) + .def("get_parameters", &AcrobotSpongController::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::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_>( m, "AcrobotGeometry", doc.AcrobotGeometry.doc) .def_static("AddToBuilder", diff --git a/bindings/pydrake/examples/examples_py_pendulum.cc b/bindings/pydrake/examples/examples_py_pendulum.cc index 7443d5727b03..2e7c953b9a0a 100644 --- a/bindings/pydrake/examples/examples_py_pendulum.cc +++ b/bindings/pydrake/examples/examples_py_pendulum.cc @@ -27,29 +27,6 @@ void DefineExamplesPendulum(py::module m) { // conversion. using T = double; - py::class_, LeafSystem>( - m, "PendulumPlant", doc.PendulumPlant.doc) - .def(py::init<>(), doc.PendulumPlant.ctor.doc) - .def("get_state_output_port", &PendulumPlant::get_state_output_port, - py_rvp::reference_internal, - doc.PendulumPlant.get_state_output_port.doc) - .def_static("get_state", - py::overload_cast&>(&PendulumPlant::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*>(&PendulumPlant::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::get_parameters, - py_rvp::reference_internal, py::arg("context"), - doc.PendulumPlant.get_parameters.doc) - .def("get_mutable_parameters", &PendulumPlant::get_mutable_parameters, - py_rvp::reference_internal, py::arg("context"), - doc.PendulumPlant.get_mutable_parameters.doc); - py::class_, BasicVector>( m, "PendulumInput", doc.PendulumInput.doc) .def(py::init<>(), doc.PendulumInput.ctor.doc) @@ -100,6 +77,29 @@ void DefineExamplesPendulum(py::module m) { .def("with_thetadot", &PendulumState::with_thetadot, py::arg("thetadot"), doc.PendulumState.with_thetadot.doc); + py::class_, LeafSystem>( + m, "PendulumPlant", doc.PendulumPlant.doc) + .def(py::init<>(), doc.PendulumPlant.ctor.doc) + .def("get_state_output_port", &PendulumPlant::get_state_output_port, + py_rvp::reference_internal, + doc.PendulumPlant.get_state_output_port.doc) + .def_static("get_state", + py::overload_cast&>(&PendulumPlant::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*>(&PendulumPlant::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::get_parameters, + py_rvp::reference_internal, py::arg("context"), + doc.PendulumPlant.get_parameters.doc) + .def("get_mutable_parameters", &PendulumPlant::get_mutable_parameters, + py_rvp::reference_internal, py::arg("context"), + doc.PendulumPlant.get_mutable_parameters.doc); + py::class_>( m, "PendulumGeometry", doc.PendulumGeometry.doc) .def_static("AddToBuilder", &PendulumGeometry::AddToBuilder, diff --git a/bindings/pydrake/examples/examples_py_rimless_wheel.cc b/bindings/pydrake/examples/examples_py_rimless_wheel.cc index edd9d7bbd0fd..34841253adba 100644 --- a/bindings/pydrake/examples/examples_py_rimless_wheel.cc +++ b/bindings/pydrake/examples/examples_py_rimless_wheel.cc @@ -22,20 +22,6 @@ void DefineExamplesRimlessWheel(py::module m) { // conversion. using T = double; - py::class_, LeafSystem>( - m, "RimlessWheel", doc.RimlessWheel.doc) - .def(py::init<>(), doc.RimlessWheel.ctor.doc) - .def("get_minimal_state_output_port", - &RimlessWheel::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::get_floating_base_state_output_port, - py_rvp::reference_internal, - doc.RimlessWheel.get_floating_base_state_output_port.doc) - .def_static("calc_alpha", &RimlessWheel::calc_alpha, py::arg("params"), - doc.RimlessWheel.calc_alpha.doc); - py::class_, BasicVector>( m, "RimlessWheelParams", doc.RimlessWheelParams.doc) .def(py::init<>(), doc.RimlessWheelParams.ctor.doc) @@ -72,6 +58,20 @@ void DefineExamplesRimlessWheel(py::module m) { .def("set_thetadot", &RimlessWheelContinuousState::set_thetadot, doc.RimlessWheelContinuousState.set_thetadot.doc); + py::class_, LeafSystem>( + m, "RimlessWheel", doc.RimlessWheel.doc) + .def(py::init<>(), doc.RimlessWheel.ctor.doc) + .def("get_minimal_state_output_port", + &RimlessWheel::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::get_floating_base_state_output_port, + py_rvp::reference_internal, + doc.RimlessWheel.get_floating_base_state_output_port.doc) + .def_static("calc_alpha", &RimlessWheel::calc_alpha, py::arg("params"), + doc.RimlessWheel.calc_alpha.doc); + py::class_>( m, "RimlessWheelGeometry", doc.RimlessWheelGeometry.doc) .def_static("AddToBuilder",