Skip to content

Commit

Permalink
Clean up van der Pol oscillator example
Browse files Browse the repository at this point in the history
Push limit cycle into main class (as a static method) a replace the CallMatlab visualization with a few lines of python matplotlib.
Add missing python bindings
Lots of small cleanup touches.
  • Loading branch information
RussTedrake committed Mar 24, 2019
1 parent 36b6c4c commit 5d45081
Show file tree
Hide file tree
Showing 8 changed files with 109 additions and 85 deletions.
13 changes: 13 additions & 0 deletions bindings/pydrake/examples/test/van_der_pol_test.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
from __future__ import print_function

import numpy as np
import unittest

from pydrake.examples.van_der_pol import VanDerPolOscillator
Expand All @@ -22,3 +23,15 @@ def test_simulation(self):
initial_state = state.CopyToVector()
simulator.StepTo(1.0)
self.assertFalse((state.CopyToVector() == initial_state).any())

def test_ports(self):
vdp = VanDerPolOscillator()

self.assertTrue(vdp.get_position_output_port().get_index().is_valid())
self.assertTrue(
vdp.get_full_state_output_port().get_index().is_valid())

def test_limit_cycle(self):
cycle = VanDerPolOscillator.CalcLimitCycle()

np.testing.assert_almost_equal(cycle[:, 0], cycle[:, -1], 2)
13 changes: 12 additions & 1 deletion bindings/pydrake/examples/van_der_pol_py.cc
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
#include "pybind11/eigen.h"
#include "pybind11/pybind11.h"

#include "drake/bindings/pydrake/documentation_pybind.h"
Expand Down Expand Up @@ -25,7 +26,17 @@ PYBIND11_MODULE(van_der_pol, m) {

py::class_<VanDerPolOscillator<T>, LeafSystem<T>>(
m, "VanDerPolOscillator", doc.VanDerPolOscillator.doc)
.def(py::init<>(), doc.VanDerPolOscillator.ctor.doc);
.def(py::init<>(), doc.VanDerPolOscillator.ctor.doc)
.def("get_position_output_port",
&VanDerPolOscillator<T>::get_position_output_port,
py_reference_internal,
doc.VanDerPolOscillator.get_position_output_port.doc)
.def("get_full_state_output_port",
&VanDerPolOscillator<T>::get_full_state_output_port,
py_reference_internal,
doc.VanDerPolOscillator.get_full_state_output_port.doc)
.def_static("CalcLimitCycle", &VanDerPolOscillator<T>::CalcLimitCycle,
doc.VanDerPolOscillator.CalcLimitCycle.doc);
}

} // namespace pydrake
Expand Down
20 changes: 11 additions & 9 deletions examples/van_der_pol/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,10 @@ load(
"drake_cc_googletest",
"drake_cc_library",
)
load(
"@drake//tools/skylark:drake_py.bzl",
"drake_py_binary",
)
load("//tools/lint:lint.bzl", "add_lint_tests")

package(default_visibility = ["//visibility:private"])
Expand All @@ -16,24 +20,22 @@ drake_cc_library(
hdrs = ["van_der_pol.h"],
visibility = ["//visibility:public"],
deps = [
"//systems/analysis:simulator",
"//systems/framework:diagram_builder",
"//systems/framework:leaf_system",
"//systems/framework:system_constraint",
"//systems/framework:vector",
"//systems/primitives:signal_logger",
],
)

