Template Class Publisher
Defined in File publisher_mock.hpp
Inheritance Relationships
Base Type
public PublisherBase
Class Documentation
-
template<typename MessageT, typename AllocatorT = std::allocator<void>>
class Publisher : public PublisherBase Public Types
-
using PublishedType = typename rclcpp::TypeAdapter<MessageT>::custom_type
MessageT::custom_type if MessageT is a TypeAdapter, otherwise just MessageT.
-
using PublishedTypeAllocatorTraits = allocator::AllocRebind<PublishedType, AllocatorT>
-
using PublishedTypeAllocator = typename PublishedTypeAllocatorTraits::allocator_type
-
using PublishedTypeDeleter = allocator::Deleter<PublishedTypeAllocator, PublishedType>
-
using ROSMessageTypeAllocatorTraits = allocator::AllocRebind<ROSMessageType, AllocatorT>
-
using ROSMessageTypeAllocator = typename ROSMessageTypeAllocatorTraits::allocator_type
-
using ROSMessageTypeDeleter = allocator::Deleter<ROSMessageTypeAllocator, ROSMessageType>
Public Functions
-
inline Publisher(rclcpp::node_interfaces::NodeBaseInterface *node_base, const std::string &topic, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator<AllocatorT> &options)
-
inline virtual void post_init_setup(rclcpp::node_interfaces::NodeBaseInterface *node_base, const std::string &topic, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator<AllocatorT> &options)
-
inline virtual ~Publisher()
-
inline void publish_(const MessageT &msg)
Internal sink publish with activation control.
- Parameters:
msg – published message
-
inline size_t get_subscription_count()
Get the subscriptions count.
- Returns:
number of real and fake subscriptions
-
inline rclcpp::LoanedMessage<ROSMessageType, AllocatorT> borrow_loaned_message()
-
template<typename T>
inline std::enable_if_t<rosidl_generator_traits::is_message<T>::value && std::is_same<T, ROSMessageType>::value> publish(std::unique_ptr<T, ROSMessageTypeDeleter> msg)
-
template<typename T>
inline std::enable_if_t<rosidl_generator_traits::is_message<T>::value && std::is_same<T, ROSMessageType>::value> publish(const T &msg)
-
template<typename T>
inline std::enable_if_t<rclcpp::TypeAdapter<MessageT>::is_specialized::value && std::is_same<T, PublishedType>::value> publish(std::unique_ptr<T, PublishedTypeDeleter> msg)
-
template<typename T>
inline std::enable_if_t<rclcpp::TypeAdapter<MessageT>::is_specialized::value && std::is_same<T, PublishedType>::value> publish(const T &msg)
-
inline void publish(const rcl_serialized_message_t &serialized_msg)
-
inline void publish(const SerializedMessage &serialized_msg)
-
inline void publish(rclcpp::LoanedMessage<ROSMessageType, AllocatorT> &&loaned_msg)
-
inline std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> duplicate_ros_message_as_unique_ptr(const ROSMessageType &msg)
Public Members
-
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> options_
-
PublishedTypeAllocator published_type_allocator_
-
PublishedTypeDeleter published_type_deleter_
-
ROSMessageTypeAllocator ros_message_type_allocator_
-
ROSMessageTypeDeleter ros_message_type_deleter_
-
BufferSharedPtr buffer_ = {nullptr}
-
using PublishedType = typename rclcpp::TypeAdapter<MessageT>::custom_type