Template Class LifecyclePublisher

Inheritance Relationships

Base Types

  • public rclcpp_lifecycle::SimpleManagedEntity (Class SimpleManagedEntity)

  • public rclcpp::Publisher< MessageT, std::allocator< void > >

Class Documentation

template<typename MessageT, typename Alloc = std::allocator<void>>
class LifecyclePublisher : public rclcpp_lifecycle::SimpleManagedEntity, public rclcpp::Publisher<MessageT, std::allocator<void>>

brief child class of rclcpp Publisher class.

Overrides all publisher functions to check for enabled/disabled state.

Public Types

using MessageAllocTraits = rclcpp::allocator::AllocRebind<MessageT, Alloc>
using MessageAlloc = typename MessageAllocTraits::allocator_type
using MessageDeleter = rclcpp::allocator::Deleter<MessageAlloc, MessageT>
using MessageUniquePtr = std::unique_ptr<MessageT, MessageDeleter>

Public Functions

inline LifecyclePublisher(rclcpp::node_interfaces::NodeBaseInterface *node_base, const std::string &topic, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator<Alloc> &options)
inline ~LifecyclePublisher()
inline virtual void publish(std::unique_ptr<MessageT, MessageDeleter> msg)

LifecyclePublisher publish function.

The publish function checks whether the communication was enabled or disabled and forwards the message to the actual rclcpp Publisher base class

inline virtual void publish(const MessageT &msg)

LifecyclePublisher publish function.

The publish function checks whether the communication was enabled or disabled and forwards the message to the actual rclcpp Publisher base class

inline virtual void publish(rclcpp::LoanedMessage<typename rclcpp::Publisher<MessageT, Alloc>::ROSMessageType, Alloc> &&loaned_msg)

LifecyclePublisher publish function.

The publish function checks whether the communication was enabled or disabled and forwards the message to the actual rclcpp Publisher base class

inline virtual void on_activate() override