Skip to content

Commit

Permalink
[systems/lcm] Use shared_ptr for LCM serializers
Browse files Browse the repository at this point in the history
For a given message type, it's OK to use one const serializer across
all systems that publish or subscribe for efficiency. This also allows
us to greatly simplify the Python bindings.

Deprecate SerializerInterface::Clone. It now has very little upside,
but is extremely difficult to override correctly in Python.
  • Loading branch information
jwnimmer-tri committed May 10, 2023
1 parent 4d4949a commit c9b02b9
Show file tree
Hide file tree
Showing 12 changed files with 106 additions and 49 deletions.
11 changes: 8 additions & 3 deletions bindings/pydrake/systems/_lcm_extra.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
# See `ExecuteExtraPythonCode` in `pydrake_pybind.h` for usage details and
# rationale.

from pydrake.common.value import AbstractValue
from pydrake.common.value import AbstractValue as _AbstractValue
from pydrake.common.deprecation import deprecated as _deprecated


class PySerializer(SerializerInterface):
Expand All @@ -16,18 +17,22 @@ def __init__(self, lcm_type):
def __repr__(self):
return f"PySerializer({self._lcm_type.__name__})"

@_deprecated(
"PySerializer objects are immutable, there is no need to copy nor "
"clone them.", date="2023-09-01")
def Clone(self):
"""(Deprecated.)"""
return PySerializer(self._lcm_type)

def CreateDefaultValue(self):
return AbstractValue.Make(self._lcm_type())
return _AbstractValue.Make(self._lcm_type())

def Deserialize(self, buffer, abstract_value):
message = self._lcm_type.decode(buffer)
abstract_value.set_value(message)

