Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[lcm] SerializerInterface is now cloneable #15394

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions bindings/pydrake/systems/_lcm_extra.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,9 @@ def __init__(self, lcm_type):
SerializerInterface.__init__(self)
self._lcm_type = lcm_type

def Clone(self):
return PySerializer(self._lcm_type)

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

Expand Down
6 changes: 6 additions & 0 deletions bindings/pydrake/systems/lcm_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,11 @@ class PySerializerInterface : public py::wrapper<SerializerInterface> {
// `PySerializerInterface`). C++ implementations will use the bindings on the
// interface below.

std::unique_ptr<SerializerInterface> Clone() const override {
PYBIND11_OVERLOAD_PURE(
std::unique_ptr<SerializerInterface>, SerializerInterface, Clone);
}

std::unique_ptr<AbstractValue> CreateDefaultValue() const override {
PYBIND11_OVERLOAD_PURE(std::unique_ptr<AbstractValue>, SerializerInterface,
CreateDefaultValue);
Expand Down Expand Up @@ -138,6 +143,7 @@ PYBIND11_MODULE(lcm, m) {
message_bytes.size());
},
py::arg("abstract_value"), cls_doc.Serialize.doc);
DefClone(&cls);
}

{
Expand Down
8 changes: 8 additions & 0 deletions bindings/pydrake/systems/test/lcm_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,10 @@ def test_serializer(self):
raw = dut.Serialize(value)
reconstruct = lcmt_quaternion.decode(raw)
self.assert_lcm_equal(reconstruct, model_message)
# Check cloning.
cloned_dut = dut.Clone()
fresh_value = dut.CreateDefaultValue().get_value()
self.assertIsInstance(fresh_value, lcmt_quaternion)

def test_serializer_cpp(self):
# Tests relevant portions of API.
Expand All @@ -82,6 +86,10 @@ def test_serializer_cpp(self):
self.assert_lcm_equal(
self._cpp_value_to_py_message(model_value), model_message)

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

def _process_event(self, dut):
# Use a Simulator to invoke the update event on `dut`. (Wouldn't it be
# nice if the Systems API was simple enough that we could apply events
Expand Down
13 changes: 10 additions & 3 deletions systems/lcm/serializer.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,9 @@ class SerializerInterface {

virtual ~SerializerInterface();

/** Creates a deep copy of this. */
virtual std::unique_ptr<SerializerInterface> Clone() const = 0;

/**
* Creates a value-initialized (zeroed) instance of the message object.
* The result can be used as the output object filled in by Deserialize.
Expand All @@ -45,7 +48,7 @@ class SerializerInterface {
std::vector<uint8_t>* message_bytes) const = 0;

protected:
SerializerInterface() {}
SerializerInterface() = default;
};

/**
Expand All @@ -59,8 +62,12 @@ class Serializer : public SerializerInterface {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Serializer)

Serializer() {}
~Serializer() override {}
Serializer() = default;
~Serializer() override = default;

std::unique_ptr<SerializerInterface> Clone() const override {
return std::make_unique<Serializer>();
}

std::unique_ptr<AbstractValue> CreateDefaultValue() const override {
// NOTE: We create the message using value-initialization ("{}") to ensure
Expand Down
8 changes: 8 additions & 0 deletions systems/lcm/test/serializer_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@

#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 @@ -42,6 +43,13 @@ 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