3#include "modulo_core/communication/SubscriptionInterface.hpp"
5#include "modulo_core/concepts.hpp"
14template<
typename MsgT>
23 std::shared_ptr<MessagePairInterface> message_pair =
nullptr,
24 const rclcpp::Logger& logger = rclcpp::get_logger(
"SubscriptionHandler"));
34 [[nodiscard]] std::shared_ptr<rclcpp::Subscription<MsgT>>
get_subscription()
const;
41 void set_subscription(
const std::shared_ptr<rclcpp::Subscription<MsgT>>& subscription);
52 std::function<void(
const std::shared_ptr<MsgT>)>
get_callback();
59 std::function<void(
const std::shared_ptr<MsgT>)>
get_callback(
const std::function<
void()>& user_callback);
69 std::shared_ptr<SubscriptionInterface>
76 void handle_callback_exceptions();
84 std::function<void(
const std::shared_ptr<MsgT>)> get_translated_callback();
92 std::function<void(
const std::shared_ptr<MsgT>)> get_raw_callback();
94 std::shared_ptr<rclcpp::Subscription<MsgT>> subscription_;
95 rclcpp::Logger logger_;
96 std::shared_ptr<rclcpp::Clock> clock_;
97 std::function<void()> user_callback_ = [] {
101template<
typename MsgT>
103 std::shared_ptr<MessagePairInterface> message_pair,
const rclcpp::Logger& logger)
104 :
SubscriptionInterface(std::move(message_pair)), logger_(logger), clock_(std::make_shared<rclcpp::Clock>()) {}
106template<
typename MsgT>
108 this->subscription_.reset();
111template<
typename MsgT>
113 return this->subscription_;
116template<
typename MsgT>
118 if (subscription ==
nullptr) {
121 this->subscription_ = subscription;
124template<
typename MsgT>
127 return get_translated_callback();
129 return get_raw_callback();
133template<
typename MsgT>
135 return [
this](
const std::shared_ptr<MsgT> message) {
137 this->get_message_pair()->template read<MsgT, MsgT>(*message);
138 this->user_callback_();
140 this->handle_callback_exceptions();
145template<
typename MsgT>
147 this->user_callback_ = user_callback;
150template<
typename MsgT>
151std::function<void(
const std::shared_ptr<MsgT>)>
153 this->set_user_callback(user_callback);
154 return this->get_callback();
157template<
typename MsgT>
159 const std::shared_ptr<rclcpp::Subscription<MsgT>>& subscription) {
160 this->set_subscription(subscription);
161 return std::shared_ptr<SubscriptionInterface>(this->shared_from_this());
164template<
typename MsgT>
170 RCLCPP_WARN_STREAM_THROTTLE(
171 this->logger_, *this->clock_, 1000,
"Exception in subscription callback: " << ex.what());
172 }
catch (
const std::exception& ex) {
173 RCLCPP_WARN_STREAM_THROTTLE(
174 this->logger_, *this->clock_, 1000,
"Unhandled exception in subscription user callback: " << ex.what());
The SubscriptionHandler handles different types of ROS subscriptions to receive data from those subsc...
std::function< void(const std::shared_ptr< MsgT >)> get_callback()
Get a callback function that will be associated with the ROS subscription to receive and translate me...
SubscriptionHandler(std::shared_ptr< MessagePairInterface > message_pair=nullptr, const rclcpp::Logger &logger=rclcpp::get_logger("SubscriptionHandler"))
Constructor with the message pair.
~SubscriptionHandler() override
Destructor to explicitly reset the subscription pointer.
std::shared_ptr< SubscriptionInterface > create_subscription_interface(const std::shared_ptr< rclcpp::Subscription< MsgT > > &subscription)
Create a SubscriptionInterface pointer through an instance of a SubscriptionHandler by providing a RO...
std::shared_ptr< rclcpp::Subscription< MsgT > > get_subscription() const
Getter of the ROS subscription.
void set_subscription(const std::shared_ptr< rclcpp::Subscription< MsgT > > &subscription)
Setter of the ROS subscription.
void set_user_callback(const std::function< void()> &user_callback)
Setter of a user callback function to be executed after the subscription callback.
Interface class to enable non-templated subscriptions with ROS subscriptions from derived Subscriptio...
A base class for all core exceptions.
An exception class to notify that a certain pointer is null.
Modulo Core communication module for handling messages on publication and subscription interfaces.