Skip to content

Commit

Permalink
[planning] Match RobotDiagram default time step to MbP's default
Browse files Browse the repository at this point in the history
This fixes some crashes when using models that need discrete-time-only
modeling features, such as implicit PD control.
  • Loading branch information
jwnimmer-tri committed Mar 6, 2024
1 parent bbafc14 commit 2dc0143
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 3 deletions.
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
2 changes: 1 addition & 1 deletion planning/robot_diagram_builder.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ class RobotDiagramBuilder {
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);
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 @@ -18,6 +18,7 @@ namespace {

using geometry::SceneGraph;
using multibody::MultibodyPlant;
using multibody::MultibodyPlantConfig;
using multibody::Parser;
using symbolic::Expression;
using systems::Context;
Expand All @@ -33,7 +34,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

0 comments on commit 2dc0143

Please sign in to comment.