Skip to content

In ROS2 galactic, fixed-size Array msg type plotting broken #77

@mwcondino

Description

@mwcondino

Title summarizes issue, but it looks like fixed-size array visualization is not working correctly.

Steps to reproduce

In one terminal window, run:

ros2 topic pub /foo sensor_msgs/msg/NavSatFix

In a separate terminal, run:

ros2 run rqt_plot rqt_plot /foo/position_covariance[0]

Observed error text:

PluginManager._load_plugin() could not load plugin "rqt_plot/Plot":
Traceback (most recent call last):
  File "/opt/ros/galactic/lib/python3.8/site-packages/qt_gui/plugin_handler.py", line 102, in load
    self._load()
  File "/opt/ros/galactic/lib/python3.8/site-packages/qt_gui/plugin_handler_direct.py", line 55, in _load
    self._plugin = self._plugin_provider.load(self._instance_id.plugin_id, self._context)
  File "/opt/ros/galactic/lib/python3.8/site-packages/qt_gui/composite_plugin_provider.py", line 72, in load
    instance = plugin_provider.load(plugin_id, plugin_context)
  File "/opt/ros/galactic/lib/python3.8/site-packages/qt_gui/composite_plugin_provider.py", line 72, in load
    instance = plugin_provider.load(plugin_id, plugin_context)
  File "/opt/ros/galactic/lib/python3.8/site-packages/rqt_gui_py/ros_py_plugin_provider.py", line 69, in load
    return super(RosPyPluginProvider, self).load(plugin_id, ros_plugin_context)
  File "/opt/ros/galactic/lib/python3.8/site-packages/qt_gui/composite_plugin_provider.py", line 72, in load
    instance = plugin_provider.load(plugin_id, plugin_context)
  File "/opt/ros/galactic/lib/python3.8/site-packages/rqt_gui/ros_plugin_provider.py", line 107, in load
    return class_ref(plugin_context)
  File "/opt/ros/galactic/lib/python3.8/site-packages/rqt_plot/plot.py", line 64, in __init__
    self._widget.switch_data_plot_widget(self._data_plot)
  File "/opt/ros/galactic/lib/python3.8/site-packages/rqt_plot/plot_widget.py", line 229, in switch_data_plot_widget
    self.add_topic(topic_name)
  File "/opt/ros/galactic/lib/python3.8/site-packages/rqt_plot/plot_widget.py", line 345, in add_topic
    for topic_name in get_plot_fields(self._node, topic_name)[0]:
  File "/opt/ros/galactic/lib/python3.8/site-packages/rqt_plot/plot_widget.py", line 125, in get_plot_fields
    if index >= current_type.maximum_size:
AttributeError: 'Array' object has no attribute 'maximum_size'

Proposed fix

Looking at https://github.com/ros2/rosidl/blob/master/rosidl_parser/rosidl_parser/definition.py#L313, it seems that both Array and BoundedSequence types in the IDL should have the size member, but only BoundedSequences have maximum_size. It looks like maximum size exclusively is used here in rqt_plot.

If we switch to using size instead of maximum_size, would this fix things?

Metadata

Metadata

Assignees

Labels

No labels
No labels

Type

No type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions