Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 17 additions & 2 deletions src/rqt_plot/data_plot/mat_data_plot.py
Original file line number Diff line number Diff line change
Expand Up @@ -101,13 +101,28 @@ def __init__(self, parent=None):
super(MatDataPlot.Canvas, self).__init__(Figure())
self.axes = self.figure.add_subplot(111)
self.axes.grid(True, color='gray')
self.figure.tight_layout()
self.safe_tight_layout()
self.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding)
self.updateGeometry()

def resizeEvent(self, event):
super(MatDataPlot.Canvas, self).resizeEvent(event)
self.figure.tight_layout()
self.safe_tight_layout()

def safe_tight_layout(self):
"""
Deal with "ValueError: bottom cannot be >= top" bug in older matplotlib versions
(before v2.2.3)

References:
- https://github.com/matplotlib/matplotlib/pull/10915
- https://github.com/ros-visualization/rqt_plot/issues/35
"""
try:
self.figure.tight_layout()
except ValueError:
if parse_version(matplotlib.__version__) >= parse_version('2.2.3'):
raise

limits_changed = Signal()

Expand Down