Skip to content

Commit

Permalink
Fix delivered message kind (#2175)
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon authored May 1, 2023
1 parent 77ede02 commit 6ca1023
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 8 deletions.
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/subscription_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -260,13 +260,13 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
bool
is_serialized() const;

/// Return the type of the subscription.
/// Return the delivered message kind.
/**
* \return `DeliveredMessageKind`, which adjusts how messages are received and delivered.
*/
RCLCPP_PUBLIC
DeliveredMessageKind
get_subscription_type() const;
get_delivered_message_kind() const;

/// Get matching publisher count.
/** \return The number of publishers on this topic. */
Expand Down Expand Up @@ -663,7 +663,7 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
RCLCPP_DISABLE_COPY(SubscriptionBase)

rosidl_message_type_support_t type_support_;
DeliveredMessageKind delivered_message_type_;
DeliveredMessageKind delivered_message_kind_;

std::atomic<bool> subscription_in_use_by_wait_set_{false};
std::atomic<bool> intra_process_subscription_waitable_in_use_by_wait_set_{false};
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -603,7 +603,7 @@ Executor::execute_subscription(rclcpp::SubscriptionBase::SharedPtr subscription)
rclcpp::MessageInfo message_info;
message_info.get_rmw_message_info().from_intra_process = false;

switch (subscription->get_subscription_type()) {
switch (subscription->get_delivered_message_kind()) {
// Deliver ROS message
case rclcpp::DeliveredMessageKind::ROS_MESSAGE:
{
Expand Down
8 changes: 4 additions & 4 deletions rclcpp/src/rclcpp/subscription_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ SubscriptionBase::SubscriptionBase(
intra_process_subscription_id_(0),
event_callbacks_(event_callbacks),
type_support_(type_support_handle),
delivered_message_type_(delivered_message_kind)
delivered_message_kind_(delivered_message_kind)
{
auto custom_deletor = [node_handle = this->node_handle_](rcl_subscription_t * rcl_subs)
{
Expand Down Expand Up @@ -261,13 +261,13 @@ SubscriptionBase::get_message_type_support_handle() const
bool
SubscriptionBase::is_serialized() const
{
return delivered_message_type_ == rclcpp::DeliveredMessageKind::SERIALIZED_MESSAGE;
return delivered_message_kind_ == rclcpp::DeliveredMessageKind::SERIALIZED_MESSAGE;
}

rclcpp::DeliveredMessageKind
SubscriptionBase::get_subscription_type() const
SubscriptionBase::get_delivered_message_kind() const
{
return delivered_message_type_;
return delivered_message_kind_;
}

size_t
Expand Down

0 comments on commit 6ca1023

Please sign in to comment.