Class RepeatMessagesNodelet

Inheritance Relationships

Base Type

  • public cras::Nodelet

Class Documentation

class RepeatMessagesNodelet : public cras::Nodelet

Nodelet for repeating messages coming at a slower rate (or even just a single message).

ROS parameters:

  • ~in_queue_size (uint, default 10): Queue size for the subscriber.

  • ~out_queue_size (uint, default $in_queue_size): Queue size for the publisher.

  • ~rate (Hz, positive double, default 1.0): The desired rate of the published messages.

  • ~lazy (bool, default False): Whether to shut down the subscriber when the publisher has no subscribers. The ~input topic will be subscribed in the beginning, and will unsubscribe automatically after the first message is received (this is needed to determine the full type of the topic to publish). This can have unexpected consequences as the nodelet doesn’t listen for new messages that came in when the publisher had no subscribers. So when the nodelet should start publishing again, it will repeat the last message it received before unsubscribing.

  • ~tcp_no_delay (bool, default False): If True, the TCP_NODELAY flag is set for the subscriber. This should decrease the latency of small messages, but might give suboptimal transmission speed for large messages.

  • ~max_age (double, no default): If set, this parameter instructs the repeater to check how old the re-published message would be. If it is older than ros::Time::now() - max_age, it will no longer be published. This setting requires that the type of the message contains a Header field at the beginning. Setting it on header-less topics can cause unexpected behavior and random rejection of messages.

  • ~max_repeats (uint, no default): If set, this parameter tells how many times a single message can be repeated.

  • ~discard_older_messages (bool, default false): If true, incoming messages’ time stamp will be compared to the last stored message, and if the incoming message is older than the stored one, it will be discarded. This setting requires that the type of the message contains a Header field at the beginning. Setting it on header-less topics can cause unexpected behavior and random rejection of messages.

  • ~reset_on_msg (bool, default true): Whether the internal repeating timer should be reset to count from 0 when an incoming message is stored.

  • ~publish_only_on_timer (bool, default false): If true, messages are only published on timer events. If false, they are also published right away as they come on the input topic.

Subscribed topics:

  • ~input (any type): The input messages. If lazy is true, it will only be subscribed when ~output has some subscribers.

  • ~reset (any type): When a message is received on this topic, the repeater is reset into its initial state (i.e. the last received message is discarded). This should happen every time the ROS time jumps, e.g. when simulation is reset or a bag file starts playing again.

Published topics:

  • ~output (same type as ~input): The output messages.

Command-line arguments: This nodelet (or node) can also be called with some arguments passed on command line. This means you can pass CLI arguments specifying the topics to subscribe/publish and the rate.

  • rosrun cras_topic_tools repeat TOPIC_IN RATE [TOPIC_OUT]

    • TOPIC_IN: The topic to subscribe. It is resolved against parent namespace of the node(let) (as opposed to the ~input topic which is resolved against the private node(let) namespace).

    • RATE: The output rate. If both this argument and ~rate parameter are specified, the ROS parameter wins.

    • TOPIC_OUT: The topic to publish. It is resolved against parent namespace of the node(let) (as opposed to the ~output topic which is resolved against the private node(let) namespace). If not specified, output topic will be ${TOPIC_IN}_repeat.

Note

If reset_on_msg and publish_only_on_timer are both true and the rate of the incoming messages is higher than rate parameter, no message will ever be published by this repeater (the timer will get reset earlier than it can ever fire).

Protected Functions

void onInit() override
virtual void onReset(const ::ros::MessageEvent<const ::topic_tools::ShapeShifter>&)

Called when the repeater should be reset. The incoming message can be of any type and should not be examined.

virtual void reset() override

Reset the repeater, e.g. after a time jump.

void processMessage(const ::ros::MessageEvent<const ::topic_tools::ShapeShifter> &event, ::ros::Publisher &pub)

Record the incoming message if it passes validations, and publish it if publishOnlyOnTimer is false.

Note

It is safe to call this function from multiple threads (access to the stored message is mutex-protected).

Parameters:
  • event[in] The incoming message event.

  • pub[in] The publisher to be used for publishing the repeated messages.

virtual void maybePublish()

Publish the last stored message (if it is eligible).

virtual bool inspectStamps() const

Whether Header should be extracted from the message and its time stamp should undergo inspection.

Returns:

Whether to extract the stamp.

void everyPeriod(const ::ros::TimerEvent&)

Timer callback. Publish the last stored message if it is eligible.

Protected Attributes

::std::unique_ptr<::cras::GenericLazyPubSub> pubSub

The lazy pair of subscriber and publisher.

::ros::Subscriber resetSub

Subscriber to the reset topic.

::std::unique_ptr<::ros::Rate> rate

The desired output rate.

::cras::optional<size_t> maxRepeats = {::cras::nullopt}

Maximum number of repetitions of a single message (only limited when set).

::cras::optional<::ros::Duration> maxAge = {::cras::nullopt}

Maximum age of a message to allow publishing it (the message has to have a Header).

bool discardOlderMessages = {false}

Whether to discard an incoming message if its stamp is older than the previously accepted message.

bool resetOnMsg = {true}

Whether to reset the publication timer when a new message arrives.

bool publishOnlyOnTimer = {false}

Whether to publish only on timer events, or also when an incoming message is received.

::std::mutex msgMutex

Mutex protecting msg, lastMsgStamp and numRepeats.

::topic_tools::ShapeShifter::ConstPtr msg

The last stored message (null if no message has been received yet).

::cras::optional<::ros::Time> lastMsgStamp

Time stamp of the last stored message (only filled if inspectStamps() returns true.

size_t numRepeats = {0}

Number of times the last stored message has been repeated.

::cras::optional<bool> hasHeader = {::cras::nullopt}
::ros::Timer timer

The timer periodically republishing the last stored message.

::ros::Publisher pub

The publisher of the repeated messages.