Commit 8754f9e 1 parent 77ede02 commit 8754f9e Copy full SHA for 8754f9e
File tree 3 files changed +8
-8
lines changed
3 files changed +8
-8
lines changed Original file line number Diff line number Diff line change @@ -260,13 +260,13 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
260
260
bool
261
261
is_serialized () const ;
262
262
263
- // / Return the type of the subscription .
263
+ // / Return the delivered message kind .
264
264
/* *
265
265
* \return `DeliveredMessageKind`, which adjusts how messages are received and delivered.
266
266
*/
267
267
RCLCPP_PUBLIC
268
268
DeliveredMessageKind
269
- get_subscription_type () const ;
269
+ get_delivered_message_kind () const ;
270
270
271
271
// / Get matching publisher count.
272
272
/* * \return The number of publishers on this topic. */
@@ -663,7 +663,7 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
663
663
RCLCPP_DISABLE_COPY (SubscriptionBase)
664
664
665
665
rosidl_message_type_support_t type_support_;
666
- DeliveredMessageKind delivered_message_type_ ;
666
+ DeliveredMessageKind delivered_message_kind_ ;
667
667
668
668
std::atomic<bool > subscription_in_use_by_wait_set_{false };
669
669
std::atomic<bool > intra_process_subscription_waitable_in_use_by_wait_set_{false };
Original file line number Diff line number Diff line change @@ -603,7 +603,7 @@ Executor::execute_subscription(rclcpp::SubscriptionBase::SharedPtr subscription)
603
603
rclcpp::MessageInfo message_info;
604
604
message_info.get_rmw_message_info ().from_intra_process = false ;
605
605
606
- switch (subscription->get_subscription_type ()) {
606
+ switch (subscription->get_delivered_message_kind ()) {
607
607
// Deliver ROS message
608
608
case rclcpp::DeliveredMessageKind::ROS_MESSAGE:
609
609
{
Original file line number Diff line number Diff line change @@ -52,7 +52,7 @@ SubscriptionBase::SubscriptionBase(
52
52
intra_process_subscription_id_(0 ),
53
53
event_callbacks_(event_callbacks),
54
54
type_support_(type_support_handle),
55
- delivered_message_type_ (delivered_message_kind)
55
+ delivered_message_kind_ (delivered_message_kind)
56
56
{
57
57
auto custom_deletor = [node_handle = this ->node_handle_ ](rcl_subscription_t * rcl_subs)
58
58
{
@@ -261,13 +261,13 @@ SubscriptionBase::get_message_type_support_handle() const
261
261
bool
262
262
SubscriptionBase::is_serialized () const
263
263
{
264
- return delivered_message_type_ == rclcpp::DeliveredMessageKind::SERIALIZED_MESSAGE;
264
+ return delivered_message_kind_ == rclcpp::DeliveredMessageKind::SERIALIZED_MESSAGE;
265
265
}
266
266
267
267
rclcpp::DeliveredMessageKind
268
- SubscriptionBase::get_subscription_type () const
268
+ SubscriptionBase::get_delivered_message_kind () const
269
269
{
270
- return delivered_message_type_ ;
270
+ return delivered_message_kind_ ;
271
271
}
272
272
273
273
size_t
You can’t perform that action at this time.
0 commit comments