Skip to content

Commit

Permalink
attic: Deprecate manipulation/util (RobotLocomotion#12679)
Browse files Browse the repository at this point in the history
This includes robot_state_msg_translator, sim_diagram_builder, and
world_sim_tree_builder.
  • Loading branch information
jwnimmer-tri authored Feb 4, 2020
1 parent 745e22b commit 74c72f6
Show file tree
Hide file tree
Showing 9 changed files with 45 additions and 8 deletions.
5 changes: 5 additions & 0 deletions attic/manipulation/util/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ drake_cc_library(
name = "world_sim_tree_builder",
srcs = ["world_sim_tree_builder.cc"],
hdrs = ["world_sim_tree_builder.h"],
copts = ["-Wno-deprecated-declarations"],
deps = [
"//attic/multibody:rigid_body_tree",
"//attic/multibody:rigid_body_tree_construction",
Expand All @@ -38,6 +39,7 @@ drake_cc_library(
name = "robot_state_msg_translator",
srcs = ["robot_state_msg_translator.cc"],
hdrs = ["robot_state_msg_translator.h"],
copts = ["-Wno-deprecated-declarations"],
deps = [
"//attic/multibody:rigid_body_tree",
"//attic/util",
Expand All @@ -50,6 +52,7 @@ drake_cc_library(
name = "sim_diagram_builder",
srcs = ["sim_diagram_builder.cc"],
hdrs = ["sim_diagram_builder.h"],
copts = ["-Wno-deprecated-declarations"],
deps = [
"//attic/multibody/rigid_body_plant",
"//attic/multibody/rigid_body_plant:drake_visualizer",
Expand All @@ -64,6 +67,7 @@ drake_cc_googletest(
name = "robot_state_msg_translator_test",
# TODO(siyuan): we should eventually move the models for test outside of
# /examples.
copts = ["-Wno-deprecated-declarations"],
data = [
"//manipulation/models/iiwa_description:models",
"//manipulation/models/wsg_50_description:models",
Expand All @@ -80,6 +84,7 @@ drake_cc_googletest(

drake_cc_googletest(
name = "sim_diagram_builder_test",
copts = ["-Wno-deprecated-declarations"],
data = [
"//examples/kuka_iiwa_arm:models",
"//manipulation/models/iiwa_description:models",
Expand Down
3 changes: 2 additions & 1 deletion attic/manipulation/util/README.md
Original file line number Diff line number Diff line change
@@ -1 +1,2 @@
All code in this drake/attic/manipulation/util folder will soon be deprecated.
All code in this drake/attic/manipulation/util folder is deprecated and will be
removed from Drake on 2020-05-01.
5 changes: 4 additions & 1 deletion attic/manipulation/util/robot_state_msg_translator.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@

#include "bot_core/robot_state_t.hpp"

#include "drake/common/drake_deprecated.h"
#include "drake/multibody/rigid_body_tree.h"

namespace drake {
Expand Down Expand Up @@ -39,7 +40,9 @@ namespace manipulation {
* comprehensive information, and the individual subscribers can pay attention
* to whatever subset of interest using reduced models.
*/
class RobotStateLcmMessageTranslator {
class DRAKE_DEPRECATED("2020-05-01",
"The attic/manipulation/util package is being removed.")
RobotStateLcmMessageTranslator {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(RobotStateLcmMessageTranslator)

Expand Down
5 changes: 4 additions & 1 deletion attic/manipulation/util/sim_diagram_builder.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include <utility>

#include "drake/common/drake_copyable.h"
#include "drake/common/drake_deprecated.h"
#include "drake/multibody/rigid_body_plant/drake_visualizer.h"
#include "drake/multibody/rigid_body_plant/rigid_body_plant.h"
#include "drake/systems/controllers/state_feedback_controller_interface.h"
Expand All @@ -23,7 +24,9 @@ namespace util {
* Access to a mutable DiagramBuilder is provided by get_mutable_builder().
*/
template <typename T>
class SimDiagramBuilder {
class DRAKE_DEPRECATED("2020-05-01",
"The attic/manipulation/util package is being removed.")
SimDiagramBuilder {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(SimDiagramBuilder)

Expand Down
19 changes: 16 additions & 3 deletions attic/manipulation/util/world_sim_tree_builder.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include <string>
#include <utility>

#include "drake/common/drake_deprecated.h"
#include "drake/multibody/rigid_body_plant/compliant_contact_model.h"
#include "drake/multibody/rigid_body_tree.h"

Expand All @@ -13,7 +14,9 @@ namespace manipulation {
namespace util {

template <typename T>
struct ModelInstanceInfo {
struct DRAKE_DEPRECATED("2020-05-01",
"The attic/manipulation/util package is being removed.")
ModelInstanceInfo {
std::string absolute_model_path;
int instance_id;
std::shared_ptr<RigidBodyFrame<T>> world_offset;
Expand All @@ -30,7 +33,9 @@ struct ModelInstanceInfo {
/// - double
///
template <typename T>
class WorldSimTreeBuilder {
class DRAKE_DEPRECATED("2020-05-01",
"The attic/manipulation/util package is being removed.")
WorldSimTreeBuilder {
public:
/// Constructs a WorldSimTreeBuilder object and specifies whether a call to
/// any of the add model instance functions should compile the tree.
Expand Down Expand Up @@ -122,9 +127,11 @@ class WorldSimTreeBuilder {
/// Adds a flat terrain to the simulation.
void AddGround();

// We are neither copyable nor moveable.
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
WorldSimTreeBuilder(const WorldSimTreeBuilder<T>& other) = delete;
WorldSimTreeBuilder& operator=(const WorldSimTreeBuilder<T>& other) = delete;
#pragma GCC diagnostic pop

/// Adds a model to the internal model database. Models are
/// described by @p model_name coupled with URDF/SDF paths in @p
Expand Down Expand Up @@ -179,9 +186,12 @@ class WorldSimTreeBuilder {
return rigid_body_tree_.get();
}

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
ModelInstanceInfo<T> get_model_info_for_instance(int id) {
return instance_id_to_model_info_.at(id);
}
#pragma GCC diagnostic pop

/// The compliant contact model parameters to use with the default material
/// parameters; these values should be passed to the plant.
Expand All @@ -204,7 +214,10 @@ class WorldSimTreeBuilder {
// loaded into the simulation.
std::map<std::string, std::string> model_map_;

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
std::map<int, ModelInstanceInfo<T>> instance_id_to_model_info_;
#pragma GCC diagnostic pop

// The default parameters for evaluating contact: the parameters for the
// model as well as the contact materials of the collision elements.
Expand Down
1 change: 0 additions & 1 deletion examples/allegro_hand/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,6 @@ drake_cc_googletest(
deps = [
":allegro_common",
":allegro_lcm",
"//attic/manipulation/util:world_sim_tree_builder",
"//common/test_utilities:eigen_matrix_compare",
"//systems/framework",
],
Expand Down
1 change: 0 additions & 1 deletion examples/allegro_hand/test/allegro_lcm_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
#include "drake/examples/allegro_hand/allegro_common.h"
#include "drake/lcmt_allegro_command.hpp"
#include "drake/lcmt_allegro_status.hpp"
#include "drake/manipulation/util/world_sim_tree_builder.h"
#include "drake/systems/framework/context.h"

namespace drake {
Expand Down
7 changes: 7 additions & 0 deletions examples/kuka_iiwa_arm/kuka_simulation.cc
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,14 @@ using systems::controllers::rbt::InverseDynamicsController;
using systems::controllers::StateFeedbackControllerInterface;

int DoMain() {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
// N.B. If SimDiagramBuilder reaches its deprecation date of 2020-05-01 prior
// to kuka_simulation being rewritten, then instead of completely removing
// the SimDiagramBuilder, we should instead mark it private, remove it from
// the installation, but keep using it here.
SimDiagramBuilder<double> builder;
#pragma GCC diagnostic pop
systems::DiagramBuilder<double>* base_builder = builder.get_mutable_builder();

// Adds a plant.
Expand Down
7 changes: 7 additions & 0 deletions examples/kuka_iiwa_arm/test/iiwa_lcm_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,15 @@ GTEST_TEST(IiwaLcmTest, IiwaContactResultsToExternalTorque) {
const std::string kIiwaUrdf =
"drake/manipulation/models/iiwa_description/urdf/"
"iiwa14_polytope_collision.urdf";
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
// N.B. If WorldSimTreeBuilder reaches its deprecation date of 2020-05-01
// prior to this test being removed, then instead of completely removing the
// WorldSimTreeBuilder, we should instead mark it private, remove it from the
// installation, but keep using it here.
auto tree_builder =
std::make_unique<manipulation::util::WorldSimTreeBuilder<double>>();
#pragma GCC diagnostic pop
tree_builder->StoreDrakeModel("iiwa", kIiwaUrdf);

tree_builder->AddFixedModelInstance("iiwa", Vector3<double>::Zero());
Expand Down

0 comments on commit 74c72f6

Please sign in to comment.