Skip to content

Commit

Permalink
Modernize event handling in SignalLogger and improve documentation. (#…
Browse files Browse the repository at this point in the history
…10269)

Remove now-unneeded fluff from examples.
  • Loading branch information
sherm1 authored Jan 15, 2019
1 parent b9e9c4f commit 952cd12
Show file tree
Hide file tree
Showing 9 changed files with 178 additions and 53 deletions.
2 changes: 0 additions & 2 deletions examples/fibonacci/test/fibonacci_difference_equation_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,6 @@ GTEST_TEST(Fibonacci, CheckSequence) {
auto diagram = builder.Build();

systems::Simulator<double> simulator(*diagram);
simulator.set_publish_every_time_step(false);
simulator.set_publish_at_initialization(false);

// Simulate forward to fibonacci(6): 0 1 1 2 3 5 8
simulator.StepTo(6 * FibonacciDifferenceEquation::kPeriod);
Expand Down
6 changes: 0 additions & 6 deletions systems/analysis/test/simulator_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1012,8 +1012,6 @@ GTEST_TEST(SimulatorTest, ExampleDiscreteSystem) {

// Create a Simulator and use it to advance time until t=3*h.
Simulator<double> simulator(*diagram);
simulator.set_publish_every_time_step(false);
simulator.set_publish_at_initialization(false);
simulator.StepTo(3 * ExampleDiscreteSystem::kPeriod);

testing::internal::CaptureStdout(); // Not in example.
Expand Down Expand Up @@ -1091,10 +1089,6 @@ GTEST_TEST(SimulatorTest, SinusoidalHybridSystem) {
const double initial_value = std::sin(-f * h); // = sin(f*-1*h)
Simulator<double> simulator(*diagram);

// TODO(sherm1) Remove these when #10269 lands (fix to SignalLogger).
simulator.set_publish_at_initialization(false);
simulator.set_publish_every_time_step(false);

simulator.get_mutable_context().get_mutable_discrete_state()[0] =
initial_value;
simulator.StepTo(t_final);
Expand Down
2 changes: 0 additions & 2 deletions systems/discrete_systems.h
Original file line number Diff line number Diff line change
Expand Up @@ -91,8 +91,6 @@ The following code fragment can be used to step this system forward:
// Create a Simulator and use it to advance time until t=3*h.
Simulator<double> simulator(*diagram);
simulator.set_publish_every_time_step(false);
simulator.set_publish_at_initialization(false);
simulator.StepTo(3 * ExampleDiscreteSystem::kPeriod);
// Print out the contents of the log.
Expand Down
9 changes: 6 additions & 3 deletions systems/lcm/test/lcm_driven_loop_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -90,18 +90,21 @@ GTEST_TEST(LcmDrivenLoopTest, TestLoop) {
sub->set_name("subscriber");
auto dummy = builder.AddSystem<DummySys>();
dummy->set_name("dummy");

auto logger = builder.AddSystem<SignalLogger<double>>(1);
logger->set_name("logger");
logger->set_forced_publish_only(); // Log only when told to do so.

builder.Connect(*sub, *dummy);
builder.Connect(*dummy, *logger);
auto sys = builder.Build();

// Makes the lcm driven loop.
lcm::LcmDrivenLoop dut(*sys, *sub, nullptr, &lcm,
std::make_unique<MilliSecTimeStampMessageToSeconds>());
// This ensures that dut calls sys->Publish() every time it handles a
// message, which triggers the logger to save its input (message time stamp)
// to the log.
// This ensures that dut calls sys->Publish() (a.k.a. "forced publish")
// every time it handles a message, which triggers the logger to save its
// input (message time stamp) to the log.
dut.set_publish_on_every_received_message(true);

// Starts the publishing thread.
Expand Down
1 change: 1 addition & 0 deletions systems/primitives/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -542,6 +542,7 @@ drake_cc_googletest(
":linear_system",
":signal_logger",
"//common/test_utilities:eigen_matrix_compare",
"//common/test_utilities:expect_throws_message",
"//systems/analysis:simulator",
"//systems/framework",
],
Expand Down
10 changes: 8 additions & 2 deletions systems/primitives/signal_log.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,10 @@ namespace drake {
namespace systems {

/**
This class serves as an in-memory cache of time-dependent vector values.
This utility class serves as an in-memory cache of time-dependent vector
values. Note that this is a standalone class, not a Drake System. It is
primarily intended to support the Drake System primitive SignalLogger, but can
be used independently.
@tparam T The vector element type, which must be a valid Eigen scalar.
*/
Expand All @@ -23,6 +26,9 @@ class SignalLog {
*/
explicit SignalLog(int input_size, int batch_allocation_size = 1000);

/** Returns the number of samples taken since construction or last reset(). */
int num_samples() const { return num_samples_; }

/** Accesses the logged time stamps. */
Eigen::VectorBlock<const VectorX<T>> sample_times() const {
return const_cast<const VectorX<T>&>(sample_times_).head(num_samples_);
Expand All @@ -34,7 +40,7 @@ class SignalLog {
return const_cast<const MatrixX<T>&>(data_).leftCols(num_samples_);
}

/** Reset the logged data. */
/** Clears the logged data. */
void reset() {
// Resetting num_samples_ is sufficient to have all future writes and
// reads re-initialized to the beginning of the data.
Expand Down
44 changes: 38 additions & 6 deletions systems/primitives/signal_logger.cc
Original file line number Diff line number Diff line change
Expand Up @@ -9,24 +9,56 @@ template <typename T>
SignalLogger<T>::SignalLogger(int input_size, int batch_allocation_size)
: log_(input_size, batch_allocation_size) {
this->DeclareInputPort("data", kVectorValued, input_size);

// Use a per-step event by default; disabled by set_publish_period() or
// set_forced_publish_only().
this->DeclarePerStepPublishEvent(&SignalLogger<T>::PerStepWriteToLog);
logging_mode_ = kPerStep;
}

template <typename T>
void SignalLogger<T>::set_publish_period(double period) {
this->DeclarePeriodicPublish(period);
switch (logging_mode_) {
case kPeriodic:
throw std::logic_error(
"SignalLogger::set_publish_period(): can only be called once.");
case kForced:
throw std::logic_error(
"SignalLogger::set_publish_period(): cannot be called if "
"set_forced_publish_only() has been called.");
case kPerStep:
this->DeclarePeriodicPublishEvent(period, 0., // period, offset
&SignalLogger<T>::WriteToLog);
logging_mode_ = kPeriodic;
return;
}
}

template <typename T>
void SignalLogger<T>::set_forced_publish_only() {
switch (logging_mode_) {
case kForced:
return; // Already forced-publishing.
case kPeriodic:
throw std::logic_error(
"SignalLogger::set_forced_publish_only(): "
"cannot be called if set_publish_period() has been called.");
case kPerStep:
this->DeclareForcedPublishEvent(&SignalLogger<T>::WriteToLog);
logging_mode_ = kForced;
return;
}
}

template <typename T>
void SignalLogger<T>::DoPublish(const Context<T>& context,
const std::vector<const PublishEvent<T>*>&)
const {
EventStatus SignalLogger<T>::WriteToLog(const Context<T>& context) const {
log_.AddData(context.get_time(),
this->EvalVectorInput(context, 0)->get_value());
return EventStatus::Succeeded();
}

template <typename T>
const InputPort<T>& SignalLogger<T>::get_input_port()
const {
const InputPort<T>& SignalLogger<T>::get_input_port() const {
return System<T>::get_input_port(0);
}

Expand Down
97 changes: 77 additions & 20 deletions systems/primitives/signal_logger.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,36 @@
namespace drake {
namespace systems {

/// A sink block which logs its input to memory. This data is then retrievable
/// (e.g. after a simulation) via a handful of accessor methods.
/// This class essentially holds a large Eigen matrix for data storage, where
/// each column corresponds to a data point. This system saves a data point and
/// the context time whenever its Publish() method is called.
// TODO(sherm1) This System has problems as discussed in issue #10228 that
// should be fixed.
/// A discrete sink block which logs its input to memory (not thread safe). This
/// data is then retrievable (e.g. after a simulation) via a handful of accessor
/// methods. This system holds a large, mutable Eigen matrix for data storage,
/// where each column corresponds to a data point. It saves a data point and
/// the context time whenever it samples its input.
///
/// By default, sampling is performed every time the Simulator completes a
/// trajectory-advancing substep (that is, via a per-step Publish event), with
/// the first sample occuring during Simulator::Initialize(). That means the
/// samples will generally be unevenly spaced in time. If you prefer regular
/// sampling, you may optionally specify a "publish period" in which case
/// sampling occurs periodically, with the first sample occurring at time 0.
/// Alternatively (not common), you can specify that logging should only occur
/// at "forced publish" events, meaning at explicit calls to System::Publish().
/// The Simulator's "publish every time step" option also results in forced
/// publish events, so should be disabled if you want to control logging
/// yourself.
///
/// @warning %SignalLogger is _not_ thread-safe because it writes to a mutable
/// buffer internally. If you have a Diagram that contains a SignalLogger,
/// even with each thread having its own Context, the threads will conflict.
/// You would have to have separate Diagrams in each thread to avoid trouble.
///
/// @see LogOutput() for a convenient way to add %logging to a Diagram.
/// @see Simulator::set_publish_every_time_step()
/// @see Simulator::set_publish_at_initialization()
///
/// @system{ SignalLogger, @input_port{data}, }
///
/// @tparam T The vector element type, which must be a valid Eigen scalar.
///
Expand All @@ -35,52 +60,84 @@ class SignalLogger : public LeafSystem<T> {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(SignalLogger)

/// Construct the signal logger system.
/// Constructs the signal logger system.
///
/// @warning %SignalLogger may become slower and slower as the number of
/// log entries increases due to memory reallocations. You can avoid that by
/// providing a `batch_allocation_size` comparable to the total expected
/// number of log entries for your simulation.
///
/// @param input_size Dimension of the (single) input port. This corresponds
/// to the number of rows of the data matrix.
/// @param batch_allocation_size Storage is (re)allocated in blocks of
/// input_size-by-batch_allocation_size.
/// @see LogOutput() helper function for a convenient way to add %logging.
explicit SignalLogger(int input_size, int batch_allocation_size = 1000);

/// Sets the publishing period of this system. See
/// LeafSystem::DeclarePeriodicPublish() for details about the semantics of
/// parameter `period`.
/// Sets the publishing period of this system to specify periodic sampling
/// and disables the default per-step sampling. This method can only be called
/// once and only if set_forced_publish_only() hasn't been called.
/// @throws std::logic_error if called more than once, or if
/// set_forced_publish_only() has been called.
/// @pre `period` must be greater than zero.
void set_publish_period(double period);

/// Limits logging to forced publish calls only, that is, explicit calls
/// to System::Publish() issued directly or by the Simulator and disables the
/// default per-step sampling. This method cannot be called if
/// set_publish_period() has been called.
/// @throws std::logic_error if set_publish_period() has been called.
void set_forced_publish_only();

/// Returns the number of samples taken since construction or last reset().
int num_samples() const { return log_.num_samples(); }

/// Access the (simulation) time of the logged data.
/// Provides access to the sample times of the logged data. Time is taken
/// from the Context when the log entry is added.
Eigen::VectorBlock<const VectorX<T>> sample_times() const {
return log_.sample_times();
}

/// Access the logged data.
Eigen::Block<const MatrixX<T>, Eigen::Dynamic, Eigen::Dynamic, true> data()
const {
/// Provides access to the logged data.
Eigen::Block<const MatrixX<T>, Eigen::Dynamic, Eigen::Dynamic, true>
data() const {
return log_.data();
}

/// Clears the logged data.
void reset() { log_.reset(); }

/// Returns the only input port.
/// Returns the only input port. The port's name is "data" so you can also
/// access this with GetInputPort("data").
const InputPort<T>& get_input_port() const;

private:
// Logging is done in this method.
void DoPublish(const Context<T>& context,
const std::vector<const systems::PublishEvent<T>*>& events)
const override;
enum LoggingMode { kPerStep, kPeriodic, kForced };

// Logging is done in this event handler.
EventStatus WriteToLog(const Context<T>& context) const;

// This event handler logs only if we're in per-step logging mode.
EventStatus PerStepWriteToLog(const Context<T>& context) const {
if (logging_mode_ == kPerStep)
return WriteToLog(context);
return EventStatus::DidNothing();
}

LoggingMode logging_mode_{kPerStep};

mutable SignalLog<T> log_;
mutable SignalLog<T> log_; // TODO(sherm1) Not thread safe :(
};

/// Provides a convenience function for adding a SignalLogger, initialized to
/// the correct size, and connected to another output in a DiagramBuilder.
/// the correct size, and connected to an output in a DiagramBuilder.
///
/// @code
/// DiagramBuilder<double> builder;
/// auto foo = builder.AddSystem<Foo>("name", 3.14);
/// auto logger = LogOutput(foo->get_output_port(), &builder);
/// @endcode
/// @relates drake::systems::SignalLogger

template <typename T>
SignalLogger<T>* LogOutput(const OutputPort<T>& src,
Expand Down
Loading

0 comments on commit 952cd12

Please sign in to comment.