Template Struct AnySubscriptionCallbackPossibleTypes

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 SharedConstPtrCallback = std::function<void(std::shared_ptr<const SubscribedType>)>
using SharedConstPtrROSMessageCallback = std::function<void(std::shared_ptr<const ROSMessageType>)>
using SharedConstPtrWithInfoCallback = std::function<void(std::shared_ptr<const SubscribedType>, const rclcpp::MessageInfo&)>
using SharedConstPtrWithInfoROSMessageCallback = std::function<void(std::shared_ptr<const ROSMessageType>, const rclcpp::MessageInfo&)>
using SharedConstPtrSerializedMessageCallback = std::function<void(std::shared_ptr<const rclcpp::SerializedMessage>)>
using SharedConstPtrSerializedMessageWithInfoCallback = std::function<void(std::shared_ptr<const rclcpp::SerializedMessage>, const rclcpp::MessageInfo&)>
using ConstRefSharedConstPtrCallback = std::function<void(const std::shared_ptr<const SubscribedType>&)>
using ConstRefSharedConstPtrROSMessageCallback = std::function<void(const std::shared_ptr<const ROSMessageType>&)>
using ConstRefSharedConstPtrWithInfoCallback = std::function<void(const std::shared_ptr<const SubscribedType>&, const rclcpp::MessageInfo&)>
using ConstRefSharedConstPtrWithInfoROSMessageCallback = std::function<void(const std::shared_ptr<const ROSMessageType>&, const rclcpp::MessageInfo&)>
using ConstRefSharedConstPtrSerializedMessageCallback = std::function<void(const std::shared_ptr<const rclcpp::SerializedMessage>&)>
using ConstRefSharedConstPtrSerializedMessageWithInfoCallback = std::function<void(const std::shared_ptr<const rclcpp::SerializedMessage>&, const rclcpp::MessageInfo&)>
using SharedPtrCallback = std::function<void(std::shared_ptr<SubscribedType>)>
using SharedPtrROSMessageCallback = std::function<void(std::shared_ptr<ROSMessageType>)>
using SharedPtrWithInfoCallback = std::function<void(std::shared_ptr<SubscribedType>, const rclcpp::MessageInfo&)>
using SharedPtrWithInfoROSMessageCallback = std::function<void(std::shared_ptr<ROSMessageType>, const rclcpp::MessageInfo&)>
using SharedPtrSerializedMessageCallback = std::function<void(std::shared_ptr<rclcpp::SerializedMessage>)>
using SharedPtrSerializedMessageWithInfoCallback = std::function<void(std::shared_ptr<rclcpp::SerializedMessage>, const rclcpp::MessageInfo&)>