diff --git a/bindings/pydrake/math_py.cc b/bindings/pydrake/math_py.cc index 919b29b1a5cd..6ed73d6667d5 100644 --- a/bindings/pydrake/math_py.cc +++ b/bindings/pydrake/math_py.cc @@ -40,7 +40,7 @@ void DoScalarDependentDefinitions(py::module m, T) { const char* doc_iso3_deprecation = "DO NOT USE!. We only offer this API for backwards compatibility with " "Isometry3 and it will be deprecated soon with the resolution of " - "#9865. This will be removed on or around 2019-07-01."; + "#9865. This will be removed on or around 2019-08-01."; constexpr auto& doc = pydrake_doc.drake.math; { @@ -95,13 +95,6 @@ void DoScalarDependentDefinitions(py::module m, T) { return *self * p_BoQ_B; }, py::arg("p_BoQ_B"), cls_doc.operator_mul.doc_1args_p_BoQ_B) - .def("multiply", - [doc_iso3_deprecation]( - const RigidTransform* self, const Isometry3& other) { - WarnDeprecated(doc_iso3_deprecation); - return *self * RigidTransform(other); - }, - py::arg("other"), doc_iso3_deprecation) .def("matrix", &RigidTransform::matrix, doc_iso3_deprecation) .def("linear", &RigidTransform::linear, py_reference_internal, doc_iso3_deprecation); diff --git a/bindings/pydrake/multibody/plant_py.cc b/bindings/pydrake/multibody/plant_py.cc index e360463f4ebb..c76057a9ece8 100644 --- a/bindings/pydrake/multibody/plant_py.cc +++ b/bindings/pydrake/multibody/plant_py.cc @@ -582,9 +582,7 @@ void DoScalarDependentDefinitions(py::module m, T) { const CoulombFriction&>( &Class::RegisterCollisionGeometry), py::arg("body"), py::arg("X_BG"), py::arg("shape"), py::arg("name"), - py::arg("coulomb_friction"), - cls_doc.RegisterCollisionGeometry - .doc_5args_body_X_BG_shape_name_coulomb_friction) + py::arg("coulomb_friction"), cls_doc.RegisterCollisionGeometry.doc) .def("RegisterCollisionGeometry", [](Class* self, const Body& body, const RigidTransform& X_BG, @@ -602,26 +600,7 @@ void DoScalarDependentDefinitions(py::module m, T) { }, py::arg("body"), py::arg("X_BG"), py::arg("shape"), py::arg("name"), py::arg("coulomb_friction"), py::arg("scene_graph"), - (std::string("(Deprecated.) ") + - cls_doc.RegisterCollisionGeometry - .doc_5args_body_X_BG_shape_name_coulomb_friction) - .c_str()) - .def("RegisterCollisionGeometry", - [](Class* self, const Body& body, const Isometry3& X_BG, - const geometry::Shape& shape, const std::string& name, - const CoulombFriction& coulomb_friction, - geometry::SceneGraph* scene_graph) { - WarnDeprecated(doc_iso3_deprecation); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - return self->RegisterCollisionGeometry(body, - RigidTransform(X_BG), shape, name, coulomb_friction, - scene_graph); -#pragma GCC diagnostic pop - }, - py::arg("body"), py::arg("X_BG"), py::arg("shape"), py::arg("name"), - py::arg("coulomb_friction"), py::arg("scene_graph") = nullptr, - doc_iso3_deprecation) + cls_doc.RegisterCollisionGeometry.doc_deprecated) .def("get_source_id", &Class::get_source_id, cls_doc.get_source_id.doc) .def("get_geometry_query_input_port", &Class::get_geometry_query_input_port, py_reference_internal, diff --git a/bindings/pydrake/systems/framework_py_semantics.cc b/bindings/pydrake/systems/framework_py_semantics.cc index 1d45dab81d59..9937bf6c58cc 100644 --- a/bindings/pydrake/systems/framework_py_semantics.cc +++ b/bindings/pydrake/systems/framework_py_semantics.cc @@ -150,17 +150,6 @@ void DefineFrameworkPySemantics(py::module m) { // Bindings for Context methods inherited from ContextBase. .def("num_input_ports", &Context::num_input_ports, doc.ContextBase.num_input_ports.doc) - .def("get_num_input_ports", - [](const Context* self) { - WarnDeprecated( - "Use num_input_ports() instead. Will be removed on or after " - "2019-07-01."); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - self->get_num_input_ports(); -#pragma GCC diagnostic pop - }, - doc.ContextBase.get_num_input_ports.doc_deprecated) .def("num_output_ports", &Context::num_output_ports, doc.ContextBase.num_output_ports.doc) // TODO(russt): Add remaining methods from ContextBase here. @@ -227,28 +216,6 @@ void DefineFrameworkPySemantics(py::module m) { .def("get_abstract_parameter", &Context::get_abstract_parameter, py::arg("index"), py_reference_internal, doc.Context.get_numeric_parameter.doc) - .def("get_num_discrete_state_groups", - [](const Context* self) { - WarnDeprecated( - "Use num_discrete_state_groups() instead. Will be removed " - "on or after 2019-07-01."); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - self->get_num_discrete_state_groups(); -#pragma GCC diagnostic pop - }, - doc.Context.get_num_discrete_state_groups.doc_deprecated) - .def("get_num_abstract_states", - [](const Context* self) { - WarnDeprecated( - "Use num_abstract_states() instead. Will be removed on or " - "after 2019-07-01."); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - self->get_num_abstract_states(); -#pragma GCC diagnostic pop - }, - doc.Context.get_num_abstract_states.doc_deprecated) // Bindings for the Context methods in the Doxygen group titled // "Methods for changing locally-stored values", placed in the same // order as the header file. @@ -298,28 +265,6 @@ void DefineFrameworkPySemantics(py::module m) { doc.Context.FixInputPort.doc_2args_index_data) .def("SetAccuracy", &Context::SetAccuracy, py::arg("accuracy"), doc.Context.SetAccuracy.doc) - .def("set_time", - [](Context* self, const T& time) { - WarnDeprecated( - "Use SetTime() instead. Will be removed on or after " - "2019-07-01."); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - self->set_time(time); -#pragma GCC diagnostic pop - }, - doc.Context.set_time.doc_deprecated) - .def("set_accuracy", - [](Context* self, const optional& accuracy) { - WarnDeprecated( - "Use SetAccuracy() instead. Will be removed on or after " - "2019-07-01."); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - self->set_accuracy(accuracy); -#pragma GCC diagnostic pop - }, - doc.Context.set_accuracy.doc_deprecated) // Bindings for the Context methods in the Doxygen group titled // "Dangerous methods for changing locally-stored values", placed in the // same order as the header file. @@ -498,17 +443,6 @@ void DefineFrameworkPySemantics(py::module m) { system_output .def("num_ports", &SystemOutput::num_ports, doc.SystemOutput.num_ports.doc) - .def("get_num_ports", - [](const SystemOutput* self) { - WarnDeprecated( - "Use num_ports() instead. Will be removed on or after " - "2019-07-01."); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - self->get_num_ports(); -#pragma GCC diagnostic pop - }, - doc.SystemOutput.get_num_ports.doc_deprecated) .def("get_data", &SystemOutput::get_data, py_reference_internal, doc.SystemOutput.get_data.doc) .def("get_vector_data", &SystemOutput::get_vector_data, diff --git a/bindings/pydrake/systems/framework_py_systems.cc b/bindings/pydrake/systems/framework_py_systems.cc index 0dd7f18d4b05..b3375f23b3ef 100644 --- a/bindings/pydrake/systems/framework_py_systems.cc +++ b/bindings/pydrake/systems/framework_py_systems.cc @@ -34,13 +34,13 @@ namespace { // TODO(eric.cousineau): Remove `*DeprecatedProtectedAlias*` cruft and // replace `PYDRAKE_TRY_PROTECTED_OVERLOAD` with `PYBIND11_OVERLOAD` once -// deprecated methods are removed (on or around 2019-07-01). +// deprecated methods are removed (on or around 2019-08-01). // Generates deprecation message pursuant to #9651. std::string DeprecatedProtectedAliasMessage( std::string name, std::string verb) { return fmt::format( - "'_{0}' is deprecated and will be removed on or around 2019-07-01. " + "'_{0}' is deprecated and will be removed on or around 2019-08-01. " "Please {1} '{0}' instead.", name, verb); } @@ -358,17 +358,6 @@ struct Impl { // Topology. .def("num_input_ports", &System::num_input_ports, doc.SystemBase.num_input_ports.doc) - .def("get_num_input_ports", - [](const System* self) { - WarnDeprecated( - "Use num_input_ports() instead. Will be removed on or after " - "2019-07-01."); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - self->get_num_input_ports(); -#pragma GCC diagnostic pop - }, - doc.SystemBase.get_num_input_ports.doc_deprecated) .def("get_input_port", &System::get_input_port, py_reference_internal, py::arg("port_index"), doc.System.get_input_port.doc) @@ -376,17 +365,6 @@ struct Impl { py::arg("port_name"), doc.System.GetInputPort.doc) .def("num_output_ports", &System::num_output_ports, doc.SystemBase.num_output_ports.doc) - .def("get_num_output_ports", - [](const System* self) { - WarnDeprecated( - "Use num_output_ports() instead. Will be removed on or " - "after 2019-07-01."); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - self->get_num_output_ports(); -#pragma GCC diagnostic pop - }, - doc.SystemBase.get_num_output_ports.doc_deprecated) .def("get_output_port", &System::get_output_port, py_reference_internal, py::arg("port_index"), doc.System.get_output_port.doc) diff --git a/bindings/pydrake/systems/framework_py_values.cc b/bindings/pydrake/systems/framework_py_values.cc index d2b0e48f788e..027be2d83044 100644 --- a/bindings/pydrake/systems/framework_py_values.cc +++ b/bindings/pydrake/systems/framework_py_values.cc @@ -141,11 +141,11 @@ void DefineFrameworkPyValues(py::module m) { .def("SetFrom", &AbstractValue::SetFrom, pydrake_doc.drake.AbstractValue.SetFrom.doc) .def("get_value", abstract_stub("get_value"), - pydrake_doc.drake.AbstractValue.GetValue.doc) + pydrake_doc.drake.AbstractValue.get_value.doc) .def("get_mutable_value", abstract_stub("get_mutable_value"), - pydrake_doc.drake.AbstractValue.GetMutableValue.doc) + pydrake_doc.drake.AbstractValue.get_mutable_value.doc) .def("set_value", abstract_stub("set_value"), - pydrake_doc.drake.AbstractValue.SetValue.doc); + pydrake_doc.drake.AbstractValue.set_value.doc); // Add value instantiations for nominal data types. Types that require more // pizazz are listed below. diff --git a/bindings/pydrake/systems/test/custom_test.py b/bindings/pydrake/systems/test/custom_test.py index ffcb3580ec66..5d03891992da 100644 --- a/bindings/pydrake/systems/test/custom_test.py +++ b/bindings/pydrake/systems/test/custom_test.py @@ -134,20 +134,14 @@ def _create_adder_system(self): def _fix_adder_inputs(self, context): self.assertEqual(context.num_input_ports(), 2) - with catch_drake_warnings(expected_count=1): - context.get_num_input_ports() context.FixInputPort(0, BasicVector([1, 2, 3])) context.FixInputPort(1, BasicVector([4, 5, 6])) def test_diagram_adder(self): system = CustomDiagram(2, 3) self.assertEqual(system.num_input_ports(), 2) - with catch_drake_warnings(expected_count=1): - system.get_num_input_ports() self.assertEqual(system.get_input_port(0).size(), 3) self.assertEqual(system.num_output_ports(), 1) - with catch_drake_warnings(expected_count=1): - system.get_num_output_ports() self.assertEqual(system.get_output_port(0).size(), 3) def test_adder_execution(self): @@ -511,8 +505,6 @@ def __init__(self): context.get_continuous_state_vector() is context.get_mutable_continuous_state_vector()) self.assertEqual(context.num_discrete_state_groups(), 1) - with catch_drake_warnings(expected_count=1): - context.get_num_discrete_state_groups() self.assertTrue( context.get_discrete_state_vector() is context.get_mutable_discrete_state_vector()) @@ -529,8 +521,6 @@ def __init__(self): context.get_mutable_discrete_state(0) is context.get_mutable_discrete_state().get_vector(0)) self.assertEqual(context.num_abstract_states(), 1) - with catch_drake_warnings(expected_count=1): - context.get_num_abstract_states() self.assertTrue( context.get_abstract_state() is context.get_mutable_abstract_state()) @@ -669,8 +659,6 @@ def DoCalcAbstractOutput(self, context, y_data): context.FixInputPort(0, AbstractValue.Make(expected_input_value)) output = system.AllocateOutput() self.assertEqual(output.num_ports(), 1) - with catch_drake_warnings(expected_count=1): - output.get_num_ports() system.CalcOutput(context, output) value = output.get_data(0) self.assertEqual(value.get_value(), expected_output_value) diff --git a/bindings/pydrake/systems/test/general_test.py b/bindings/pydrake/systems/test/general_test.py index 839453dbcec3..bb6f9cd0b0b8 100644 --- a/bindings/pydrake/systems/test/general_test.py +++ b/bindings/pydrake/systems/test/general_test.py @@ -334,12 +334,8 @@ def check_output(context): # Create simulator specifying context. context = system.CreateDefaultContext() - with catch_drake_warnings(expected_count=1): - context.set_time(0.) context.SetTime(0.) - with catch_drake_warnings(expected_count=1): - context.set_accuracy(1e-4) context.SetAccuracy(1e-4) self.assertEqual(context.get_accuracy(), 1e-4) diff --git a/common/test/value_test.cc b/common/test/value_test.cc index 7fb3b539e813..91ea7c722fc5 100644 --- a/common/test/value_test.cc +++ b/common/test/value_test.cc @@ -197,18 +197,6 @@ GTEST_TEST(ValueTest, MaybeGetValue) { ASSERT_NE(string_value->maybe_get_value(), nullptr); EXPECT_EQ(*string_value->maybe_get_value(), "hello"); - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - EXPECT_EQ(double_value->MaybeGetValue(), nullptr); - EXPECT_EQ(string_value->MaybeGetValue(), nullptr); - - ASSERT_NE(double_value->MaybeGetValue(), nullptr); - EXPECT_EQ(*double_value->MaybeGetValue(), 3.); - - ASSERT_NE(string_value->MaybeGetValue(), nullptr); - EXPECT_EQ(*string_value->MaybeGetValue(), "hello"); -#pragma GCC diagnostic pop } TYPED_TEST(TypedValueTest, Access) { @@ -219,14 +207,6 @@ TYPED_TEST(TypedValueTest, Access) { EXPECT_EQ(3, erased.get_value()); ASSERT_NE(erased.maybe_get_value(), nullptr); EXPECT_EQ(3, *erased.maybe_get_value()); - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - EXPECT_EQ(3, erased.GetValue()); - EXPECT_EQ(3, erased.GetValueOrThrow()); - ASSERT_NE(erased.MaybeGetValue(), nullptr); - EXPECT_EQ(3, *erased.MaybeGetValue()); -#pragma GCC diagnostic pop } TYPED_TEST(TypedValueTest, Clone) { @@ -248,18 +228,6 @@ TYPED_TEST(TypedValueTest, Mutation) { EXPECT_EQ(5, erased.get_value()); erased.SetFrom(Value(6)); EXPECT_EQ(6, erased.get_value()); - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - erased.SetValue(T{7}); - EXPECT_EQ(7, erased.GetValue()); - erased.SetValueOrThrow(T{8}); - EXPECT_EQ(8, erased.GetValue()); - erased.SetFrom(Value(9)); - EXPECT_EQ(9, erased.GetValue()); - erased.SetFromOrThrow(Value(10)); - EXPECT_EQ(10, erased.GetValue()); -#pragma GCC diagnostic pop } TYPED_TEST(TypedValueTest, BadCast) { @@ -271,14 +239,6 @@ TYPED_TEST(TypedValueTest, BadCast) { EXPECT_THROW(erased.get_mutable_value(), std::logic_error); EXPECT_THROW(erased.set_value(T{3}), std::logic_error); EXPECT_THROW(erased.SetFrom(Value(2)), std::logic_error); - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - EXPECT_THROW(erased.GetValueOrThrow(), std::logic_error); - EXPECT_THROW(erased.GetMutableValueOrThrow(), std::logic_error); - EXPECT_THROW(erased.SetValueOrThrow(T{3}), std::logic_error); - EXPECT_THROW(erased.SetFromOrThrow(Value(2)), std::logic_error); -#pragma GCC diagnostic pop } class PrintInterface { diff --git a/common/value.h b/common/value.h index cd25c931ba35..fc9cdfe463e8 100644 --- a/common/value.h +++ b/common/value.h @@ -9,7 +9,6 @@ #include "drake/common/copyable_unique_ptr.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/hash.h" #include "drake/common/is_cloneable.h" #include "drake/common/nice_type_name.h" @@ -103,60 +102,6 @@ class AbstractValue { template const T* maybe_get_value() const; - /// Returns the value wrapped in this AbstractValue, which must be of - /// exactly type T. T cannot be a superclass, abstract or otherwise. - /// In Debug builds, if the types don't match, an std::logic_error will be - /// thrown with a helpful error message. In Release builds, this is not - /// guaranteed. - template - DRAKE_DEPRECATED("2019-07-01", "Use get_value() instead.") - const T& GetValue() const; - - /// Like GetValue, but throws std::logic_error on mismatched types even in - /// Release builds. - template - DRAKE_DEPRECATED("2019-07-01", "Use get_value() instead.") - const T& GetValueOrThrow() const; - - /// Like GetValue, but quietly returns nullptr on mismatched types, - /// even in Release builds. - /// @returns A pointer to the stored value if T is the right type, - /// otherwise nullptr. - template - DRAKE_DEPRECATED("2019-07-01", "Use maybe_get_value() instead.") - const T* MaybeGetValue() const; - - /// Returns the value wrapped in this AbstractValue, which must be of - /// exactly type T. T cannot be a superclass, abstract or otherwise. - /// In Debug builds, if the types don't match, an std::logic_error will be - /// thrown with a helpful error message. In Release builds, this is not - /// guaranteed. Intentionally not const: holders of const references to the - /// AbstractValue should not be able to mutate the value it contains. - template - DRAKE_DEPRECATED("2019-07-01", "Use get_mutable_value() instead.") - T& GetMutableValue(); - - /// Like GetMutableValue, but throws std::logic_error on mismatched types even - /// in Release builds. - template - DRAKE_DEPRECATED("2019-07-01", "Use get_mutable_value() instead.") - T& GetMutableValueOrThrow(); - - /// Sets the value wrapped in this AbstractValue, which must be of - /// exactly type T. T cannot be a superclass, abstract or otherwise. - /// @param value_to_set The value to be copied or cloned into this - /// AbstractValue. In Debug builds, if the types don't match, - /// an std::logic_error will be thrown with a helpful error message. In - /// Release builds, this is not guaranteed. - template - DRAKE_DEPRECATED("2019-07-01", "Use set_value() instead.") - void SetValue(const T& value_to_set); - - /// Like SetValue, but throws on mismatched types even in Release builds. - template - DRAKE_DEPRECATED("2019-07-01", "Use set_value() instead.") - void SetValueOrThrow(const T& value_to_set); - /// Returns a copy of this AbstractValue. virtual std::unique_ptr Clone() const = 0; @@ -165,11 +110,6 @@ class AbstractValue { /// message. virtual void SetFrom(const AbstractValue& other) = 0; - /// Like SetFrom, but throws std::logic_error on mismatched types even in - /// Release builds. - DRAKE_DEPRECATED("2019-07-01", "Use SetFrom() instead.") - virtual void SetFromOrThrow(const AbstractValue& other) = 0; - /// Returns typeid of the contained object of type T. If T is polymorphic, /// this returns the typeid of the most-derived type of the contained object. virtual const std::type_info& type_info() const = 0; @@ -280,7 +220,6 @@ class Value : public AbstractValue { // AbstractValue overrides. std::unique_ptr Clone() const override; void SetFrom(const AbstractValue& other) override; - void SetFromOrThrow(const AbstractValue& other) final; const std::type_info& type_info() const final; const std::type_info& static_type_info() const final; @@ -686,46 +625,6 @@ const T* AbstractValue::maybe_get_value() const { return &self.get_value(); } -template -const T& AbstractValue::GetValue() const { - return get_value(); -} - -template -const T& AbstractValue::GetValueOrThrow() const { - if (typeid(T) != static_type_info()) { ThrowCastError(); } - return get_value(); -} - -template -const T* AbstractValue::MaybeGetValue() const { - if (typeid(T) != static_type_info()) { return nullptr; } - auto* value = static_cast*>(this); - return &value->get_value(); -} - -template -T& AbstractValue::GetMutableValue() { - return get_mutable_value(); -} - -template -T& AbstractValue::GetMutableValueOrThrow() { - if (typeid(T) != static_type_info()) { ThrowCastError(); } - return get_mutable_value(); -} - -template -void AbstractValue::SetValue(const T& value_to_set) { - set_value(value_to_set); -} - -template -void AbstractValue::SetValueOrThrow(const T& value_to_set) { - if (typeid(T) != static_type_info()) { ThrowCastError(); } - set_value(value_to_set); -} - // In Debug mode, returns true iff `this` is-a `Value`. In Release mode, a // false return means `this` is definitely not a `Value`; true means `this` // is-probably-a `Value`, but might rarely appear even for mismatched types. @@ -844,14 +743,6 @@ void Value::SetFrom(const AbstractValue& other) { value_ = Traits::to_storage(other.get_value()); } -template -void Value::SetFromOrThrow(const AbstractValue& other) { -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - value_ = Traits::to_storage(other.GetValueOrThrow()); -#pragma GCC diagnostic pop -} - template const std::type_info& Value::type_info() const { return typeid(get_value()); diff --git a/doc/bazel.rst b/doc/bazel.rst index 3f492c9ef177..380819be7027 100644 --- a/doc/bazel.rst +++ b/doc/bazel.rst @@ -264,7 +264,7 @@ See https://docs.bazel.build/versions/master/user-manual.html#bazelrc. Drake offers two flavors of SNOPT bindings for the MathematicalProgram: - The ``--config snopt_f2c`` option selects the legacy bindings that use the - f2c compiler; these bindings will be removed on 2019-07-01. + f2c compiler; these bindings will be removed on 2019-08-01. - The ``--config snopt_fortran`` option selects the bindings that use the gfortran compiler; these bindings will be supported for the foreseeable future. diff --git a/examples/allegro_hand/joint_control/allegro_single_object_simulation.cc b/examples/allegro_hand/joint_control/allegro_single_object_simulation.cc index 04441ea05542..ab66df61383c 100644 --- a/examples/allegro_hand/joint_control/allegro_single_object_simulation.cc +++ b/examples/allegro_hand/joint_control/allegro_single_object_simulation.cc @@ -87,7 +87,7 @@ void DoMain() { const auto& joint_hand_root = plant.GetBodyByName("hand_root"); plant.AddJoint("weld_hand", plant.world_body(), nullopt, joint_hand_root, nullopt, - Isometry3::Identity()); + RigidTransformd::Identity()); if (!FLAGS_add_gravity) { plant.mutable_gravity_field().set_gravity_vector( diff --git a/examples/allegro_hand/run_allegro_constant_load_demo.cc b/examples/allegro_hand/run_allegro_constant_load_demo.cc index 1904448acbf9..84d66a40e660 100644 --- a/examples/allegro_hand/run_allegro_constant_load_demo.cc +++ b/examples/allegro_hand/run_allegro_constant_load_demo.cc @@ -74,7 +74,7 @@ void DoMain() { // Weld the hand to the world frame const auto& joint_hand_root = plant.GetBodyByName("hand_root"); plant.AddJoint("weld_hand", plant.world_body(), nullopt, - joint_hand_root, nullopt, Isometry3::Identity()); + joint_hand_root, nullopt, math::RigidTransformd::Identity()); if (!FLAGS_add_gravity) { plant.mutable_gravity_field().set_gravity_vector( diff --git a/examples/kuka_iiwa_arm/iiwa_lcm.h b/examples/kuka_iiwa_arm/iiwa_lcm.h index 0831749e8ce0..ae9363e8e1a5 100644 --- a/examples/kuka_iiwa_arm/iiwa_lcm.h +++ b/examples/kuka_iiwa_arm/iiwa_lcm.h @@ -66,7 +66,6 @@ using manipulation::kuka_iiwa::IiwaCommandReceiver; using manipulation::kuka_iiwa::IiwaCommandSender; using manipulation::kuka_iiwa::IiwaStatusReceiver; using manipulation::kuka_iiwa::IiwaStatusSender; -using manipulation::kuka_iiwa::MakeIiwaCommandLcmSubscriberSystem; using manipulation::kuka_iiwa::kIiwaLcmStatusPeriod; } // namespace kuka_iiwa_arm diff --git a/geometry/geometry_frame.h b/geometry/geometry_frame.h index bd16e6a593e4..9644ea5599f0 100644 --- a/geometry/geometry_frame.h +++ b/geometry/geometry_frame.h @@ -44,20 +44,6 @@ class GeometryFrame { ThrowIfInvalid(); } - /** Constructor. - @param frame_name The name of the frame. - @param X_PF The initial pose of this frame F, measured and - expressed in the _intended_ parent frame P. - @param frame_group_id The optional frame group identifier. If unspecified, - defaults to the common, 0 group. Must be - non-negative. */ - DRAKE_DEPRECATED("2019-07-01", - "GeometryFrame no longer requires a pose X_PF; prefer the " - "constructor without pose.") - GeometryFrame(const std::string& frame_name, const Isometry3&, - int frame_group_id = 0) - : GeometryFrame(frame_name, frame_group_id) {} - /** Returns the globally unique id for this geometry specification. Every instantiation of %FrameInstance will contain a unique id value. The id value is preserved across copies. After successfully registering this diff --git a/manipulation/kuka_iiwa/iiwa_command_receiver.cc b/manipulation/kuka_iiwa/iiwa_command_receiver.cc index 6fa156e1ec83..158060c0ac5f 100644 --- a/manipulation/kuka_iiwa/iiwa_command_receiver.cc +++ b/manipulation/kuka_iiwa/iiwa_command_receiver.cc @@ -118,14 +118,6 @@ IiwaCommandReceiver::MapVectorXd IiwaCommandReceiver::input_torque( message.joint_torque.size()); } -std::unique_ptr -MakeIiwaCommandLcmSubscriberSystem( - int, const std::string& channel, - drake::lcm::DrakeLcmInterface* lcm) { - return systems::lcm::LcmSubscriberSystem::Make( - channel, lcm); -} - } // namespace kuka_iiwa } // namespace manipulation } // namespace drake diff --git a/manipulation/kuka_iiwa/iiwa_command_receiver.h b/manipulation/kuka_iiwa/iiwa_command_receiver.h index 42bcd7285743..35f96f185b44 100644 --- a/manipulation/kuka_iiwa/iiwa_command_receiver.h +++ b/manipulation/kuka_iiwa/iiwa_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_iiwa_command.hpp" #include "drake/manipulation/kuka_iiwa/iiwa_constants.h" @@ -23,15 +22,9 @@ namespace kuka_iiwa { /// LcmSubscriberSystem::Make(). /// /// It has one input port, "lcmt_iiwa_command". -/// (As well as some deprecated input ports; see below.) /// /// It has two output ports: one for the commanded position for each joint, and /// one for commanded additional feedforward joint torque. -/// (As well as some deprecated output ports; see below.) -/// -/// It also has one additional, deprecated output port -- "state" for the -/// commanded position AND an estimate of the commanded velocity for each -/// joint. /// /// @system { IiwaCommandReceiver, /// @input_port{lcmt_iiwa_command} @@ -68,14 +61,6 @@ class IiwaCommandReceiver : public systems::LeafSystem { const systems::CacheEntry* groomed_input_{}; }; -/// Creates a LcmSubscriberSystem for lcmt_iiwa_command. -DRAKE_DEPRECATED("2019-07-01", - "Call LcmSubscriberSystem::Make instead.") -std::unique_ptr -MakeIiwaCommandLcmSubscriberSystem( - int num_joints, const std::string& channel, - drake::lcm::DrakeLcmInterface* lcm); - } // namespace kuka_iiwa } // namespace manipulation } // namespace drake diff --git a/manipulation/planner/test/differential_inverse_kinematics_test.cc b/manipulation/planner/test/differential_inverse_kinematics_test.cc index 992231bd2596..cf9b058b5213 100644 --- a/manipulation/planner/test/differential_inverse_kinematics_test.cc +++ b/manipulation/planner/test/differential_inverse_kinematics_test.cc @@ -49,7 +49,8 @@ class DifferentialInverseKinematicsTest : public ::testing::Test { Translation3d(Vector3d(0.1, 0, 0)) * AngleAxis(M_PI, Vector3d::UnitZ()); frame_E_ = &plant_->AddFrame(std::make_unique>( - plant_->GetBodyByName("iiwa_link_7").body_frame(), X_7E)); + plant_->GetBodyByName("iiwa_link_7").body_frame(), + math::RigidTransformd(X_7E))); plant_->Finalize(); owned_context_ = plant_->CreateDefaultContext(); context_ = owned_context_.get(); diff --git a/math/rigid_transform.h b/math/rigid_transform.h index adba73f3725e..75f437cc64a9 100644 --- a/math/rigid_transform.h +++ b/math/rigid_transform.h @@ -5,7 +5,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" @@ -306,15 +305,6 @@ class RigidTransform { } #ifndef DRAKE_DOXYGEN_CXX - /// Until #9865 is resolved, this operator temporarily allows users mixing the - /// use of %RigidTransform with Isometry3. - DRAKE_DEPRECATED("2019-07-01", - "Do not mix RigidTransform with Isometry3. Only use " - "RigidTransform per #9865.") - RigidTransform operator*(const Isometry3& isometry3) const { - return *this * RigidTransform(isometry3); - } - // DO NOT USE. These methods will soon be deprecated as #9865 is resolved. // They are only provided to support backwards compatibility with // Isometry3 as we migrate Drake's codebase to use RigidTransform. New uses of diff --git a/multibody/plant/multibody_plant.h b/multibody/plant/multibody_plant.h index 2080854cad02..2d1694f10f3b 100644 --- a/multibody/plant/multibody_plant.h +++ b/multibody/plant/multibody_plant.h @@ -3222,172 +3222,6 @@ class MultibodyPlant : public internal::MultibodyTreeSystem { internal_tree().SetRandomState(context, state, generator); } -#ifndef DRAKE_DOXYGEN_CXX - // These APIs using Isometry3 will be deprecated soon with the resolution of - // #9865. Right now we offer them for backwards compatibility. - - DRAKE_DEPRECATED( - "2019-07-01", - "This Isometry3 overload will be removed pending the resolution of " - "#9865. Use the RigidTransform overload instead.") - void SetFreeBodyPose(systems::Context* context, const Body& body, - const Isometry3& X_WB) const { - SetFreeBodyPose(context, body, math::RigidTransform(X_WB)); - } - - DRAKE_DEPRECATED( - "2019-07-01", - "This Isometry3 overload will be removed pending the resolution of " - "#9865. Use the RigidTransform overload instead.") - void SetFreeBodyPose(const systems::Context& context, - systems::State* state, const Body& body, - const Isometry3& X_WB) const { - SetFreeBodyPose(context, state, body, math::RigidTransform(X_WB)); - } - - // Allows having a non-empty X_PF isometry and a nullopt X_BM. - template