Skip to content

Commit

Permalink
Remove deprecated methods (2019-05) (RobotLocomotion#11358)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored May 1, 2019
1 parent cfe03ec commit 68567cb
Show file tree
Hide file tree
Showing 70 changed files with 208 additions and 2,895 deletions.
7 changes: 1 addition & 6 deletions attic/manipulation/planner/robot_plan_interpolator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -181,12 +181,7 @@ void RobotPlanInterpolator::DoCalcUnrestrictedUpdate(
if (encoded_msg != plan.encoded_msg) {
plan.encoded_msg.swap(encoded_msg);
if (plan_input.num_states == 0) {
// The plan is empty. Encode a plan for the current measured
// position.
const systems::BasicVector<double>* state_input =
this->EvalVectorInput(context, state_input_port_);
DRAKE_DEMAND(state_input);

// The plan is empty. Encode a plan for the current planned position.
const double current_plan_time = context.get_time() - plan.start_time;
MakeFixedPlan(context.get_time(),
plan.pp.value(current_plan_time),
Expand Down
2 changes: 2 additions & 0 deletions attic/manipulation/planner/robot_plan_interpolator.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ enum class InterpolatorType {
/// It has two input ports, one for robot_plan_t messages containing a
/// plan to follow, and another vector-valued port which expects the
/// current (q,v) state of the robot.
/// (The q,v input port is vestigial and should be left disconnected.)
///
/// The system has two output ports, one with the current desired
/// state (q,v) of the robot and another for the accelerations.
Expand All @@ -42,6 +43,7 @@ class RobotPlanInterpolator : public systems::LeafSystem<double> {
double update_interval = kDefaultPlanUpdateInterval);
~RobotPlanInterpolator() override;

/// N.B. This input port is useless and may be left disconnected.
const systems::InputPort<double>& get_plan_input_port() const {
return this->get_input_port(plan_input_port_);
}
Expand Down
14 changes: 0 additions & 14 deletions automotive/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@ load(
load(
"@drake//tools/vector_gen:vector_gen.bzl",
"drake_cc_vector_gen_library",
"drake_cc_vector_gen_translator_library",
)
load("//tools/lint:lint.bzl", "add_lint_tests")

Expand All @@ -36,7 +35,6 @@ drake_cc_package_library(
":curve2",
":driving_command_mux",
":dynamic_bicycle_car",
":generated_translators",
":generated_vectors",
":idm_controller",
":idm_planner",
Expand Down Expand Up @@ -84,17 +82,6 @@ drake_cc_vector_gen_library(
] + _LCM_ENABLED_NAMED_VECTORS,
)

drake_cc_vector_gen_translator_library(
name = "generated_translators",
srcs = _LCM_ENABLED_NAMED_VECTORS,
deprecation = "The LcmAndVectorBaseTranslator and its related code are deprecated, and will be removed on 2019-05-01.", # noqa
tags = ["manual"], # Avoid 'build //...' yelling at us.
deps = [
":generated_vectors",
"//lcmtypes:automotive",
],
)

drake_cc_library(
name = "trajectory",
srcs = ["trajectory.cc"],
Expand Down Expand Up @@ -420,7 +407,6 @@ drake_cc_library(
"//lcmtypes:lcmtypes_drake_cc",
"//systems/analysis",
"//systems/lcm:lcm_pubsub_system",
"//systems/lcm:lcmt_drake_signal_translator",
"//systems/primitives:constant_value_source",
"//systems/rendering:pose_aggregator",
"//systems/rendering:pose_bundle_to_draw_message",
Expand Down
12 changes: 0 additions & 12 deletions bindings/pydrake/attic/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -60,16 +60,4 @@ install(
deps = get_drake_py_installs(PY_LIBRARIES_WITH_INSTALL),
)

drake_py_unittest(
name = "attic_forwarding_test",
deps = [
"//bindings/pydrake/attic/multibody",
"//bindings/pydrake/attic/solvers",
"//bindings/pydrake/attic/systems",
"//bindings/pydrake/multibody",
"//bindings/pydrake/solvers",
"//bindings/pydrake/systems",
],
)

add_lint_tests_pydrake()
2 changes: 1 addition & 1 deletion bindings/pydrake/attic/solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ drake_pybind_library(
cc_srcs = ["ik_py.cc"],
package_info = PACKAGE_INFO,
py_deps = [
"//bindings/pydrake/multibody:rigid_body_tree_py",
"//bindings/pydrake/attic/multibody:rigid_body_tree_py",
],
py_srcs = ["_ik_extra.py"],
)
Expand Down
4 changes: 2 additions & 2 deletions bindings/pydrake/attic/systems/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ drake_pybind_library(
cc_srcs = ["sensors_py.cc"],
package_info = PACKAGE_INFO,
py_deps = [
"//bindings/pydrake/multibody:rigid_body_tree_py",
"//bindings/pydrake/attic/multibody:rigid_body_tree_py",
"//bindings/pydrake/systems:sensors_py",
],
)
Expand Down Expand Up @@ -93,7 +93,7 @@ drake_py_unittest(
],
deps = [
":controllers_py",
"//bindings/pydrake/multibody:rigid_body_tree_py",
"//bindings/pydrake/attic/multibody:rigid_body_tree_py",
],
)

Expand Down
56 changes: 0 additions & 56 deletions bindings/pydrake/attic/test/attic_forwarding_test.py

This file was deleted.

23 changes: 1 addition & 22 deletions bindings/pydrake/multibody/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,6 @@ load(
"drake_py_library",
"drake_py_unittest",
)
load(
"@drake//tools/skylark:alias.bzl",
"drake_py_library_aliases",
)
load("//bindings/pydrake:pydrake.bzl", "add_lint_tests_pydrake")

package(default_visibility = [
Expand Down Expand Up @@ -136,23 +132,6 @@ drake_pybind_library(
],
)

PY_LIBRARIES_ATTIC_ALIASES = [
":collision_py",
":joints_py",
":parsers_py",
":rigid_body_plant_py",
":rigid_body_py",
":rigid_body_tree_py",
":shapes_py",
]

drake_py_library_aliases(
actual_subdir = "bindings/pydrake/attic/multibody",
add_deprecation_warning = 1,
deprecation_removal_date = "2019-05-01",
relative_labels = PY_LIBRARIES_ATTIC_ALIASES,
)

PY_LIBRARIES_WITH_INSTALL = [
":benchmarks_py",
":inverse_kinematics_py",
Expand All @@ -163,7 +142,7 @@ PY_LIBRARIES_WITH_INSTALL = [
":tree_py",
]

PY_LIBRARIES = PY_LIBRARIES_ATTIC_ALIASES + [
PY_LIBRARIES = [
":module_py",
]

Expand Down
8 changes: 0 additions & 8 deletions bindings/pydrake/multibody/all.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,14 +3,6 @@
# Deprecated symbols.
with warnings.catch_warnings():
warnings.simplefilter("ignore", DeprecationWarning)
# - Attic (#9314)
from .collision import *
from .joints import *
from .parsers import *
from .rigid_body_plant import *
from .rigid_body_tree import *
from .rigid_body import *
from .shapes import *
# - Shuffle (#9314. #9366)
from .multibody_tree.all import * # noqa

Expand Down
17 changes: 1 addition & 16 deletions bindings/pydrake/solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,6 @@ load(
"drake_py_test",
"drake_py_unittest",
)
load(
"@drake//tools/skylark:alias.bzl",
"drake_py_library_aliases",
)
load("//bindings/pydrake:pydrake.bzl", "add_lint_tests_pydrake")

package(default_visibility = [
Expand Down Expand Up @@ -127,17 +123,6 @@ drake_pybind_library(
py_deps = [":mathematicalprogram_py"],
)

PY_LIBRARIES_ATTIC_ALIASES = [
":ik_py",
]

drake_py_library_aliases(
actual_subdir = "bindings/pydrake/attic/solvers",
add_deprecation_warning = 1,
deprecation_removal_date = "2019-05-01",
relative_labels = PY_LIBRARIES_ATTIC_ALIASES,
)

PY_LIBRARIES_WITH_INSTALL = [
":gurobi_py",
":ipopt_py",
Expand All @@ -147,7 +132,7 @@ PY_LIBRARIES_WITH_INSTALL = [
":snopt_py",
]

PY_LIBRARIES = PY_LIBRARIES_ATTIC_ALIASES + [
PY_LIBRARIES = [
":module_py",
]

Expand Down
6 changes: 0 additions & 6 deletions bindings/pydrake/solvers/all.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,4 @@
from __future__ import absolute_import
import warnings

# Deprecated symbols.
with warnings.catch_warnings():
warnings.simplefilter("ignore", DeprecationWarning)
from .ik import *

from .mathematicalprogram import * # noqa
# TODO(eric.cousineau): Merge these into `mathematicalprogram`.
Expand Down
2 changes: 0 additions & 2 deletions bindings/pydrake/systems/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,6 @@ drake_pybind_library(
"//bindings/pydrake:symbolic_py",
"//bindings/pydrake/multibody:multibody_tree_py",
],
py_srcs = ["_controllers_extra.py"],
)

drake_pybind_library(
Expand Down Expand Up @@ -178,7 +177,6 @@ drake_pybind_library(
"//bindings/pydrake/common:cpp_template_py",
"//bindings/pydrake/common:eigen_geometry_py",
],
py_srcs = ["_sensors_extra.py"],
)

drake_pybind_library(
Expand Down
8 changes: 0 additions & 8 deletions bindings/pydrake/systems/_controllers_extra.py

This file was deleted.

8 changes: 0 additions & 8 deletions bindings/pydrake/systems/_sensors_extra.py

This file was deleted.

2 changes: 0 additions & 2 deletions bindings/pydrake/systems/controllers_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -153,8 +153,6 @@ PYBIND11_MODULE(controllers, m) {
py::arg("system"), py::arg("context"), py::arg("Q"), py::arg("R"),
py::arg("N") = Eigen::Matrix<double, 0, 0>::Zero(),
py::arg("input_port_index") = 0, doc.LinearQuadraticRegulator.doc_6args);

ExecuteExtraPythonCode(m);
}

} // namespace pydrake
Expand Down
11 changes: 1 addition & 10 deletions bindings/pydrake/systems/lcm_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -160,16 +160,7 @@ PYBIND11_MODULE(lcm, m) {
py::arg("channel"), py::arg("serializer"), py::arg("lcm"),
py::arg("publish_period") = 0.0,
// Keep alive: `self` keeps `DrakeLcmInterface` alive.
py::keep_alive<1, 3>(), doc.LcmPublisherSystem.ctor.doc_4args)
.def("set_publish_period",
[](Class* self, double period) {
WarnDeprecated("set_publish_period() is deprecated");
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
self->set_publish_period(period);
#pragma GCC diagnostic pop
},
py::arg("period"), cls_doc.set_publish_period.doc_deprecated);
py::keep_alive<1, 3>(), cls_doc.ctor.doc_4args);
}

{
Expand Down
2 changes: 0 additions & 2 deletions bindings/pydrake/systems/sensors_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -215,8 +215,6 @@ PYBIND11_MODULE(sensors, m) {
};
type_visit(def_image_input_port, PixelTypeList{});
}

ExecuteExtraPythonCode(m);
}

} // namespace pydrake
Expand Down
2 changes: 1 addition & 1 deletion doc/bazel.rst
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,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-05-01.
f2c compiler; these bindings will be removed on 2019-06-01.
- The ``--config snopt_fortran`` option selects the bindings that use the
gfortran compiler; these bindings will be supported for the foreseeable
future.
Expand Down
7 changes: 6 additions & 1 deletion examples/kuka_iiwa_arm/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,6 @@ drake_cc_library(
"//manipulation/kuka_iiwa",
"//systems/framework:leaf_system",
"//systems/lcm:lcm_pubsub_system",
"//systems/lcm:translator",
],
)

Expand Down Expand Up @@ -146,6 +145,9 @@ drake_cc_binary(
"//lcm",
"//manipulation/schunk_wsg",
"//systems/analysis",
"//systems/primitives:constant_vector_source",
"//systems/primitives:demultiplexer",
"//systems/primitives:discrete_derivative",
],
)

Expand Down Expand Up @@ -173,6 +175,9 @@ drake_cc_binary(
"//lcm",
"//systems/analysis",
"//systems/controllers:state_feedback_controller_interface",
"//systems/primitives:constant_vector_source",
"//systems/primitives:demultiplexer",
"//systems/primitives:discrete_derivative",
],
)

Expand Down
1 change: 0 additions & 1 deletion examples/kuka_iiwa_arm/iiwa_lcm.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#include "drake/manipulation/kuka_iiwa/iiwa_status_receiver.h"
#include "drake/manipulation/kuka_iiwa/iiwa_status_sender.h"
#include "drake/systems/framework/leaf_system.h"
#include "drake/systems/lcm/lcm_and_vector_base_translator.h"
#include "drake/systems/lcm/lcm_subscriber_system.h"

namespace drake {
Expand Down
Loading

0 comments on commit 68567cb

Please sign in to comment.