Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

py mbp: Bind MultibodyPlant.time_step() #13355

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
1 change: 1 addition & 0 deletions bindings/pydrake/multibody/plant_py.cc
Expand Up @@ -152,6 +152,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
// Forwarded methods from `MultibodyTree`.
cls // BR
.def(py::init<double>(), py::arg("time_step"), cls_doc.ctor.doc)
.def("time_step", &Class::time_step, cls_doc.time_step.doc)
.def("num_bodies", &Class::num_bodies, cls_doc.num_bodies.doc)
.def("num_joints", &Class::num_joints, cls_doc.num_joints.doc)
.def("num_actuators", &Class::num_actuators, cls_doc.num_actuators.doc)
Expand Down
1 change: 1 addition & 0 deletions bindings/pydrake/multibody/test/plant_test.py
Expand Up @@ -153,6 +153,7 @@ def test_multibody_plant_construction_api(self, T):

builder = DiagramBuilder()
plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0)
self.assertEqual(plant.time_step(), 0.0)
spatial_inertia = SpatialInertia()
body = plant.AddRigidBody(name="new_body",
M_BBo_B=spatial_inertia)
Expand Down