Template Class RclcppPublisherWrapper
Defined in File rclcpp_publisher_wrapper.hpp
Class Documentation
-
template<typename MessageT, typename AllocatorT = std::allocator<void>>
class RclcppPublisherWrapper A wrapper class for rclcpp::Publisher with virtual methods for publishing and borrowing loan messages.
This class is designed to be used when need to have ability to mock the publisher in tests.
Note
Due to the virtual methods and indirection this class is not as efficient as using rclcpp::Publisher directly, so it should be used only when performance overhead is considered and justified.
- Template Parameters:
MessageT – must be a ROS message type with its own type support (e. g. std_msgs::msgs::String)
AllocatorT – the allocator type used for loaned messages, defaults to std::allocator<void>.
Public Functions
-
inline virtual ~RclcppPublisherWrapper()
-
inline virtual void publish(rclcpp::LoanedMessage<MessageT, AllocatorT> &&loaned_msg)
-
inline virtual rclcpp::LoanedMessage<MessageT, AllocatorT> borrow_loaned_message()
-
inline virtual bool can_loan_messages() const
-
inline virtual const char *get_topic_name() const
Protected Attributes
-
rclcpp::Publisher<MessageT, AllocatorT>::SharedPtr publisher_