Skip to content

Commit

Permalink
Override handle_serialized_message. (#21)
Browse files Browse the repository at this point in the history
* Override handle_serialized_message.

This should allow it to build against rolling again.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Remove the override flag with a note explaining why.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
  • Loading branch information
clalancette committed May 19, 2021
1 parent 603357e commit 0ff31bd
Show file tree
Hide file tree
Showing 2 changed files with 17 additions and 0 deletions.
8 changes: 8 additions & 0 deletions src/domain_bridge/generic_subscription.cpp
Expand Up @@ -79,6 +79,14 @@ void GenericSubscription::handle_loaned_message(
(void) message_info;
}

void GenericSubscription::handle_serialized_message(
const std::shared_ptr<rclcpp::SerializedMessage> & serialized_message,
const rclcpp::MessageInfo & message_info)
{
(void) serialized_message;
(void) message_info;
}

void GenericSubscription::return_message(std::shared_ptr<void> & message)
{
auto typed_message = std::static_pointer_cast<rclcpp::SerializedMessage>(message);
Expand Down
9 changes: 9 additions & 0 deletions src/domain_bridge/generic_subscription.hpp
Expand Up @@ -69,6 +69,15 @@ class GenericSubscription : public rclcpp::SubscriptionBase
void handle_loaned_message(
void * loaned_message, const rclcpp::MessageInfo & message_info) override;

// Post-Galactic, handle_serialized_message is a pure virtual function in
// rclcpp::SubscriptionBase, so we must override it. However, in order to
// make this change compatible with both Galactic and later, we leave off
// the 'override' flag.
void
handle_serialized_message(
const std::shared_ptr<rclcpp::SerializedMessage> & serialized_message,
const rclcpp::MessageInfo & message_info);

// Same as return_serialized_message() as the subscription is to serialized_messages only
void return_message(std::shared_ptr<void> & message) override;

Expand Down

0 comments on commit 0ff31bd

Please sign in to comment.