Skip to content

Commit

Permalink
Move protobuf support in drake/common into subdir
Browse files Browse the repository at this point in the history
Bazel's support for protobuf does not have good backward compatibility.
As such, its helpful an important build file (drake/common/BUILD) didn't
mention @protobuf in a load() stanza.  Thus, we'll move the protobuf
support into a different package folder, so that only folks that truly
need it have to pay for it with their WORKSPACE entries.
  • Loading branch information
jwnimmer-tri committed Jul 6, 2017
1 parent 51770a0 commit 651ef7b
Show file tree
Hide file tree
Showing 29 changed files with 123 additions and 79 deletions.
3 changes: 1 addition & 2 deletions drake/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -56,17 +56,16 @@ _LIBDRAKE_COMPONENTS = [
"//drake/common:functional_form",
"//drake/common:is_approx_equal_abstol",
"//drake/common:is_cloneable",
"//drake/common:matlab_rpc",
"//drake/common:monomial",
"//drake/common:nice_type_name",
"//drake/common:number_traits",
"//drake/common:polynomial",
"//drake/common:protobuf",
"//drake/common:reinit_after_move",
"//drake/common:scoped_singleton",
"//drake/common:sorted_vectors_have_intersection",
"//drake/common:symbolic",
"//drake/common:text_logging_gflags",
"//drake/common/proto:protobuf",
"//drake/common/trajectories:piecewise_function",
"//drake/common/trajectories:piecewise_polynomial",
"//drake/common/trajectories:piecewise_polynomial_trajectory",
Expand Down
2 changes: 1 addition & 1 deletion drake/automotive/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -645,8 +645,8 @@ drake_cc_googletest(
tags = ["snopt"],
deps = [
":simple_car",
"//drake/common:call_matlab",
"//drake/common:eigen_matrix_compare",
"//drake/common/proto:call_matlab",
"//drake/systems/trajectory_optimization:direct_collocation",
],
)
Expand Down
4 changes: 2 additions & 2 deletions drake/automotive/test/trajectory_optimization_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
#include <gtest/gtest.h>

#include "drake/automotive/simple_car.h"
#include "drake/common/call_matlab.h"
#include "drake/common/eigen_matrix_compare.h"
#include "drake/common/proto/call_matlab.h"
#include "drake/systems/trajectory_optimization/direct_collocation.h"

namespace drake {
Expand Down Expand Up @@ -75,7 +75,7 @@ GTEST_TEST(TrajectoryOptimizationTest, SimpleCarDircolTest) {
EXPECT_EQ(result, solvers::SolutionResult::kSolutionFound);

// Plot the solution.
// Note: see lcm_call_matlab.h for instructions on viewing the plot.
// Note: see call_matlab.h for instructions on viewing the plot.
Eigen::MatrixXd inputs;
Eigen::MatrixXd states;
std::vector<double> times_out;
Expand Down
45 changes: 0 additions & 45 deletions drake/common/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@ load(
)
load("//tools:python_lint.bzl", "python_lint")
load("//tools:install.bzl", "install")
load("@protobuf//:protobuf.bzl", "cc_proto_library")

package(default_visibility = ["//visibility:public"])

Expand Down Expand Up @@ -236,24 +235,6 @@ drake_cc_library(
hdrs = ["test/is_memcpy_movable.h"],
)

cc_proto_library(
name = "matlab_rpc",
srcs = [
"matlab_rpc.proto",
],
)

drake_cc_library(
name = "call_matlab",
testonly = 1,
srcs = ["call_matlab.cc"],
hdrs = ["call_matlab.h"],
deps = [
":common",
":matlab_rpc",
],
)

drake_cc_library(
name = "monomial",
srcs = [
Expand Down Expand Up @@ -346,15 +327,6 @@ drake_cc_library(
],
)

drake_cc_library(
name = "protobuf",
srcs = ["protobuf.cc"],
hdrs = ["protobuf.h"],
deps = [
"@protobuf",
],
)

drake_cc_binary(
name = "resource_tool",
srcs = ["resource_tool.cc"],
Expand Down Expand Up @@ -405,13 +377,6 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "call_matlab_test",
deps = [
":call_matlab",
],
)

drake_cc_googletest(
name = "reinit_after_move_test",
deps = [
Expand Down Expand Up @@ -652,16 +617,6 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "protobuf_test",
data = [
"test/test_string.txt",
],
deps = [
":protobuf",
],
)

drake_cc_googletest(
name = "sorted_vectors_have_intersection_test",
deps = [
Expand Down
10 changes: 3 additions & 7 deletions drake/common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,6 @@
# Drake common library
#

protobuf_generate_cpp(PROTO_SRCS PROTO_HDRS matlab_rpc.proto)

# Generated code.
set(cmake_project_source_dir_cc ${PROJECT_BINARY_DIR}/generated/drake/common/cmake_project_source_dir.cc)
set(THIS_FILE_IS_USED_BY_CMAKE_TO_CREATE_GENERATED_CODE
Expand All @@ -12,7 +10,6 @@ configure_file(cmake_project_source_dir.cc.in ${cmake_project_source_dir_cc})

# List all source files used to build libdrakeCommon.
set(sources
call_matlab.cc ${PROTO_SRCS}
${cmake_project_source_dir_cc}
double_overloads.cc
drake_assert_and_throw.cc
Expand All @@ -39,7 +36,6 @@ set(sources
# are available elsewhere via #include "drake/common/xxx.h".
set(installed_headers
autodiff_overloads.h
call_matlab.h ${PROTO_HDRS}
cond.h
constants.h
copyable_unique_ptr.h
Expand Down Expand Up @@ -95,15 +91,14 @@ set(private_headers
# Create the library target and note its dependencies.
add_library_with_exports(LIB_NAME drakeCommon
SOURCE_FILES ${sources} ${installed_headers} ${private_headers})
target_include_directories(drakeCommon PUBLIC ${PROTOBUF_INCLUDE_DIRS})
target_include_directories(drakeCommon PUBLIC)
target_link_libraries(drakeCommon
Eigen3::Eigen
fmt
gflags
spruce
stx
Threads::Threads
${PROTOBUF_LIBRARIES})
Threads::Threads)

set(drakeCommon_CFLAGS)
set(drakeCommon_REQUIRES)
Expand Down Expand Up @@ -140,4 +135,5 @@ if(BUILD_TESTING)
add_subdirectory(test)
endif()

add_subdirectory(proto)
add_subdirectory(trajectories)
61 changes: 61 additions & 0 deletions drake/common/proto/BUILD
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
# -*- python -*-
# This file contains rules for Bazel; see drake/doc/bazel.rst.

load("//tools:cpplint.bzl", "cpplint")
load(
"//tools:drake.bzl",
"drake_cc_googletest",
"drake_cc_library",
)
load("@protobuf//:protobuf.bzl", "cc_proto_library")

package(default_visibility = ["//visibility:public"])

cc_proto_library(
name = "matlab_rpc",
srcs = [
"matlab_rpc.proto",
],
testonly = 1,
)

drake_cc_library(
name = "call_matlab",
testonly = 1,
srcs = ["call_matlab.cc"],
hdrs = ["call_matlab.h"],
deps = [
"//drake/common",
":matlab_rpc",
],
)

drake_cc_library(
name = "protobuf",
srcs = ["protobuf.cc"],
hdrs = ["protobuf.h"],
deps = [
"@protobuf",
],
)

# === test/ ===

drake_cc_googletest(
name = "call_matlab_test",
deps = [
":call_matlab",
],
)

drake_cc_googletest(
name = "protobuf_test",
data = [
"test/test_string.txt",
],
deps = [
":protobuf",
],
)

cpplint()
29 changes: 29 additions & 0 deletions drake/common/proto/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
protobuf_generate_cpp(PROTO_SRCS PROTO_HDRS matlab_rpc.proto)

set(sources
${PROTO_SRCS}
call_matlab.cc
protobuf.cc
)

set(installed_headers
${PROTO_HDRS}
call_matlab.h
protobuf.h
)

add_library_with_exports(LIB_NAME drakeCommonProto
SOURCE_FILES ${sources} ${installed_headers})
target_include_directories(drakeCommonProto PUBLIC ${PROTOBUF_INCLUDE_DIRS})
target_link_libraries(drakeCommonProto
${PROTOBUF_LIBRARIES}
drakeCommon
Eigen3::Eigen
)
set(drakeCommonProto_CFLAGS)
set(drakeCommonProto_REQUIRES)

drake_install_headers(${installed_headers})
drake_install_libraries(drakeCommonProto)

# N.B. The tests are not built with CMake.
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "drake/common/call_matlab.h"
#include "drake/common/proto/call_matlab.h"

#include <fcntl.h>
#include <sys/stat.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <vector>

#include "drake/common/eigen_types.h"
#include "drake/common/matlab_rpc.pb.h"
#include "drake/common/proto/matlab_rpc.pb.h"

/// @file Utilities for calling Matlab from C++
///
Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "drake/common/protobuf.h"
#include "drake/common/proto/protobuf.h"

#include <fcntl.h>

Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "drake/common/call_matlab.h"
#include "drake/common/proto/call_matlab.h"

#include <cmath>

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "drake/common/protobuf.h"
#include "drake/common/proto/protobuf.h"

#include <string>

Expand All @@ -10,7 +10,7 @@ namespace {

GTEST_TEST(ProtobufUtilsTest, MakeFileInputStreamSucceeds) {
auto istream = MakeFileInputStreamOrThrow(
"drake/common/test/test_string.txt");
"drake/common/proto/test/test_string.txt");
google::protobuf::io::CodedInputStream coded_stream(istream.get());
std::string expected("test string");
std::string contents;
Expand Down
File renamed without changes.
2 changes: 1 addition & 1 deletion drake/examples/Acrobot/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -111,8 +111,8 @@ drake_cc_binary(
test_rule_args = ["-realtime_factor=0.0"],
deps = [
":acrobot_plant",
"//drake/common:call_matlab",
"//drake/common:find_resource",
"//drake/common/proto:call_matlab",
"//drake/lcm",
"//drake/multibody:rigid_body_tree",
"//drake/multibody/joints",
Expand Down
4 changes: 2 additions & 2 deletions drake/examples/Acrobot/acrobot_run_lqr_w_estimator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@

#include <gflags/gflags.h>

#include "drake/common/call_matlab.h"
#include "drake/common/find_resource.h"
#include "drake/common/proto/call_matlab.h"
#include "drake/examples/Acrobot/acrobot_plant.h"
#include "drake/examples/Acrobot/gen/acrobot_state_vector.h"
#include "drake/lcm/drake_lcm.h"
Expand Down Expand Up @@ -146,7 +146,7 @@ int do_main(int argc, char* argv[]) {
simulator.Initialize();
simulator.StepTo(5);

// Plot the results (launch lcm_call_matlab_client to see the plots).
// Plot the results (launch call_matlab_client to see the plots).
using common::CallMatlab;
CallMatlab("figure", 1);
CallMatlab("plot", x_logger->sample_times(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ drake_cc_library(
deps = [
":id_controller_config",
":rigid_body_tree_alias_groups",
"//drake/common:protobuf",
"//drake/common/proto:protobuf",
"//drake/examples/QPInverseDynamicsForHumanoids:qp_controller_common",
"@yaml_cpp",
],
Expand All @@ -47,7 +47,7 @@ drake_cc_library(
hdrs = ["rigid_body_tree_alias_groups.h"],
deps = [
":alias_groups",
"//drake/common:protobuf",
"//drake/common/proto:protobuf",
"//drake/multibody:rigid_body_tree",
],
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#include "google/protobuf/text_format.h"

#include "drake/common/drake_assert.h"
#include "drake/common/protobuf.h"
#include "drake/common/proto/protobuf.h"
#include "drake/examples/QPInverseDynamicsForHumanoids/param_parsers/id_controller_config.pb.h"
#include "drake/util/drakeUtil.h"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

#include "google/protobuf/text_format.h"

#include "drake/common/protobuf.h"
#include "drake/common/proto/protobuf.h"
#include "drake/examples/QPInverseDynamicsForHumanoids/param_parsers/alias_groups.pb.h"

namespace drake {
Expand Down
2 changes: 1 addition & 1 deletion drake/examples/ZMP/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ drake_cc_binary(
srcs = ["zmp_example.cc"],
deps = [
":zmp_test_util",
"//drake/common:call_matlab",
"//drake/common/proto:call_matlab",
],
)

Expand Down
2 changes: 1 addition & 1 deletion drake/examples/ZMP/zmp_example.cc
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#include <chrono>
#include <thread>

#include "drake/common/call_matlab.h"
#include "drake/common/proto/call_matlab.h"
#include "drake/examples/ZMP/zmp_test_util.h"

void PlotResults(const drake::examples::zmp::ZMPTestTraj& traj) {
Expand Down
Loading

0 comments on commit 651ef7b

Please sign in to comment.