Skip to content

Commit

Permalink
common: Add add_text_logging_gflags, deprecate text_logging_gflags (R…
Browse files Browse the repository at this point in the history
…obotLocomotion#12287)

It is difficult to support Drake-installed libraries that depend on
gflags, due to how gflags is designed for static linking and lacks
CMake-supporting infrastructure. Thus, we are deprecating (and will
later remove) Drake's support for installing anything that touches
gflags.
  • Loading branch information
jwnimmer-tri authored Oct 31, 2019
1 parent 2ebcca6 commit b7f7cdb
Show file tree
Hide file tree
Showing 52 changed files with 109 additions and 90 deletions.
3 changes: 1 addition & 2 deletions attic/manipulation/scene_generation/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ drake_cc_binary(
":random_clutter_generator",
":simulate_plant_to_rest",
"//common",
"//common:text_logging_gflags",
"//common:add_text_logging_gflags",
"@gflags",
],
)
Expand All @@ -69,7 +69,6 @@ drake_cc_googletest(
":random_clutter_generator",
":simulate_plant_to_rest",
"//common",
"//common:text_logging_gflags",
"//common/test_utilities:eigen_matrix_compare",
"@gflags",
],
Expand Down
2 changes: 0 additions & 2 deletions attic/manipulation/scene_generation/random_clutter_demo.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
#include <gflags/gflags.h>

