Class CountMessagesComponent
Defined in File count_messages.hpp
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class CountMessagesComponent : public rclcpp::Node
Component for counting messages and their size.
ROS parameters:
~in_queue_size(uint, default 1000): Queue size for the subscriber.~qos_profile(string, default empty string): If nonempty, specifies the QoS profile to use for subscription.~count(uint, output parameter): The number of messages received so far.~bytes(uint, output parameter): The size of messages received so far (in bytes).
Subscribed topics:
~input(any type): The input messages.~reset(any type): When a message is received on this topic, the counter is reset to zero.
Public Functions
-
explicit CountMessagesComponent(const ::rclcpp::NodeOptions &options)
Protected Functions
Called when the counter should be reset. The incoming message can be of any type and should not be examined.
Callback for counting the messages.
- Parameters:
message – [in] The message event.
-
void reportCb()
Callback for periodic reports.
-
void discoverTopicAndSubscribe()
Check if the input topic is available. Subscribe to it when it is.
-
void discoverResetTopicAndSubscribe()
Check if the reset topic is available. Subscribe to it when it is.
Protected Attributes
-
::rclcpp::GenericSubscription::SharedPtr sub
The message subscriber.
-
::rclcpp::GenericSubscription::SharedPtr resetSub
The reset message subscriber.
-
::rclcpp::TimerBase::SharedPtr discoveryTimer
Timer for input topic type discovery.
-
::rclcpp::TimerBase::SharedPtr resetDiscoveryTimer
Timer for reset topic type discovery.
-
::rclcpp::TimerBase::SharedPtr reportTimer
Timer for printing reports.
-
std::string topic = {"input"}
The unresolved input topic name.
-
::std::string resolvedTopic
Resolved name of the input topic.
-
::std::string resolvedResetTopic
Resolved name of the reset topic.
-
::rclcpp::QoS qosProfile = {1000}
QoS for the input topic subscription.
-
bool useParams = {true}
Whether the current message and byte count should be set as parameters of the node.
-
bool topicStats = {false}
Whether to publish topic statistics for the subscription.
-
bool intraprocessComms = {true}
Whether to enable intraprocess comms for the subscription.
-
::size_t bytes = {0}
Byte size of the received messages.
-
::size_t count = {0}
Number of received messages.
-
::size_t countSinceLastReport = {0}
Number of received messages since last report.
-
::std::mutex mutex
Mutex protecting
countandbytes.
-
::std::optional<::rclcpp::Time> lastReportStamp
Time when the message count was last reported.