drake_cc_binary(
drake_py_binary(
name = "plot_limit_cycle",
testonly = 1,
srcs = ["plot_limit_cycle.cc"],
srcs = ["plot_limit_cycle.py"],
add_test_rule = 1,
test_rule_args = ["--test"],
deps = [
"van_der_pol",
"//common:is_approx_equal_abstol",
"//common/proto:call_matlab",
"//systems/analysis:simulator",
"//systems/framework",
"//systems/primitives:signal_logger",
"//bindings/pydrake",
],
)

Expand Down
67 changes: 0 additions & 67 deletions examples/van_der_pol/plot_limit_cycle.cc

This file was deleted.

23 changes: 23 additions & 0 deletions examples/van_der_pol/plot_limit_cycle.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
import argparse
import matplotlib.pyplot as plt

from pydrake.examples.van_der_pol import VanDerPolOscillator

parser = argparse.ArgumentParser()
parser.add_argument("--test",
action='store_true',
help="Run without blocking for user input.",
default=False)
args = parser.parse_args()

x = VanDerPolOscillator.CalcLimitCycle()

fig, ax = plt.subplots()
ax.plot(x[0, :], x[1, :], color='k', linewidth=2)
ax.set_xlim([-2.5, 2.5])
ax.set_ylim([-3, 3])
ax.set_xlabel('q')
ax.set_ylabel('qdot')

if not args.test:
plt.show()
8 changes: 8 additions & 0 deletions examples/van_der_pol/test/van_der_pol_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,14 @@ GTEST_TEST(VanDerPolTest, ScalarConversionTest) {
EXPECT_TRUE(is_symbolic_convertible(vdp));
}

GTEST_TEST(VanDerPolTest, LimitCycle) {
const auto cycle = VanDerPolOscillator<double>::CalcLimitCycle();

const int N = cycle.cols();
EXPECT_NEAR(cycle(0, 0), cycle(0, N - 1), 1e-2);
EXPECT_NEAR(cycle(1, 0), cycle(1, N - 1), 5e-3);
}

} // namespace
} // namespace van_der_pol
} // namespace examples
Expand Down
38 changes: 32 additions & 6 deletions examples/van_der_pol/van_der_pol.cc
Original file line number Diff line number Diff line change
@@ -1,8 +1,11 @@
#include "drake/examples/van_der_pol/van_der_pol.h"

#include "drake/common/default_scalars.h"
#include "drake/systems/analysis/simulator.h"
#include "drake/systems/framework/basic_vector.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/framework/system_constraint.h"
#include "drake/systems/primitives/signal_logger.h"

namespace drake {
namespace examples {
Expand All @@ -27,12 +30,35 @@ VanDerPolOscillator<T>::VanDerPolOscillator()
this->DeclareNumericParameter(systems::BasicVector<T>(Vector1<T>(1.0)));

// Declare μ≥0 constraint.
systems::ContextConstraintCalc<T> mu =
[](const systems::Context<T>& context, VectorX<T>* value) {
// Extract μ from the parameters.
*value = Vector1<T>(context.get_numeric_parameter(0).GetAtIndex(0));
};
this->DeclareInequalityConstraint(mu, { Vector1d(0), nullopt }, "mu ≥ 0");
systems::ContextConstraintCalc<T> mu = [](const systems::Context<T>& context,
VectorX<T>* value) {
// Extract μ from the parameters.
*value = Vector1<T>(context.get_numeric_parameter(0).GetAtIndex(0));
};
this->DeclareInequalityConstraint(mu, {Vector1d(0), nullopt}, "mu ≥ 0");
}

template <typename T>
Eigen::Matrix2Xd VanDerPolOscillator<T>::CalcLimitCycle() {
systems::DiagramBuilder<double> builder;

auto vdp = builder.AddSystem<VanDerPolOscillator<double>>();
auto logger = LogOutput(vdp->get_full_state_output_port(), &builder);
auto diagram = builder.Build();

systems::Simulator<double> simulator(*diagram);

// The following initial state was pre-computed (by running the simulation
// with μ=1 long enough for it to effectively reach the steady-state limit
// cycle).
simulator.get_mutable_context().SetContinuousState(
Eigen::Vector2d{-0.1144, 2.0578});

// Simulate for the approximate period (acquired by inspection of numerical
// simulation results) of the cycle for μ=1.
simulator.StepTo(6.667);

return logger->data();
}

// q̈ + μ(q² - 1)q̇ + q = 0
Expand Down
12 changes: 10 additions & 2 deletions examples/van_der_pol/van_der_pol.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@ namespace van_der_pol {
///
/// The van der Pol oscillator, governed by the following equations:
/// q̈ + μ(q² - 1)q̇ + q = 0, μ > 0
/// y = q
/// y = [q,q̇]'
/// y = q
/// y = [q,q̇]'
/// is a canonical example of a nonlinear system that exhibits a
/// limit cycle stability. As such it serves as an important for
/// examining nonlinear stability and stochastic stability.
Expand Down Expand Up @@ -51,6 +51,14 @@ class VanDerPolOscillator final : public systems::LeafSystem<T> {
return this->get_output_port(1);
}

// TODO(russt): generalize this to any mu using trajectory optimization
// (this could also improve the numerical accuracy).
/// Returns a 2-row matrix containing the result of simulating the oscillator
/// with the default mu=1 from (approximately) one point on the limit cycle
/// for (approximately) one period. The first row is q, and the second row
/// is q̇.
static Eigen::Matrix2Xd CalcLimitCycle();

private:
void DoCalcTimeDerivatives(
const systems::Context<T>& context,
Expand Down

0 comments on commit 5d45081

Please sign in to comment.