#include "drake/common/eigen_types.h"
#include "drake/common/text_logging_gflags.h"
#include "drake/lcm/drake_lcm.h"
#include "drake/manipulation/scene_generation/random_clutter_generator.h"
#include "drake/manipulation/scene_generation/simulate_plant_to_rest.h"
Expand Down Expand Up @@ -162,6 +161,5 @@ int DoMain() {

int main(int argc, char* argv[]) {
gflags::ParseCommandLineFlags(&argc, &argv, true);
drake::logging::HandleSpdlogGflags();
drake::manipulation::scene_generation::DoMain();
}
2 changes: 1 addition & 1 deletion attic/systems/sensors/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ drake_cc_binary(
],
deps = [
":accelerometer_example_diagram",
"//common:text_logging_gflags",
"//common:add_text_logging_gflags",
"//lcm",
"//systems/analysis:simulator",
"@gflags",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
#include <gflags/gflags.h>

#include "drake/common/drake_assert.h"
#include "drake/common/text_logging_gflags.h"
#include "drake/lcm/drake_lcm.h"
#include "drake/systems/analysis/simulator.h"
#include "drake/systems/sensors/test/accelerometer_test/accelerometer_example_diagram.h"
Expand All @@ -28,7 +27,6 @@ namespace {

int exec(int argc, char* argv[]) {
gflags::ParseCommandLineFlags(&argc, &argv, true);
logging::HandleSpdlogGflags();

DRAKE_DEMAND(FLAGS_simulation_sec >= 0);
::drake::lcm::DrakeLcm real_lcm;
Expand Down
38 changes: 30 additions & 8 deletions common/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -446,16 +446,32 @@ drake_cc_library(
],
)

# This is a Drake-internal utility for use only as a direct dependency
# of executable (drake_cc_binary) targets. Thus, we exclude it from
# the ":common" package library and from libdrake.
drake_cc_library(
name = "add_text_logging_gflags",
srcs = ["add_text_logging_gflags.cc"],
tags = [
"exclude_from_libdrake",
"exclude_from_package",
],
visibility = ["//:__subpackages__"],
deps = [
":essential",
":unused",
"@gflags",
],
alwayslink = 1,
)

# TODO(jwnimmer-tri) When this header file is removed, be sure to also remove
# the CMake install helpers related to gflags (in drake.cps, FindGFlags.cmake,
# etc).
drake_cc_library(
name = "text_logging_gflags",
hdrs = ["text_logging_gflags.h"],
# TODO(jwnimmer-tri) Ideally, gflags BUILD would do this for us. Figure
# out what's going on. Definitely don't let "-pthread" get copy-pasta'd
# throughout our code.
linkopts = select({
"//tools/cc_toolchain:linux": ["-pthread"],
"//conditions:default": [],
}),
deprecation = "DRAKE DEPRECATED: The drake/common/text_logging_gflags.h convenience header is being removed from Drake on or after 2020-02-01. Downstream projects should maintain their own implementation of this feature. See drake/common/add_text_logging_gflags.cc for an example.", # noqa
tags = [
# Don't add this library into the ":common" package library.
# Only programs with a main() function should ever use this header.
Expand All @@ -467,13 +483,19 @@ drake_cc_library(
# this cc_library entirely, and use a separate rule below for the
# installation.
"exclude_from_libdrake",
# Avoid 'build //...' yelling at us.
"manual",
],
deps = [
":essential",
"@gflags",
],
)

# TODO(jwnimmer-tri) When this header file is removed, be sure to also remove
# the CMake install helpers related to gflags (in drake.cps, FindGFlags.cmake,
# etc).
#
# Compared to the above rule, this removes the deps attribute; we don't want to
# link against gflags for libdrake.so, we just want to publish this header for
# callers who have their own gflags to link against.
Expand Down Expand Up @@ -533,9 +555,9 @@ drake_cc_binary(
name = "resource_tool",
srcs = ["resource_tool.cc"],
deps = [
":add_text_logging_gflags",
":essential",
":find_resource",
":text_logging_gflags",
],
)

Expand Down
26 changes: 26 additions & 0 deletions common/add_text_logging_gflags.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
// This is a Drake-internal utility for use only as a direct dependency
// of executable (drake_cc_binary) targets.
//
// To add --spdlog_level to the gflags command line of any `drake_cc_binary`,
// add "//common:add_text_logging_gflags" to the `deps` attribute in its BUILD.

#include <string>

#include <gflags/gflags.h>

#include "drake/common/text_logging.h"
#include "drake/common/unused.h"

// Declare the --spdlog_level gflags option.
DEFINE_string(spdlog_level, drake::logging::kSetLogLevelUnchanged,
drake::logging::kSetLogLevelHelpMessage);

// Validate --spdlog_level and update Drake's configuration to match the flag.
namespace {
bool ValidateSpdlogLevel(const char* name, const std::string& value) {
drake::unused(name);
drake::logging::set_log_level(value);
return true;
}
} // namespace
DEFINE_validator(spdlog_level, &ValidateSpdlogLevel);
2 changes: 0 additions & 2 deletions common/resource_tool.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
#include <gflags/gflags.h>

#include "drake/common/find_resource.h"
#include "drake/common/text_logging_gflags.h"

DEFINE_string(
print_resource_path, "",
Expand All @@ -23,7 +22,6 @@ namespace {
int main(int argc, char* argv[]) {
gflags::SetUsageMessage("Find Drake-related resources");
gflags::ParseCommandLineFlags(&argc, &argv, true);
logging::HandleSpdlogGflags();

// The user must supply exactly one of --print_resource_path or
// --print_resource_root_environment_variable_name.
Expand Down
2 changes: 1 addition & 1 deletion common/test_utilities/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ drake_cc_library(
"exclude_from_package",
],
deps = [
"//common:text_logging_gflags",
"//common:add_text_logging_gflags",
"@gtest//:without_main",
],
)
Expand Down
6 changes: 1 addition & 5 deletions common/test_utilities/drake_cc_googletest_main.cc
Original file line number Diff line number Diff line change
@@ -1,10 +1,9 @@
/// @file
/// This is Drake's default main() function for gtest-based unit tests.

#include <gflags/gflags.h>
#include <gmock/gmock.h>

#include "drake/common/text_logging_gflags.h"

// TODO(SeanCurtis-TRI): Remove this when CLion bazel plug-in no longer executes
// its debugger with the --gunit_color flag. Most recent versions known to be
// an issue:
Expand All @@ -25,9 +24,6 @@ int main(int argc, char** argv) {
google::SetUsageMessage(" "); // Nerf a silly warning emitted by gflags.
google::ParseCommandLineFlags(&argc, &argv, true);

// Adjust Drake's log setting per the gflags results.
drake::logging::HandleSpdlogGflags();

// Actually run the tests.
return RUN_ALL_TESTS();
}
5 changes: 5 additions & 0 deletions common/text_logging_gflags.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,12 @@
/// This file defines gflags settings to control spdlog levels.
/// Only include this from translation units that declare a `main` function.

// NOLINTNEXTLINE(whitespace/line_length)
#warning DRAKE DEPRECATED: The drake/common/text_logging_gflags.h convenience header is being removed from Drake on or after 2020-02-01. Downstream projects should maintain their own implementation of this feature. See drake/common/add_text_logging_gflags.cc for an example.

#include <gflags/gflags.h>

#include "drake/common/drake_deprecated.h"
#include "drake/common/text_logging.h"

// Declare the --spdlog_level gflags option.
Expand All @@ -18,6 +22,7 @@ namespace logging {

/// Check the gflags settings for validity. If spdlog is enabled, update its
/// configuration to match the flags.
DRAKE_DEPRECATED("2020-02-01", "The drake/common/text_logging_gflags.h convenience header is being removed from Drake. Downstream projects should maintain their own implementation of this feature. See drake/common/add_text_logging_gflags.cc for an example.") // NOLINT(whitespace/line_length)
inline void HandleSpdlogGflags() {
drake::logging::set_log_level(FLAGS_spdlog_level);
}
Expand Down
2 changes: 1 addition & 1 deletion examples/allegro_hand/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,8 @@ drake_cc_binary(
"//manipulation/models/allegro_hand_description:models",
],
deps = [
"//common:add_text_logging_gflags",
"//common:find_resource",
"//common:text_logging_gflags",
"//geometry:geometry_visualization",
"//lcm",
"//multibody/parsing",
Expand Down
2 changes: 1 addition & 1 deletion examples/allegro_hand/joint_control/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@ drake_cc_binary(
"//manipulation/models/allegro_hand_description:models",
],
deps = [
"//common:add_text_logging_gflags",
"//common:find_resource",
"//common:text_logging_gflags",
"//examples/allegro_hand:allegro_common",
"//examples/allegro_hand:allegro_lcm",
"//geometry:geometry_visualization",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@

#include "drake/common/drake_assert.h"
#include "drake/common/find_resource.h"
#include "drake/common/text_logging_gflags.h"
#include "drake/examples/allegro_hand/allegro_common.h"
#include "drake/examples/allegro_hand/allegro_lcm.h"
#include "drake/geometry/geometry_visualization.h"
Expand Down
1 change: 0 additions & 1 deletion examples/allegro_hand/run_allegro_constant_load_demo.cc
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@

#include "drake/common/drake_assert.h"
#include "drake/common/find_resource.h"
#include "drake/common/text_logging_gflags.h"
#include "drake/geometry/geometry_visualization.h"
#include "drake/geometry/scene_graph.h"
#include "drake/lcm/drake_lcm.h"
Expand Down
2 changes: 1 addition & 1 deletion examples/atlas/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@ drake_cc_binary(
"--target_realtime_rate=0.0",
],
deps = [
"//common:add_text_logging_gflags",
"//common:find_resource",
"//common:text_logging_gflags",
"//geometry:geometry_visualization",
"//multibody/parsing",
"//multibody/plant:contact_results_to_lcm",
Expand Down
2 changes: 0 additions & 2 deletions examples/atlas/atlas_run_dynamics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
#include <gflags/gflags.h>

#include "drake/common/find_resource.h"
#include "drake/common/text_logging_gflags.h"
#include "drake/geometry/geometry_visualization.h"
#include "drake/geometry/scene_graph.h"
#include "drake/lcm/drake_lcm.h"
Expand Down Expand Up @@ -132,6 +131,5 @@ int main(int argc, char* argv[]) {
"\njoint limits. "
"\nLaunch drake-visualizer before running this example.");
gflags::ParseCommandLineFlags(&argc, &argv, true);
drake::logging::HandleSpdlogGflags();
return drake::examples::atlas::do_main();
}
2 changes: 1 addition & 1 deletion examples/double_pendulum/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,9 @@ drake_cc_binary(
"//attic/multibody:rigid_body_tree",
"//attic/multibody/rigid_body_plant",
"//attic/multibody/rigid_body_plant:drake_visualizer",
"//common:add_text_logging_gflags",
"//common:essential",
"//common:find_resource",
"//common:text_logging_gflags",
"//lcm",
"//systems/analysis",
"//systems/framework",
Expand Down
4 changes: 2 additions & 2 deletions examples/double_pendulum/double_pendulum_demo.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,9 @@
#include <limits>
#include <memory>

#include <gflags/gflags.h>

#include "drake/common/find_resource.h"
#include "drake/common/text_logging_gflags.h"
#include "drake/examples/double_pendulum/sdf_helpers.h"
#include "drake/multibody/rigid_body_plant/drake_visualizer.h"
#include "drake/multibody/rigid_body_plant/rigid_body_plant.h"
Expand Down Expand Up @@ -36,7 +37,6 @@ int main(int argc, char* argv[]) {
gflags::SetUsageMessage("Simple sdformat usage example, just"
"make sure drake-visualizer is running!");
gflags::ParseCommandLineFlags(&argc, &argv, true);
logging::HandleSpdlogGflags();
// Load and parse double pendulum SDF from file into a tree.
const std::string sdf_path = FindResourceOrThrow(kDoublePendulumSdfPath);
auto tree = std::make_unique<RigidBodyTree<double>>();
Expand Down
6 changes: 3 additions & 3 deletions examples/kinova_jaco_arm/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@ drake_cc_binary(
],
deps = [
":jaco_lcm",
"//common:add_text_logging_gflags",
"//common:find_resource",
"//common:text_logging_gflags",
"//lcm",
"//manipulation/planner:robot_plan_interpolator",
"//systems/analysis:simulator",
Expand All @@ -60,8 +60,8 @@ drake_cc_binary(
test_rule_args = ["--simulation_sec=0.1"],
deps = [
":jaco_lcm",
"//common:add_text_logging_gflags",
"//common:find_resource",
"//common:text_logging_gflags",
"//geometry:geometry_visualization",
"//geometry:scene_graph",
"//multibody/parsing",
Expand All @@ -80,8 +80,8 @@ drake_cc_binary(
],
deps = [
":jaco_lcm",
"//common:add_text_logging_gflags",
"//common:find_resource",
"//common:text_logging_gflags",
"//lcmtypes:jaco",
"//manipulation/planner:differential_inverse_kinematics",
"//math:geometric_transform",
Expand Down
1 change: 0 additions & 1 deletion examples/kinova_jaco_arm/jaco_controller.cc
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
#include "drake/common/drake_assert.h"
#include "drake/common/find_resource.h"
#include "drake/common/text_logging.h"
#include "drake/common/text_logging_gflags.h"
#include "drake/examples/kinova_jaco_arm/jaco_lcm.h"
#include "drake/lcm/drake_lcm.h"
#include "drake/lcmt_jaco_command.hpp"
Expand Down
2 changes: 0 additions & 2 deletions examples/kinova_jaco_arm/move_jaco_ee.cc
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@

#include "drake/common/find_resource.h"
#include "drake/common/text_logging.h"
#include "drake/common/text_logging_gflags.h"
#include "drake/lcmt_jaco_command.hpp"
#include "drake/lcmt_jaco_status.hpp"
#include "drake/manipulation/planner/differential_inverse_kinematics.h"
Expand Down Expand Up @@ -182,7 +181,6 @@ class MoveDemoRunner {

int main(int argc, char* argv[]) {
gflags::ParseCommandLineFlags(&argc, &argv, true);
drake::logging::HandleSpdlogGflags();
drake::examples::kinova_jaco_arm::MoveDemoRunner runner;
runner.Run();
}
Loading

0 comments on commit b7f7cdb

Please sign in to comment.