def Serialize(self, abstract_value):
assert isinstance(abstract_value, AbstractValue)
assert isinstance(abstract_value, _AbstractValue)
message = abstract_value.get_value()
assert isinstance(message, self._lcm_type)
return message.encode()
Expand Down
59 changes: 37 additions & 22 deletions bindings/pydrake/systems/lcm_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -41,10 +41,13 @@ class PySerializerInterface : public py::wrapper<SerializerInterface> {
// `PySerializerInterface`). C++ implementations will use the bindings on the
// interface below.

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
std::unique_ptr<SerializerInterface> Clone() const override {
PYBIND11_OVERLOAD_PURE(
std::unique_ptr<SerializerInterface>, SerializerInterface, Clone);
}
#pragma GCC diagnostic pop

std::unique_ptr<AbstractValue> CreateDefaultValue() const override {
PYBIND11_OVERLOAD_PURE(std::unique_ptr<AbstractValue>, SerializerInterface,
Expand Down Expand Up @@ -113,7 +116,8 @@ PYBIND11_MODULE(lcm, m) {
{
using Class = SerializerInterface;
constexpr auto& cls_doc = doc.SerializerInterface;
py::class_<Class, PySerializerInterface> cls(m, "SerializerInterface");
py::class_<Class, PySerializerInterface, std::shared_ptr<Class>> cls(
m, "SerializerInterface");
cls // BR
// Adding a constructor permits implementing this interface in Python.
.def(py::init(
Expand Down Expand Up @@ -144,7 +148,24 @@ PYBIND11_MODULE(lcm, m) {
message_bytes.size());
},
py::arg("abstract_value"), cls_doc.Serialize.doc);
DefClone(&cls);
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
constexpr char kCloneDeprecation[] =
"PySerializer objects are immutable, there is no need to copy nor "
"clone them. The deprecated code will be removed from Drake on or "
"after 2023-09-01.";
cls // BR
.def("Clone", WrapDeprecated(kCloneDeprecation, &Class::Clone),
kCloneDeprecation)
.def("__copy__", WrapDeprecated(kCloneDeprecation, &Class::Clone),
kCloneDeprecation)
.def("__deepcopy__",
WrapDeprecated(kCloneDeprecation,
[](const Class* self, py::dict /* memo */) {
return self->Clone();
}),
kCloneDeprecation);
#pragma GCC diagnostic pop
}

{
Expand All @@ -171,36 +192,32 @@ PYBIND11_MODULE(lcm, m) {
constexpr auto& cls_doc = doc.LcmPublisherSystem;
py::class_<Class, LeafSystem<double>> cls(m, "LcmPublisherSystem");
cls // BR
.def(py::init<const std::string&, std::unique_ptr<SerializerInterface>,
.def(py::init<const std::string&,
std::shared_ptr<const SerializerInterface>,
LcmInterfaceSystem*, double>(),
py::arg("channel"), py::arg("serializer"), py::arg("lcm"),
py::arg("publish_period") = 0.0,
// Keep alive, ownership: `serializer` keeps `self` alive.
py::keep_alive<3, 1>(),
// Keep alive, reference: `self` keeps `lcm` alive.
py::keep_alive<1, 4>(), cls_doc.ctor.doc_4args)
.def(py::init<const std::string&, std::unique_ptr<SerializerInterface>,
DrakeLcmInterface*, double>(),
.def(py::init<const std::string&,
std::shared_ptr<const SerializerInterface>, DrakeLcmInterface*,
double>(),
py::arg("channel"), py::arg("serializer"), py::arg("lcm"),
py::arg("publish_period") = 0.0,
// Keep alive, ownership: `serializer` keeps `self` alive.
py::keep_alive<3, 1>(),
// Keep alive, reference: `self` keeps `lcm` alive.
py::keep_alive<1, 4>(), cls_doc.ctor.doc_4args)
.def(py::init<const std::string&, std::unique_ptr<SerializerInterface>,
.def(py::init<const std::string&,
std::shared_ptr<const SerializerInterface>,
LcmInterfaceSystem*, const systems::TriggerTypeSet&, double>(),
py::arg("channel"), py::arg("serializer"), py::arg("lcm"),
py::arg("publish_triggers"), py::arg("publish_period") = 0.0,
// Keep alive, ownership: `serializer` keeps `self` alive.
py::keep_alive<3, 1>(),
// Keep alive, reference: `self` keeps `lcm` alive.
py::keep_alive<1, 4>(), cls_doc.ctor.doc_4args)
.def(py::init<const std::string&, std::unique_ptr<SerializerInterface>,
DrakeLcmInterface*, const systems::TriggerTypeSet&, double>(),
.def(py::init<const std::string&,
std::shared_ptr<const SerializerInterface>, DrakeLcmInterface*,
const systems::TriggerTypeSet&, double>(),
py::arg("channel"), py::arg("serializer"), py::arg("lcm"),
py::arg("publish_triggers"), py::arg("publish_period") = 0.0,
// Keep alive, ownership: `serializer` keeps `self` alive.
py::keep_alive<3, 1>(),
// Keep alive, reference: `self` keeps `lcm` alive.
py::keep_alive<1, 4>(), cls_doc.ctor.doc_4args);
}
Expand All @@ -209,18 +226,16 @@ PYBIND11_MODULE(lcm, m) {
using Class = LcmSubscriberSystem;
constexpr auto& cls_doc = doc.LcmSubscriberSystem;
py::class_<Class, LeafSystem<double>>(m, "LcmSubscriberSystem")
.def(py::init<const std::string&, std::unique_ptr<SerializerInterface>,
.def(py::init<const std::string&,
std::shared_ptr<const SerializerInterface>,
LcmInterfaceSystem*>(),
py::arg("channel"), py::arg("serializer"), py::arg("lcm"),
// Keep alive, ownership: `serializer` keeps `self` alive.
py::keep_alive<3, 1>(),
// Keep alive, reference: `self` keeps `lcm` alive.
py::keep_alive<1, 4>(), doc.LcmSubscriberSystem.ctor.doc)
.def(py::init<const std::string&, std::unique_ptr<SerializerInterface>,
.def(py::init<const std::string&,
std::shared_ptr<const SerializerInterface>,
DrakeLcmInterface*>(),
py::arg("channel"), py::arg("serializer"), py::arg("lcm"),
// Keep alive, ownership: `serializer` keeps `self` alive.
py::keep_alive<3, 1>(),
// Keep alive, reference: `self` keeps `lcm` alive.
py::keep_alive<1, 4>(), doc.LcmSubscriberSystem.ctor.doc)
.def("WaitForMessage", &Class::WaitForMessage,
Expand Down
7 changes: 4 additions & 3 deletions bindings/pydrake/systems/lcm_pybind.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
/// @file
/// Helpers for defining C++ LCM type serializers.

#include <memory>
#include <string>
#include <utility>

Expand Down Expand Up @@ -32,9 +33,9 @@ py::object BindCppSerializer(const std::string& lcm_package) {
py::object py_type =
py::module::import(lcm_package.c_str()).attr(CppType::getTypeName());
py::module lcm_py = py::module::import("pydrake.systems.lcm");
auto py_cls =
DefineTemplateClassWithDefault<Serializer<CppType>, SerializerInterface>(
lcm_py, "_Serializer", py::make_tuple(py_type));
auto py_cls = DefineTemplateClassWithDefault<Serializer<CppType>,
SerializerInterface, std::shared_ptr<Serializer<CppType>>>(
lcm_py, "_Serializer", py::make_tuple(py_type));
py_cls.def(py::init());
// We use move here because the type of py_class differs from our declared
// return type.
Expand Down
6 changes: 4 additions & 2 deletions bindings/pydrake/systems/test/lcm_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,8 @@ def test_serializer(self):
reconstruct = lcmt_quaternion.decode(raw)
self.assert_lcm_equal(reconstruct, model_message)
# Check cloning.
cloned_dut = dut.Clone()
with catch_drake_warnings(expected_count=1):
cloned_dut = dut.Clone()
fresh_value = dut.CreateDefaultValue().get_value()
self.assertIsInstance(fresh_value, lcmt_quaternion)

Expand All @@ -92,7 +93,8 @@ def test_serializer_cpp(self):

def test_serializer_cpp_clone(self):
serializer = mut._Serializer_[lcmt_quaternion]()
serializer.Clone().CreateDefaultValue()
with catch_drake_warnings(expected_count=1):
serializer.Clone().CreateDefaultValue()

def test_all_serializers_exist(self):
"""Checks that all of Drake's Python LCM messages have a matching C++
Expand Down
9 changes: 9 additions & 0 deletions systems/lcm/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -216,4 +216,13 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "serializer_deprecated_test",
copts = ["-Wno-deprecated-declarations"],
deps = [
":serializer",
"//lcmtypes:drake_signal",
],
)

add_lint_tests()
4 changes: 2 additions & 2 deletions systems/lcm/lcm_publisher_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ using systems::TriggerTypeSet;

LcmPublisherSystem::LcmPublisherSystem(
const std::string& channel,
std::unique_ptr<SerializerInterface> serializer,
std::shared_ptr<const SerializerInterface> serializer,
DrakeLcmInterface* lcm,
const TriggerTypeSet& publish_triggers,
double publish_period)
Expand Down Expand Up @@ -73,7 +73,7 @@ LcmPublisherSystem::LcmPublisherSystem(

LcmPublisherSystem::LcmPublisherSystem(
const std::string& channel,
std::unique_ptr<SerializerInterface> serializer,
std::shared_ptr<const SerializerInterface> serializer,
DrakeLcmInterface* lcm, double publish_period)
: LcmPublisherSystem(channel, std::move(serializer), lcm,
(publish_period > 0.0) ?
Expand Down
6 changes: 3 additions & 3 deletions systems/lcm/lcm_publisher_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ class LcmPublisherSystem : public LeafSystem<double> {
* @pre publish_period is non-negative.
*/
LcmPublisherSystem(const std::string& channel,
std::unique_ptr<SerializerInterface> serializer,
std::shared_ptr<const SerializerInterface> serializer,
drake::lcm::DrakeLcmInterface* lcm,
double publish_period = 0.0);

Expand Down Expand Up @@ -173,7 +173,7 @@ class LcmPublisherSystem : public LeafSystem<double> {
* @pre publish_triggers contains a subset of {kForced, kPeriodic, kPerStep}.
*/
LcmPublisherSystem(const std::string& channel,
std::unique_ptr<SerializerInterface> serializer,
std::shared_ptr<const SerializerInterface> serializer,
drake::lcm::DrakeLcmInterface* lcm,
const systems::TriggerTypeSet& publish_triggers,
double publish_period = 0.0);
Expand Down Expand Up @@ -235,7 +235,7 @@ class LcmPublisherSystem : public LeafSystem<double> {
InitializationPublisher initialization_publisher_;

// Converts Value<LcmMessage> objects into LCM message bytes.
const std::unique_ptr<SerializerInterface> serializer_;
const std::shared_ptr<const SerializerInterface> serializer_;

// If we're not given a DrakeLcm object, we allocate one and keep it here.
// The unique_ptr is const, not the held object.
Expand Down
2 changes: 1 addition & 1 deletion systems/lcm/lcm_subscriber_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ constexpr int kMagic = 6832; // An arbitrary value.

LcmSubscriberSystem::LcmSubscriberSystem(
const std::string& channel,
std::unique_ptr<SerializerInterface> serializer,
std::shared_ptr<const SerializerInterface> serializer,
drake::lcm::DrakeLcmInterface* lcm)
: channel_(channel),
serializer_(std::move(serializer)),
Expand Down
4 changes: 2 additions & 2 deletions systems/lcm/lcm_subscriber_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ class LcmSubscriberSystem : public LeafSystem<double> {
* @param lcm A non-null pointer to the LCM subsystem to subscribe on.
*/
LcmSubscriberSystem(const std::string& channel,
std::unique_ptr<SerializerInterface> serializer,
std::shared_ptr<const SerializerInterface> serializer,
drake::lcm::DrakeLcmInterface* lcm);

~LcmSubscriberSystem() override;
Expand Down Expand Up @@ -134,7 +134,7 @@ class LcmSubscriberSystem : public LeafSystem<double> {

// Converts LCM message bytes to Value<LcmMessage> objects.
// Will be non-null iff our output port is abstract-valued.
const std::unique_ptr<SerializerInterface> serializer_;
const std::shared_ptr<const SerializerInterface> serializer_;

// The mutex that guards received_message_ and received_message_count_.
mutable std::mutex received_message_mutex_;
Expand Down
9 changes: 6 additions & 3 deletions systems/lcm/serializer.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@

#include "drake/common/drake_assert.h"
#include "drake/common/drake_copyable.h"
#include "drake/common/drake_deprecated.h"
#include "drake/common/drake_throw.h"
#include "drake/common/value.h"

Expand All @@ -16,16 +17,18 @@ namespace lcm {
/**
* %SerializerInterface translates between LCM message bytes and
* drake::AbstractValue objects that contain LCM messages, e.g., a
* Value<lcmt_drake_signal>. See Serializer for a message-specific concrete
* subclass.
* Value<lcmt_drake_signal>. All `const` methods are threadsafe.
* See Serializer for a message-specific concrete subclass.
*/
class SerializerInterface {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(SerializerInterface)

virtual ~SerializerInterface();

/** Creates a deep copy of this. */
DRAKE_DEPRECATED(
"2023-09-01",
"Use a shared_ptr<const SerializerInterface> instead of cloning.")
virtual std::unique_ptr<SerializerInterface> Clone() const = 0;

/**
Expand Down
30 changes: 30 additions & 0 deletions systems/lcm/test/serializer_deprecated_test.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#include <gtest/gtest.h>

#include "drake/common/is_cloneable.h"
#include "drake/lcmt_drake_signal.hpp"
#include "drake/systems/lcm/serializer.h"

namespace drake {
namespace systems {
namespace lcm {
namespace {

GTEST_TEST(SerializerDeprecatedTest, BasicTest) {
// The device under test.
auto dut = std::make_unique<Serializer<lcmt_drake_signal>>();

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
// Cloning works.
EXPECT_TRUE(is_cloneable<SerializerInterface>::value);
auto fresh = dut->Clone();
ASSERT_NE(fresh, nullptr);
auto fresh_value = fresh->CreateDefaultValue();
EXPECT_EQ(fresh_value->get_value<lcmt_drake_signal>().dim, 0);
#pragma GCC diagnostic pop
}

} // namespace
} // namespace lcm
} // namespace systems
} // namespace drake
8 changes: 0 additions & 8 deletions systems/lcm/test/serializer_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@

#include <gtest/gtest.h>

#include "drake/common/is_cloneable.h"
#include "drake/lcm/lcmt_drake_signal_utils.h"
#include "drake/lcmt_drake_signal.hpp"

Expand Down Expand Up @@ -43,13 +42,6 @@ GTEST_TEST(SerializerTest, BasicTest) {
abstract_value.get());
EXPECT_TRUE(CompareLcmtDrakeSignalMessages(
abstract_value->get_value<lcmt_drake_signal>(), sample_data));

// Cloning works.
EXPECT_TRUE(is_cloneable<SerializerInterface>::value);
auto fresh = dut->Clone();
ASSERT_NE(fresh, nullptr);
auto fresh_value = fresh->CreateDefaultValue();
EXPECT_EQ(fresh_value->get_value<lcmt_drake_signal>().dim, 0);
}

} // namespace
Expand Down

0 comments on commit c9b02b9

Please sign in to comment.