From ad8b7e588a7bbab186b33bdb3cdc4d6e05449507 Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Tue, 31 May 2022 19:01:29 -0700 Subject: [PATCH] Remove deprecated code 2022-06 (#17296) --- bindings/pydrake/math_py.cc | 25 +----- bindings/pydrake/multibody/math_py.cc | 68 ++------------- bindings/pydrake/multibody/test/math_test.py | 18 ---- bindings/pydrake/test/math_test.py | 6 -- common/test_utilities/expect_throws_message.h | 84 ++++--------------- .../kinova_jaco/jaco_command_receiver.cc | 11 --- .../kinova_jaco/jaco_command_receiver.h | 19 ----- .../test/jaco_command_receiver_test.cc | 24 ------ math/rigid_transform.h | 6 -- math/rotation_matrix.h | 6 -- math/test/rigid_transform_test.cc | 24 ------ math/test/rotation_matrix_test.cc | 4 - 12 files changed, 25 insertions(+), 270 deletions(-) diff --git a/bindings/pydrake/math_py.cc b/bindings/pydrake/math_py.cc index 1037cdddcfae..f853fc4575b2 100644 --- a/bindings/pydrake/math_py.cc +++ b/bindings/pydrake/math_py.cc @@ -104,17 +104,7 @@ void DoScalarDependentDefinitions(py::module m, T) { .def("IsExactlyIdentity", &Class::IsExactlyIdentity, cls_doc.IsExactlyIdentity.doc) .def("IsNearlyIdentity", &Class::IsNearlyIdentity, - py::arg("translation_tolerance"), cls_doc.IsNearlyIdentity.doc); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - cls // BR - .def("IsIdentityToEpsilon", - WrapDeprecated(cls_doc.IsIdentityToEpsilon.doc_deprecated, - &Class::IsIdentityToEpsilon), - py::arg("translation_tolerance"), - cls_doc.IsIdentityToEpsilon.doc_deprecated); -#pragma GCC diagnostic pop // pop -Wdeprecated-declarations - cls // BR + py::arg("translation_tolerance"), cls_doc.IsNearlyIdentity.doc) .def("IsNearlyEqualTo", &Class::IsNearlyEqualTo, py::arg("other"), py::arg("tolerance"), cls_doc.IsNearlyEqualTo.doc) .def("inverse", &Class::inverse, cls_doc.inverse.doc) @@ -208,17 +198,8 @@ void DoScalarDependentDefinitions(py::module m, T) { .def("IsNearlyIdentity", &Class::IsNearlyIdentity, py::arg("tolerance") = Class::get_internal_tolerance_for_orthonormality(), - cls_doc.IsNearlyIdentity.doc); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - cls // BR - .def("IsIdentityToInternalTolerance", - WrapDeprecated(cls_doc.IsIdentityToInternalTolerance.doc_deprecated, - &Class::IsIdentityToInternalTolerance), - cls_doc.IsIdentityToInternalTolerance.doc_deprecated); -#pragma GCC diagnostic pop // pop -Wdeprecated-declarations - cls // BR - // Does not return the quality_factor + cls_doc.IsNearlyIdentity.doc) + // Does not return the quality_factor .def_static( "ProjectToRotationMatrix", [](const Matrix3& M) { diff --git a/bindings/pydrake/multibody/math_py.cc b/bindings/pydrake/multibody/math_py.cc index 7b9fca61e5e4..d521a04e20ab 100644 --- a/bindings/pydrake/multibody/math_py.cc +++ b/bindings/pydrake/multibody/math_py.cc @@ -9,7 +9,6 @@ #include "drake/bindings/pydrake/common/value_pybind.h" #include "drake/bindings/pydrake/documentation_pybind.h" #include "drake/bindings/pydrake/pydrake_pybind.h" -#include "drake/common/drake_deprecated.h" #include "drake/multibody/math/spatial_algebra.h" namespace drake { @@ -106,54 +105,18 @@ void DoScalarDependentDefinitions(py::module m, T) { py::arg("w"), py::arg("v"), cls_doc.ctor.doc_2args) .def( py::init&>(), py::arg("V"), cls_doc.ctor.doc_1args) - .def("Shift", &Class::Shift, py::arg("offset"), cls_doc.Shift.doc); - constexpr char doc_Shift_deprecatedArgName[] = - "The keyword argument (kwarg) has been renamed from" - " Shift(p_BqBq_E) to" - " Shift(offset)." - " Deprecated kwarg will be unavailable after 2022-06-01."; - cls.def("Shift", WrapDeprecated(doc_Shift_deprecatedArgName, &Class::Shift), - py::arg("p_BpBq_E"), doc_Shift_deprecatedArgName) .def("ComposeWithMovingFrameVelocity", &Class::ComposeWithMovingFrameVelocity, py::arg("position_of_moving_frame"), py::arg("velocity_of_moving_frame"), - cls_doc.ComposeWithMovingFrameVelocity.doc); - constexpr char doc_ComposeWithMovingFrameVelocity_deprecatedArgName[] = - "The keyword arguments (kwargs) have been renamed from" - " ComposeWithMovingFrameVelocity(p_PoBo_E, V_PB_E) to" - " ComposeWithMovingFrameVelocity(position_of_moving_frame," - " velocity_of_moving_frame)." - " Deprecated kwargs will be unavailable after 2022-06-01."; - cls.def("ComposeWithMovingFrameVelocity", - WrapDeprecated(doc_ComposeWithMovingFrameVelocity_deprecatedArgName, - &Class::ComposeWithMovingFrameVelocity), - py::arg("p_PoBo_E"), py::arg("V_PB_E"), - doc_ComposeWithMovingFrameVelocity_deprecatedArgName); - cls.def("dot", - overload_cast_explicit&>(&Class::dot), - py::arg("force"), cls_doc.dot.doc_1args_force); - constexpr char doc_dot_deprecatedArgNameF_Bp_E[] = - "The keyword argument (kwarg) has been renamed from" - " dot(F_Bp_E) to" - " dot(force)." - " Deprecated kwarg will be unavailable after 2022-06-01."; - cls.def("dot", - WrapDeprecated(doc_dot_deprecatedArgNameF_Bp_E, - overload_cast_explicit&>(&Class::dot)), - py::arg("F_Bp_E"), doc_dot_deprecatedArgNameF_Bp_E); - cls.def("dot", - overload_cast_explicit&>(&Class::dot), - py::arg("momentum"), cls_doc.dot.doc_1args_momentum); - constexpr char doc_dot_deprecatedArgNameL_WBp_E[] = - "The keyword argument (kwarg) has been renamed from" - " dot(L_WBp_E) to" - " dot(momentum)." - " Deprecated kwarg will be unavailable after 2022-06-01."; - cls.def("dot", - WrapDeprecated(doc_dot_deprecatedArgNameL_WBp_E, - overload_cast_explicit&>(&Class::dot)), - py::arg("L_WBp_E"), doc_dot_deprecatedArgNameL_WBp_E); + cls_doc.ComposeWithMovingFrameVelocity.doc) + .def("Shift", &Class::Shift, py::arg("offset"), cls_doc.Shift.doc) + .def("dot", + overload_cast_explicit&>(&Class::dot), + py::arg("force"), cls_doc.dot.doc_1args_force) + .def("dot", + overload_cast_explicit&>(&Class::dot), + py::arg("momentum"), cls_doc.dot.doc_1args_momentum); cls.attr("__matmul__") = cls.attr("dot"); AddValueInstantiation(m); // Some ports need `Value>`. @@ -180,14 +143,6 @@ void DoScalarDependentDefinitions(py::module m, T) { cls.def("Shift", WrapDeprecated(doc_Shift_deprecatedArgName, &Class::Shift), py::arg("p_BpBq_E"), doc_Shift_deprecatedArgName) .def("dot", &Class::dot, py::arg("velocity"), cls_doc.dot.doc); - constexpr char doc_dotWithArgumentNameV_IBp_E_deprecated[] = - "The keyword argument (kwarg) has been renamed from" - " dot(V_IBp_E) to" - " dot(velocity)." - " Deprecated kwarg will be unavailable after 2022-06-01."; - cls.def("dot", - WrapDeprecated(doc_dotWithArgumentNameV_IBp_E_deprecated, &Class::dot), - py::arg("V_IBp_E"), doc_dotWithArgumentNameV_IBp_E_deprecated); cls.attr("__matmul__") = cls.attr("dot"); AddValueInstantiation(m); // Some ports need `Value>`. @@ -286,13 +241,6 @@ void DoScalarDependentDefinitions(py::module m, T) { cls.def("dot", overload_cast_explicit&>(&Class::dot), py::arg("velocity"), cls_doc.dot.doc); - constexpr char doc_dot_deprecatedArgName[] = - "The keyword argument (kwarg) has been renamed from" - " dot(V_IBp_E) to" - " dot(velocity)." - " Deprecated kwarg will be unavailable after 2022-06-01."; - cls.def("dot", WrapDeprecated(doc_dot_deprecatedArgName, &Class::dot), - py::arg("V_IBp_E"), doc_dot_deprecatedArgName); cls.attr("__matmul__") = cls.attr("dot"); AddValueInstantiation(m); // Some ports need `Value>`. diff --git a/bindings/pydrake/multibody/test/math_test.py b/bindings/pydrake/multibody/test/math_test.py index 010b71159dee..701ba20f90b0 100644 --- a/bindings/pydrake/multibody/test/math_test.py +++ b/bindings/pydrake/multibody/test/math_test.py @@ -126,18 +126,6 @@ def test_spatial_velocity(self, T): L = SpatialMomentum_[T].Zero() self.assertIsInstance(V.dot(momentum=L), T) self.assertIsInstance(V @ L, T) - # TODO(2022-06-01) Remove with completion of deprecation. - with catch_drake_warnings(expected_count=4): - self.assertIsInstance(V.Shift(p_BpBq_E=p), SpatialVelocity_[T]) - self.assertIsInstance( - V.ComposeWithMovingFrameVelocity(p_PoBo_E=p, V_PB_E=V), - SpatialVelocity_[T]) - F = SpatialForce_[T].Zero() - self.assertIsInstance(V.dot(F_Bp_E=F), T) - self.assertIsInstance(V @ F, T) - L = SpatialMomentum_[T].Zero() - self.assertIsInstance(V.dot(L_WBp_E=L), T) - self.assertIsInstance(V @ L, T) @numpy_compare.check_all_types def test_spatial_acceleration(self, T): @@ -195,9 +183,6 @@ def test_spatial_force(self, T): V = SpatialVelocity_[T].Zero() self.assertIsInstance(F.dot(velocity=V), T) self.assertIsInstance(F @ V, T) - # TODO(2022-06-01) Remove with completion of deprecation. - with catch_drake_warnings(expected_count=1): - self.assertIsInstance(F.dot(V_IBp_E=V), T) @numpy_compare.check_all_types def test_spatial_momentum(self, T): @@ -215,6 +200,3 @@ def test_spatial_momentum(self, T): self.assertIsInstance(dut.Shift(p_BpBq_E=p), SpatialMomentum_[T]) self.assertIsInstance(dut.dot(velocity=V), T) self.assertIsInstance(dut @ V, T) - # TODO(2022-06-01) Remove with completion of deprecation. - with catch_drake_warnings(expected_count=1): - self.assertIsInstance(dut.dot(V_IBp_E=V), T) diff --git a/bindings/pydrake/test/math_test.py b/bindings/pydrake/test/math_test.py index 156a3a785cab..6b1386aea01d 100644 --- a/bindings/pydrake/test/math_test.py +++ b/bindings/pydrake/test/math_test.py @@ -168,9 +168,6 @@ def check_equality(X_actual, X_expected_matrix): self.assertTrue(X.IsExactlyIdentity()) self.assertTrue(X.IsNearlyIdentity(translation_tolerance=0)) self.assertTrue(X.IsNearlyEqualTo(other=X, tolerance=0)) - # TODO(2022-06-01) Remove with completion of deprecation. - with catch_drake_warnings(expected_count=1): - self.assertTrue(X.IsIdentityToEpsilon(translation_tolerance=0)) # - Test shaping (#13885). v = np.array([0., 0., 0.]) vs = np.array([[1., 2., 3.], [4., 5., 6.]]).T @@ -306,9 +303,6 @@ def test_rotation_matrix(self, T): numpy_compare.assert_equal(R.IsExactlyIdentity(), True) numpy_compare.assert_equal(R.IsNearlyIdentity(0.0), True) numpy_compare.assert_equal(R.IsNearlyIdentity(tolerance=1E-15), True) - # TODO(2022-06-01) Remove with completion of deprecation. - with catch_drake_warnings(expected_count=1): - numpy_compare.assert_equal(R.IsIdentityToInternalTolerance(), True) # - Repr. z = repr(T(0.0)) i = repr(T(1.0)) diff --git a/common/test_utilities/expect_throws_message.h b/common/test_utilities/expect_throws_message.h index b2abe4977990..e9cf012a9e4a 100644 --- a/common/test_utilities/expect_throws_message.h +++ b/common/test_utilities/expect_throws_message.h @@ -56,37 +56,21 @@ whenever `DRAKE_ENABLE_ASSERTS` is defined, which Debug builds do by default. #else // DRAKE_DOXYGEN_CXX -namespace drake { -namespace internal { -template -constexpr void DrakeExpectThrowsWasUsedWithThreeArgs() {} -template<> -[[deprecated("DRAKE DEPRECATED: The middle argument (exception type) of " -"DRAKE_EXPECT_THROWS_MESSAGE is deprecated, as well as for all of the other " -"similar macros (DRAKE_EXPECT_THROWS_MESSAGE_IF_ARMED, " -"DRAKE_ASSERT_THROWS_MESSAGE, DRAKE_ASSERT_THROWS_MESSAGE_IF_ARMED). " -"Remove the middle argument from the call site. " -"The deprecated code will be removed from Drake on or after 2022-06-01.")]] -constexpr void DrakeExpectThrowsWasUsedWithThreeArgs() {} -} // namespace internal -} // namespace drake - #define DRAKE_EXPECT_THROWS_MESSAGE_HELPER( \ - expression, exception, deprecated, regexp, must_throw, fatal_failure) \ + expression, regexp, must_throw, fatal_failure) \ do { \ try { \ expression; \ if (must_throw) { \ - std::string message = "\tExpected: " #expression " throws an exception " \ - "of type " #exception ".\n Actual: it throws " \ - "nothing"; \ + std::string message = "\tExpected: " #expression " throws an exception.\n" \ + " Actual: it throws nothing"; \ if (fatal_failure) { \ GTEST_FATAL_FAILURE_(message.c_str()); \ } else { \ GTEST_NONFATAL_FAILURE_(message.c_str());\ } \ } \ -} catch (const exception& err) { \ +} catch (const std::exception& err) { \ auto matcher = [](const char* s, const std::string& re) { \ return std::regex_match(s, std::regex(re)); }; \ if (fatal_failure) { \ @@ -95,74 +79,34 @@ try { \ EXPECT_PRED2(matcher, err.what(), regexp); \ } \ } catch (...) { \ - std::string message = "\tExpected: " #expression " throws an exception of " \ - "type " #exception ".\n Actual: it throws a different type."; \ + std::string message = "\tExpected: " #expression " throws an exception.\n" \ + " Actual: it throws a non-exception object."; \ if (fatal_failure) { \ GTEST_FATAL_FAILURE_(message.c_str()); \ } else { \ GTEST_NONFATAL_FAILURE_(message.c_str()); \ } \ } \ -::drake::internal::DrakeExpectThrowsWasUsedWithThreeArgs(); \ } while (0) -#define DRAKE_EXPECT_THROWS_MESSAGE_3(expression, exception, regexp) \ - DRAKE_EXPECT_THROWS_MESSAGE_HELPER( \ - expression, exception, true /*deprecated*/, regexp, \ - true /*must_throw*/, false /*non-fatal*/) - -#define DRAKE_ASSERT_THROWS_MESSAGE_3(expression, exception, regexp) \ - DRAKE_EXPECT_THROWS_MESSAGE_HELPER( \ - expression, exception, true /*deprecated*/, regexp, \ - true /*must_throw*/, true /*fatal*/) - -#define DRAKE_EXPECT_THROWS_MESSAGE_IF_ARMED_3(expression, exception, regexp) \ +#define DRAKE_EXPECT_THROWS_MESSAGE(expression, regexp) \ DRAKE_EXPECT_THROWS_MESSAGE_HELPER( \ - expression, exception, true /*deprecated*/, regexp, \ - ::drake::kDrakeAssertIsArmed /*must_throw*/, false /*non-fatal*/) - -#define DRAKE_ASSERT_THROWS_MESSAGE_IF_ARMED_3(expression, exception, regexp) \ - DRAKE_EXPECT_THROWS_MESSAGE_HELPER( \ - expression, exception, true /*deprecated*/, regexp, \ - ::drake::kDrakeAssertIsArmed /*must_throw*/, true /*fatal*/) - -#define DRAKE_EXPECT_THROWS_MESSAGE_2(expression, regexp) \ - DRAKE_EXPECT_THROWS_MESSAGE_HELPER( \ - expression, std::exception, false /*deprecated*/, regexp, \ + expression, regexp, \ true /*must_throw*/, false /*non-fatal*/) -#define DRAKE_ASSERT_THROWS_MESSAGE_2(expression, regexp) \ +#define DRAKE_ASSERT_THROWS_MESSAGE(expression, regexp) \ DRAKE_EXPECT_THROWS_MESSAGE_HELPER( \ - expression, std::exception, false /*deprecated*/, regexp, \ + expression, regexp, \ true /*must_throw*/, true /*fatal*/) -#define DRAKE_EXPECT_THROWS_MESSAGE_IF_ARMED_2(expression, regexp) \ +#define DRAKE_EXPECT_THROWS_MESSAGE_IF_ARMED(expression, regexp) \ DRAKE_EXPECT_THROWS_MESSAGE_HELPER( \ - expression, std::exception, false /*deprecated*/, regexp, \ + expression, regexp, \ ::drake::kDrakeAssertIsArmed /*must_throw*/, false /*non-fatal*/) -#define DRAKE_ASSERT_THROWS_MESSAGE_IF_ARMED_2(expression, regexp) \ +#define DRAKE_ASSERT_THROWS_MESSAGE_IF_ARMED(expression, regexp) \ DRAKE_EXPECT_THROWS_MESSAGE_HELPER( \ - expression, std::exception, false /*deprecated*/, regexp, \ + expression, regexp, \ ::drake::kDrakeAssertIsArmed /*must_throw*/, true /*fatal*/) -// Now overload the macro based on 2 vs 3 arguments. -#define DRAKE_OVERLOAD_THROWS_MESSAGE_MACRO_ARITY(_1, _2, _3, NAME, ...) NAME -#define DRAKE_EXPECT_THROWS_MESSAGE(...) \ - DRAKE_OVERLOAD_THROWS_MESSAGE_MACRO_ARITY(__VA_ARGS__, \ - DRAKE_EXPECT_THROWS_MESSAGE_3, \ - DRAKE_EXPECT_THROWS_MESSAGE_2)(__VA_ARGS__) -#define DRAKE_ASSERT_THROWS_MESSAGE(...) \ - DRAKE_OVERLOAD_THROWS_MESSAGE_MACRO_ARITY(__VA_ARGS__, \ - DRAKE_ASSERT_THROWS_MESSAGE_3, \ - DRAKE_ASSERT_THROWS_MESSAGE_2)(__VA_ARGS__) -#define DRAKE_EXPECT_THROWS_MESSAGE_IF_ARMED(...) \ - DRAKE_OVERLOAD_THROWS_MESSAGE_MACRO_ARITY(__VA_ARGS__, \ - DRAKE_EXPECT_THROWS_MESSAGE_IF_ARMED_3, \ - DRAKE_EXPECT_THROWS_MESSAGE_IF_ARMED_2)(__VA_ARGS__) -#define DRAKE_ASSERT_THROWS_MESSAGE_IF_ARMED(...) \ - DRAKE_OVERLOAD_THROWS_MESSAGE_MACRO_ARITY(__VA_ARGS__, \ - DRAKE_ASSERT_THROWS_MESSAGE_IF_ARMED_3, \ - DRAKE_ASSERT_THROWS_MESSAGE_IF_ARMED_2)(__VA_ARGS__) - #endif // DRAKE_DOXYGEN_CXX diff --git a/manipulation/kinova_jaco/jaco_command_receiver.cc b/manipulation/kinova_jaco/jaco_command_receiver.cc index 371b2c8b4f94..4e1102f21d4a 100644 --- a/manipulation/kinova_jaco/jaco_command_receiver.cc +++ b/manipulation/kinova_jaco/jaco_command_receiver.cc @@ -90,17 +90,6 @@ void JacoCommandReceiver::LatchInitialPosition( LatchInitialPosition(*context, &context->get_mutable_discrete_state()); } -void JacoCommandReceiver::set_initial_position( - Context* context, const Eigen::Ref& q) const { - DRAKE_THROW_UNLESS(q.size() == num_joints_ + num_fingers_); - - DiscreteValues* values = &context->get_mutable_discrete_state(); - const auto& bool_index = latched_position_measured_is_set_; - const auto& value_index = latched_position_measured_; - values->get_mutable_value(bool_index)[0] = 1.0; - values->get_mutable_vector(value_index).SetFromVector(q); -} - // TODO(jwnimmer-tri) This is quite a cumbersome syntax to use for declaring a // "now" event. We should try to consolidate it with other similar uses within // the source tree. Relates to #11403 somewhat. diff --git a/manipulation/kinova_jaco/jaco_command_receiver.h b/manipulation/kinova_jaco/jaco_command_receiver.h index 3542937133ce..07ae2bbf3b39 100644 --- a/manipulation/kinova_jaco/jaco_command_receiver.h +++ b/manipulation/kinova_jaco/jaco_command_receiver.h @@ -5,7 +5,6 @@ #include #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/eigen_types.h" #include "drake/lcmt_jaco_command.hpp" #include "drake/manipulation/kinova_jaco/jaco_constants.h" @@ -80,24 +79,6 @@ class JacoCommandReceiver : public systems::LeafSystem { } //@} - DRAKE_DEPRECATED("2022-06-01", - "To provide position commands prior to receiving the first message, " - "connect the position_measured ports instead of setting this " - "parameter") - void set_initial_position( - systems::Context* context, - const Eigen::Ref& q) const; - - DRAKE_DEPRECATED("2022-06-01", "Use get_message_input_port() instead.") - const systems::InputPort& get_input_port() const { - return get_message_input_port(); - } - - DRAKE_DEPRECATED("2022-08-01", "Use the other output ports instead.") - const systems::OutputPort& get_output_port() const { - return *state_output_; - } - private: Eigen::VectorXd input_state(const systems::Context&) const; void CalcInput(const systems::Context&, lcmt_jaco_command*) const; diff --git a/manipulation/kinova_jaco/test/jaco_command_receiver_test.cc b/manipulation/kinova_jaco/test/jaco_command_receiver_test.cc index 479e119f7b0e..4e79e13a2702 100644 --- a/manipulation/kinova_jaco/test/jaco_command_receiver_test.cc +++ b/manipulation/kinova_jaco/test/jaco_command_receiver_test.cc @@ -14,9 +14,6 @@ using Eigen::VectorXd; constexpr int N = kJacoDefaultArmNumJoints; constexpr int N_F = kJacoDefaultArmNumFingers; -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - class JacoCommandReceiverTestBase : public testing::Test { public: JacoCommandReceiverTestBase(int num_joints, int num_fingers) @@ -38,10 +35,6 @@ class JacoCommandReceiverTestBase : public testing::Test { template get_mutable_value() = message; } - VectorXd state() const { - return dut_.get_output_port().Eval(context_); - } - VectorXd position() const { return dut_.get_commanded_position_output_port().Eval(context_); } @@ -71,23 +64,6 @@ class JacoCommandReceiverNoFingersTest : public JacoCommandReceiverTestBase { kJacoDefaultArmNumJoints, 0) {} }; -TEST_F(JacoCommandReceiverTest, DeprecatedInitialPositionTest) { - constexpr int total_dof = - kJacoDefaultArmNumJoints + kJacoDefaultArmNumFingers; - - // Check that the commanded pose starts out at zero. - EXPECT_TRUE(CompareMatrices(state(), VectorXd::Zero(total_dof * 2))); - - // Check that we can set a different initial position. - const VectorXd q0 = VectorXd::LinSpaced(total_dof, 0.1, 0.2); - dut_.set_initial_position(&context_, q0); - EXPECT_TRUE(CompareMatrices(state().head(total_dof), q0)); - EXPECT_TRUE(CompareMatrices(state().tail(total_dof), - VectorXd::Zero(total_dof))); -} - -#pragma GCC diagnostic pop - TEST_F(JacoCommandReceiverTest, AcceptanceTestWithoutMeasuredPositionInput) { // When no message has been received and *no* position measurement is // connected, the command is all zeros. diff --git a/math/rigid_transform.h b/math/rigid_transform.h index 6184f9682c6e..a1b943f42e64 100644 --- a/math/rigid_transform.h +++ b/math/rigid_transform.h @@ -8,7 +8,6 @@ #include "drake/common/drake_assert.h" #include "drake/common/drake_bool.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/eigen_types.h" #include "drake/common/never_destroyed.h" #include "drake/math/rotation_matrix.h" @@ -416,11 +415,6 @@ class RigidTransform { rotation().IsNearlyIdentity(); } - DRAKE_DEPRECATED("2022-06-01", "Use RigidTransform::IsNearlyIdentity()") - boolean IsIdentityToEpsilon(double translation_tolerance) const { - return IsNearlyIdentity(translation_tolerance); - } - /// Returns X_BA = X_AB⁻¹, the inverse of `this` %RigidTransform. /// @note The inverse of %RigidTransform X_AB is X_BA, which contains the /// rotation matrix R_BA = R_AB⁻¹ = R_ABᵀ and the position vector `p_BoAo_B_` diff --git a/math/rotation_matrix.h b/math/rotation_matrix.h index e46e2c72c311..c47a4b5bf8ed 100644 --- a/math/rotation_matrix.h +++ b/math/rotation_matrix.h @@ -12,7 +12,6 @@ #include "drake/common/drake_assert.h" #include "drake/common/drake_bool.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/drake_throw.h" #include "drake/common/eigen_types.h" #include "drake/common/never_destroyed.h" @@ -571,11 +570,6 @@ class RotationMatrix { return IsNearlyEqualTo(matrix(), Matrix3::Identity(), tolerance); } - DRAKE_DEPRECATED("2022-06-01", "Use RotationMatrix::IsNearlyIdentity()") - boolean IsIdentityToInternalTolerance() const { - return IsNearlyIdentity(); - } - /// Compares each element of `this` to the corresponding element of `other` /// to check if they are the same to within a specified `tolerance`. /// @param[in] other %RotationMatrix to compare to `this`. diff --git a/math/test/rigid_transform_test.cc b/math/test/rigid_transform_test.cc index 3a3acd4737db..06fdb9ca9e1f 100644 --- a/math/test/rigid_transform_test.cc +++ b/math/test/rigid_transform_test.cc @@ -381,10 +381,6 @@ GTEST_TEST(RigidTransform, IsIdentity) { RigidTransform X1; EXPECT_TRUE(X1.IsExactlyIdentity()); EXPECT_TRUE(X1.IsNearlyIdentity(0.0)); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - EXPECT_TRUE(X1.IsIdentityToEpsilon(0.0)); -#pragma GCC diagnostic pop EXPECT_TRUE(X1.rotation().IsExactlyIdentity()); EXPECT_TRUE((X1.translation().array() == 0).all()); @@ -399,11 +395,6 @@ GTEST_TEST(RigidTransform, IsIdentity) { EXPECT_FALSE(X2.IsExactlyIdentity()); EXPECT_FALSE(X2.IsNearlyIdentity(3.99)); EXPECT_TRUE(X2.IsNearlyIdentity(4.01)); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - EXPECT_FALSE(X2.IsIdentityToEpsilon(3.99)); - EXPECT_TRUE(X2.IsIdentityToEpsilon(4.01)); -#pragma GCC diagnostic pop // Change position vector to zero vector. const Vector3d zero_vector(0, 0, 0); @@ -552,11 +543,6 @@ GTEST_TEST(RigidTransform, SymbolicRigidTransformSimpleTests) { // Test IsNearlyIdentity() nominally works with Expression. test_Bool = X.IsNearlyIdentity(kEpsilon); EXPECT_TRUE(test_Bool); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - test_Bool = X.IsIdentityToEpsilon(kEpsilon); - EXPECT_TRUE(test_Bool); -#pragma GCC diagnostic pop // Test IsExactlyEqualTo() nominally works for Expression. const RigidTransform& X_built_in_identity = @@ -579,11 +565,6 @@ GTEST_TEST(RigidTransform, SymbolicRigidTransformSimpleTests) { // Test IsNearlyIdentity() works with Expression. test_Bool = X.IsNearlyIdentity(kEpsilon); EXPECT_FALSE(test_Bool); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - test_Bool = X.IsIdentityToEpsilon(kEpsilon); - EXPECT_FALSE(test_Bool); -#pragma GCC diagnostic pop // Test IsExactlyEqualTo() works for Expression. test_Bool = X.IsExactlyEqualTo(X_built_in_identity); @@ -612,11 +593,6 @@ GTEST_TEST(RigidTransform, SymbolicRigidTransformThrowsExceptions) { test_Bool = X_symbolic.IsNearlyIdentity(kEpsilon); EXPECT_THROW(test_Bool.Evaluate(), std::exception); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - test_Bool = X_symbolic.IsIdentityToEpsilon(kEpsilon); - EXPECT_THROW(test_Bool.Evaluate(), std::exception); -#pragma GCC diagnostic pop const RigidTransform& X_identity = RigidTransform::Identity(); diff --git a/math/test/rotation_matrix_test.cc b/math/test/rotation_matrix_test.cc index 2230a7eac0e1..3e2224c37665 100644 --- a/math/test/rotation_matrix_test.cc +++ b/math/test/rotation_matrix_test.cc @@ -84,10 +84,6 @@ GTEST_TEST(RotationMatrix, IsIdentity) { RotationMatrix R; // Default constructor is identity matrix. EXPECT_TRUE(R.IsExactlyIdentity()); EXPECT_TRUE(R.IsNearlyIdentity(0.0)); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - EXPECT_TRUE(R.IsIdentityToInternalTolerance()); -#pragma GCC diagnostic pop // Test non-identity matrix. const double theta = 256 * kEpsilon;