Skip to content

Commit

Permalink
Merge pull request #8104 from EricCousineau-TRI/issue/8041
Browse files Browse the repository at this point in the history
 drake_py: Add mechanism for #8041 to prevent submodule shadowing
  • Loading branch information
jwnimmer-tri authored Feb 20, 2018
2 parents 8f68c27 + 91b0038 commit 080db50
Show file tree
Hide file tree
Showing 10 changed files with 94 additions and 24 deletions.
12 changes: 2 additions & 10 deletions bindings/pydrake/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ drake_py_library(

drake_pybind_library(
name = "math_py",
cc_so_name = "_math",
cc_so_name = "math",
cc_srcs = ["math_py.cc"],
package_info = PACKAGE_INFO,
py_deps = [
Expand Down Expand Up @@ -222,21 +222,13 @@ drake_py_test(
)

drake_py_test(
# Note the non-standard name due to #8041.
name = "test/math_test",
name = "math_test",
size = "small",
srcs = ["test/math_test.py"],
main = "test/math_test.py",
deps = [
":math_py",
],
)

alias(
name = "math_test",
actual = "test/math_test",
)

drake_py_test(
name = "symbolic_variables_test",
size = "small",
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/all.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
from .autodiffutils import *
from .common import *
from .forwarddiff import *
from ._math import *
from .math import *
from .symbolic import *

# Submodules.
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/math_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
namespace drake {
namespace pydrake {

PYBIND11_MODULE(_math, m) {
PYBIND11_MODULE(math, m) {
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
using namespace drake::math;

Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/systems/controllers_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ PYBIND11_MODULE(controllers, m) {
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
using namespace drake::systems::controllers;

py::module::import("pydrake._math");
py::module::import("pydrake.math");
py::module::import("pydrake.symbolic");
py::module::import("pydrake.systems.primitives");

Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/systems/test/controllers_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@

from pydrake.examples.pendulum import PendulumPlant
from pydrake.systems.analysis import Simulator
from pydrake._math import BarycentricMesh
from pydrake.math import BarycentricMesh
from pydrake.systems.controllers import (
DynamicProgrammingOptions, FittedValueIteration,
LinearProgrammingApproximateDynamicProgramming,
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/test/math_test.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
from __future__ import absolute_import, division, print_function

import unittest
from pydrake._math import BarycentricMesh
from pydrake.math import BarycentricMesh
import numpy as np


Expand Down
6 changes: 4 additions & 2 deletions tools/lint/bazel_lint.bzl
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
# -*- mode: python -*-
# vi: set ft=python :

load("//tools/skylark:drake_py.bzl", "py_test_isolated")

#------------------------------------------------------------------------------
# Internal helper; set up test given name and list of files. Will do nothing
# if no files given.
Expand All @@ -11,7 +13,7 @@ def _bazel_lint(name, files, ignore):

locations = ["$(locations %s)" % f for f in files]

native.py_test(
py_test_isolated(
name = name + "_codestyle",
size = "small",
srcs = ["@drake//tools/lint:bzlcodestyle"],
Expand All @@ -22,7 +24,7 @@ def _bazel_lint(name, files, ignore):
tags = ["bzlcodestyle", "lint"],
)

native.py_test(
py_test_isolated(
name = name + "_buildifier",
size = "small",
srcs = ["@drake//tools/lint:buildifier"],
Expand Down
6 changes: 4 additions & 2 deletions tools/lint/cpplint.bzl
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
# -*- python -*-

load("//tools/skylark:drake_py.bzl", "py_test_isolated")

# From https://bazel.build/versions/master/docs/be/c-cpp.html#cc_library.srcs
_SOURCE_EXTENSIONS = [source_ext for source_ext in """
.c
Expand Down Expand Up @@ -63,7 +65,7 @@ def _add_linter_rules(source_labels, source_filenames, name, data = None):
])

# Google cpplint.
native.py_test(
py_test_isolated(
name = name + "_cpplint",
srcs = ["@styleguide//:cpplint"],
data = data + cpplint_cfg + source_labels,
Expand All @@ -74,7 +76,7 @@ def _add_linter_rules(source_labels, source_filenames, name, data = None):
)

# Additional Drake lint.
native.py_test(
py_test_isolated(
name = name + "_drake_lint",
srcs = ["@drake//tools/lint:drakelint"],
data = data + source_labels,
Expand Down
4 changes: 3 additions & 1 deletion tools/lint/python_lint.bzl
Original file line number Diff line number Diff line change
@@ -1,14 +1,16 @@
# -*- mode: python -*-
# vi: set ft=python :

load("//tools/skylark:drake_py.bzl", "py_test_isolated")

#------------------------------------------------------------------------------
# Internal helper; set up test given name and list of files. Will do nothing
# if no files given.
def _python_lint(name, files, ignore):
if ignore:
ignore = ["--ignore=" + ",".join(["E%s" % e for e in ignore])]

native.py_test(
py_test_isolated(
name = name,
size = "small",
srcs = ["@pycodestyle//:pycodestyle"],
Expand Down
80 changes: 76 additions & 4 deletions tools/skylark/drake_py.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -18,19 +18,70 @@ def drake_py_library(
data = data,
**kwargs)

def _py_target_isolated(
name,
py_target = None,
srcs = None,
main = None,
isolate = True,
visibility = None,
**kwargs):
# See #8041 for more details.
if py_target == None:
fail("Must supply macro function for defining `py_target`.")
# Do not isolate targets that are already isolated. This generally happens
# when linting tests (which are isolated) are invoked for isolated Python
# targets. Without this check, the actual test turns into
# `_isolated/_isolated/{name}`.
prefix = "_isolated/"
if isolate and not name.startswith(prefix):
actual = prefix + name
# Preserve original functionality.
if not main:
main = name + ".py"
if not srcs:
srcs = [name + ".py"]
py_target(
name = actual,
srcs = srcs,
main = main,
visibility = ["//visibility:private"],
**kwargs)
native.alias(
name = name,
actual = actual,
visibility = visibility,
)
else:
py_target(
name = name,
srcs = srcs,
main = main,
visibility = visibility,
**kwargs)

def drake_py_binary(
name,
srcs = None,
deps = None,
data = None,
isolate = False,
**kwargs):
"""A wrapper to insert Drake-specific customizations."""
"""A wrapper to insert Drake-specific customizations.
@param isolate (optional, default is False)
If True, the binary will be placed in a folder isolated from the
library code. This prevents submodules from leaking in as top-level
submodules. For more detail, see #8041.
"""
deps = adjust_labels_for_drake_hoist(deps)
data = adjust_labels_for_drake_hoist(data)
# Work around https://github.com/bazelbuild/bazel/issues/1567.
deps = (deps or []) + ["//:module_py"]
native.py_binary(
_py_target_isolated(
name = name,
py_target = native.py_binary,
isolate = isolate,
srcs = srcs,
deps = deps,
data = data,
Expand All @@ -41,17 +92,38 @@ def drake_py_test(
srcs = None,
deps = None,
data = None,
isolate = True,
**kwargs):
"""A wrapper to insert Drake-specific customizations."""
"""A wrapper to insert Drake-specific customizations.
@param isolate (optional, default is True)
If True, the test binary will be placed in a folder isolated from the
library code. This prevents submodules from leaking in as top-level
submodules. For more detail, see #8041.
"""
if srcs == None:
srcs = ["test/%s.py" % name]
deps = adjust_labels_for_drake_hoist(deps)
data = adjust_labels_for_drake_hoist(data)
# Work around https://github.com/bazelbuild/bazel/issues/1567.
deps = (deps or []) + ["//:module_py"]
native.py_test(
_py_target_isolated(
name = name,
py_target = native.py_test,
isolate = isolate,
srcs = srcs,
deps = deps,
data = data,
**kwargs)

def py_test_isolated(
name,
**kwargs):
"""Provides a directory-isolated Python test, robust against shadowing
(#8041).
"""
_py_target_isolated(
name = name,
py_target = native.py_test,
isolate = True,
**kwargs)

0 comments on commit 080db50

Please sign in to comment.