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

Switch pub/sub serializers away from unique_ptr #374

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
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
4 changes: 2 additions & 2 deletions drake_ros/core/ros_publisher_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -13,13 +13,13 @@ namespace drake_ros {
namespace core {
struct RosPublisherSystem::Impl {
// Interface for message (de)serialization.
std::unique_ptr<SerializerInterface> serializer;
std::shared_ptr<const SerializerInterface> serializer;
// Publisher for serialized messages.
std::unique_ptr<internal::Publisher> pub;
};

RosPublisherSystem::RosPublisherSystem(
std::unique_ptr<SerializerInterface> serializer,
std::shared_ptr<const SerializerInterface> serializer,
const std::string& topic_name, const rclcpp::QoS& qos, DrakeRos* ros,
const std::unordered_set<drake::systems::TriggerType>& publish_triggers,
double publish_period)
Expand Down
2 changes: 1 addition & 1 deletion drake_ros/core/ros_publisher_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ class RosPublisherSystem : public drake::systems::LeafSystem<double> {
@param[in] publish_period optional publishing period, in seconds.
Only applicable when periodic publishing is enabled.
*/
RosPublisherSystem(std::unique_ptr<SerializerInterface> serializer,
RosPublisherSystem(std::shared_ptr<const SerializerInterface> serializer,
const std::string& topic_name, const rclcpp::QoS& qos,
DrakeRos* ros,
const std::unordered_set<drake::systems::TriggerType>&
Expand Down
4 changes: 2 additions & 2 deletions drake_ros/core/ros_subscriber_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class MessageQueue {

struct RosSubscriberSystem::Impl {
// Interface for message (de)serialization.
std::unique_ptr<SerializerInterface> serializer;
std::shared_ptr<const SerializerInterface> serializer;
// Subscription to serialized messages.
std::shared_ptr<internal::Subscription> sub;
// Queue of serialized messages.
Expand All @@ -45,7 +45,7 @@ struct RosSubscriberSystem::Impl {
};

RosSubscriberSystem::RosSubscriberSystem(
std::unique_ptr<SerializerInterface> serializer,
std::shared_ptr<const SerializerInterface> serializer,
const std::string& topic_name, const rclcpp::QoS& qos, DrakeRos* ros)
: impl_(new Impl()) {
impl_->serializer = std::move(serializer);
Expand Down
4 changes: 2 additions & 2 deletions drake_ros/core/ros_subscriber_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ class RosSubscriberSystem : public drake::systems::LeafSystem<double> {
static std::unique_ptr<RosSubscriberSystem> Make(ArgsT&&... args) {
// Assume C++ typesupport since this is a C++ template function
return std::make_unique<RosSubscriberSystem>(
std::make_unique<Serializer<MessageT>>(), std::forward<ArgsT>(args)...);
std::make_shared<Serializer<MessageT>>(), std::forward<ArgsT>(args)...);
}

/** A constructor for the ROS subscriber system.
Expand All @@ -41,7 +41,7 @@ class RosSubscriberSystem : public drake::systems::LeafSystem<double> {
@param[in] qos QoS profile for the underlying ROS subscription.
@param[in] ros interface to a live ROS node to publish from.
*/
RosSubscriberSystem(std::unique_ptr<SerializerInterface> serializer,
RosSubscriberSystem(std::shared_ptr<const SerializerInterface> serializer,
const std::string& topic_name, const rclcpp::QoS& qos,
DrakeRos* ros);

Expand Down
21 changes: 15 additions & 6 deletions drake_ros/drake_ros/core/cc_pybind.cc
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,9 @@ using py_rvp = pybind11::return_value_policy;

// A (de)serialization interface implementation for Python ROS messages
// that can be overriden from Python itself.
class PySerializerInterface : public py::wrapper<SerializerInterface> {
class PySerializerInterface : public SerializerInterface {
public:
using Base = py::wrapper<SerializerInterface>;
using Base = SerializerInterface;

PySerializerInterface() : Base() {}

Expand All @@ -50,8 +50,17 @@ class PySerializerInterface : public py::wrapper<SerializerInterface> {
}

std::unique_ptr<drake::AbstractValue> CreateDefaultValue() const override {
PYBIND11_OVERLOAD_PURE(std::unique_ptr<drake::AbstractValue>,
SerializerInterface, CreateDefaultValue);
// Our required unique_ptr return type cannot be directly fulfilled by a
// Python override, so we only ask the Python override for a py::object and
// then just Clone it to obtain the necessary C++ signature. Because the
// PYBIND11_OVERLOAD_PURE macro embeds a `return ...;` statement, we must
// wrap it in lambda so that we can post-process the return value.
py::object default_value = [this]() -> py::object {
PYBIND11_OVERLOAD_PURE(
py::object, SerializerInterface, CreateDefaultValue);
}();
DRAKE_THROW_UNLESS(!default_value.is_none());
return default_value.template cast<const drake::AbstractValue*>()->Clone();
}

rclcpp::SerializedMessage Serialize(
Expand Down Expand Up @@ -247,7 +256,7 @@ void DefCore(py::module m) {
});

py::class_<RosPublisherSystem, LeafSystem<double>>(m, "RosPublisherSystem")
.def(py::init([](std::unique_ptr<SerializerInterface> serializer,
.def(py::init([](std::shared_ptr<const SerializerInterface> serializer,
const char* topic_name, QoS qos, DrakeRos* ros_interface,
std::unordered_set<TriggerType> publish_triggers,
double publish_period) {
Expand All @@ -257,7 +266,7 @@ void DefCore(py::module m) {
}));

py::class_<RosSubscriberSystem, LeafSystem<double>>(m, "RosSubscriberSystem")
.def(py::init([](std::unique_ptr<SerializerInterface> serializer,
.def(py::init([](std::shared_ptr<const SerializerInterface> serializer,
const char* topic_name, QoS qos,
DrakeRos* ros_interface) {
return std::make_unique<RosSubscriberSystem>(
Expand Down
Loading