Class PublisherBase
Defined in File publisher_base.hpp
Inheritance Relationships
Base Type
public std::enable_shared_from_this< PublisherBase >
Derived Types
public rclcpp::Publisher< rcl_interfaces::msg::ParameterEvent >
(Template Class Publisher)public rclcpp::Publisher< statistics_msgs::msg::MetricsMessage >
(Template Class Publisher)public rclcpp::GenericPublisher
(Class GenericPublisher)public rclcpp::Publisher< MessageT, AllocatorT >
(Template Class Publisher)
Class Documentation
-
class PublisherBase : public std::enable_shared_from_this<PublisherBase>
Subclassed by rclcpp::Publisher< rcl_interfaces::msg::ParameterEvent >, rclcpp::Publisher< statistics_msgs::msg::MetricsMessage >, rclcpp::GenericPublisher, rclcpp::Publisher< MessageT, AllocatorT >
Public Types
Public Functions
-
PublisherBase(rclcpp::node_interfaces::NodeBaseInterface *node_base, const std::string &topic, const rosidl_message_type_support_t &type_support, const rcl_publisher_options_t &publisher_options, const PublisherEventCallbacks &event_callbacks, bool use_default_callbacks)
Default constructor.
Typically, a publisher is not created through this method, but instead is created through a call to
Node::create_publisher
.- Parameters:
node_base – [in] A pointer to the NodeBaseInterface for the parent node.
topic – [in] The topic that this publisher publishes on.
type_support – The type support structure for the type to be published.
publisher_options – [in] QoS settings for this publisher.
-
virtual ~PublisherBase()
-
void bind_event_callbacks(const PublisherEventCallbacks &event_callbacks, bool use_default_callbacks)
Add event handlers for passed in event_callbacks.
-
const char *get_topic_name() const
Get the topic that this publisher publishes on.
- Returns:
The topic name.
-
size_t get_queue_size() const
Get the queue size for this publisher.
- Returns:
The queue size.
-
const rmw_gid_t &get_gid() const
Get the global identifier for this publisher (used in rmw and by DDS).
- Returns:
The gid.
-
std::shared_ptr<rcl_publisher_t> get_publisher_handle()
Get the rcl publisher handle.
- Returns:
The rcl publisher handle.
-
std::shared_ptr<const rcl_publisher_t> get_publisher_handle() const
Get the rcl publisher handle.
- Returns:
The rcl publisher handle.
-
const std::unordered_map<rcl_publisher_event_type_t, std::shared_ptr<rclcpp::EventHandlerBase>> &get_event_handlers() const
Get all the QoS event handlers associated with this publisher.
- Returns:
The map of QoS event handlers.
-
size_t get_subscription_count() const
Get subscription count.
- Returns:
The number of subscriptions.
-
size_t get_intra_process_subscription_count() const
Get intraprocess subscription count.
- Returns:
The number of intraprocess subscriptions.
-
bool is_durability_transient_local() const
Get if durability is transient local.
- Returns:
If durability is transient local
-
bool assert_liveliness() const
Manually assert that this Publisher is alive (for RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC).
If the rmw Liveliness policy is set to RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC, the creator of this publisher may manually call
assert_liveliness
at some point in time to signal to the rest of the system that this Node is still alive.- Returns:
true
if the liveliness was asserted successfully, otherwisefalse
-
rclcpp::QoS get_actual_qos() const
Get the actual QoS settings, after the defaults have been determined.
The actual configuration applied when using RMW_QOS_POLICY_*_SYSTEM_DEFAULT can only be resolved after the creation of the publisher, and it depends on the underlying rmw implementation. If the underlying setting in use can’t be represented in ROS terms, it will be set to RMW_QOS_POLICY_*_UNKNOWN. May throw runtime_error when an unexpected error occurs.
- Returns:
The actual qos settings.
-
bool can_loan_messages() const
Check if publisher instance can loan messages.
Depending on the middleware and the message type, this will return true if the middleware can allocate a ROS message instance.
-
bool operator==(const rmw_gid_t &gid) const
Compare this publisher to a gid.
Note that this function calls the next function.
- Parameters:
gid – [in] Reference to a gid.
- Returns:
True if the publisher’s gid matches the input.
-
bool operator==(const rmw_gid_t *gid) const
Compare this publisher to a pointer gid.
A wrapper for comparing this publisher’s gid to the input using rmw_compare_gids_equal.
- Parameters:
gid – [in] A pointer to a gid.
- Returns:
True if this publisher’s gid matches the input.
Implementation utility function used to setup intra process publishing after creation.
-
std::vector<rclcpp::NetworkFlowEndpoint> get_network_flow_endpoints() const
Get network flow endpoints.
Describes network flow endpoints that this publisher is sending messages out on
- Returns:
vector of NetworkFlowEndpoint
-
size_t lowest_available_ipm_capacity() const
Return the lowest available capacity for all subscription buffers.
For intraprocess communication return the lowest buffer capacity for all subscriptions. If intraprocess is disabled or no intraprocess subscriptions present, return maximum of size_t. On failure return 0.
- Returns:
lowest buffer capacity for all subscriptions
-
template<typename DurationRepT = int64_t, typename DurationT = std::milli>
inline bool wait_for_all_acked(std::chrono::duration<DurationRepT, DurationT> timeout = std::chrono::duration<DurationRepT, DurationT>(-1)) const Wait until all published messages are acknowledged or until the specified timeout elapses.
This method waits until all published messages are acknowledged by all matching subscriptions or the given timeout elapses.
If the timeout is negative then this method will block indefinitely until all published messages are acknowledged. If the timeout is zero then this method will not block, it will check if all published messages are acknowledged and return immediately. If the timeout is greater than zero, this method will wait until all published messages are acknowledged or the timeout elapses.
This method only waits for acknowledgments if the publisher’s QoS profile is RELIABLE. Otherwise this method will immediately return
true
.- Parameters:
timeout – [in] the duration to wait for all published messages to be acknowledged.
- Throws:
rclcpp::exceptions::RCLError – if middleware doesn’t support or internal error occurs
std::invalid_argument – if timeout is greater than std::chrono::nanoseconds::max() or less than std::chrono::nanoseconds::min()
- Returns:
true
if all published messages were acknowledged before the given timeout elapsed, otherwisefalse
.
-
inline void set_on_new_qos_event_callback(std::function<void(size_t)> callback, rcl_publisher_event_type_t event_type)
Set a callback to be called when each new qos event instance occurs.
The callback receives a size_t which is the number of events that occurred since the last time this callback was called. Normally this is 1, but can be > 1 if events occurred before any callback was set.
Since this callback is called from the middleware, you should aim to make it fast and not blocking. If you need to do a lot of work or wait for some other event, you should spin it off to another thread, otherwise you risk blocking the middleware.
Calling it again will clear any previously set callback.
An exception will be thrown if the callback is not callable.
This function is thread-safe.
If you want more information available in the callback, like the qos event or other information, you may use a lambda with captures or std::bind.
- Parameters:
callback – [in] functor to be called when a new event occurs
event_type – [in] identifier for the qos event we want to attach the callback to
-
inline void clear_on_new_qos_event_callback(rcl_publisher_event_type_t event_type)
Unset the callback registered for new qos events, if any.
Protected Types
-
using IntraProcessManagerWeakPtr = std::weak_ptr<rclcpp::experimental::IntraProcessManager>
Protected Functions
-
template<typename EventCallbackT>
inline void add_event_handler(const EventCallbackT &callback, const rcl_publisher_event_type_t event_type)
-
void default_incompatible_qos_callback(QOSOfferedIncompatibleQoSInfo &info) const
-
void default_incompatible_type_callback(IncompatibleTypeInfo &info) const
Protected Attributes
-
std::shared_ptr<rcl_node_t> rcl_node_handle_
-
std::shared_ptr<rcl_publisher_t> publisher_handle_
-
std::unordered_map<rcl_publisher_event_type_t, std::shared_ptr<rclcpp::EventHandlerBase>> event_handlers_
-
bool intra_process_is_enabled_
-
IntraProcessManagerWeakPtr weak_ipm_
-
uint64_t intra_process_publisher_id_
-
rmw_gid_t rmw_gid_
-
const rosidl_message_type_support_t type_support_
-
const PublisherEventCallbacks event_callbacks_
-
PublisherBase(rclcpp::node_interfaces::NodeBaseInterface *node_base, const std::string &topic, const rosidl_message_type_support_t &type_support, const rcl_publisher_options_t &publisher_options, const PublisherEventCallbacks &event_callbacks, bool use_default_callbacks)