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

[planning] Match RobotDiagram default time step to MbP's default #21098

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.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion bindings/pydrake/planning/planning_py_robot_diagram.cc
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,8 @@ void DefinePlanningRobotDiagram(py::module m) {
auto cls = DefineTemplateClassWithDefault<Class>(
m, "RobotDiagramBuilder", GetPyParam<T>(), cls_doc.doc);
cls // BR
.def(py::init<double>(), py::arg("time_step") = 0.0, cls_doc.ctor.doc)
.def(py::init<double>(), py::arg("time_step") = 0.001,
cls_doc.ctor.doc)
.def("builder",
overload_cast_explicit<systems::DiagramBuilder<T>&>(
&Class::builder),
Expand Down
9 changes: 8 additions & 1 deletion bindings/pydrake/planning/test/robot_diagram_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,18 @@
from pydrake.common.test_utilities import numpy_compare
from pydrake.geometry import SceneGraph_
from pydrake.multibody.parsing import Parser
from pydrake.multibody.plant import MultibodyPlant_
from pydrake.multibody.plant import MultibodyPlant_, MultibodyPlantConfig
from pydrake.systems.framework import Context_, DiagramBuilder_


class TestRobotDiagram(unittest.TestCase):
@numpy_compare.check_all_types
def test_robot_diagram_builder_default_time_step(self, T):
Class = mut.RobotDiagramBuilder_[T]
dut = Class()
self.assertEqual(dut.plant().time_step(),
MultibodyPlantConfig().time_step)

@numpy_compare.check_all_types
def test_robot_diagram_builder(self, T):
"""Tests the full RobotDiagramBuilder API.
Expand Down
9 changes: 7 additions & 2 deletions planning/robot_diagram_builder.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,13 @@ class RobotDiagramBuilder {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(RobotDiagramBuilder)

/** Constructs with the specified time step for the contained plant. */
explicit RobotDiagramBuilder(double time_step = 0.0);
/** Constructs with the specified time step for the contained plant.
@param time_step Governs whether the MultibodyPlant is modeled as a discrete
system (`time_step > 0`) or as a continuous system (`time_step = 0`). See
@ref time_advancement_strategy "Choice of Time Advancement Strategy" for
further details. The default here matches the default value from
multibody::MultibodyPlantConfig. */
explicit RobotDiagramBuilder(double time_step = 0.001);

~RobotDiagramBuilder();

Expand Down
9 changes: 8 additions & 1 deletion planning/test/robot_diagram_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ namespace {

using geometry::SceneGraph;
using multibody::MultibodyPlant;
using multibody::MultibodyPlantConfig;
using multibody::Parser;
using symbolic::Expression;
using systems::Context;
Expand All @@ -32,7 +33,13 @@ std::unique_ptr<RobotDiagramBuilder<double>> MakeSampleDut() {
return builder;
}

GTEST_TEST(RobotDiagramBuilderTest, TimeStep) {
GTEST_TEST(RobotDiagramBuilderTest, TimeStepDefault) {
const MultibodyPlantConfig default_plant_config;
auto builder = std::make_unique<RobotDiagramBuilder<double>>();
EXPECT_EQ(builder->plant().time_step(), default_plant_config.time_step);
}

GTEST_TEST(RobotDiagramBuilderTest, TimeStepExplicit) {
const double time_step = 0.01;
auto builder = std::make_unique<RobotDiagramBuilder<double>>(time_step);
EXPECT_EQ(builder->plant().time_step(), time_step);
Expand Down