Skip to content

Commit

Permalink
primitives: Add python bindings for VectorLogSink and friends (#15581)
Browse files Browse the repository at this point in the history
* primitives: Add python bindings for VectorLogSink and friends

Relevant to: #10228

This is step 3 of 4 to deprecate and replace SignalLogger and SignalLog
with a logging system that avoids threading hazards (SignalLogger) and
slow memory management (SignalLog).

The patch adds bindings for VectorLog, VectorLogSink, and the
LogVectorOutput convenience function, with bindings tests.

Also addressed is a loose end from prior patches: the duplication of the
type name TriggerTypeSet in systems:: and systems::lcm::. The
systems::lcm:: definition is deprecated (likely with no downstream
impact), and aliased to the identical systems:: definition. The
surviving definition is moved to event.h to prepare for a possible
future refactoring of redundant code using TriggerTypeSet.
  • Loading branch information
rpoyner-tri authored Aug 10, 2021
1 parent a33c138 commit fcf8137
Show file tree
Hide file tree
Showing 7 changed files with 207 additions and 11 deletions.
91 changes: 90 additions & 1 deletion bindings/pydrake/systems/primitives_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#include "drake/systems/primitives/trajectory_affine_system.h"
#include "drake/systems/primitives/trajectory_linear_system.h"
#include "drake/systems/primitives/trajectory_source.h"
#include "drake/systems/primitives/vector_log_sink.h"
#include "drake/systems/primitives/wrap_to_system.h"
#include "drake/systems/primitives/zero_order_hold.h"

Expand All @@ -52,7 +53,7 @@ PYBIND11_MODULE(primitives, m) {

py::module::import("pydrake.systems.framework");
// N.B. Capturing `&doc` should not be required; workaround per #9600.
auto bind_common_scalar_types = [m, &doc](auto dummy) {
auto bind_common_scalar_types = [&m, &doc](auto dummy) {
using T = decltype(dummy);

DefineTemplateClassWithDefault<Adder<T>, LeafSystem<T>>(
Expand Down Expand Up @@ -320,6 +321,94 @@ PYBIND11_MODULE(primitives, m) {
&SymbolicVectorSystem<T>::dynamics_for_variable, py::arg("var"),
doc.SymbolicVectorSystem.dynamics_for_variable.doc);

DefineTemplateClassWithDefault<VectorLog<T>>(
m, "VectorLog", GetPyParam<T>(), doc.VectorLog.doc)
.def_property_readonly_static("kDefaultCapacity",
[](py::object) { return VectorLog<T>::kDefaultCapacity; })
.def(py::init<int>(), py::arg("input_size"), doc.VectorLog.ctor.doc)
.def("num_samples", &VectorLog<T>::num_samples,
doc.VectorLog.num_samples.doc)
.def(
"sample_times",
[](const VectorLog<T>* self) {
// Reference
return CopyIfNotPodType(self->sample_times());
},
return_value_policy_for_scalar_type<T>(),
doc.VectorLog.sample_times.doc)
.def(
"data",
[](const VectorLog<T>* self) {
// Reference.
return CopyIfNotPodType(self->data());
},
return_value_policy_for_scalar_type<T>(), doc.VectorLog.data.doc)
.def("Clear", &VectorLog<T>::Clear, doc.VectorLog.Clear.doc)
.def("Reserve", &VectorLog<T>::Reserve, doc.VectorLog.Reserve.doc)
.def("AddData", &VectorLog<T>::AddData, py::arg("time"),
py::arg("sample"), doc.VectorLog.AddData.doc)
.def("get_input_size", &VectorLog<T>::get_input_size,
doc.VectorLog.get_input_size.doc);

DefineTemplateClassWithDefault<VectorLogSink<T>, LeafSystem<T>>(
m, "VectorLogSink", GetPyParam<T>(), doc.VectorLogSink.doc)
.def(py::init<int, double>(), py::arg("input_size"),
py::arg("publish_period") = 0.0, doc.VectorLogSink.ctor.doc_2args)
.def(py::init<int, const TriggerTypeSet&, double>(),
py::arg("input_size"), py::arg("publish_triggers"),
py::arg("publish_period") = 0.0, doc.VectorLogSink.ctor.doc_3args)
.def(
"GetLog",
[](const VectorLogSink<T>* self, const Context<T>& context)
-> const VectorLog<T>& { return self->GetLog(context); },
py::arg("context"),
// Keep alive, ownership: `return` keeps `context` alive.
py::keep_alive<0, 2>(), py_rvp::reference,
doc.VectorLogSink.GetLog.doc)
.def(
"GetMutableLog",
[](const VectorLogSink<T>* self, Context<T>* context)
-> VectorLog<T>& { return self->GetMutableLog(context); },
py::arg("context"),
// Keep alive, ownership: `return` keeps `context` alive.
py::keep_alive<0, 2>(), py_rvp::reference,
doc.VectorLogSink.GetMutableLog.doc)
.def(
"FindLog",
[](const VectorLogSink<T>* self, const Context<T>& context)
-> const VectorLog<T>& { return self->FindLog(context); },
py::arg("context"),
// Keep alive, ownership: `return` keeps `context` alive.
py::keep_alive<0, 2>(), py_rvp::reference,
doc.VectorLogSink.FindLog.doc)
.def(
"FindMutableLog",
[](const VectorLogSink<T>* self, Context<T>* context)
-> VectorLog<T>& { return self->FindMutableLog(context); },
py::arg("context"),
// Keep alive, ownership: `return` keeps `context` alive.
py::keep_alive<0, 2>(), py_rvp::reference,
doc.VectorLogSink.FindMutableLog.doc);

m.def("LogVectorOutput",
py::overload_cast<const OutputPort<T>&, DiagramBuilder<T>*, double>(
&LogVectorOutput<T>),
py::arg("src"), py::arg("builder"), py::arg("publish_period") = 0.0,
// Keep alive, ownership: `return` keeps `builder` alive.
py::keep_alive<0, 2>(),
// See #11531 for why `py_rvp::reference` is needed.
py_rvp::reference, doc.LogVectorOutput.doc_3args);

m.def("LogVectorOutput",
py::overload_cast<const OutputPort<T>&, DiagramBuilder<T>*,
const TriggerTypeSet&, double>(&LogVectorOutput<T>),
py::arg("src"), py::arg("builder"), py::arg("publish_triggers"),
py::arg("publish_period") = 0.0,
// Keep alive, ownership: `return` keeps `builder` alive.
py::keep_alive<0, 2>(),
// See #11531 for why `py_rvp::reference` is needed.
py_rvp::reference, doc.LogVectorOutput.doc_4args);

DefineTemplateClassWithDefault<WrapToSystem<T>, LeafSystem<T>>(
m, "WrapToSystem", GetPyParam<T>(), doc.WrapToSystem.doc)
.def(py::init<int>(), doc.WrapToSystem.ctor.doc)
Expand Down
97 changes: 97 additions & 0 deletions bindings/pydrake/systems/test/primitives_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
BasicVector,
DiagramBuilder,
DiagramBuilder_,
TriggerType,
VectorBase,
)
from pydrake.systems.test.test_util import (
Expand All @@ -41,6 +42,7 @@
LinearSystem, LinearSystem_,
LinearTransformDensity, LinearTransformDensity_,
LogOutput,
LogVectorOutput,
MatrixGain,
Multiplexer, Multiplexer_,
ObservabilityMatrix,
Expand All @@ -55,6 +57,7 @@
TrajectoryAffineSystem, TrajectoryAffineSystem_,
TrajectoryLinearSystem, TrajectoryLinearSystem_,
TrajectorySource,
VectorLog, VectorLogSink, VectorLogSink_,
WrapToSystem, WrapToSystem_,
ZeroOrderHold, ZeroOrderHold_,
)
Expand Down Expand Up @@ -104,6 +107,7 @@ def test_instantiations(self):
supports_symbolic=False)
self._check_instantiations(TrajectoryLinearSystem_,
supports_symbolic=False)
self._check_instantiations(VectorLogSink_)
self._check_instantiations(WrapToSystem_)
self._check_instantiations(ZeroOrderHold_)

Expand Down Expand Up @@ -666,3 +670,96 @@ def test_state_interpolator_with_discrete_derivative(self):
state_interpolator = StateInterpolatorWithDiscreteDerivative(
num_positions=5, time_step=0.4, suppress_initial_transient=True)
self.assertTrue(state_interpolator.suppress_initial_transient())

@numpy_compare.check_nonsymbolic_types
def test_log_vector_output(self, T):
# Add various redundant loggers to a system, to exercise the
# LogVectorOutput bindings.
builder = DiagramBuilder_[T]()
kSize = 1
integrator = builder.AddSystem(Integrator_[T](kSize))
port = integrator.get_output_port(0)
loggers = []
loggers.append(LogVectorOutput(port, builder))
loggers.append(LogVectorOutput(src=port, builder=builder))
loggers.append(LogVectorOutput(port, builder, 0.125))
loggers.append(LogVectorOutput(
src=port, builder=builder, publish_period=0.125))

loggers.append(LogVectorOutput(port, builder, {TriggerType.kForced}))
loggers.append(LogVectorOutput(
src=port, builder=builder, publish_triggers={TriggerType.kForced}))
loggers.append(LogVectorOutput(
port, builder, {TriggerType.kPeriodic}, 0.125))
loggers.append(LogVectorOutput(
src=port, builder=builder,
publish_triggers={TriggerType.kPeriodic}, publish_period=0.125))

# Check the returned loggers by calling some trivial methods.
diagram = builder.Build()
context = diagram.CreateDefaultContext()
self.assertTrue(all(logger.FindLog(context).num_samples() == 0
for logger in loggers))

@numpy_compare.check_nonsymbolic_types
def test_vector_log(self, T):
kSize = 1
dut = VectorLog(kSize)
self.assertEqual(dut.get_input_size(), kSize)
dut.AddData(0.1, [22.22])
self.assertEqual(dut.num_samples(), 1)
self.assertEqual(dut.sample_times(), [0.1])
self.assertEqual(dut.data(), [22.22])
dut.Clear()
self.assertEqual(dut.num_samples(), 0)
# There is no good way from python to test the semantics of Reserve(),
# but test the binding anyway.
dut.Reserve(VectorLog.kDefaultCapacity * 3)

@numpy_compare.check_nonsymbolic_types
def test_vector_log_sink(self, T):
# Add various redundant loggers to a system, to exercise the
# VectorLog constructor bindings.
builder = DiagramBuilder_[T]()
kSize = 1
constructors = [VectorLogSink_[T]]
loggers = []
if T == float:
constructors.append(VectorLogSink)
for constructor in constructors:
loggers.append(builder.AddSystem(constructor(kSize)))
loggers.append(builder.AddSystem(constructor(input_size=kSize)))
loggers.append(builder.AddSystem(constructor(kSize, 0.125)))
loggers.append(builder.AddSystem(
constructor(input_size=kSize, publish_period=0.125)))
loggers.append(builder.AddSystem(
constructor(kSize, {TriggerType.kForced})))
loggers.append(builder.AddSystem(
constructor(input_size=kSize,
publish_triggers={TriggerType.kForced})))
loggers.append(builder.AddSystem(
constructor(kSize, {TriggerType.kPeriodic}, 0.125)))
loggers.append(builder.AddSystem(
constructor(input_size=kSize,
publish_triggers={TriggerType.kPeriodic},
publish_period=0.125)))

# Exercise all of the log access methods.
diagram = builder.Build()
context = diagram.CreateDefaultContext()
# FindLog and FindMutableLog find the same object.
self.assertTrue(
all(logger.FindLog(context) == logger.FindMutableLog(context)
for logger in loggers))
# Build a list of pairs of loggers and their local contexts.
loggers_and_contexts = [(x, x.GetMyContextFromRoot(context))
for x in loggers]
# GetLog and GetMutableLog find the same object.
self.assertTrue(
all(logger.GetLog(logger_context)
== logger.GetMutableLog(logger_context)
for logger, logger_context in loggers_and_contexts))
# GetLog and FindLog find the same object, given the proper contexts.
self.assertTrue(
all(logger.GetLog(logger_context) == logger.FindLog(context)
for logger, logger_context in loggers_and_contexts))
7 changes: 7 additions & 0 deletions systems/framework/event.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#include <limits>
#include <memory>
#include <unordered_set>
#include <utility>

#include "drake/common/drake_copyable.h"
Expand Down Expand Up @@ -419,6 +420,12 @@ enum class TriggerType {
kWitness,
};

/**
* This set-type alias provides a convenient API vocabulary for systems to
* specify multiple trigger types.
*/
using TriggerTypeSet = std::unordered_set<TriggerType, DefaultHash>;

/**
* Abstract base class that represents an event. The base event contains two
* main pieces of information: an enum trigger type and an optional attribute
Expand Down
3 changes: 2 additions & 1 deletion systems/lcm/lcm_publisher_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ namespace lcm {

using drake::lcm::DrakeLcmInterface;
using drake::lcm::DrakeLcm;
using systems::TriggerTypeSet;

LcmPublisherSystem::LcmPublisherSystem(
const std::string& channel,
Expand Down Expand Up @@ -89,7 +90,7 @@ void LcmPublisherSystem::AddInitializationMessage(
initialization_publisher_ = std::move(initialization_publisher);

DeclareInitializationEvent(systems::PublishEvent<double>(
systems::TriggerType::kInitialization,
TriggerType::kInitialization,
[this](const systems::Context<double>& context,
const systems::PublishEvent<double>&) {
this->initialization_publisher_(context, this->lcm_);
Expand Down
8 changes: 5 additions & 3 deletions systems/lcm/lcm_publisher_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,9 @@ class DrakeLcm;
namespace systems {
namespace lcm {

using TriggerTypeSet = std::unordered_set<TriggerType, DefaultHash>;
using TriggerTypeSet
DRAKE_DEPRECATED("2021-12-01", "Use drake::systems::TriggerTypeSet instead.")
= systems::TriggerTypeSet;

/**
* Publishes an LCM message containing information from its input port.
Expand Down Expand Up @@ -114,7 +116,7 @@ class LcmPublisherSystem : public LeafSystem<double> {
static std::unique_ptr<LcmPublisherSystem> Make(
const std::string& channel,
drake::lcm::DrakeLcmInterface* lcm,
const TriggerTypeSet& publish_triggers,
const systems::TriggerTypeSet& publish_triggers,
double publish_period = 0.0) {
return std::make_unique<LcmPublisherSystem>(
channel, std::make_unique<Serializer<LcmMessage>>(), lcm,
Expand Down Expand Up @@ -178,7 +180,7 @@ class LcmPublisherSystem : public LeafSystem<double> {
LcmPublisherSystem(const std::string& channel,
std::unique_ptr<SerializerInterface> serializer,
drake::lcm::DrakeLcmInterface* lcm,
const TriggerTypeSet& publish_triggers,
const systems::TriggerTypeSet& publish_triggers,
double publish_period = 0.0);

~LcmPublisherSystem() override;
Expand Down
5 changes: 5 additions & 0 deletions systems/primitives/vector_log_sink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,11 @@
namespace drake {
namespace systems {

// TODO(rpoyner-tri) All of the multi-trigger API and implementation here
// (TriggerTypeSet usage, logic for trigger types and publish periods) is
// duplicated from LcmPublisherSystem. It should all be factored to LeafSystem,
// especially if a third use of this pattern turns up.

template <typename T>
VectorLogSink<T>::VectorLogSink(int input_size, double publish_period)
: VectorLogSink<T>(
Expand Down
7 changes: 1 addition & 6 deletions systems/primitives/vector_log_sink.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,19 +10,14 @@
#include "drake/common/eigen_types.h"
#include "drake/systems/framework/context.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/framework/event.h"
#include "drake/systems/framework/leaf_system.h"
#include "drake/systems/framework/output_port.h"
#include "drake/systems/primitives/vector_log.h"

namespace drake {
namespace systems {

// TODO(rpoyner-tri) All of the multi-trigger API and implementation here
// (TriggerTypeSet, logic for trigger types and publish periods) is duplicated
// from LcmPublisherSystem. It should all be factored to LeafSystem, especially
// if a third use of this pattern turns up.
using TriggerTypeSet = std::unordered_set<TriggerType, DefaultHash>;

/// A discrete sink block which logs its vector-valued input to per-context
/// memory. This data is then retrievable outside of System operation,
/// e.g. after a simulation. See the warning below.
Expand Down

0 comments on commit fcf8137

Please sign in to comment.