Template Struct AnySubscriptionCallbackPossibleTypes
Defined in File any_subscription_callback.hpp
Struct Documentation
-
template<typename MessageT, typename AllocatorT>
struct AnySubscriptionCallbackPossibleTypes Struct which contains all possible callback signatures, with or without a TypeAdapter.s.
Public Types
-
using SubscribedType = typename rclcpp::TypeAdapter<MessageT>::custom_type
MessageT::custom_type if MessageT is a TypeAdapter, otherwise just MessageT.
-
using ROSMessageType = typename rclcpp::TypeAdapter<MessageT>::ros_message_type
MessageT::ros_message_type if MessageT is a TypeAdapter, otherwise just MessageT.
-
using SubscribedMessageDeleter = typename MessageDeleterHelper<SubscribedType, AllocatorT>::Deleter
-
using ROSMessageDeleter = typename MessageDeleterHelper<ROSMessageType, AllocatorT>::Deleter
-
using SerializedMessageDeleter = typename MessageDeleterHelper<rclcpp::SerializedMessage, AllocatorT>::Deleter
-
using ConstRefCallback = std::function<void(const SubscribedType&)>
-
using ConstRefROSMessageCallback = std::function<void(const ROSMessageType&)>
-
using ConstRefWithInfoCallback = std::function<void(const SubscribedType&, const rclcpp::MessageInfo&)>
-
using ConstRefWithInfoROSMessageCallback = std::function<void(const ROSMessageType&, const rclcpp::MessageInfo&)>
-
using ConstRefSerializedMessageCallback = std::function<void(const rclcpp::SerializedMessage&)>
-
using ConstRefSerializedMessageWithInfoCallback = std::function<void(const rclcpp::SerializedMessage&, const rclcpp::MessageInfo&)>
-
using UniquePtrCallback = std::function<void(std::unique_ptr<SubscribedType, SubscribedMessageDeleter>)>
-
using UniquePtrROSMessageCallback = std::function<void(std::unique_ptr<ROSMessageType, ROSMessageDeleter>)>
-
using UniquePtrWithInfoCallback = std::function<void(std::unique_ptr<SubscribedType, SubscribedMessageDeleter>, const rclcpp::MessageInfo&)>
-
using UniquePtrWithInfoROSMessageCallback = std::function<void(std::unique_ptr<ROSMessageType, ROSMessageDeleter>, const rclcpp::MessageInfo&)>
-
using UniquePtrSerializedMessageCallback = std::function<void(std::unique_ptr<rclcpp::SerializedMessage, SerializedMessageDeleter>)>
-
using UniquePtrSerializedMessageWithInfoCallback = std::function<void(std::unique_ptr<rclcpp::SerializedMessage, SerializedMessageDeleter>, const rclcpp::MessageInfo&)>
-
using SubscribedType = typename rclcpp::TypeAdapter<MessageT>::custom_type