Skip to content

Commit

Permalink
[pydrake] Add bindings for LcmScopeSystem (RobotLocomotion#15309)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Jul 13, 2021
1 parent 94dc50b commit f13bf96
Show file tree
Hide file tree
Showing 2 changed files with 40 additions and 0 deletions.
28 changes: 28 additions & 0 deletions bindings/pydrake/systems/lcm_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
#include "drake/systems/lcm/connect_lcm_scope.h"
#include "drake/systems/lcm/lcm_interface_system.h"
#include "drake/systems/lcm/lcm_publisher_system.h"
#include "drake/systems/lcm/lcm_scope_system.h"
#include "drake/systems/lcm/lcm_subscriber_system.h"
#include "drake/systems/lcm/serializer.h"

Expand Down Expand Up @@ -169,6 +170,33 @@ PYBIND11_MODULE(lcm, m) {
py::arg("timeout") = -1, cls_doc.WaitForMessage.doc);
}

{
using Class = LcmScopeSystem;
constexpr auto& cls_doc = doc.LcmScopeSystem;
py::class_<Class, LeafSystem<double>>(m, "LcmScopeSystem")
.def(py::init<int>(), py::arg("size"), cls_doc.ctor.doc)
.def_static(
"AddToBuilder",
[](systems::DiagramBuilder<double>* builder,
drake::lcm::DrakeLcmInterface* lcm,
const OutputPort<double>& signal, const std::string& channel,
double publish_period) {
auto [scope, publisher] = LcmScopeSystem::AddToBuilder(
builder, lcm, signal, channel, publish_period);
// Annotate the proper rvp on the tuple of pointers.
py::object py_builder = py::cast(builder, py_rvp::reference);
py::list result;
result.append(
py::cast(scope, py_rvp::reference_internal, py_builder));
result.append(
py::cast(publisher, py_rvp::reference_internal, py_builder));
return result;
},
py::arg("builder"), py::arg("lcm"), py::arg("signal"),
py::arg("channel"), py::arg("publish_period"),
cls_doc.AddToBuilder.doc);
}

m.def("ConnectLcmScope", &ConnectLcmScope, py::arg("src"), py::arg("channel"),
py::arg("builder"), py::arg("lcm") = nullptr,
py::arg("publish_period") = 0.0, py::keep_alive<0, 2>(),
Expand Down
12 changes: 12 additions & 0 deletions bindings/pydrake/systems/test/lcm_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -192,6 +192,18 @@ def test_diagram_publisher(self):
diagram = builder.Build()
diagram.Publish(diagram.CreateDefaultContext())

def test_lcm_scope(self):
builder = DiagramBuilder()
source = builder.AddSystem(ConstantVectorSource(np.zeros(4)))
scope, publisher = mut.LcmScopeSystem.AddToBuilder(
builder=builder,
lcm=DrakeLcm(),
signal=source.get_output_port(0),
channel="TEST_CHANNEL",
publish_period=0.001)
self.assertIsInstance(scope, mut.LcmScopeSystem)
self.assertIsInstance(publisher, mut.LcmPublisherSystem)

def test_connect_lcm_scope(self):
builder = DiagramBuilder()
source = builder.AddSystem(ConstantVectorSource(np.zeros(4)))
Expand Down

0 comments on commit f13bf96

Please sign in to comment.