Skip to content

Commit

Permalink
van_der_pol: Add self-contained example Python bindings
Browse files Browse the repository at this point in the history
  • Loading branch information
EricCousineau-TRI committed Oct 11, 2018
1 parent a6e6f4a commit f503576
Show file tree
Hide file tree
Showing 7 changed files with 151 additions and 2 deletions.
2 changes: 2 additions & 0 deletions bindings/pydrake/examples/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,8 @@ drake_pybind_library(
],
)

# N.B. This is duplicated from `//examples/van_der_pol`, and will be removed
# as part of (#9645).
drake_pybind_library(
name = "van_der_pol_py",
cc_deps = [
Expand Down
3 changes: 3 additions & 0 deletions bindings/pydrake/examples/test/van_der_pol_test.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,6 @@
# N.B. This is duplicated from `//examples/van_der_pol`, and will be removed
# as part of (#9645).

from __future__ import print_function

import unittest
Expand Down
3 changes: 3 additions & 0 deletions bindings/pydrake/examples/van_der_pol_py.cc
Original file line number Diff line number Diff line change
@@ -1,3 +1,6 @@
// N.B. This is duplicated from `//examples/van_der_pol`, and will be removed
// as part of (#9645).

#include "pybind11/pybind11.h"

#include "drake/bindings/pydrake/documentation_pybind.h"
Expand Down
1 change: 1 addition & 0 deletions examples/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,7 @@ filegroup(
# issues #4224 and #1766).
INSTALLED_EXAMPLES = [
"//examples/kuka_iiwa_arm",
"//examples/van_der_pol",
]

install(
Expand Down
84 changes: 82 additions & 2 deletions examples/van_der_pol/BUILD.bazel
Original file line number Diff line number Diff line change
@@ -1,12 +1,26 @@
# -*- python -*-

load(
"//tools:drake.bzl",
"@drake//tools/skylark:drake_cc.bzl",
"drake_cc_binary",
"drake_cc_googletest",
"drake_cc_library",
)
load("//tools/lint:lint.bzl", "add_lint_tests")
load(
"@drake//tools/skylark:drake_py.bzl",
"drake_py_binary",
)
load(
"@drake//tools/skylark:pybind.bzl",
"drake_pybind_library",
"generate_pybind_documentation_header",
)
load(
"@drake//tools/install:install.bzl",
"generate_install_test_file",
"install",
)
load("@drake//tools/lint:lint.bzl", "add_lint_tests")

drake_cc_library(
name = "van_der_pol",
Expand Down Expand Up @@ -43,4 +57,70 @@ drake_cc_googletest(
],
)

# TODO(eric.cousineau): Try to hide more of these details for authoring Python
# binding examples.

generate_pybind_documentation_header(
name = "generate_documentation_pybind",
out = "documentation_pybind.h",
root_name = "van_der_pol_doc",
targets = [":van_der_pol"],
)

drake_cc_library(
name = "documentation_pybind",
hdrs = ["documentation_pybind.h"],
tags = ["nolint"],
)

van_der_pol_py = drake_pybind_library(
name = "van_der_pol_py",
# This is specific to `pydrake`.
add_install = 0,
cc_deps = [":documentation_pybind"],
cc_so_name = "van_der_pol",
cc_srcs = [
# To avoid ODR with static upstream dependencies of `:van_der_pol`, we
# will recompile the relevant source files.
"van_der_pol.cc",
"van_der_pol.h",
"van_der_pol_py.cc",
],
py_deps = ["//bindings/pydrake/systems:analysis_py"],
)

drake_py_binary(
name = "van_der_pol_py_example",
srcs = ["van_der_pol_example.py"],
add_test_rule = 1,
# N.B. Imports are only required by this binary in Bazel runfiles, because
# Bazel somehow munges the paths such that we do not already have access to
# `van_der_pol_py`. This will not be an issue for installation.
imports = ["."],
deps = ["van_der_pol_py"],
)

generate_install_test_file(
name = "test/van_der_pol_installed_test.py",
cmd = "{python} {install_dir}/share/drake/examples/van_der_pol/van_der_pol_example.py", # noqa
)

install(
name = "install",
install_tests = [
":test/van_der_pol_installed_test.py",
],
targets = [
van_der_pol_py.cc_so_target,
],
library_dest = "share/drake/examples/van_der_pol",
# N.B. We use `data` so that we may install the Python files; we should
# not be installing the Bazel-generated wrapper files.
data = [
"van_der_pol_example.py",
],
data_dest = "share/drake/examples/van_der_pol",
visibility = ["//visibility:public"],
)

add_lint_tests()
28 changes: 28 additions & 0 deletions examples/van_der_pol/van_der_pol_example.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
"""Provides example of running van_der_pol bindings.
To run from an installation, please execute:
python {install_dir}/share/drake/examples/van_der_pol/van_der_pol_example.py # noqa
"""

from __future__ import print_function

from pydrake.systems.analysis import Simulator

from van_der_pol import VanDerPolOscillator


van_der_pol = VanDerPolOscillator()

# Create the simulator.
simulator = Simulator(van_der_pol)
context = simulator.get_mutable_context()

# Set the initial state.
state = context.get_mutable_continuous_state_vector()
state.SetFromVector([0., 2.])

# Simulate (and make sure the state actually changes).
initial_state = state.CopyToVector()
simulator.StepTo(1.0)
print("Final state: {}".format(state.CopyToVector()))
32 changes: 32 additions & 0 deletions examples/van_der_pol/van_der_pol_py.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
#include "pybind11/pybind11.h"

#include "drake/bindings/pydrake/pydrake_pybind.h"
#include "drake/examples/van_der_pol/documentation_pybind.h"
#include "drake/examples/van_der_pol/van_der_pol.h"

namespace drake {
namespace pydrake {

PYBIND11_MODULE(van_der_pol, m) {
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
using namespace drake::systems;
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
using namespace drake::examples::van_der_pol;
constexpr auto& doc = van_der_pol_doc.drake.examples.van_der_pol;

m.doc() = "Bindings for the van_der_pol example.";

py::module::import("pydrake.systems.framework");

// TODO(eric.cousineau): At present, we only bind doubles.
// In the future, we will bind more scalar types, and enable scalar
// conversion.
using T = double;

py::class_<VanDerPolOscillator<T>, LeafSystem<T>>(m, "VanDerPolOscillator",
doc.VanDerPolOscillator.doc)
.def(py::init<>(), doc.VanDerPolOscillator.ctor.doc_3);
}

} // namespace pydrake
} // namespace drake

0 comments on commit f503576

Please sign in to comment.