Skip to content

Commit 8754f9e

Browse files
committed
Fix delivered message kind
Signed-off-by: methylDragon <[email protected]>
1 parent 77ede02 commit 8754f9e

File tree

3 files changed

+8
-8
lines changed

3 files changed

+8
-8
lines changed

rclcpp/include/rclcpp/subscription_base.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -260,13 +260,13 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
260260
bool
261261
is_serialized() const;
262262

263-
/// Return the type of the subscription.
263+
/// Return the delivered message kind.
264264
/**
265265
* \return `DeliveredMessageKind`, which adjusts how messages are received and delivered.
266266
*/
267267
RCLCPP_PUBLIC
268268
DeliveredMessageKind
269-
get_subscription_type() const;
269+
get_delivered_message_kind() const;
270270

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

665665
rosidl_message_type_support_t type_support_;
666-
DeliveredMessageKind delivered_message_type_;
666+
DeliveredMessageKind delivered_message_kind_;
667667

668668
std::atomic<bool> subscription_in_use_by_wait_set_{false};
669669
std::atomic<bool> intra_process_subscription_waitable_in_use_by_wait_set_{false};

rclcpp/src/rclcpp/executor.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -603,7 +603,7 @@ Executor::execute_subscription(rclcpp::SubscriptionBase::SharedPtr subscription)
603603
rclcpp::MessageInfo message_info;
604604
message_info.get_rmw_message_info().from_intra_process = false;
605605

606-
switch (subscription->get_subscription_type()) {
606+
switch (subscription->get_delivered_message_kind()) {
607607
// Deliver ROS message
608608
case rclcpp::DeliveredMessageKind::ROS_MESSAGE:
609609
{

rclcpp/src/rclcpp/subscription_base.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ SubscriptionBase::SubscriptionBase(
5252
intra_process_subscription_id_(0),
5353
event_callbacks_(event_callbacks),
5454
type_support_(type_support_handle),
55-
delivered_message_type_(delivered_message_kind)
55+
delivered_message_kind_(delivered_message_kind)
5656
{
5757
auto custom_deletor = [node_handle = this->node_handle_](rcl_subscription_t * rcl_subs)
5858
{
@@ -261,13 +261,13 @@ SubscriptionBase::get_message_type_support_handle() const
261261
bool
262262
SubscriptionBase::is_serialized() const
263263
{
264-
return delivered_message_type_ == rclcpp::DeliveredMessageKind::SERIALIZED_MESSAGE;
264+
return delivered_message_kind_ == rclcpp::DeliveredMessageKind::SERIALIZED_MESSAGE;
265265
}
266266

267267
rclcpp::DeliveredMessageKind
268-
SubscriptionBase::get_subscription_type() const
268+
SubscriptionBase::get_delivered_message_kind() const
269269
{
270-
return delivered_message_type_;
270+
return delivered_message_kind_;
271271
}
272272

273273
size_t

0 commit comments

Comments
 (0)