Skip to content

Commit

Permalink
SignalLogger: Remove context-per-thread hazard (breaking)
Browse files Browse the repository at this point in the history
Relevant to: RobotLocomotion#10228

Move the internal SignalLog member to become a cache entry. Abandon the data
access methods on SignalLogger, and instead provide ergonomic lookup methods to
get the SignalLog itself.

Make SignalLog copyable and movable for compatibility with the cache.

Provide complete python bindings for SignalLogger and SignalLog.

Update numerous tests and examples.

This patch is breaking; it removes existing (if problematic) APIs without
deprecation.
  • Loading branch information
rpoyner-tri committed Jul 19, 2021
1 parent 1f2b1ba commit c09900e
Show file tree
Hide file tree
Showing 21 changed files with 235 additions and 120 deletions.
67 changes: 54 additions & 13 deletions bindings/pydrake/systems/primitives_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -229,31 +229,72 @@ PYBIND11_MODULE(primitives, m) {
py::arg("min_value"), py::arg("max_value"),
doc.Saturation.ctor.doc_2args);

DefineTemplateClassWithDefault<SignalLogger<T>, LeafSystem<T>>(
m, "SignalLogger", GetPyParam<T>(), doc.SignalLogger.doc)
DefineTemplateClassWithDefault<SignalLog<T>>(
m, "SignalLog", GetPyParam<T>(), doc.SignalLog.doc)
.def(py::init<int, int>(), py::arg("input_size"),
py::arg("batch_allocation_size") = 1000, doc.SignalLogger.ctor.doc)
.def("set_publish_period", &SignalLogger<T>::set_publish_period,
py::arg("period"), doc.SignalLogger.set_publish_period.doc)
.def("set_forced_publish_only",
&SignalLogger<T>::set_forced_publish_only,
doc.SignalLogger.set_forced_publish_only.doc)
py::arg("batch_allocation_size") = 1000, doc.SignalLog.ctor.doc)
.def("num_samples", &SignalLog<T>::num_samples,
doc.SignalLog.num_samples.doc)
.def(
"sample_times",
[](const SignalLogger<T>* self) {
[](const SignalLog<T>* self) {
// Reference
return CopyIfNotPodType(self->sample_times());
},
return_value_policy_for_scalar_type<T>(),
doc.SignalLogger.sample_times.doc)
doc.SignalLog.sample_times.doc)
.def(
"data",
[](const SignalLogger<T>* self) {
[](const SignalLog<T>* self) {
// Reference.
return CopyIfNotPodType(self->data());
},
return_value_policy_for_scalar_type<T>(), doc.SignalLogger.data.doc)
.def("reset", &SignalLogger<T>::reset, doc.SignalLogger.reset.doc);
return_value_policy_for_scalar_type<T>(), doc.SignalLog.data.doc)
.def("reset", &SignalLog<T>::reset, doc.SignalLog.reset.doc)
.def("AddData", &SignalLog<T>::AddData, py::arg("time"),
py::arg("sample"), doc.SignalLog.AddData.doc)
.def("get_input_size", &SignalLog<T>::get_input_size,
doc.SignalLog.get_input_size.doc);

auto cls =
DefineTemplateClassWithDefault<SignalLogger<T>, LeafSystem<T>>(
m, "SignalLogger", GetPyParam<T>(), doc.SignalLogger.doc)
.def(py::init<int, int>(), py::arg("input_size"),
py::arg("batch_allocation_size") = 1000,
doc.SignalLogger.ctor.doc)
.def("set_publish_period", &SignalLogger<T>::set_publish_period,
py::arg("period"), doc.SignalLogger.set_publish_period.doc)
.def("set_forced_publish_only",
&SignalLogger<T>::set_forced_publish_only,
doc.SignalLogger.set_forced_publish_only.doc)
.def(
"GetLog",
[](const SignalLogger<T>* self, const Context<T>& context)
-> const SignalLog<T>& { return self->GetLog(context); },
py::arg("context"), py_rvp::reference,
doc.SignalLogger.GetLog.doc_1args)
.def(
"GetLog",
[](const SignalLogger<T>* self, const System<T>& outer_system,
const Context<T>& outer_context) -> const SignalLog<T>& {
return self->GetLog(outer_system, outer_context);
},
py::arg("outer_system"), py::arg("outer_context"),
py_rvp::reference, doc.SignalLogger.GetLog.doc_2args)
.def(
"GetMutableLog",
[](const SignalLogger<T>* self, const Context<T>& context)
-> SignalLog<T>& { return self->GetMutableLog(context); },
py::arg("context"), py_rvp::reference,
doc.SignalLogger.GetMutableLog.doc_1args)
.def(
"GetMutableLog",
[](const SignalLogger<T>* self, const System<T>& outer_system,
const Context<T>& outer_context) -> SignalLog<T>& {
return self->GetMutableLog(outer_system, outer_context);
},
py::arg("outer_system"), py::arg("outer_context"),
py_rvp::reference, doc.SignalLogger.GetMutableLog.doc_2args);

