diff --git a/Jenkinsfile b/Jenkinsfile index c22adb90..23d628aa 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -45,6 +45,49 @@ node('linux-jammy-unprovisioned') { } } } +node('linux-jammy-unprovisioned') { + timeout(600) { + ansiColor('xterm') { + def triggers = [] + if (env.BRANCH_NAME == 'main') { + triggers << cron('H H(7-8) * * *') + } + properties ([ + pipelineTriggers(triggers) + ]) + try { + dir('src') { + stage('checkout') { + checkout scm + } + } + dir('src/drake_bazel_external_legacy'){ + stage('bazel_external_legacy setup') { + sh '.github/setup' + } + stage('bazel_external_legacy build and test') { + sh '.github/ci_build_test' + } + } + } catch (e) { + if (env.BRANCH_NAME == 'main') { + emailext ( + subject: "Build failed in Jenkins: ${env.JOB_NAME} #${env.BUILD_NUMBER}", + body: "See <${env.BUILD_URL}display/redirect?page=changes>", + recipientProviders: [[$class: 'DevelopersRecipientProvider']], + to: '$DEFAULT_RECIPIENTS', + ) + } + throw e + } finally { + deleteDir() + dir("${env.WORKSPACE}@tmp") { + deleteDir() + } + } + } + } +} node('linux-jammy-unprovisioned') { timeout(600) { ansiColor('xterm') { diff --git a/drake_bazel_external/README.md b/drake_bazel_external/README.md index e953587a..86757ab8 100644 --- a/drake_bazel_external/README.md +++ b/drake_bazel_external/README.md @@ -1,6 +1,9 @@ # Bazel Project with Drake as an External -This pulls in Drake via the Bazel workspace mechanism. +This pulls in Drake and builds it from source via Bazel's WORKSPACE mechanism, +which is deprecated as of Bazel 8 and will be removed in Bazel 9. Therefore, +we will be rewriting this example to use Bazel modules ("bzlmod") in the near +future. Stay tuned! For an introduction to Bazel, refer to [Getting Started with Bazel](https://bazel.build/start). diff --git a/drake_bazel_external_legacy/.bazelignore b/drake_bazel_external_legacy/.bazelignore new file mode 100644 index 00000000..889b4e07 --- /dev/null +++ b/drake_bazel_external_legacy/.bazelignore @@ -0,0 +1,2 @@ +# Used for setup, do not build +drake-master diff --git a/drake_bazel_external_legacy/.bazelproject b/drake_bazel_external_legacy/.bazelproject new file mode 100644 index 00000000..47ea888f --- /dev/null +++ b/drake_bazel_external_legacy/.bazelproject @@ -0,0 +1,7 @@ +# SPDX-License-Identifier: MIT-0 + +directories: + . + +targets: + //...:all diff --git a/drake_bazel_external_legacy/.bazelrc b/drake_bazel_external_legacy/.bazelrc new file mode 100644 index 00000000..30f6a273 --- /dev/null +++ b/drake_bazel_external_legacy/.bazelrc @@ -0,0 +1,33 @@ +# SPDX-License-Identifier: MIT-0 + +# Don't use bzlmod yet. +common --enable_workspace=true +common --enable_bzlmod=false + +# Default to an optimized build. +build --compilation_mode=opt + +# Default build options. +build --strip=never + +# Default test options. +build --test_output=errors +build --test_summary=terse + +# Use C++20. +build --cxxopt=-std=c++20 +build --host_cxxopt=-std=c++20 + +# https://github.com/bazelbuild/bazel/issues/1164 +build --action_env=CCACHE_DISABLE=1 + +# For Ubuntu builds, this flag can cut build times in half. For macOS builds, +# this flag might cause build errors. We suggest turning it on if and only if +# your project doesn't use macOS. +## build --force_pic=yes + +# TODO(jwnimmer-tri) We should see if we can reuse more of Drake's +# customizations somehow. + +# Try to import user-specific configuration local to workspace. +try-import %workspace%/user.bazelrc diff --git a/drake_bazel_external_legacy/.bazelversion b/drake_bazel_external_legacy/.bazelversion new file mode 100644 index 00000000..ae9a76b9 --- /dev/null +++ b/drake_bazel_external_legacy/.bazelversion @@ -0,0 +1 @@ +8.0.0 diff --git a/drake_bazel_external_legacy/.clang-format b/drake_bazel_external_legacy/.clang-format new file mode 100644 index 00000000..57a1cc0b --- /dev/null +++ b/drake_bazel_external_legacy/.clang-format @@ -0,0 +1,22 @@ +# -*- mode: yaml -*- +# vi: set ft=yaml : +# SPDX-License-Identifier: MIT-0 + +--- +BasedOnStyle: Google +--- +Language: Cpp +DerivePointerAlignment: false +PointerAlignment: Left + +IncludeCategories: + - Regex: '^[<"](aio|arpa/inet|assert|complex|cpio|ctype|curses|dirent|dlfcn|errno|fcntl|fenv|float|fmtmsg|fnmatch|ftw|glob|grp|iconv|inttypes|iso646|langinfo|libgen|limits|locale|math|monetary|mqueue|ndbm|netdb|net/if|netinet/in|netinet/tcp|nl_types|poll|pthread|pwd|regex|sched|search|semaphore|setjmp|signal|spawn|stdalign|stdarg|stdatomic|stdbool|stddef|stdint|stdio|stdlib|stdnoreturn|string|strings|stropts|sys/ipc|syslog|sys/mman|sys/msg|sys/resource|sys/select|sys/sem|sys/shm|sys/socket|sys/stat|sys/statvfs|sys/time|sys/times|sys/types|sys/uio|sys/un|sys/utsname|sys/wait|tar|term|termios|tgmath|threads|time|trace|uchar|ulimit|uncntrl|unistd|utime|utmpx|wchar|wctype|wordexp)\.h[">]$' + Priority: 10 + - Regex: '^[<"](algorithm|array|atomic|bitset|cassert|ccomplex|cctype|cerrno|cfenv|cfloat|chrono|cinttypes|ciso646|climits|clocale|cmath|codecvt|complex|condition_variable|csetjmp|csignal|cstdalign|cstdarg|cstdbool|cstddef|cstdint|cstdio|cstdlib|cstring|ctgmath|ctime|cuchar|cwchar|cwctype|deque|exception|forward_list|fstream|functional|future|initializer_list|iomanip|ios|iosfwd|iostream|istream|iterator|limits|list|locale|map|memory|mutex|new|numeric|ostream|queue|random|ratio|regex|scoped_allocator|set|shared_mutex|sstream|stack|stdexcept|streambuf|string|strstream|system_error|thread|tuple|type_traits|typeindex|typeinfo|unordered_map|unordered_set|utility|valarray|vector)[">]$' + Priority: 20 + - Regex: '^<' + Priority: 30 + - Regex: '^"(drake|drake_external_examples)' + Priority: 50 + - Regex: '^"' + Priority: 40 diff --git a/drake_bazel_external_legacy/.github/ci_build_test b/drake_bazel_external_legacy/.github/ci_build_test new file mode 100755 index 00000000..672ca65e --- /dev/null +++ b/drake_bazel_external_legacy/.github/ci_build_test @@ -0,0 +1,7 @@ +#!/bin/bash +# SPDX-License-Identifier: MIT-0 + +set -euxo pipefail + +bazel version +bazel test //... diff --git a/drake_bazel_external_legacy/.github/setup b/drake_bazel_external_legacy/.github/setup new file mode 100755 index 00000000..daf45d54 --- /dev/null +++ b/drake_bazel_external_legacy/.github/setup @@ -0,0 +1,10 @@ +#!/bin/bash +# SPDX-License-Identifier: MIT-0 + +set -euxo pipefail + +# CI setup +sudo .github/ubuntu_setup + +# drake source setup +setup/install_prereqs diff --git a/drake_bazel_external_legacy/.github/ubuntu_setup b/drake_bazel_external_legacy/.github/ubuntu_setup new file mode 100755 index 00000000..c0d49e9d --- /dev/null +++ b/drake_bazel_external_legacy/.github/ubuntu_setup @@ -0,0 +1,22 @@ +#!/bin/bash +# SPDX-License-Identifier: MIT-0 + +set -euxo pipefail + +if [[ "${EUID:-}" -ne 0 ]]; then + echo 'This script must be run as root' >&2 + exit 2 +fi + +echo 'APT::Acquire::Retries "4";' > /etc/apt/apt.conf.d/80-acquire-retries +echo 'APT::Get::Assume-Yes "true";' > /etc/apt/apt.conf.d/90-get-assume-yes + +export DEBIAN_FRONTEND='noninteractive' + +apt-get update +apt-get install --no-install-recommends lsb-release + +if [[ "$(lsb_release -sc)" != 'jammy' ]]; then + echo 'This script requires Ubuntu 22.04 (Jammy)' >&2 + exit 3 +fi diff --git a/drake_bazel_external_legacy/.gitignore b/drake_bazel_external_legacy/.gitignore new file mode 100644 index 00000000..ad8d446d --- /dev/null +++ b/drake_bazel_external_legacy/.gitignore @@ -0,0 +1,4 @@ +# SPDX-License-Identifier: MIT-0 + +/bazel-* +/user.bazelrc diff --git a/drake_bazel_external_legacy/BUILD.bazel b/drake_bazel_external_legacy/BUILD.bazel new file mode 100644 index 00000000..9f1deb5b --- /dev/null +++ b/drake_bazel_external_legacy/BUILD.bazel @@ -0,0 +1,4 @@ +# SPDX-License-Identifier: MIT-0 + +# This is an empty BUILD file, to ensure that this project's root directory is +# a Bazel package. diff --git a/drake_bazel_external_legacy/CPPLINT.cfg b/drake_bazel_external_legacy/CPPLINT.cfg new file mode 100644 index 00000000..a5dd11fb --- /dev/null +++ b/drake_bazel_external_legacy/CPPLINT.cfg @@ -0,0 +1,7 @@ +# SPDX-License-Identifier: MIT-0 + +set noparent + +filter=-build/c++11 +filter=-build/header_guard +filter=-build/include_subdir diff --git a/drake_bazel_external_legacy/LICENSE b/drake_bazel_external_legacy/LICENSE new file mode 100644 index 00000000..cdacdc00 --- /dev/null +++ b/drake_bazel_external_legacy/LICENSE @@ -0,0 +1,16 @@ +Copyright (c) 2017-2023 by the drake-external-examples developers. + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/drake_bazel_external_legacy/README.md b/drake_bazel_external_legacy/README.md new file mode 100644 index 00000000..46818c19 --- /dev/null +++ b/drake_bazel_external_legacy/README.md @@ -0,0 +1,41 @@ +# Bazel Project with Drake as an External (legacy style) + +This pulls in Drake and builds it from source via Bazel's WORKSPACE mechanism, +which is deprecated as of Bazel 8 and will be removed in Bazel 9. Therefore, +we do not recommend using this example for new projects; instead, refer to +the `drake_bazel_external` example. The legacy example primarily serves +as a regression test for the deprecated behavior. + +For an introduction to Bazel, refer to +[Getting Started with Bazel](https://bazel.build/start). + +## Instructions + +First, run the `install_prereqs` script to download the drake source and run +drake's source setup script to install the required Ubuntu packages: + +``` +setup/install_prereqs.sh +``` + +Then, to build and test all apps: +``` +bazel test //... +``` + +As an example to run a binary directly: +``` +bazel run //apps:simple_logging_example +``` + +You may also run the binary directly per the `bazel-bin/...` path that the +above command prints out; however, be aware that your working directories may +cause differences. This is important when using tools like +`drake::FindResource` / `pydrake.common.FindResource`. +You may generally want to stick to using `bazel run` when able. + +## Python Versions + +By default, Python 3 is the Python interpreter that Drake will use when built +with Bazel. To see which Python versions are supported, see the +[supported configurations](https://drake.mit.edu/developers.html#supported-configurations). diff --git a/drake_bazel_external_legacy/WORKSPACE b/drake_bazel_external_legacy/WORKSPACE new file mode 100644 index 00000000..fd35af05 --- /dev/null +++ b/drake_bazel_external_legacy/WORKSPACE @@ -0,0 +1,55 @@ +# SPDX-License-Identifier: MIT-0 + +workspace(name = "drake_external_examples") + +DRAKE_COMMIT = "master" +DRAKE_CHECKSUM = "" + +# Or choose a specific revision of Drake to use. +# DRAKE_COMMIT = "be4f658487f739ba04ec079de46f9459b719636d" +# DRAKE_CHECKSUM = "31ec8f87df3ceb6516de3c33a14c5d59ac5c003b4faf93ac526877d2e150b394" +# +# You can also use DRAKE_COMMIT to choose a Drake release; eg: +# DRAKE_COMMIT = "v0.15.0" +# +# Before changing the COMMIT, temporarily uncomment the next line so that Bazel +# displays the suggested new value for the CHECKSUM. +# DRAKE_CHECKSUM = "0" * 64 + +# Or to temporarily build against a local checkout of Drake, at the bash prompt +# set an environment variable before building: +# export EXAMPLES_LOCAL_DRAKE_PATH=/home/user/stuff/drake + +# Load an environment variable. +load("//:environ.bzl", "environ_repository") +environ_repository(name = "environ", vars = ["EXAMPLES_LOCAL_DRAKE_PATH"]) +load("@environ//:environ.bzl", EXAMPLES_LOCAL_DRAKE_PATH = "EXAMPLES_LOCAL_DRAKE_PATH") + +# This declares the `@drake` repository as an http_archive from github, +# iff EXAMPLES_LOCAL_DRAKE_PATH is unset. When it is set, this declares a +# `@drake_ignored` package which is never referenced, and thus is ignored. +load("@bazel_tools//tools/build_defs/repo:http.bzl", "http_archive") +http_archive( + name = "drake" if not EXAMPLES_LOCAL_DRAKE_PATH else "drake_ignored", + urls = [x.format(DRAKE_COMMIT) for x in [ + "https://github.com/RobotLocomotion/drake/archive/{}.tar.gz", + ]], + sha256 = DRAKE_CHECKSUM, + strip_prefix = "drake-{}".format(DRAKE_COMMIT.lstrip("v")), +) + +# This declares the `@drake` repository as a local directory, +# iff EXAMPLES_LOCAL_DRAKE_PATH is set. When it is unset, this declares a +# `@drake_ignored` package which is never referenced, and thus is ignored. +local_repository( + name = "drake" if EXAMPLES_LOCAL_DRAKE_PATH else "drake_ignored", + path = EXAMPLES_LOCAL_DRAKE_PATH, +) +print("Using EXAMPLES_LOCAL_DRAKE_PATH={}".format(EXAMPLES_LOCAL_DRAKE_PATH)) if EXAMPLES_LOCAL_DRAKE_PATH else None # noqa + +# Reference external software libraries, tools, and toolchains per Drake's +# defaults. Some software will come from the host system (Ubuntu or macOS); +# other software will be downloaded in source or binary form from GitHub or +# other sites. +load("@drake//tools/workspace:default.bzl", "add_default_workspace") +add_default_workspace() diff --git a/drake_bazel_external_legacy/apps/BUILD.bazel b/drake_bazel_external_legacy/apps/BUILD.bazel new file mode 100644 index 00000000..6bdbed24 --- /dev/null +++ b/drake_bazel_external_legacy/apps/BUILD.bazel @@ -0,0 +1,106 @@ +# SPDX-License-Identifier: MIT-0 + +load("@drake//tools/skylark:py.bzl", "py_binary", "py_test") +load("@drake//tools/skylark:pybind.bzl", "pybind_py_library") + +# Compile a sample application. +cc_binary( + name = "simple_continuous_time_system", + srcs = ["simple_continuous_time_system.cc"], + deps = [ + "@drake//systems/analysis", + "@drake//systems/framework", + ], +) + +# Make a simple Python application. +py_binary( + name = "simple_logging_example", + srcs = ["simple_logging_example.py"], + deps = [ + "@drake//bindings/pydrake", + ], +) + +# This ensures that downstream Bazel projects can use Drake's `find_resource` +# functionality without needing to resort to environment variables. +py_test( + name = "find_resource_test", + srcs = ["find_resource_test.py"], + deps = [ + "@drake//bindings/pydrake", + ], +) + +# Run the applications to make sure they complete successfully. +# N.B. For actual development, you should prefer language-specific test rules, +# such as `cc_test` and `py_test`. +sh_test( + name = "simple_continuous_time_system_test", + size = "small", + srcs = [":simple_continuous_time_system"], +) + +sh_test( + name = "simple_logging_example_test", + size = "small", + srcs = ["exec.sh"], + args = ["$(location :simple_logging_example)"], + data = [":simple_logging_example"], +) + +# For custom bindings, you *must* link against `drake_shared_library` for *all* +# C++ libraries; not doing so will lead to ODR (One Definition Rule) linking +# issues. +cc_library( + name = "simple_adder", + srcs = [ + # While the `*-inl.h` pattern is not required, this does ensure that we + # test separate compilation and linking. + "simple_adder.cc", + "simple_adder-inl.h", + ], + hdrs = [ + "simple_adder.h", + ], + deps = [ + # N.B. Per the above comment, this does NOT link to static libraries + # (e.g. "@drake//systems/analysis"). + "@drake//:drake_shared_library", + ], +) + +# Show that the C++ functionality works as-is. +cc_test( + name = "simple_adder_test", + srcs = ["simple_adder_test.cc"], + deps = [":simple_adder"], +) + +pybind_py_library( + name = "simple_adder_py", + cc_so_name = "simple_adder", + cc_srcs = ["simple_adder_py.cc"], + cc_deps = [ + ":simple_adder", + "@drake//bindings/pydrake/common:cpp_template_pybind", + "@drake//bindings/pydrake/common:default_scalars_pybind", + ], + py_deps = ["@drake//bindings/pydrake"], + py_imports = ["."], +) + +# Mimic the C++ test in Python to show the bindings. +py_test( + name = "simple_adder_py_test", + srcs = ["simple_adder_py_test.py"], + deps = [":simple_adder_py"], +) + +py_test( + name = "import_all_test", + srcs = ["import_all_test.py"], + deps = [ + "@drake//bindings/pydrake", + ], +) diff --git a/drake_bazel_external_legacy/apps/exec.sh b/drake_bazel_external_legacy/apps/exec.sh new file mode 100755 index 00000000..9898af2e --- /dev/null +++ b/drake_bazel_external_legacy/apps/exec.sh @@ -0,0 +1,6 @@ +#!/bin/bash +# SPDX-License-Identifier: MIT-0 + +# Proxy script for things such as passing a `py_binary` to a `sh_test`, since +# we cannot list the Python binary in `srcs` for the test. +exec "$@" diff --git a/drake_bazel_external_legacy/apps/find_resource_test.py b/drake_bazel_external_legacy/apps/find_resource_test.py new file mode 100644 index 00000000..6bf8bf64 --- /dev/null +++ b/drake_bazel_external_legacy/apps/find_resource_test.py @@ -0,0 +1,16 @@ +# SPDX-License-Identifier: MIT-0 + +""" +Provides an example (and test) of finding resources with Python from a Bazel +project. +""" + +import logging + +from pydrake.common import FindResourceOrThrow + +# If you have trouble finding resources, you can enable debug logging to see +# how `FindResource*` is searching. +logging.getLogger("drake").setLevel(logging.DEBUG) + +FindResourceOrThrow("drake/examples/pendulum/Pendulum.urdf") diff --git a/drake_bazel_external_legacy/apps/import_all_test.py b/drake_bazel_external_legacy/apps/import_all_test.py new file mode 100644 index 00000000..86cff92e --- /dev/null +++ b/drake_bazel_external_legacy/apps/import_all_test.py @@ -0,0 +1,7 @@ +# SPDX-License-Identifier: MIT-0 + +""" +Provides an example of importing all modules available in pydrake. +""" + +import pydrake.all diff --git a/drake_bazel_external_legacy/apps/simple_adder-inl.h b/drake_bazel_external_legacy/apps/simple_adder-inl.h new file mode 100644 index 00000000..8107b486 --- /dev/null +++ b/drake_bazel_external_legacy/apps/simple_adder-inl.h @@ -0,0 +1,37 @@ +// SPDX-License-Identifier: MIT-0 + +/** + * @file + * Provides an example of creating a simple Drake C++ system that will later be + * bound. + * + * This is the definition portion of the -inl.h pattern: + * http://drake.mit.edu/cxx_inl.html#cxx-inl-files + */ + +#include "simple_adder.h" + +namespace drake_external_examples { + +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::LeafSystem; +using drake::systems::kVectorValued; + +template +SimpleAdder::SimpleAdder(T add) + : add_(add) { + this->DeclareInputPort("in", kVectorValued, 1); + this->DeclareVectorOutputPort( + "out", BasicVector(1), &SimpleAdder::CalcOutput); +} + +template +void SimpleAdder::CalcOutput( + const Context& context, BasicVector* output) const { + auto u = this->get_input_port(0).Eval(context); + auto&& y = output->get_mutable_value(); + y.array() = u.array() + add_; +} + +} // namespace drake_external_examples diff --git a/drake_bazel_external_legacy/apps/simple_adder.cc b/drake_bazel_external_legacy/apps/simple_adder.cc new file mode 100644 index 00000000..a125887c --- /dev/null +++ b/drake_bazel_external_legacy/apps/simple_adder.cc @@ -0,0 +1,17 @@ +// SPDX-License-Identifier: MIT-0 + +/** + * @file + * Provides an example of creating a simple Drake C++ system that will later be + * bound. + * + * This is the instantiation portion of the -inl.h pattern: + * http://drake.mit.edu/cxx_inl.html#cxx-inl-files + */ + +#include "simple_adder-inl.h" + +#include + +DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS( + class ::drake_external_examples::SimpleAdder); diff --git a/drake_bazel_external_legacy/apps/simple_adder.h b/drake_bazel_external_legacy/apps/simple_adder.h new file mode 100644 index 00000000..f2921df2 --- /dev/null +++ b/drake_bazel_external_legacy/apps/simple_adder.h @@ -0,0 +1,30 @@ +// SPDX-License-Identifier: MIT-0 + +/** + * @file + * Provides an example of creating a simple Drake C++ system that will later be + * bound. + * + * This is the header portion of the -inl.h pattern: + * http://drake.mit.edu/cxx_inl.html#cxx-inl-files + */ + +#include + +namespace drake_external_examples { + +/// Adds a constant to an input. +template +class SimpleAdder : public drake::systems::LeafSystem { + public: + explicit SimpleAdder(T add); + + private: + void CalcOutput( + const drake::systems::Context& context, + drake::systems::BasicVector* output) const; + + const T add_{}; +}; + +} // namespace drake_external_examples diff --git a/drake_bazel_external_legacy/apps/simple_adder_py.cc b/drake_bazel_external_legacy/apps/simple_adder_py.cc new file mode 100644 index 00000000..f8947d91 --- /dev/null +++ b/drake_bazel_external_legacy/apps/simple_adder_py.cc @@ -0,0 +1,42 @@ +// SPDX-License-Identifier: MIT-0 + +/** + * @file + * Provides an example of binding a simple Drake C++ system in pybind11, to be + * used with pydrake. + */ + +#include + +#include "drake/bindings/pydrake/common/cpp_template_pybind.h" +#include "drake/bindings/pydrake/common/default_scalars_pybind.h" + +#include "simple_adder.h" + +namespace py = pybind11; + +using drake::pydrake::CommonScalarPack; +using drake::pydrake::DefineTemplateClassWithDefault; +using drake::pydrake::GetPyParam; +using drake::systems::LeafSystem; + +namespace drake_external_examples { +namespace { + +PYBIND11_MODULE(simple_adder, m) { + m.doc() = "Example module interfacing with pydrake and Drake C++"; + + py::module::import("pydrake.systems.framework"); + + auto bind_common_scalar_types = [m](auto dummy) { + using T = decltype(dummy); + + DefineTemplateClassWithDefault, LeafSystem>( + m, "SimpleAdder", GetPyParam()) + .def(py::init(), py::arg("add")); + }; + type_visit(bind_common_scalar_types, CommonScalarPack{}); +} + +} // namespace +} // namespace drake_external_examples diff --git a/drake_bazel_external_legacy/apps/simple_adder_py_test.py b/drake_bazel_external_legacy/apps/simple_adder_py_test.py new file mode 100644 index 00000000..13abdc5b --- /dev/null +++ b/drake_bazel_external_legacy/apps/simple_adder_py_test.py @@ -0,0 +1,56 @@ +# SPDX-License-Identifier: MIT-0 + +""" +Provides an example of using pybind11-bound Drake C++ system with pydrake. +""" + +from __future__ import print_function + +from simple_adder import SimpleAdder, SimpleAdder_ + +import numpy as np + +from pydrake.autodiffutils import AutoDiffXd +from pydrake.symbolic import Expression +from pydrake.systems.analysis import Simulator +from pydrake.systems.framework import DiagramBuilder +from pydrake.systems.primitives import ( + ConstantVectorSource, + VectorLogSink, +) + + +def main(): + # Simulate with doubles. + builder = DiagramBuilder() + source = builder.AddSystem(ConstantVectorSource([10.])) + adder = builder.AddSystem(SimpleAdder(100.)) + builder.Connect(source.get_output_port(0), adder.get_input_port(0)) + logger = builder.AddSystem(VectorLogSink(1)) + builder.Connect(adder.get_output_port(0), logger.get_input_port(0)) + diagram = builder.Build() + + simulator = Simulator(diagram) + simulator.AdvanceTo(1) + + x = logger.FindLog(simulator.get_context()).data() + print("Output values: {}".format(x)) + assert np.allclose(x, 110.) + + # Compute outputs with AutoDiff and Symbolic. + for T in (AutoDiffXd, Expression): + adder_T = SimpleAdder_[T](100.) + context = adder_T.CreateDefaultContext() + adder_T.get_input_port().FixValue(context, [10.]) + output = adder_T.AllocateOutput() + adder_T.CalcOutput(context, output) + # N.B. At present, you cannot get a reference to existing AutoDiffXd + # or Expression numpy arrays, so we will explictly copy the vector: + # https://github.com/RobotLocomotion/drake/issues/8116 + value, = output.get_vector_data(0).CopyToVector() + assert isinstance(value, T) + print("Output from {}: {}".format(type(adder_T), repr(value))) + + +if __name__ == "__main__": + main() diff --git a/drake_bazel_external_legacy/apps/simple_adder_test.cc b/drake_bazel_external_legacy/apps/simple_adder_test.cc new file mode 100644 index 00000000..9e6c8c15 --- /dev/null +++ b/drake_bazel_external_legacy/apps/simple_adder_test.cc @@ -0,0 +1,53 @@ +// SPDX-License-Identifier: MIT-0 + +/** + * @file + * Provides an example of testing a custom C++ Drake system which will also + * be bound in Python. + */ + +#include + +#include +#include +#include +#include +#include + +#include "simple_adder.h" + +using drake::systems::Simulator; +using drake::systems::DiagramBuilder; +using drake::systems::ConstantVectorSource; +using drake::systems::VectorLogSink; + +namespace drake_external_examples { +namespace { + +int DoMain() { + DiagramBuilder builder; + auto source = builder.AddSystem>( + Eigen::VectorXd::Constant(1, 10.)); + auto adder = builder.AddSystem>(100.); + builder.Connect(source->get_output_port(), adder->get_input_port(0)); + auto logger = builder.AddSystem>(1); + builder.Connect(adder->get_output_port(0), logger->get_input_port()); + auto diagram = builder.Build(); + + Simulator simulator(*diagram); + simulator.AdvanceTo(1); + + auto x = logger->FindLog(simulator.get_context()).data(); + Eigen::VectorXd x_expected = Eigen::Vector2d(110., 110.); + std::cout << "Output values: " << x << std::endl; + DRAKE_DEMAND(x.isApprox(x_expected.transpose())); + + return 0; +} + +} // namespace +} // namespace drake_external_examples + +int main() { + return drake_external_examples::DoMain(); +} diff --git a/drake_bazel_external_legacy/apps/simple_continuous_time_system.cc b/drake_bazel_external_legacy/apps/simple_continuous_time_system.cc new file mode 100644 index 00000000..1a706e8f --- /dev/null +++ b/drake_bazel_external_legacy/apps/simple_continuous_time_system.cc @@ -0,0 +1,72 @@ +// SPDX-License-Identifier: MIT-0 + +// Simple Continuous Time System Example +// +// This is meant to be a sort of "hello world" example for the drake::system +// classes. It defines a very simple continuous time system and simulates it +// from a given initial condition. + +#include + +#include +#include +#include +#include +#include +#include + +namespace drake_external_examples { +namespace systems { + +// Simple Continuous Time System +// xdot = -x + x³ +// y = x +class SimpleContinuousTimeSystem : public drake::systems::LeafSystem { + public: + SimpleContinuousTimeSystem() { + DeclareVectorOutputPort("y", drake::systems::BasicVector(1), + &SimpleContinuousTimeSystem::CopyStateOut); + DeclareContinuousState(1); // One state variable. + } + + private: + // xdot = -x + x³ + void DoCalcTimeDerivatives( + const drake::systems::Context& context, + drake::systems::ContinuousState* derivatives) const override { + const double x = context.get_continuous_state()[0]; + const double xdot = -x + std::pow(x, 3.0); + (*derivatives)[0] = xdot; + } + + // y = x + void CopyStateOut(const drake::systems::Context& context, + drake::systems::BasicVector* output) const { + const double x = context.get_continuous_state()[0]; + (*output)[0] = x; + } +}; + +} // namespace systems +} // namespace drake_external_examples + +int main() { + // Create the simple system. + drake_external_examples::systems::SimpleContinuousTimeSystem system; + + // Create the simulator. + drake::systems::Simulator simulator(system); + + // Set the initial conditions x(0). + drake::systems::ContinuousState& state = + simulator.get_mutable_context().get_mutable_continuous_state(); + state[0] = 0.9; + + // Simulate for 10 seconds. + simulator.AdvanceTo(10); + + // Make sure the simulation converges to the stable fixed point at x = 0. + DRAKE_DEMAND(state[0] < 1.0e-4); + + return 0; +} diff --git a/drake_bazel_external_legacy/apps/simple_logging_example.py b/drake_bazel_external_legacy/apps/simple_logging_example.py new file mode 100644 index 00000000..d38e24e5 --- /dev/null +++ b/drake_bazel_external_legacy/apps/simple_logging_example.py @@ -0,0 +1,37 @@ +# SPDX-License-Identifier: MIT-0 + +""" +Provides an example of using pydrake from a Bazel external. +""" + +from __future__ import print_function + +import numpy as np + +from pydrake.systems.analysis import Simulator +from pydrake.systems.framework import ( + DiagramBuilder, +) +from pydrake.systems.primitives import ( + ConstantVectorSource, + VectorLogSink, +) + + +def main(): + builder = DiagramBuilder() + source = builder.AddSystem(ConstantVectorSource([10.])) + logger = builder.AddSystem(VectorLogSink(1)) + builder.Connect(source.get_output_port(0), logger.get_input_port(0)) + diagram = builder.Build() + + simulator = Simulator(diagram) + simulator.AdvanceTo(1) + + x = logger.FindLog(simulator.get_context()).data() + print("Output values: {}".format(x)) + assert np.allclose(x, 10.) + + +if __name__ == "__main__": + main() diff --git a/drake_bazel_external_legacy/environ.bzl b/drake_bazel_external_legacy/environ.bzl new file mode 100644 index 00000000..1403d12b --- /dev/null +++ b/drake_bazel_external_legacy/environ.bzl @@ -0,0 +1,45 @@ +# SPDX-License-Identifier: MIT-0 + +# Write out a repository that contains: +# - An empty BUILD file, to define a package. +# - An environ.bzl file with variable assignments for each ENV_NAMES item. +def _impl(repository_ctx): + vars = repository_ctx.attr.vars + bzl_content = [] + for key in vars: + value = repository_ctx.os.environ.get(key, "") + bzl_content.append("{}='{}'\n".format(key, value)) + repository_ctx.file( + "BUILD.bazel", + content = "\n", + executable = False, + ) + repository_ctx.file( + "environ.bzl", + content = "".join(bzl_content), + executable = False, + ) + +_string_list = attr.string_list() + +def environ_repository(name = None, vars = []): + """Provide specific environment variables for use in a WORKSPACE file. + The `vars` are the environment variables to provide. + + Example: + environ_repository(name = "foo", vars = ["BAR", "BAZ"]) + load("@foo//:environ.bzl", "BAR", "BAZ") + print(BAR) + """ + rule = repository_rule( + implementation = _impl, + attrs = { + "vars": _string_list, + }, + local = True, + environ = vars, + ) + rule( + name = name, + vars = vars, + ) diff --git a/drake_bazel_external_legacy/setup/install_prereqs b/drake_bazel_external_legacy/setup/install_prereqs new file mode 100755 index 00000000..b91143ed --- /dev/null +++ b/drake_bazel_external_legacy/setup/install_prereqs @@ -0,0 +1,48 @@ +#!/bin/bash + +# Copyright (c) 2020, Massachusetts Institute of Technology. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright notice, this +# list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright notice, +# this list of conditions and the following disclaimer in the documentation +# and/or other materials provided with the distribution. +# +# * Neither the name of the copyright holder nor the names of its contributors +# may be used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +set -euxo pipefail + +sudo apt-get install --no-install-recommends $(cat <