From bff7e4c4df4aa6013594f475b96d88af869e7aaa Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Thu, 28 Feb 2019 10:54:32 -0500 Subject: [PATCH] Deprecate and remove all uses of DRAKE_ABORT_MSG (#10781) We want to remove DRAKE_ABORT_MSG, because in pydrake we should never take down the interpreter. Many uses are replaced by throwing an exception, or else perhaps by using the DRAKE_UNREACHABLE macro. --- attic/manipulation/dev/quasistatic_system.cc | 2 +- .../util/robot_state_msg_translator.cc | 6 ++- attic/multibody/collision/drake_collision.cc | 3 +- attic/multibody/collision/fcl_model.cc | 23 +++++------- attic/multibody/collision/test/model_test.cc | 35 +++++++++--------- attic/multibody/collision/unusable_model.cc | 22 ++++++----- attic/multibody/rigid_body.h | 3 +- .../viewer_draw_translator.cc | 2 +- attic/systems/sensors/rgbd_renderer_ospray.cc | 3 +- attic/systems/sensors/rgbd_renderer_vtk.cc | 3 +- automotive/maliput/multilane/builder.h | 5 +-- .../maliput/simplerulebook/simple_rulebook.cc | 3 +- automotive/maliput_railcar.cc | 4 +- common/drake_assert.h | 17 +++++---- common/symbolic_expression_visitor.h | 3 +- common/test/drake_assert_test.cc | 3 ++ examples/bead_on_a_wire/bead_on_a_wire-inl.h | 5 ++- examples/double_pendulum/sdf_helpers.cc | 4 +- examples/kuka_iiwa_arm/iiwa_controller.cc | 6 ++- .../manipulation_station.cc | 2 +- .../mock_station_simulation.cc | 4 +- .../manipulation_station/proof_of_life.cc | 5 ++- examples/rod2d/rod2d-inl.h | 6 +-- geometry/dev/render/render_engine_vtk.cc | 3 +- geometry/internal_geometry.cc | 2 +- geometry/proximity_engine.cc | 3 +- geometry/test/proximity_engine_test.cc | 14 +++---- multibody/plant/multibody_plant.cc | 3 +- multibody/tree/joint.h | 7 +++- solvers/mixed_integer_optimization_util.cc | 4 +- solvers/moby_lcp_solver.cc | 3 +- solvers/unrevised_lemke_solver.cc | 3 +- .../analysis/implicit_euler_integrator-inl.h | 3 +- systems/framework/input_port_base.cc | 3 +- systems/framework/port_base.cc | 2 +- systems/framework/system.h | 37 +++++++++++-------- .../primitives/first_order_low_pass_filter.cc | 3 +- systems/primitives/linear_system.cc | 4 +- systems/primitives/random_source.cc | 14 +++---- systems/rendering/pose_aggregator.cc | 12 +++--- systems/rendering/pose_aggregator.h | 3 +- systems/sensors/image_to_lcm_image_array_t.cc | 2 +- systems/sensors/image_writer.cc | 27 +++++++------- 43 files changed, 172 insertions(+), 149 deletions(-) diff --git a/attic/manipulation/dev/quasistatic_system.cc b/attic/manipulation/dev/quasistatic_system.cc index 8b2928f8c7a7..39c9d265c11d 100644 --- a/attic/manipulation/dev/quasistatic_system.cc +++ b/attic/manipulation/dev/quasistatic_system.cc @@ -386,7 +386,7 @@ void QuasistaticSystem::DoCalcWnWfJnJfPhiAnalytic( static_cast(Jn_ptr); static_cast(Jf_ptr); static_cast(phi_ptr); - DRAKE_ABORT_MSG( + throw std::logic_error( "Analytic expressions for Wn, Wf, Jn, Jf and phi are not " "available."); } diff --git a/attic/manipulation/util/robot_state_msg_translator.cc b/attic/manipulation/util/robot_state_msg_translator.cc index 0fe6cbad84da..196e0b438605 100644 --- a/attic/manipulation/util/robot_state_msg_translator.cc +++ b/attic/manipulation/util/robot_state_msg_translator.cc @@ -164,7 +164,8 @@ void RobotStateLcmMessageTranslator::DecodeMessageKinematics( v.segment<3>(velocity_start) = R_BJ * V_WB_J.head<3>(); // Rotate. v.segment<3>(velocity_start + 3) = R_BJ * V_WB_J.tail<3>(); // Translate. } else { - DRAKE_ABORT_MSG("Floating joint is neither a RPY or a Quaternion joint."); + throw std::domain_error( + "Floating joint is neither a RPY or a Quaternion joint."); } } @@ -276,7 +277,8 @@ void RobotStateLcmMessageTranslator::EncodeMessageKinematics( V_JB.head<3>() = R_JB * v.segment<3>(velocity_start); V_JB.tail<3>() = R_JB * v.segment<3>(velocity_start + 3); } else { - DRAKE_ABORT_MSG("Floating joint is neither a RPY or a Quaternion joint."); + throw std::domain_error( + "Floating joint is neither a RPY or a Quaternion joint."); } } else { // Fixed base, the transformation is the joint's pose in the world frame. diff --git a/attic/multibody/collision/drake_collision.cc b/attic/multibody/collision/drake_collision.cc index fe434a51716b..73a8eb4bef29 100644 --- a/attic/multibody/collision/drake_collision.cc +++ b/attic/multibody/collision/drake_collision.cc @@ -31,9 +31,8 @@ unique_ptr newModel(ModelType type) { return unique_ptr(new BulletModel()); } #endif - default: - DRAKE_ABORT_MSG("Unexpected collision model type."); } + DRAKE_UNREACHABLE(); } } // namespace collision diff --git a/attic/multibody/collision/fcl_model.cc b/attic/multibody/collision/fcl_model.cc index 4238599bb9d6..b44e52d2dde3 100644 --- a/attic/multibody/collision/fcl_model.cc +++ b/attic/multibody/collision/fcl_model.cc @@ -1,5 +1,6 @@ #include "drake/multibody/collision/fcl_model.h" +#include #include #include @@ -98,8 +99,7 @@ void FclModel::DoAddElement(const Element& element) { std::make_shared(cylinder.radius, cylinder.length); } break; default: - DRAKE_ABORT_MSG("Not implemented."); - break; + throw std::logic_error("Not implemented."); } auto fcl_object = std::make_unique(fcl_geometry); @@ -147,8 +147,7 @@ bool FclModel::ClosestPointsAllToAll( const std::vector& ids_to_check, bool use_margins, std::vector>* closest_points) { drake::unused(ids_to_check, use_margins, closest_points); - DRAKE_ABORT_MSG("Not implemented."); - return false; + throw std::logic_error("Not implemented."); } bool FclModel::ComputeMaximumDepthCollisionPoints( @@ -165,20 +164,19 @@ bool FclModel::ClosestPointsPairwise( const std::vector& id_pairs, bool use_margins, std::vector>* closest_points) { drake::unused(id_pairs, use_margins, closest_points); - DRAKE_ABORT_MSG("Not implemented."); - return false; + throw std::logic_error("Not implemented."); } void FclModel::CollisionDetectFromPoints( const Eigen::Matrix3Xd& points, bool use_margins, std::vector>* closest_points) { drake::unused(points, use_margins, closest_points); - DRAKE_ABORT_MSG("Not implemented."); + throw std::logic_error("Not implemented."); } void FclModel::ClearCachedResults(bool use_margins) { drake::unused(use_margins); - DRAKE_ABORT_MSG("Not implemented."); + throw std::logic_error("Not implemented."); } bool FclModel::CollisionRaycast(const Eigen::Matrix3Xd& origins, @@ -186,24 +184,21 @@ bool FclModel::CollisionRaycast(const Eigen::Matrix3Xd& origins, bool use_margins, Eigen::VectorXd* distances, Eigen::Matrix3Xd* normals) { drake::unused(origins, ray_endpoints, use_margins, distances, normals); - DRAKE_ABORT_MSG("Not implemented."); - return false; + throw std::logic_error("Not implemented."); } bool FclModel::CollidingPointsCheckOnly( const std::vector& input_points, double collision_threshold) { drake::unused(input_points, collision_threshold); - DRAKE_ABORT_MSG("Not implemented."); - return false; + throw std::logic_error("Not implemented."); } std::vector FclModel::CollidingPoints( const std::vector& input_points, double collision_threshold) { drake::unused(input_points, collision_threshold); - DRAKE_ABORT_MSG("Not implemented."); - return std::vector(); + throw std::logic_error("Not implemented."); } } // namespace collision diff --git a/attic/multibody/collision/test/model_test.cc b/attic/multibody/collision/test/model_test.cc index 465ef7f61f1a..414f088b41de 100644 --- a/attic/multibody/collision/test/model_test.cc +++ b/attic/multibody/collision/test/model_test.cc @@ -162,11 +162,12 @@ INSTANTIATE_TEST_CASE_P(UsableModelTypesTests, UsableModelTypesTests, #ifndef DRAKE_DISABLE_FCL // Fixture for locking down FclModel's not-yet-implemented functions. -class FclModelDeathTests : public ModelTestBase, - public ::testing::WithParamInterface< - std::function> { +class FclModelNotImplementedTests : + public ModelTestBase, + public ::testing::WithParamInterface< + std::function> { public: - FclModelDeathTests() { + FclModelNotImplementedTests() { model_ = drake::multibody::collision::newModel(ModelType::kFcl); } @@ -219,22 +220,22 @@ class FclModelDeathTests : public ModelTestBase, } }; -TEST_P(FclModelDeathTests, NotImplemented) { - ::testing::FLAGS_gtest_death_test_style = "threadsafe"; - EXPECT_DEATH(GetParam()(this), "Not implemented."); +TEST_P(FclModelNotImplementedTests, NotImplemented) { + EXPECT_THROW(GetParam()(this), std::exception); } INSTANTIATE_TEST_CASE_P( - NotImplementedTest, FclModelDeathTests, - ::testing::Values(&FclModelDeathTests::CallAddBox, - &FclModelDeathTests::CallAddCapsule, - &FclModelDeathTests::CallAddMesh, - &FclModelDeathTests::CallClosestPointsAllToAll, - &FclModelDeathTests::CallCollisionDetectFromPoints, - &FclModelDeathTests::CallClearCachedResults, - &FclModelDeathTests::CallCollisionRaycast, - &FclModelDeathTests::CallCollidingPointsCheckOnly, - &FclModelDeathTests::CallCollidingPoints)); + NotImplementedTest, FclModelNotImplementedTests, + ::testing::Values( + &FclModelNotImplementedTests::CallAddBox, + &FclModelNotImplementedTests::CallAddCapsule, + &FclModelNotImplementedTests::CallAddMesh, + &FclModelNotImplementedTests::CallClosestPointsAllToAll, + &FclModelNotImplementedTests::CallCollisionDetectFromPoints, + &FclModelNotImplementedTests::CallClearCachedResults, + &FclModelNotImplementedTests::CallCollisionRaycast, + &FclModelNotImplementedTests::CallCollidingPointsCheckOnly, + &FclModelNotImplementedTests::CallCollidingPoints)); #endif // Fixture for testing collision queries involving pairs of collision diff --git a/attic/multibody/collision/unusable_model.cc b/attic/multibody/collision/unusable_model.cc index d032f4f1578a..6e9775814f53 100644 --- a/attic/multibody/collision/unusable_model.cc +++ b/attic/multibody/collision/unusable_model.cc @@ -1,5 +1,7 @@ #include "drake/multibody/collision/unusable_model.h" +#include + #include "drake/common/drake_assert.h" namespace drake { @@ -7,48 +9,48 @@ namespace multibody { namespace collision { void UnusableModel::UpdateModel() { - DRAKE_ABORT_MSG( + throw std::domain_error( "Compile Drake with a collision library backend for collision support!"); return; } bool UnusableModel::UpdateElementWorldTransform( ElementId, const Eigen::Isometry3d&) { - DRAKE_ABORT_MSG( + throw std::domain_error( "Compile Drake with a collision library backend for collision support!"); return false; } bool UnusableModel::ClosestPointsAllToAll(const std::vector&, bool, std::vector>*) { - DRAKE_ABORT_MSG( + throw std::domain_error( "Compile Drake with a collision library backend for collision support!"); return false; } bool UnusableModel::ComputeMaximumDepthCollisionPoints( bool, std::vector>*) { - DRAKE_ABORT_MSG( + throw std::domain_error( "Compile Drake with a collision library backend for collision support!"); return false; } bool UnusableModel::ClosestPointsPairwise( const std::vector&, bool, std::vector>*) { - DRAKE_ABORT_MSG( + throw std::domain_error( "Compile Drake with a collision library backend for collision support!"); return false; } void UnusableModel::CollisionDetectFromPoints( const Eigen::Matrix3Xd&, bool, std::vector>*) { - DRAKE_ABORT_MSG( + throw std::domain_error( "Compile Drake with a collision library backend for collision support!"); return; } void UnusableModel::ClearCachedResults(bool) { - DRAKE_ABORT_MSG( + throw std::domain_error( "Compile Drake with a collision library backend for collision support!"); return; } @@ -58,21 +60,21 @@ bool UnusableModel::CollisionRaycast(const Eigen::Matrix3Xd&, bool, Eigen::VectorXd*, Eigen::Matrix3Xd*) { - DRAKE_ABORT_MSG( + throw std::domain_error( "Compile Drake with a collision library backend for collision support!"); return false; } bool UnusableModel::CollidingPointsCheckOnly( const std::vector&, double) { - DRAKE_ABORT_MSG( + throw std::domain_error( "Compile Drake with a collision library backend for collision support!"); return false; } std::vector UnusableModel::CollidingPoints( const std::vector&, double) { - DRAKE_ABORT_MSG( + throw std::domain_error( "Compile Drake with a collision library backend for collision support!"); return std::vector(); } diff --git a/attic/multibody/rigid_body.h b/attic/multibody/rigid_body.h index 3febbf442e10..118be972791c 100644 --- a/attic/multibody/rigid_body.h +++ b/attic/multibody/rigid_body.h @@ -4,6 +4,7 @@ #include #include #include +#include #include #include #include @@ -113,7 +114,7 @@ class RigidBody { template JointType* add_joint(RigidBody* parent, std::unique_ptr joint) { if (joint_ != nullptr) { - DRAKE_ABORT_MSG( + throw std::logic_error( "Attempting to assign a new joint to a body that already has one"); } set_parent(parent); diff --git a/attic/multibody/rigid_body_plant/viewer_draw_translator.cc b/attic/multibody/rigid_body_plant/viewer_draw_translator.cc index f7f01fc63e36..abd789eca0ac 100644 --- a/attic/multibody/rigid_body_plant/viewer_draw_translator.cc +++ b/attic/multibody/rigid_body_plant/viewer_draw_translator.cc @@ -29,7 +29,7 @@ ViewerDrawTranslator::ViewerDrawTranslator(const RigidBodyTree& tree) void ViewerDrawTranslator::Deserialize( const void*, int, VectorBase*) const { - DRAKE_ABORT_MSG( + throw std::logic_error( "The translator that converts from a drake::lcmt_viewer_draw message to " "a VectorBase object that contains the RigidBodyTree's state vector has not" "been implemented yet."); diff --git a/attic/systems/sensors/rgbd_renderer_ospray.cc b/attic/systems/sensors/rgbd_renderer_ospray.cc index 2ca31efc9a3c..d917ec2af4c5 100644 --- a/attic/systems/sensors/rgbd_renderer_ospray.cc +++ b/attic/systems/sensors/rgbd_renderer_ospray.cc @@ -4,6 +4,7 @@ #include #include #include +#include #include #include @@ -83,7 +84,7 @@ using ActorCollection = std::vector>; std::string RemoveFileExtension(const std::string& filepath) { const size_t last_dot = filepath.find_last_of("."); if (last_dot == std::string::npos) { - DRAKE_ABORT_MSG("File has no extension."); + throw std::logic_error("File has no extension."); } return filepath.substr(0, last_dot); } diff --git a/attic/systems/sensors/rgbd_renderer_vtk.cc b/attic/systems/sensors/rgbd_renderer_vtk.cc index dde3cd69dcde..3e4150731add 100644 --- a/attic/systems/sensors/rgbd_renderer_vtk.cc +++ b/attic/systems/sensors/rgbd_renderer_vtk.cc @@ -4,6 +4,7 @@ #include #include #include +#include #include #include @@ -85,7 +86,7 @@ struct ModuleInitVtkRenderingOpenGL2 { std::string RemoveFileExtension(const std::string& filepath) { const size_t last_dot = filepath.find_last_of("."); if (last_dot == std::string::npos) { - DRAKE_ABORT_MSG("File has no extension."); + throw std::logic_error("File has no extension."); } return filepath.substr(0, last_dot); } diff --git a/automotive/maliput/multilane/builder.h b/automotive/maliput/multilane/builder.h index 3003d586a403..9a6c0d8f8757 100644 --- a/automotive/maliput/multilane/builder.h +++ b/automotive/maliput/multilane/builder.h @@ -3,6 +3,7 @@ #include #include #include +#include #include #include #include @@ -656,14 +657,12 @@ class Builder : public BuilderBase { case -1: { return true; } case 1: { return false; } case 0: { return false; } - default: { DRAKE_ABORT_MSG("fuzzy_compare domain error"); } } } - default: { DRAKE_ABORT_MSG("fuzzy_compare domain error"); } } } - default: { DRAKE_ABORT_MSG("fuzzy_compare domain error"); } } + throw std::domain_error("fuzzy_compare domain error"); } private: diff --git a/automotive/maliput/simplerulebook/simple_rulebook.cc b/automotive/maliput/simplerulebook/simple_rulebook.cc index 9957595fee4a..6f43a0b029df 100644 --- a/automotive/maliput/simplerulebook/simple_rulebook.cc +++ b/automotive/maliput/simplerulebook/simple_rulebook.cc @@ -1,6 +1,7 @@ #include "drake/automotive/maliput/simplerulebook/simple_rulebook.h" #include +#include #include #include "drake/common/drake_optional.h" @@ -211,7 +212,7 @@ QueryResults SimpleRulebook::DoFindRules( } else if (id.s) { result.speed_limit.push_back(speed_limits_.at(*id.s)); } else { - DRAKE_ABORT_MSG("IdVariant is empty"); + throw std::domain_error("SimpleRulebook: IdVariant is empty"); } } } diff --git a/automotive/maliput_railcar.cc b/automotive/maliput_railcar.cc index abc5e2ff7236..01af2c6c9238 100644 --- a/automotive/maliput_railcar.cc +++ b/automotive/maliput_railcar.cc @@ -3,6 +3,7 @@ #include #include #include +#include #include #include @@ -449,7 +450,8 @@ void MaliputRailcar::DoCalcUnrestrictedUpdate( } if (!next_branch) { - DRAKE_ABORT_MSG("MaliputRailcar::DoCalcUnrestrictedUpdate: ERROR: " + throw std::logic_error( + "MaliputRailcar::DoCalcUnrestrictedUpdate: ERROR: " "Vehicle should switch lanes but no default or ongoing branch " "exists."); } else { diff --git a/common/drake_assert.h b/common/drake_assert.h index e1ee485c936d..1b856db86c94 100644 --- a/common/drake_assert.h +++ b/common/drake_assert.h @@ -62,8 +62,8 @@ /// to silence false positive warnings. When in doubt, throw an exception /// manually instead of using this macro. #define DRAKE_UNREACHABLE() -/// Aborts the program (via ::abort) with a message showing at least the -/// given message (macro argument), function name, file, and line. +/// (Deprecated.) Aborts the program (via ::abort) with a message showing at +/// least the given message (macro argument), function name, file, and line. #define DRAKE_ABORT_MSG(message) #else // DRAKE_DOXYGEN_CXX @@ -93,10 +93,11 @@ __attribute__((noreturn)) /* gcc is ok with [[noreturn]]; clang is not. */ void Abort(const char* condition, const char* func, const char* file, int line); __attribute__((noreturn)) __attribute__((deprecated( - "\nDRAKE DEPRECATED: DRAKE_ABORT() is deprecated; use DRAKE_ABORT_MSG(); " - "this macro will be removed on 2019-05-01."))) -inline void DeprecatedAbort(const char* func, const char* file, int line) { - Abort(nullptr, func, file, line); + "\nDRAKE DEPRECATED: DRAKE_ABORT() and DRAKE_ABORT_MSG() are deprecated; " + "use 'throw' instead; this macro will be removed on 2019-06-01."))) +inline void DeprecatedAbort( + const char* condition, const char* func, const char* file, int line) { + Abort(condition, func, file, line); } // Report an assertion failure; will either Abort(...) or throw. __attribute__((noreturn)) /* gcc is ok with [[noreturn]]; clang is not. */ @@ -120,7 +121,7 @@ struct ConditionTraits { } // namespace drake #define DRAKE_ABORT() \ - ::drake::detail::DeprecatedAbort(__func__, __FILE__, __LINE__) + ::drake::detail::DeprecatedAbort(nullptr, __func__, __FILE__, __LINE__) #define DRAKE_UNREACHABLE() \ ::drake::detail::Abort( \ @@ -138,7 +139,7 @@ struct ConditionTraits { } while (0) #define DRAKE_ABORT_MSG(msg) \ - ::drake::detail::Abort(msg, __func__, __FILE__, __LINE__) + ::drake::detail::DeprecatedAbort(msg, __func__, __FILE__, __LINE__) #ifdef DRAKE_ASSERT_IS_ARMED // Assertions are enabled. diff --git a/common/symbolic_expression_visitor.h b/common/symbolic_expression_visitor.h index 98768e5b44db..fb1757cea79d 100644 --- a/common/symbolic_expression_visitor.h +++ b/common/symbolic_expression_visitor.h @@ -71,7 +71,8 @@ Result VisitPolynomial(Visitor* v, const Expression& e, Args&&... args) { case ExpressionKind::IfThenElse: case ExpressionKind::UninterpretedFunction: // Unreachable because of `DRAKE_DEMAND(e.is_polynomial())` at the top. - DRAKE_ABORT_MSG("Unexpected Kind was is_polynomial"); + throw std::domain_error( + "Unexpected Kind was is_polynomial in VisitPolynomial"); } // Unreachable because all switch cases are accounted for above. DRAKE_UNREACHABLE(); diff --git a/common/test/drake_assert_test.cc b/common/test/drake_assert_test.cc index e25e4bb81215..aa37b85b10ad 100644 --- a/common/test/drake_assert_test.cc +++ b/common/test/drake_assert_test.cc @@ -36,10 +36,13 @@ GTEST_TEST(DrakeAssertDeathTest, AbortTest) { GTEST_TEST(DrakeAssertDeathTest, AbortMsgTest) { ::testing::FLAGS_gtest_death_test_style = "threadsafe"; +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" ASSERT_DEATH( { DRAKE_ABORT_MSG("stuff"); }, "abort: Failure at .*drake_assert_test.cc:.. in TestBody..: " "condition 'stuff' failed"); +#pragma GCC diagnostic pop } GTEST_TEST(DrakeAssertDeathTest, DemandTest) { diff --git a/examples/bead_on_a_wire/bead_on_a_wire-inl.h b/examples/bead_on_a_wire/bead_on_a_wire-inl.h index 9238c12bb3a2..5187b3104110 100644 --- a/examples/bead_on_a_wire/bead_on_a_wire-inl.h +++ b/examples/bead_on_a_wire/bead_on_a_wire-inl.h @@ -169,7 +169,10 @@ Eigen::VectorXd BeadOnAWire::DoCalcVelocityChangeFromConstraintImpulses( // TODO(edrumwri): Test this method as soon as DAE solver is available, // (necessarily removing abort() first). - DRAKE_ABORT_MSG("This method requires testing."); + if (true) { + throw std::logic_error( + "DoCalcVelocityChangeFromConstraintImpulses requires testing."); + } // The bead on the wire is unit mass, so the velocity change is equal to // simply Jᵀλ diff --git a/examples/double_pendulum/sdf_helpers.cc b/examples/double_pendulum/sdf_helpers.cc index 33bcb2d697a7..e505d0591fdd 100644 --- a/examples/double_pendulum/sdf_helpers.cc +++ b/examples/double_pendulum/sdf_helpers.cc @@ -78,7 +78,7 @@ void ParseGeometry(sdf::ElementPtr sdf_geometry_element, return; } // TODO(hidmic): Support mesh and sphere geometries. - DRAKE_ABORT_MSG("Unsupported geometry!"); + throw std::domain_error("Unsupported geometry!"); } // Parses a visual geometry from the given SDF element and adds a @@ -258,7 +258,7 @@ ParseJointType(sdf::ElementPtr sdf_joint_element, return std::move(joint); } // TODO(hidmic): Support prismatic and fixed joints. - DRAKE_ABORT_MSG("Unsupported joint type!"); + throw std::domain_error("Unsupported joint type!"); } // Parses a joint from the given SDF element and adds a DrakeJoint instance diff --git a/examples/kuka_iiwa_arm/iiwa_controller.cc b/examples/kuka_iiwa_arm/iiwa_controller.cc index 8b52b9887e81..273622b41559 100644 --- a/examples/kuka_iiwa_arm/iiwa_controller.cc +++ b/examples/kuka_iiwa_arm/iiwa_controller.cc @@ -2,6 +2,7 @@ /// /// Implements a controller for a KUKA iiwa arm. +#include #include #include @@ -75,10 +76,11 @@ int DoMain() { } else if (interp_str == "pchip") { interpolator_type = InterpolatorType::Pchip; } else { - DRAKE_ABORT_MSG( + std::cerr << "Robot plan interpolation type not recognized. " "Use the gflag --helpshort to display " - "flag options for interpolator type."); + "flag options for interpolator type.\n"; + return EXIT_FAILURE; } auto plan_interpolator = builder.AddSystem(urdf, interpolator_type); diff --git a/examples/manipulation_station/manipulation_station.cc b/examples/manipulation_station/manipulation_station.cc index c1f2bcd60386..5dca3b956e61 100644 --- a/examples/manipulation_station/manipulation_station.cc +++ b/examples/manipulation_station/manipulation_station.cc @@ -909,7 +909,7 @@ void ManipulationStation::AddDefaultIiwa( "iiwa7_with_box_collision.sdf"); break; default: - DRAKE_ABORT_MSG("Unrecognized collision_model."); + throw std::domain_error("Unrecognized collision_model."); } const auto X_WI = RigidTransform::Identity(); auto iiwa_instance = internal::AddAndWeldModelFrom( diff --git a/examples/manipulation_station/mock_station_simulation.cc b/examples/manipulation_station/mock_station_simulation.cc index 0cff484c3ce9..51b394fe89b1 100644 --- a/examples/manipulation_station/mock_station_simulation.cc +++ b/examples/manipulation_station/mock_station_simulation.cc @@ -54,8 +54,8 @@ int do_main(int argc, char* argv[]) { } else if (FLAGS_setup == "clutter_clearing") { station->SetupClutterClearingStation(); } else { - DRAKE_ABORT_MSG("Unrecognized station type. Options are " - "{default, clutter_clearing}."); + throw std::domain_error( + "Unrecognized station type. Options are {default, clutter_clearing}."); } // TODO(russt): Load sdf objects specified at the command line. Requires // #9747. diff --git a/examples/manipulation_station/proof_of_life.cc b/examples/manipulation_station/proof_of_life.cc index a691423a40cc..5fef8b747fcb 100644 --- a/examples/manipulation_station/proof_of_life.cc +++ b/examples/manipulation_station/proof_of_life.cc @@ -100,8 +100,9 @@ int do_main(int argc, char* argv[]) { // Check that the arm is (very roughly) in the commanded position. VectorXd q = station->GetIiwaPosition(station_context); if (!is_approx_equal_abstol(q, q0, 1.e-3)) { - std::cout << "q - q0 = " << (q - q0).transpose() << std::endl; - DRAKE_ABORT_MSG("q is not sufficiently close to q0."); + std::cout << "q is not sufficiently close to q0.\n"; + std::cout << "q - q0 = " << (q - q0).transpose() << "\n"; + return EXIT_FAILURE; } return 0; diff --git a/examples/rod2d/rod2d-inl.h b/examples/rod2d/rod2d-inl.h index 112b2ffcfeda..6d65e84f523c 100644 --- a/examples/rod2d/rod2d-inl.h +++ b/examples/rod2d/rod2d-inl.h @@ -12,6 +12,7 @@ #include #include #include +#include #include #include @@ -82,8 +83,7 @@ int Rod2D::DetermineNumWitnessFunctions( return 0; // TODO(edrumwri): Flesh out this stub. - DRAKE_ABORT_MSG("Rod2D::DetermineNumWitnessFunctions is stubbed"); - return 0; + throw std::domain_error("Rod2D::DetermineNumWitnessFunctions is stubbed"); } /// Gets the integer variable 'k' used to determine the point of contact @@ -1036,7 +1036,7 @@ void Rod2D::DoCalcTimeDerivatives( return CalcAccelerationsCompliantContactAndBallistic(context, derivatives); } else { // TODO(edrumwri): Implement the piecewise DAE approach. - DRAKE_ABORT_MSG( + throw std::domain_error( "Rod2D::DoCalcTimeDerivatives: piecewise DAE isn't implemented yet"); } } diff --git a/geometry/dev/render/render_engine_vtk.cc b/geometry/dev/render/render_engine_vtk.cc index 80d9131493a9..149fe83413c8 100644 --- a/geometry/dev/render/render_engine_vtk.cc +++ b/geometry/dev/render/render_engine_vtk.cc @@ -1,6 +1,7 @@ #include "drake/geometry/dev/render/render_engine_vtk.h" #include +#include #include #include @@ -99,7 +100,7 @@ struct RegistrationData { std::string RemoveFileExtension(const std::string& filepath) { const size_t last_dot = filepath.find_last_of("."); if (last_dot == std::string::npos) { - DRAKE_ABORT_MSG("File has no extension."); + throw std::logic_error("File has no extension."); } return filepath.substr(0, last_dot); } diff --git a/geometry/internal_geometry.cc b/geometry/internal_geometry.cc index 7fbe8c2328df..e89b5d3e90b0 100644 --- a/geometry/internal_geometry.cc +++ b/geometry/internal_geometry.cc @@ -29,7 +29,7 @@ bool InternalGeometry::has_role(Role role) const { case Role::kUnassigned: return !(has_proximity_role() || has_illustration_role()); } - DRAKE_ABORT_MSG("Unreachable code; switch on enum had unexpected value"); + DRAKE_UNREACHABLE(); } } // namespace internal diff --git a/geometry/proximity_engine.cc b/geometry/proximity_engine.cc index 2d3c55a93ae1..5859be451ad0 100644 --- a/geometry/proximity_engine.cc +++ b/geometry/proximity_engine.cc @@ -5,6 +5,7 @@ #include #include #include +#include #include #include #include @@ -1102,7 +1103,7 @@ class ProximityEngine::Impl : public ShapeReifier { } void ImplementGeometry(const Mesh&, void*) override { - DRAKE_ABORT_MSG("The proximity engine does not support meshes yet"); + throw std::domain_error("The proximity engine does not support meshes yet"); } // diff --git a/geometry/test/proximity_engine_test.cc b/geometry/test/proximity_engine_test.cc index b9e050a738e2..a57301195865 100644 --- a/geometry/test/proximity_engine_test.cc +++ b/geometry/test/proximity_engine_test.cc @@ -2489,25 +2489,23 @@ TEST_F(BoxPenetrationTest, TangentConvex2) { // Attempting to add a dynamic Mesh should cause an abort. GTEST_TEST(ProximityEngineTests, AddDynamicMesh) { - ::testing::FLAGS_gtest_death_test_style = "threadsafe"; ProximityEngine engine; Mesh mesh{"invalid/path/thing.obj", 1.0}; - ASSERT_DEATH( + DRAKE_EXPECT_THROWS_MESSAGE( engine.AddDynamicGeometry(mesh, GeometryIndex(0)), - "abort: .*proximity_engine.*" - "The proximity engine does not support meshes yet.*"); + std::exception, + ".*The proximity engine does not support meshes yet.*"); } // Attempting to add a anchored Mesh should cause an abort. GTEST_TEST(ProximityEngineTests, AddAnchoredMesh) { - ::testing::FLAGS_gtest_death_test_style = "threadsafe"; ProximityEngine engine; Mesh mesh{"invalid/path/thing.obj", 1.0}; - ASSERT_DEATH( + DRAKE_EXPECT_THROWS_MESSAGE( engine.AddAnchoredGeometry(mesh, Isometry3d::Identity(), GeometryIndex(0)), - "abort: .*proximity_engine.*" - "The proximity engine does not support meshes yet.*"); + std::exception, + ".*The proximity engine does not support meshes yet.*"); } // This is a one-off test. Exposed in issue #10577. A point penetration pair diff --git a/multibody/plant/multibody_plant.cc b/multibody/plant/multibody_plant.cc index 9b4348491df6..64be173e6767 100644 --- a/multibody/plant/multibody_plant.cc +++ b/multibody/plant/multibody_plant.cc @@ -3,6 +3,7 @@ #include #include #include +#include #include #include "drake/common/drake_throw.h" @@ -933,7 +934,7 @@ template std::vector> MultibodyPlant::CalcPointPairPenetrations( const systems::Context&) const { - DRAKE_ABORT_MSG("This method only supports T = double."); + throw std::domain_error("This method only supports T = double."); } template diff --git a/multibody/tree/joint.h b/multibody/tree/joint.h index ac1f9980efa2..0984a304f6ff 100644 --- a/multibody/tree/joint.h +++ b/multibody/tree/joint.h @@ -2,6 +2,7 @@ #include #include +#include #include #include #include @@ -439,7 +440,8 @@ class Joint : public MultibodyTreeElement, JointIndex> { /// Revolute and prismatic are examples of joints that will want to implement /// this method. virtual const T& DoGetOnePosition(const systems::Context&) const { - DRAKE_ABORT_MSG("This method can only be called on single-dof joints."); + throw std::domain_error( + "GetOnePosition can only be called on single-dof joints."); } /// Implementation to the NVI GetOneVelocity() that must only be implemented @@ -449,7 +451,8 @@ class Joint : public MultibodyTreeElement, JointIndex> { /// Revolute and prismatic are examples of joints that will want to implement /// this method. virtual const T& DoGetOneVelocity(const systems::Context&) const { - DRAKE_ABORT_MSG("This method can only be called on single-dof joints."); + throw std::domain_error( + "GetOneVelocity can only be called on single-dof joints."); } /// Adds into `forces` a force along the one of the joint's degrees of diff --git a/solvers/mixed_integer_optimization_util.cc b/solvers/mixed_integer_optimization_util.cc index 21296234a563..96b96efb81f0 100644 --- a/solvers/mixed_integer_optimization_util.cc +++ b/solvers/mixed_integer_optimization_util.cc @@ -16,9 +16,7 @@ std::string to_string(IntervalBinning binning) { return "logarithmic_binning"; } } - // The following line should not be reached. We add it due to a compiler - // defect. - DRAKE_ABORT_MSG("Should not reach this part of the code."); + DRAKE_UNREACHABLE(); } std::ostream& operator<<(std::ostream& os, const IntervalBinning& binning) { diff --git a/solvers/moby_lcp_solver.cc b/solvers/moby_lcp_solver.cc index 0c563ea0e474..c2f8c2526434 100644 --- a/solvers/moby_lcp_solver.cc +++ b/solvers/moby_lcp_solver.cc @@ -7,6 +7,7 @@ #include #include #include +#include #include #include @@ -152,7 +153,7 @@ template <> void MobyLCPSolver>::DoSolve( const MathematicalProgram&, const Eigen::VectorXd&, const SolverOptions&, MathematicalProgramResult*) const { - DRAKE_ABORT_MSG( + throw std::logic_error( "MobyLCPSolver cannot yet be used in a MathematicalProgram " "while templatized as an AutoDiff"); } diff --git a/solvers/unrevised_lemke_solver.cc b/solvers/unrevised_lemke_solver.cc index adf283c72e6f..595dd85bd7ad 100644 --- a/solvers/unrevised_lemke_solver.cc +++ b/solvers/unrevised_lemke_solver.cc @@ -7,6 +7,7 @@ #include #include #include +#include #include #include @@ -80,7 +81,7 @@ template <> void UnrevisedLemkeSolver::DoSolve( const MathematicalProgram&, const Eigen::VectorXd&, const SolverOptions&, MathematicalProgramResult*) const { - DRAKE_ABORT_MSG( + throw std::logic_error( "UnrevisedLemkeSolver cannot yet be used in a " "MathematicalProgram while templatized as an AutoDiff"); } diff --git a/systems/analysis/implicit_euler_integrator-inl.h b/systems/analysis/implicit_euler_integrator-inl.h index 99dec75b95e3..a30ad0cad46d 100644 --- a/systems/analysis/implicit_euler_integrator-inl.h +++ b/systems/analysis/implicit_euler_integrator-inl.h @@ -12,6 +12,7 @@ #include #include #include +#include #include #include "drake/common/text_logging.h" @@ -397,7 +398,7 @@ bool ImplicitEulerIntegrator::CalcMatrices(const T& tf, const T& dt, } default: - DRAKE_ABORT_MSG("Unexpected trial number."); + throw std::domain_error("Unexpected trial number."); } } } diff --git a/systems/framework/input_port_base.cc b/systems/framework/input_port_base.cc index 4bc5aaddb447..77e2b1c01f0f 100644 --- a/systems/framework/input_port_base.cc +++ b/systems/framework/input_port_base.cc @@ -1,5 +1,6 @@ #include "drake/systems/framework/input_port_base.h" +#include #include #include @@ -20,7 +21,7 @@ InputPortBase::InputPortBase( eval_(std::move(eval)), random_type_(random_type) { if (is_random() && data_type != kVectorValued) { - DRAKE_ABORT_MSG("Random input ports must be vector valued."); + throw std::logic_error("Random input ports must be vector valued."); } DRAKE_DEMAND(eval_ != nullptr); } diff --git a/systems/framework/port_base.cc b/systems/framework/port_base.cc index 9edaaca0a327..c19c41c2d2c0 100644 --- a/systems/framework/port_base.cc +++ b/systems/framework/port_base.cc @@ -25,7 +25,7 @@ PortBase::PortBase( DRAKE_DEMAND(owning_system != nullptr); DRAKE_DEMAND(!name_.empty()); if (size_ == kAutoSize) { - DRAKE_ABORT_MSG("Auto-size ports are not yet implemented."); + throw std::domain_error("Auto-size ports are not yet implemented."); } } diff --git a/systems/framework/system.h b/systems/framework/system.h index 918f28eacc14..89bafb6b1980 100644 --- a/systems/framework/system.h +++ b/systems/framework/system.h @@ -1451,24 +1451,29 @@ class System : public SystemBase { continue; } - if (input_port.get_data_type() == kVectorValued) { - // For vector-valued input ports, we placewise initialize a fixed input - // vector using the explicit conversion from double to T. - const Eigen::VectorBlock> other_vec = - other_port.Eval(other_context); - auto our_vec = this->AllocateInputVector(input_port); - for (int j = 0; j < our_vec->size(); ++j) { - (*our_vec)[j] = T(other_vec[j]); + switch (input_port.get_data_type()) { + case kVectorValued: { + // For vector-valued input ports, we placewise initialize a fixed + // input vector using the explicit conversion from double to T. + const Eigen::VectorBlock> other_vec = + other_port.Eval(other_context); + auto our_vec = this->AllocateInputVector(input_port); + for (int j = 0; j < our_vec->size(); ++j) { + (*our_vec)[j] = T(other_vec[j]); + } + target_context->FixInputPort(i, *our_vec); + continue; + } + case kAbstractValued: { + // For abstract-valued input ports, we just clone the value and fix + // it to the port. + const auto& other_value = + other_port.Eval(other_context); + target_context->FixInputPort(i, other_value); + continue; } - target_context->FixInputPort(i, *our_vec); - } else if (input_port.get_data_type() == kAbstractValued) { - // For abstract-valued input ports, we just clone the value and fix - // it to the port. - const auto& other_value = other_port.Eval(other_context); - target_context->FixInputPort(i, other_value); - } else { - DRAKE_ABORT_MSG("Unknown input port type."); } + DRAKE_UNREACHABLE(); } } diff --git a/systems/primitives/first_order_low_pass_filter.cc b/systems/primitives/first_order_low_pass_filter.cc index cd27256ed60c..0c604ef228d9 100644 --- a/systems/primitives/first_order_low_pass_filter.cc +++ b/systems/primitives/first_order_low_pass_filter.cc @@ -1,6 +1,7 @@ #include "drake/systems/primitives/first_order_low_pass_filter.h" #include +#include #include "drake/common/default_scalars.h" #include "drake/common/drake_assert.h" @@ -39,7 +40,7 @@ double FirstOrderLowPassFilter::get_time_constant() const { s << "The time constants vector, [" << time_constants_ << "], cannot be " "represented as a scalar value. Please use " "FirstOrderLowPassFilter::get_time_constants_vector() instead."; - DRAKE_ABORT_MSG(s.str().c_str()); + throw std::domain_error(s.str()); } return time_constants_[0]; } diff --git a/systems/primitives/linear_system.cc b/systems/primitives/linear_system.cc index dd6876f167f7..86f4b47191cf 100644 --- a/systems/primitives/linear_system.cc +++ b/systems/primitives/linear_system.cc @@ -125,7 +125,7 @@ std::unique_ptr> DoFirstOrderTaylorApproximation( input_port_index < system.get_num_input_ports()) { input_port = &(autodiff_system->get_input_port(input_port_index)); } else if (input_port_index != kNoInput) { - DRAKE_ABORT_MSG("Invalid input_port_index specified."); + throw std::domain_error("Invalid input_port_index specified."); } // By default, use the first input / output ports (if they exist). @@ -138,7 +138,7 @@ std::unique_ptr> DoFirstOrderTaylorApproximation( output_port_index < system.get_num_output_ports()) { output_port = &(autodiff_system->get_output_port(output_port_index)); } else if (output_port_index != kNoOutput) { - DRAKE_ABORT_MSG("Invalid output_port_index specified."); + throw std::domain_error("Invalid output_port_index specified."); } // Verify that the input port is not abstract valued. diff --git a/systems/primitives/random_source.cc b/systems/primitives/random_source.cc index ace336191d8b..c75c60e97b0f 100644 --- a/systems/primitives/random_source.cc +++ b/systems/primitives/random_source.cc @@ -39,28 +39,28 @@ int AddRandomInputs(double sampling_interval_sec, continue; } + count++; switch (port.get_random_type().value()) { case RandomDistribution::kUniform: { const auto* uniform = builder->AddSystem( port.size(), sampling_interval_sec); builder->Connect(uniform->get_output_port(0), port); - } break; + continue; + } case RandomDistribution::kGaussian: { const auto* gaussian = builder->AddSystem( port.size(), sampling_interval_sec); builder->Connect(gaussian->get_output_port(0), port); - } break; + continue; + } case RandomDistribution::kExponential: { const auto* exponential = builder->AddSystem( port.size(), sampling_interval_sec); builder->Connect(exponential->get_output_port(0), port); - } break; - default: { - DRAKE_ABORT_MSG( - "InputPort has an unsupported RandomDistribution."); + continue; } } - count++; + DRAKE_UNREACHABLE(); } } return count; diff --git a/systems/rendering/pose_aggregator.cc b/systems/rendering/pose_aggregator.cc index 9056d67659cc..ac7638f9c397 100644 --- a/systems/rendering/pose_aggregator.cc +++ b/systems/rendering/pose_aggregator.cc @@ -78,7 +78,7 @@ void PoseAggregator::CalcPoseBundle(const Context& context, bundle.set_pose(pose_index, value.get_isometry()); bundle.set_model_instance_id(pose_index, record.model_instance_id); pose_index++; - break; + continue; } case InputRecord::kSingleVelocity: { // Single velocities are associated with the single pose that must @@ -97,7 +97,7 @@ void PoseAggregator::CalcPoseBundle(const Context& context, // Write the velocity to the previous pose_index, and do not increment // the pose_index, because this input was not a pose. bundle.set_velocity(prev_pose_index, value); - break; + continue; } case InputRecord::kBundle: { // Concatenate the poses of the input pose bundle into the output. @@ -115,10 +115,10 @@ void PoseAggregator::CalcPoseBundle(const Context& context, value.get_model_instance_id(j)); pose_index++; } - break; + continue; } - default: { DRAKE_ABORT_MSG("Unknown PoseInputType."); } } + DRAKE_UNREACHABLE(); } } @@ -183,10 +183,8 @@ PoseAggregator::DeclareInput(const InputRecord& record) { case InputRecord::kBundle: return this->DeclareAbstractInputPort( kUseDefaultName, Value>()); - case InputRecord::kUnknown: - break; } - DRAKE_ABORT_MSG("Invariant failure"); + DRAKE_UNREACHABLE(); } } // namespace rendering diff --git a/systems/rendering/pose_aggregator.h b/systems/rendering/pose_aggregator.h index 4d23993235b8..4d46106fc5b9 100644 --- a/systems/rendering/pose_aggregator.h +++ b/systems/rendering/pose_aggregator.h @@ -158,13 +158,12 @@ namespace pose_aggregator_detail { // parameter @p T. struct InputRecord { enum PoseInputType { - kUnknown = 0, kSinglePose = 1, kSingleVelocity = 2, kBundle = 3, }; - PoseInputType type{kUnknown}; + PoseInputType type{kSinglePose}; int num_poses{0}; // name is only valid if type is kSingle{Pose, Velocity} or kBundle. std::string name{}; diff --git a/systems/sensors/image_to_lcm_image_array_t.cc b/systems/sensors/image_to_lcm_image_array_t.cc index b6c7c1563aed..5e3c7891db29 100644 --- a/systems/sensors/image_to_lcm_image_array_t.cc +++ b/systems/sensors/image_to_lcm_image_array_t.cc @@ -129,7 +129,7 @@ void PackImageToLcmImageT(const AbstractValue& untyped_image, break; } case PixelType::kExpr: - DRAKE_ABORT_MSG("PixelType::kExpr is not supported."); + throw std::domain_error("PixelType::kExpr is not supported."); } } diff --git a/systems/sensors/image_writer.cc b/systems/sensors/image_writer.cc index 6a1ef63bed63..b1940ed4cc1c 100644 --- a/systems/sensors/image_writer.cc +++ b/systems/sensors/image_writer.cc @@ -111,20 +111,19 @@ const InputPort& ImageWriter::DeclareImageInputPort( DirectoryFromFormat(file_name_format, port_name, kPixelType)}; FolderState folder_state = ValidateDirectory(test_dir.getStr()); if (folder_state != FolderState::kValid) { - std::string reason; - switch (folder_state) { - case FolderState::kMissing: - reason = "the directory does not exist"; - break; - case FolderState::kIsFile: - reason = "the directory is actually a file"; - break; - case FolderState::kUnwritable: - reason = "no permissions to write the directory"; - break; - default: - DRAKE_ABORT_MSG("Directory is not valid; unhandled failure condition"); - } + const char* const reason = [folder_state]() { + switch (folder_state) { + case FolderState::kValid: + DRAKE_UNREACHABLE(); + case FolderState::kMissing: + return "the directory does not exist"; + case FolderState::kIsFile: + return "the directory is actually a file"; + case FolderState::kUnwritable: + return "no permissions to write the directory"; + } + DRAKE_UNREACHABLE(); + }(); throw std::logic_error( fmt::format("ImageWriter: The format string `{}` implied the invalid " "directory: '{}'; {}",