Skip to content

Commit

Permalink
Merge pull request #7766 from RussTedrake/py_pendulum
Browse files Browse the repository at this point in the history
initial bindings for pendulum example
  • Loading branch information
RussTedrake authored Jan 18, 2018
2 parents cef91e9 + 5f701b3 commit 3b3b395
Show file tree
Hide file tree
Showing 5 changed files with 170 additions and 0 deletions.
1 change: 1 addition & 0 deletions bindings/pydrake/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,7 @@ PYBIND_LIBRARIES = adjust_labels_for_drake_hoist([
":parsers_py",
":rbtree_py",
":symbolic_py",
"//drake/bindings/pydrake/examples",
"//drake/bindings/pydrake/solvers",
"//drake/bindings/pydrake/systems",
"//drake/bindings/pydrake/util",
Expand Down
89 changes: 89 additions & 0 deletions bindings/pydrake/examples/BUILD.bazel
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
# -*- python -*-

load("@drake//tools/install:install.bzl", "install")
load("//tools/lint:lint.bzl", "add_lint_tests")
load(
"//tools/skylark:pybind.bzl",
"drake_pybind_library",
"get_drake_pybind_installs",
"get_pybind_package_info",
)
load(
"//tools/skylark:drake_py.bzl",
"drake_py_binary",
"drake_py_library",
"drake_py_test",
)
load(
"//tools/skylark:6996.bzl",
"adjust_label_for_drake_hoist",
"adjust_labels_for_drake_hoist",
)

package(default_visibility = adjust_labels_for_drake_hoist([
"//drake/bindings/pydrake:__subpackages__",
]))

# This determines how `PYTHONPATH` is configured, and how to install the
# bindings.
PACKAGE_INFO = get_pybind_package_info(
base_package = adjust_label_for_drake_hoist("//drake/bindings"),
)

# @note Symbols are NOT imported directly into
# `__init__.py` to simplify dependency management, meaning that
# classes are organized by their directory structure rather than
# by C++ namespace.
drake_py_library(
name = "module_py",
srcs = ["__init__.py"],
imports = PACKAGE_INFO.py_imports,
deps = [
"//drake/bindings/pydrake:common_py",
],
)

drake_pybind_library(
name = "pendulum_py",
cc_deps = [
"//drake/examples/pendulum:pendulum_plant",
],
cc_so_name = "pendulum",
cc_srcs = ["pendulum_py.cc"],
package_info = PACKAGE_INFO,
py_deps = [
":module_py",
],
)

PYBIND_LIBRARIES = [
":pendulum_py",
]

PY_LIBRARIES = [
":module_py",
]

drake_py_library(
name = "examples",
imports = PACKAGE_INFO.py_imports,
deps = PYBIND_LIBRARIES + PY_LIBRARIES,
)

install(
name = "install",
targets = PY_LIBRARIES,
py_dest = PACKAGE_INFO.py_dest,
deps = get_drake_pybind_installs(PYBIND_LIBRARIES),
)

drake_py_test(
name = "pendulum_test",
size = "small",
deps = [
":pendulum_py",
"//drake/bindings/pydrake/systems",
],
)

add_lint_tests()
1 change: 1 addition & 0 deletions bindings/pydrake/examples/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
# Blank Python module.
29 changes: 29 additions & 0 deletions bindings/pydrake/examples/pendulum_py.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
#include <pybind11/eigen.h>
#include <pybind11/pybind11.h>

#include "drake/examples/pendulum/pendulum_plant.h"

namespace py = pybind11;

using std::make_unique;
using std::unique_ptr;
using std::vector;

PYBIND11_MODULE(pendulum, m) {
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
using namespace drake;
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
using namespace drake::systems;
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
using namespace drake::examples::pendulum;

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

// 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_<PendulumPlant<T>, LeafSystem<T>>(m, "PendulumPlant")
.def(py::init<>());
}
50 changes: 50 additions & 0 deletions bindings/pydrake/examples/test/pendulum_test.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
#!/usr/bin/env python

from __future__ import print_function

import copy
import unittest
import numpy as np

import pydrake.systems.framework as framework
from pydrake.examples.pendulum import (
PendulumPlant,
)
from pydrake.systems.analysis import (
Simulator
)
from pydrake.systems.primitives import (
ConstantVectorSource,
)


class TestPendulum(unittest.TestCase):
def test_simulation(self):
# Basic constant-torque pendulum simulation.

builder = framework.DiagramBuilder()

pendulum = builder.AddSystem(PendulumPlant())
source = builder.AddSystem(ConstantVectorSource([1.0]))

builder.Connect(source.get_output_port(0),
pendulum.get_input_port(0))

diagram = builder.Build()
simulator = Simulator(diagram)
simulator.Initialize()

# TODO(russt): Clean up state vector access below.
state = simulator.get_mutable_context().get_mutable_state()\
.get_mutable_continuous_state().get_mutable_vector()

initial_state = np.array([1.0, 0.0])
state.SetFromVector(initial_state)

simulator.StepTo(1.0)

self.assertFalse((state.CopyToVector() == initial_state).all())


if __name__ == '__main__':
unittest.main()

0 comments on commit 3b3b395

Please sign in to comment.