Class RecorderEventNotifier

Class Documentation

class RecorderEventNotifier

Public Types

using WriteSplitEvent = rosbag2_interfaces::msg::WriteSplitEvent
using MessagesLostEvent = rosbag2_interfaces::msg::MessagesLostEvent

Public Functions

explicit RecorderEventNotifier(rclcpp::Node *node, const rosbag2_transport::RecordOptions &record_options = {}, RclcppPublisherWrapper<WriteSplitEvent>::SharedPtr split_event_pub = nullptr, RclcppPublisherWrapper<MessagesLostEvent>::SharedPtr msgs_lost_event_pub = nullptr)

Constructor for the RecorderEventNotifier class.

This constructor initializes the event notifier with a node and optional publishers for split events and messages lost events.

Parameters:
  • node – Pointer to the rclcpp Node that will be used for publishing events.

  • record_options – The record options used by the recorder.

  • split_event_pub – Optional publisher for WriteSplitEvent messages. If not provided, a new publisher will be created with the topic name “events/write_split”.

  • msgs_lost_event_pub – Optional publisher for MessagesLostEvent messages. If not provided, a new publisher will be created with the topic name “events/rosbag2_messages_lost”.

virtual ~RecorderEventNotifier()

Destructor for the RecorderEventNotifier class.

void set_messages_lost_statistics_max_publishing_rate(float update_rate_hz)

Set the maximum update rate for messages lost statistics.

This controls how often the statistics about messages lost are published.

Note

Event notifier will not publish statistics if there are no messages lost since the last time it was published.

Parameters:

update_rate_hz – Maximum publishing rate in times per second (Hz) for messages lost statistics. A value of 0.0 means that the statistics will not be published.

Throws:

std::invalid_argument – if the update rate is negative or if the update rate more than or equal 1000.00 Hz.

void on_bag_split_in_recorder(const rosbag2_cpp::bag_events::BagSplitInfo &bag_split_info)

Callback for when a bag split occurs in the recorder.

void on_messages_lost_in_recorder(const std::vector<rosbag2_cpp::bag_events::MessagesLostInfo> &msgs_lost_info)

Callback for when messages are lost in recorder.

void on_messages_lost_in_transport(const std::string &topic_name, const rclcpp::QOSMessageLostInfo &qos_msgs_lost_info)

Callback for when messages are lost in transport.

uint64_t get_total_num_messages_lost_in_transport() const

Getter for the total number of messages lost in transport.

Returns:

The total number of messages lost in transport.

uint64_t get_total_num_messages_lost_in_recorder() const

Getter for the total number of messages lost in recorder.

Returns:

The total number of messages lost in recorder.

void reset_total_num_messages_lost_in_transport()

Reset the counters for messages lost in transport.

void reset_total_num_messages_lost_in_recorder()

Reset the counters for messages lost in recorder.

std::string_view get_write_split_topic_name() const

Get the topic name used for publishing write split events.

std::string_view get_messages_lost_topic_name() const

Get the topic name used for publishing messages lost events.

rclcpp::QoS get_write_split_qos() const

Get the QoS profile used for write split event publisher.

Returns:

The QoS profile used for publishing write split events.

rclcpp::QoS get_messages_lost_qos() const

Get the QoS profile used for messages lost event publisher.

Returns:

The QoS profile used for publishing messages lost events.

Public Static Functions

static const char *get_default_write_split_topic_name()

Get the default topic name for write split events.

static const char *get_default_messages_lost_topic_name()

Get the default topic name for messages lost events.