Skip to content

Commit

Permalink
Improve error message when calling iris clique cover without joint li…
Browse files Browse the repository at this point in the history
…mits (RobotLocomotion#21207)

Previously the error was an unhelpful throw from HPolyhedron saying
some set was unbounded (which is confusing for a method whose goal is
to use complex logic to assemble new hpolyhedron). We can fail-fast on
this one and give a much more clear/specific error message.
  • Loading branch information
RussTedrake authored Mar 28, 2024
1 parent 306d34b commit 9c59bbe
Show file tree
Hide file tree
Showing 3 changed files with 37 additions and 1 deletion.
6 changes: 5 additions & 1 deletion planning/iris/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,10 @@ drake_cc_library(
drake_cc_googletest(
name = "iris_from_clique_cover_test",
timeout = "moderate",
data = ["//multibody/parsing:test_models"],
data = [
"//examples/pendulum:models",
"//multibody/parsing:test_models",
],
# Running with multiple threads is an essential part of our test coverage.
num_threads = 4,
shard_count = 4,
Expand All @@ -55,6 +58,7 @@ drake_cc_googletest(
],
deps = [
":iris_from_clique_cover",
"//common/test_utilities:expect_throws_message",
"//common/test_utilities:maybe_pause_for_user",
"//geometry/test_utilities:meshcat_environment",
"//multibody/parsing:parser",
Expand Down
7 changes: 7 additions & 0 deletions planning/iris/iris_from_clique_cover.cc
Original file line number Diff line number Diff line change
Expand Up @@ -330,6 +330,13 @@ void IrisInConfigurationSpaceFromCliqueCover(
DRAKE_THROW_UNLESS(options.coverage_termination_threshold > 0);
DRAKE_THROW_UNLESS(options.iteration_limit > 0);

// Note: Even though the iris_options.bounding_region may be provided,
// IrisInConfigurationSpace (currently) requires finite joint limits.
DRAKE_THROW_UNLESS(
checker.plant().GetPositionLowerLimits().array().isFinite().all());
DRAKE_THROW_UNLESS(
checker.plant().GetPositionUpperLimits().array().isFinite().all());

const HPolyhedron domain = options.iris_options.bounding_region.value_or(
HPolyhedron::MakeBox(checker.plant().GetPositionLowerLimits(),
checker.plant().GetPositionUpperLimits()));
Expand Down
25 changes: 25 additions & 0 deletions planning/iris/test/iris_from_clique_cover_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

#include "drake/common/find_resource.h"
#include "drake/common/ssize.h"
#include "drake/common/test_utilities/expect_throws_message.h"
#include "drake/common/test_utilities/maybe_pause_for_user.h"
#include "drake/geometry/optimization/hpolyhedron.h"
#include "drake/geometry/optimization/hyperrectangle.h"
Expand Down Expand Up @@ -159,6 +160,30 @@ GTEST_TEST(IrisInConfigurationSpaceFromCliqueCover, BoxConfigurationSpaceTest) {
EXPECT_EQ(vpoly.CalcVolume(), 16.0);
}

// Plants that don't have joint limits get a reasonable error message.
GTEST_TEST(IrisInConfigurationSpaceFromCliqueCover, NoJointLimits) {
CollisionCheckerParams params;

RobotDiagramBuilder<double> builder(0.0);
params.robot_model_instances = builder.parser().AddModelsFromUrl(
"package://drake/examples/pendulum/Pendulum.urdf");
params.edge_step_size = 0.01;

params.model = builder.Build();
auto checker =
std::make_unique<SceneGraphCollisionChecker>(std::move(params));

IrisFromCliqueCoverOptions options;
std::vector<HPolyhedron> sets;

RandomGenerator generator(0);

DRAKE_EXPECT_THROWS_MESSAGE(
IrisInConfigurationSpaceFromCliqueCover(*checker, options, &generator,
&sets, nullptr),
".*.GetPositionLowerLimits.*isFinite.* failed.");
}

/* A movable sphere with fixed boxes in all corners.
┌───────────────┐
│┌────┐ ┌────┐│
Expand Down

0 comments on commit 9c59bbe

Please sign in to comment.