Skip to content

Commit

Permalink
Remove deprecated code 2022-06 (RobotLocomotion#17296)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Jun 1, 2022
1 parent e8193f8 commit ad8b7e5
Show file tree
Hide file tree
Showing 12 changed files with 25 additions and 270 deletions.
25 changes: 3 additions & 22 deletions bindings/pydrake/math_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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<T>& M) {
Expand Down
68 changes: 8 additions & 60 deletions bindings/pydrake/multibody/math_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down Expand Up @@ -106,54 +105,18 @@ void DoScalarDependentDefinitions(py::module m, T) {
py::arg("w"), py::arg("v"), cls_doc.ctor.doc_2args)
.def(
py::init<const Vector6<T>&>(), 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<T, const SpatialForce<T>&>(&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<T, const SpatialForce<T>&>(&Class::dot)),
py::arg("F_Bp_E"), doc_dot_deprecatedArgNameF_Bp_E);
cls.def("dot",
overload_cast_explicit<T, const SpatialMomentum<T>&>(&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<T, const SpatialMomentum<T>&>(&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<T, const SpatialForce<T>&>(&Class::dot),
py::arg("force"), cls_doc.dot.doc_1args_force)
.def("dot",
overload_cast_explicit<T, const SpatialMomentum<T>&>(&Class::dot),
py::arg("momentum"), cls_doc.dot.doc_1args_momentum);
cls.attr("__matmul__") = cls.attr("dot");
AddValueInstantiation<Class>(m);
// Some ports need `Value<std::vector<Class>>`.
Expand All @@ -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<Class>(m);
// Some ports need `Value<std::vector<Class>>`.
Expand Down Expand Up @@ -286,13 +241,6 @@ void DoScalarDependentDefinitions(py::module m, T) {
cls.def("dot",
overload_cast_explicit<T, const SpatialVelocity<T>&>(&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<Class>(m);
// Some ports need `Value<std::vector<Class>>`.
Expand Down
18 changes: 0 additions & 18 deletions bindings/pydrake/multibody/test/math_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -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):
Expand Down Expand Up @@ -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):
Expand All @@ -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)
6 changes: 0 additions & 6 deletions bindings/pydrake/test/math_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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))
Expand Down
84 changes: 14 additions & 70 deletions common/test_utilities/expect_throws_message.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <bool>
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<true>() {}
} // 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) { \
Expand All @@ -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<deprecated>(); \
} 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
11 changes: 0 additions & 11 deletions manipulation/kinova_jaco/jaco_command_receiver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -90,17 +90,6 @@ void JacoCommandReceiver::LatchInitialPosition(
LatchInitialPosition(*context, &context->get_mutable_discrete_state());
}

void JacoCommandReceiver::set_initial_position(
Context<double>* context, const Eigen::Ref<const VectorXd>& q) const {
DRAKE_THROW_UNLESS(q.size() == num_joints_ + num_fingers_);

DiscreteValues<double>* 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.
Expand Down
19 changes: 0 additions & 19 deletions manipulation/kinova_jaco/jaco_command_receiver.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
#include <vector>

#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"
Expand Down Expand Up @@ -80,24 +79,6 @@ class JacoCommandReceiver : public systems::LeafSystem<double> {
}
//@}

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<double>* context,
const Eigen::Ref<const Eigen::VectorXd>& q) const;

DRAKE_DEPRECATED("2022-06-01", "Use get_message_input_port() instead.")
const systems::InputPort<double>& get_input_port() const {
return get_message_input_port();
}

DRAKE_DEPRECATED("2022-08-01", "Use the other output ports instead.")
const systems::OutputPort<double>& get_output_port() const {
return *state_output_;
}

private:
Eigen::VectorXd input_state(const systems::Context<double>&) const;
void CalcInput(const systems::Context<double>&, lcmt_jaco_command*) const;
Expand Down
Loading

0 comments on commit ad8b7e5

Please sign in to comment.