AddTemplateFunction(m, "LogOutput", &LogOutput<T>, GetPyParam<T>(),
py::arg("src"), py::arg("builder"),
Expand Down
6 changes: 3 additions & 3 deletions bindings/pydrake/systems/pyplot_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
from warnings import warn

from pydrake.systems.framework import LeafSystem, PublishEvent, TriggerType
from pydrake.systems.primitives import SignalLogger
from pydrake.systems.primitives import SignalLog
from pydrake.trajectories import Trajectory


Expand Down Expand Up @@ -108,7 +108,7 @@ def get_recording_as_animation(self, **kwargs):
def animate(self, log, resample=True, **kwargs):
"""
Args:
log: A reference to a pydrake.systems.primitives.SignalLogger
log: A reference to a pydrake.systems.primitives.SignalLog
or a pydrake.trajectories.Trajectory that contains the plant
state after running a simulation.
resample: Whether we should do a resampling operation to make the
Expand All @@ -117,7 +117,7 @@ def animate(self, log, resample=True, **kwargs):
matches the sample timestep of the log.
Additional kwargs are passed through to FuncAnimation.
"""
if isinstance(log, SignalLogger):
if isinstance(log, SignalLog):
t = log.sample_times()
x = log.data()

Expand Down
16 changes: 10 additions & 6 deletions bindings/pydrake/systems/test/primitives_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -141,27 +141,31 @@ def test_signal_logger(self, T):

diagram = builder.Build()
simulator = Simulator_[T](diagram)
context = simulator.get_context()
kTime = 1.
simulator.AdvanceTo(kTime)

# Verify outputs of the every-step logger
t = logger_per_step.sample_times()
x = logger_per_step.data()
log_per_step = logger_per_step.GetMutableLog(diagram, context)
t = log_per_step.sample_times()
x = log_per_step.data()

self.assertTrue(t.shape[0] > 2)
self.assertTrue(t.shape[0] == x.shape[1])
numpy_compare.assert_allclose(
t[-1]*kValue, x[0, -1], atol=1e-15, rtol=0
)
numpy_compare.assert_equal(x, logger_per_step_2.data())
log_per_step_2 = logger_per_step_2.GetLog(diagram, context)
numpy_compare.assert_equal(x, log_per_step_2.data())

# Verify outputs of the periodic logger
t = logger_periodic.sample_times()
x = logger_periodic.data()
log_periodic = logger_periodic.GetLog(diagram, context)
t = log_periodic.sample_times()
x = log_periodic.data()
# Should log exactly once every kPeriod, up to and including kTime.
self.assertTrue(t.shape[0] == np.floor(kTime / kPeriod) + 1.)

logger_per_step.reset()
log_per_step.reset()

# Verify that t and x retain their values after systems are deleted.
t_copy = t.copy()
Expand Down
3 changes: 2 additions & 1 deletion bindings/pydrake/systems/test/pyplot_visualizer_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -84,9 +84,10 @@ def test_simple_visualizer(self):
context.SetContinuousState([0.9])

simulator = Simulator(diagram, context)
log = logger.GetLog(diagram, context)
simulator.AdvanceTo(.1)

ani = visualizer.animate(logger, repeat=True)
ani = visualizer.animate(log, repeat=True)
self.assertIsInstance(ani, animation.FuncAnimation)

def test_trajectory(self):
Expand Down
15 changes: 9 additions & 6 deletions examples/acrobot/run_lqr_w_estimator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -103,6 +103,9 @@ int do_main() {
// Build the system/simulator.
auto diagram = builder.Build();
systems::Simulator<double> simulator(*diagram);
const auto& context = simulator.get_context();
const auto& x_log = x_logger->GetLog(*diagram, context);
const auto& xhat_log = xhat_logger->GetLog(*diagram, context);

// Set an initial condition near the upright fixed point.
AcrobotState<double>& x0 = acrobot_w_encoder->get_mutable_acrobot_state(
Expand Down Expand Up @@ -135,18 +138,18 @@ int do_main() {
using common::ToPythonTuple;
CallPython("figure", 1);
CallPython("clf");
CallPython("plot", x_logger->sample_times(),
(x_logger->data().row(0).array() - M_PI)
CallPython("plot", x_log.sample_times(),
(x_log.data().row(0).array() - M_PI)
.matrix().transpose());
CallPython("plot", x_logger->sample_times(),
x_logger->data().row(1).transpose());
CallPython("plot", x_log.sample_times(),
x_log.data().row(1).transpose());
CallPython("legend", ToPythonTuple("theta1 - PI", "theta2"));
CallPython("axis", "tight");

CallPython("figure", 2);
CallPython("clf");
CallPython("plot", x_logger->sample_times(),
(x_logger->data().array() - xhat_logger->data().array())
CallPython("plot", x_log.sample_times(),
(x_log.data().array() - xhat_log.data().array())
.matrix().transpose());
CallPython("ylabel", "error");
CallPython("legend", ToPythonTuple("theta1", "theta2", "theta1dot",
Expand Down
2 changes: 1 addition & 1 deletion examples/acrobot/spong_sim.cc
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ std::string Simulate(const YAML::Node& scenario_node) {
simulator.AdvanceTo(scenario.t_final);

Output output;
output.x_tape = state_logger->data();
output.x_tape = state_logger->GetLog(*diagram, context).data();
drake::yaml::YamlWriteArchive writer;
writer.Accept(output);
// The EmitString call below saves a document like so:
Expand Down
3 changes: 2 additions & 1 deletion examples/acrobot/spong_sim.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,14 +37,15 @@ def simulate(*, initial_state, controller_params, t_final, tape_period):
plant_context = diagram.GetMutableSubsystemContext(plant, context)
controller_context = diagram.GetMutableSubsystemContext(
controller, context)
log = state_logger.GetLog(diagram, context)

plant_context.SetContinuousState(initial_state)
controller_context.get_mutable_numeric_parameter(0).SetFromVector(
controller_params)

simulator.AdvanceTo(t_final)

x_tape = state_logger.data()
x_tape = log.data()
return x_tape


Expand Down
7 changes: 4 additions & 3 deletions examples/fibonacci/run_fibonacci.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,12 +29,13 @@ int main(int argc, char* argv[]) {

// Create a Simulator and use it to advance time until t=steps*h.
systems::Simulator<double> simulator(*diagram);
const auto& log = logger->GetLog(*diagram, simulator.get_context());
simulator.AdvanceTo(FLAGS_steps * FibonacciDifferenceEquation::kPeriod);

// Print out the contents of the log.
for (int n = 0; n < logger->sample_times().size(); ++n) {
const double t = logger->sample_times()[n];
std::cout << n << ": " << logger->data()(0, n)
for (int n = 0; n < log.sample_times().size(); ++n) {
const double t = log.sample_times()[n];
std::cout << n << ": " << log.data()(0, n)
<< " (t=" << t << ")\n";
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,14 +22,15 @@ GTEST_TEST(Fibonacci, CheckSequence) {
auto diagram = builder.Build();

systems::Simulator<double> simulator(*diagram);
const auto& log = logger->GetLog(*diagram, simulator.get_context());

// Simulate forward to fibonacci(6): 0 1 1 2 3 5 8
simulator.AdvanceTo(6 * FibonacciDifferenceEquation::kPeriod);

Eigen::VectorXd expected(7);
expected << 0, 1, 1, 2, 3, 5, 8;

EXPECT_EQ(logger->data().transpose(), expected);
EXPECT_EQ(log.data().transpose(), expected);
}

} // namespace
Expand Down
6 changes: 4 additions & 2 deletions examples/manipulation_station/end_effector_teleop_sliders.py
Original file line number Diff line number Diff line change
Expand Up @@ -380,13 +380,15 @@ def main():
differential_ik, simulator.get_mutable_context()), q0)

simulator.set_target_realtime_rate(args.target_realtime_rate)
iiwa_velocities_log = iiwa_velocities.GetLog(
diagram, simulator.get_context())
simulator.AdvanceTo(args.duration)

# Ensure that our initialization logic was correct, by inspecting our
# logged joint velocities.
if args.test:
for time, qdot in zip(iiwa_velocities.sample_times(),
iiwa_velocities.data().transpose()):
for time, qdot in zip(iiwa_velocities_log.sample_times(),
iiwa_velocities_log.data().transpose()):
# TODO(jwnimmer-tri) We should be able to do better than a 40
# rad/sec limit, but that's the best we can enforce for now.
if qdot.max() > 0.1:
Expand Down
6 changes: 4 additions & 2 deletions examples/manipulation_station/joint_teleop.py
Original file line number Diff line number Diff line change
Expand Up @@ -152,8 +152,10 @@ def main():
# Ensure that our initialization logic was correct, by inspecting our
# logged joint velocities.
if args.test:
for time, qdot in zip(iiwa_velocities.sample_times(),
iiwa_velocities.data().transpose()):
iiwa_velocities_log = iiwa_velocities.GetLog(
diagram, simulator.get_context())
for time, qdot in zip(iiwa_velocities_log.sample_times(),
iiwa_velocities_log.data().transpose()):
# TODO(jwnimmer-tri) We should be able to do better than a 40
# rad/sec limit, but that's the best we can enforce for now.
if qdot.max() > 0.1:
Expand Down
2 changes: 1 addition & 1 deletion examples/van_der_pol/van_der_pol.cc
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ Eigen::Matrix2Xd VanDerPolOscillator<T>::CalcLimitCycle() {
// simulation results) of the cycle for μ=1.
simulator.AdvanceTo(6.667);

return logger->data();
return logger->GetLog(*diagram, simulator.get_context()).data();
}

// q̈ + μ(q² - 1)q̇ + q = 0
Expand Down
19 changes: 11 additions & 8 deletions systems/analysis/test/simulator_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1086,14 +1086,16 @@ GTEST_TEST(SimulatorTest, ExampleDiscreteSystem) {

// Create a Simulator and use it to advance time until t=3*h.
Simulator<double> simulator(*diagram);
const auto& log = logger->GetLog(*diagram, simulator.get_context());

simulator.AdvanceTo(3 * ExampleDiscreteSystem::kPeriod);

testing::internal::CaptureStdout(); // Not in example.

// Print out the contents of the log.
for (int n = 0; n < logger->sample_times().size(); ++n) {
const double t = logger->sample_times()[n];
std::cout << n << ": " << logger->data()(0, n)
for (int n = 0; n < log.sample_times().size(); ++n) {
const double t = log.sample_times()[n];
std::cout << n << ": " << log.data()(0, n)
<< " (" << t << ")\n";
}

Expand Down Expand Up @@ -1162,9 +1164,10 @@ GTEST_TEST(SimulatorTest, SinusoidalHybridSystem) {
const double t_final = 10.0;
const double initial_value = std::sin(-f * h); // = sin(f*-1*h)
Simulator<double> simulator(*diagram);
auto& context = simulator.get_mutable_context();
const auto& log = logger->GetLog(*diagram, context);

simulator.get_mutable_context().get_mutable_discrete_state()[0] =
initial_value;
context.get_mutable_discrete_state()[0] = initial_value;
simulator.AdvanceTo(t_final);

// Set a very tight tolerance value.
Expand All @@ -1180,8 +1183,8 @@ GTEST_TEST(SimulatorTest, SinusoidalHybridSystem) {
// y₂ 2 t = 2 h sin(f h)
// y₃ 3 t = 3 h sin(f 2 h)
// ...
const VectorX<double> times = logger->sample_times();
const MatrixX<double> data = logger->data();
const VectorX<double> times = log.sample_times();
const MatrixX<double> data = log.data();

ASSERT_EQ(times.size(), std::round(t_final/h) + 1);
ASSERT_EQ(data.rows(), 1);
Expand Down Expand Up @@ -1819,7 +1822,7 @@ GTEST_TEST(SimulatorTest, Issue10443) {
// Should log exactly once every kPeriod, up to and including
// kTime.
Eigen::VectorBlock<const VectorX<double>> t_periodic =
periodic_logger.sample_times();
periodic_logger.GetLog(*diagram, simulator.get_context()).sample_times();
EXPECT_EQ(t_periodic.size(), kTime * kFrequency + 1);
}

Expand Down
13 changes: 7 additions & 6 deletions systems/primitives/signal_log.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ namespace systems {
template <typename T>
class SignalLog {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(SignalLog)
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(SignalLog)

/** Constructs the signal log.
@param input_size Dimension of the per-time step data set.
Expand Down Expand Up @@ -58,12 +58,13 @@ class SignalLog {
int64_t get_input_size() const { return data_.rows(); }

private:
const int batch_allocation_size_{1000};
// This is logically constant over an instance, but is not declared const so
// that default copy and assignment can work.
int batch_allocation_size_{1000};

// Use mutable variables to hold the logged data.
mutable int64_t num_samples_{0};
mutable VectorX<T> sample_times_;
mutable MatrixX<T> data_;
int64_t num_samples_{0};
VectorX<T> sample_times_;
MatrixX<T> data_;
};
} // namespace systems
} // namespace drake
Loading

0 comments on commit c09900e

Please sign in to comment.