PlotJuggler / plotjuggler-ros-plugins

Many PlotJuggler plugins for ROS and ROS2.
GNU Affero General Public License v3.0
106 stars 44 forks source link

Diagnostic messages being dropped when publishing multiple on same topic #51

Open frankkusters opened 2 years ago

frankkusters commented 2 years ago

When publishing multiple Diagnostics messages on the same topic but with a different key, messages are being dropped. It is visible in the screenshot below, where 'b' has no dropped messages, but 'a' has. You can see the sine wave for 'a' is oddly shaped.

image

I managed to create a minimal node which can reproduce this problem. It's based off of the ROS2 Galactic tutorial, with diagnostic_msgs added as dependency.

from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
import rclpy
from rclpy.node import Node

class MinimalPublisher(Node):
    def __init__(self):
        super().__init__('minimal_publisher')
        self.diagnostics_publisher = self.create_publisher(DiagnosticArray, '/diagnostics', 10)
        timer_period = 0.5  # seconds
        self.timer = self.create_timer(timer_period, self.timer_callback)
        self.sine_values = [500, 794, 976, 976, 794, 500, 206, 24, 24, 206]
        self.i = 0

    def timer_callback(self):
        self._publish_message('a')
        self._publish_message('b')
        self.i += 1
        if self.i == len(self.sine_values):
            self.i = 0

    def _publish_message(self, name):
        array = DiagnosticArray()
        array.header.stamp = self.get_clock().now().to_msg()

        status = DiagnosticStatus(level=DiagnosticStatus.OK, name=name, message='OK')
        status.values.append(KeyValue(key='sine', value=str(self.sine_values[self.i])))
        array.status.append(status)

        self.diagnostics_publisher.publish(array)

def main(args=None):
    rclpy.init(args=args)
    minimal_publisher = MinimalPublisher()
    rclpy.spin(minimal_publisher)
    minimal_publisher.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()
facontidavide commented 2 years ago

I wonder if this is a problem of DDS and QoS. On the other hand, the frequency is very low and it should work.

Thanks for sharing the script, I will check

frankkusters commented 2 years ago

While debugging this on my own code base, I noticed the problem disappeared when changing the order of publishing (switching 'a' and 'b', essentially). Unfortunately I can't share that code for IP reasons.

Leafing through Plotjugglers code, I noticed this:

  void pushBack(Point&& p) override
  {
    bool need_sorting = (!_points.empty() && p.x < this->back().x);

    if (need_sorting)
    {
      auto it = std::upper_bound(_points.begin(), _points.end(), p, TimeCompare);
      PlotDataBase<double, Value>::insert(it, std::move(p));
    }
    else
    {
      PlotDataBase<double, Value>::pushBack(std::move(p));
    }
    trimRange();
  }

The performance of this code could be sensitive to specific worst-case usage scenarios - although I wouldn't expect any performance problems at this data rate.