Skip to content

Commit d7fdb61

Browse files
mauropasseMauro Passerino
andauthored
Declare rclcpp callbacks before the rcl entities (#2024)
This is to ensure callbacks are destroyed last on entities destruction, avoiding the gap in time in which rmw entities hold a reference to a destroyed function. Signed-off-by: Mauro Passerino <[email protected]> Co-authored-by: Mauro Passerino <[email protected]>
1 parent 58bcd3b commit d7fdb61

File tree

3 files changed

+22
-9
lines changed

3 files changed

+22
-9
lines changed

rclcpp/include/rclcpp/client.hpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -363,12 +363,16 @@ class ClientBase
363363
std::shared_ptr<rclcpp::Context> context_;
364364
rclcpp::Logger node_logger_;
365365

366+
std::recursive_mutex callback_mutex_;
367+
// It is important to declare on_new_response_callback_ before
368+
// client_handle_, so on destruction the client is
369+
// destroyed first. Otherwise, the rmw client callback
370+
// would point briefly to a destroyed function.
371+
std::function<void(size_t)> on_new_response_callback_{nullptr};
372+
// Declare client_handle_ after callback
366373
std::shared_ptr<rcl_client_t> client_handle_;
367374

368375
std::atomic<bool> in_use_by_wait_set_{false};
369-
370-
std::recursive_mutex callback_mutex_;
371-
std::function<void(size_t)> on_new_response_callback_{nullptr};
372376
};
373377

374378
template<typename ServiceT>

rclcpp/include/rclcpp/service.hpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -265,15 +265,19 @@ class ServiceBase
265265

266266
std::shared_ptr<rcl_node_t> node_handle_;
267267

268+
std::recursive_mutex callback_mutex_;
269+
// It is important to declare on_new_request_callback_ before
270+
// service_handle_, so on destruction the service is
271+
// destroyed first. Otherwise, the rmw service callback
272+
// would point briefly to a destroyed function.
273+
std::function<void(size_t)> on_new_request_callback_{nullptr};
274+
// Declare service_handle_ after callback
268275
std::shared_ptr<rcl_service_t> service_handle_;
269276
bool owns_rcl_handle_ = true;
270277

271278
rclcpp::Logger node_logger_;
272279

273280
std::atomic<bool> in_use_by_wait_set_{false};
274-
275-
std::recursive_mutex callback_mutex_;
276-
std::function<void(size_t)> on_new_request_callback_{nullptr};
277281
};
278282

279283
template<typename ServiceT>

rclcpp/include/rclcpp/subscription_base.hpp

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -645,6 +645,14 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
645645
rclcpp::node_interfaces::NodeBaseInterface * const node_base_;
646646

647647
std::shared_ptr<rcl_node_t> node_handle_;
648+
649+
std::recursive_mutex callback_mutex_;
650+
// It is important to declare on_new_message_callback_ before
651+
// subscription_handle_, so on destruction the subscription is
652+
// destroyed first. Otherwise, the rmw subscription callback
653+
// would point briefly to a destroyed function.
654+
std::function<void(size_t)> on_new_message_callback_{nullptr};
655+
// Declare subscription_handle_ after callback
648656
std::shared_ptr<rcl_subscription_t> subscription_handle_;
649657
std::shared_ptr<rcl_subscription_t> intra_process_subscription_handle_;
650658
rclcpp::Logger node_logger_;
@@ -669,9 +677,6 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
669677
std::atomic<bool> intra_process_subscription_waitable_in_use_by_wait_set_{false};
670678
std::unordered_map<rclcpp::EventHandlerBase *,
671679
std::atomic<bool>> qos_events_in_use_by_wait_set_;
672-
673-
std::recursive_mutex callback_mutex_;
674-
std::function<void(size_t)> on_new_message_callback_{nullptr};
675680
};
676681

677682
} // namespace rclcpp

0 commit comments

Comments
 (0)