TAMSVIZ
Visualization and annotation tool for ROS
plot.cpp
1 // TAMSVIZ
2 // (c) 2020 Philipp Ruppel
3 
4 #include "plot.h"
5 
6 #include "../core/profiler.h"
7 
8 #include <sensor_msgs/JointState.h>
9 #include <std_msgs/Float64.h>
10 #include <tf2_msgs/TFMessage.h>
11 
12 inline QColor toQColor(const Color3 &c) {
13  return QColor::fromRgbF(c.r(), c.g(), c.b());
14 }
15 
16 void PlotRenderer::PlotRendererData::update() {
17  topics.resize(display->topics().size());
18  for (size_t itopic = 0; itopic < topics.size(); itopic++) {
19  auto &topic_display = display->topics()[itopic];
20  auto &topic_renderer = topics[itopic];
21 
22  if (!topic_renderer.subscriber ||
23  topic_renderer.subscriber->topic() != topic_display.topic.topic()) {
24  topic_renderer.subscriber = topic_display.subscriber.lock();
25  topic_renderer.queries.clear();
26  }
27  if (!topic_renderer.subscriber ||
28  topic_renderer.subscriber->topic() != topic_display.topic.topic()) {
29  topic_renderer.subscriber =
30  std::make_shared<TimeSeriesSubscriber>(topic_display.topic.topic());
31  topic_renderer.queries.clear();
32  }
33  topic_display.subscriber = topic_renderer.subscriber;
34  topic_renderer.subscriber->duration(display->duration());
35 
36  topic_renderer.queries.resize(topic_display.queries.size());
37  for (size_t iquery = 0; iquery < topic_renderer.queries.size(); iquery++) {
38  auto &query_display = topic_display.queries[iquery];
39  auto &query_renderer = topic_renderer.queries[iquery];
40  query_renderer.color = query_display.color;
41  if (query_renderer.query == nullptr ||
42  query_renderer.query->query().str() != query_display.query.str()) {
43  query_renderer.query =
44  std::make_shared<TimeSeriesQuery>(query_display.query.query());
45  topic_renderer.subscriber->addListener(query_renderer.query);
46  }
47  // query_display.query.subscriber(topic_renderer.subscriber->subscriber());
48  }
49  }
50 }
51 
52 PlotRenderer::PlotRenderer(const std::shared_ptr<PlotDisplay> &display) {
53  _data->display = display;
54  auto *data = _data.get();
55  LockScope()->modified.connect(_data, [data]() {
56  LockScope ws;
57  data->update();
58  });
59  data->update();
60 }
61 
62 void PlotRenderer::renderSync() {
63  PROFILER("PlotRenderer sync");
64  _data->update();
65  _duration = _data->display->duration();
66  if (_data->display) {
67  _style = _data->display->style();
68  } else {
69  _style = PlotStyle();
70  }
71  _topics_async = _data->topics;
72  _bag_player = LockScope()->player;
73 }
74 
75 inline double stepSize(double diff) {
76  static std::vector<double> steps = {
77  std::log10(1),
78  std::log10(2),
79  std::log10(5),
80  std::log10(10),
81  };
82  double lg = std::log10(diff);
83  double frac = lg - std::floor(lg);
84  double step = steps[0];
85  for (auto &s : steps) {
86  if (std::abs(s - frac) < std::abs(step - frac)) {
87  step = s;
88  }
89  }
90  return std::pow(10.0, std::floor(lg) + step);
91 }
92 
93 void PlotRenderer::renderAsync(QPainter *painter) {
94  PROFILER("PlotRenderer async");
95  bool init = false;
96  int64_t tmin = 0, tmax = 0;
97  double vmin = 0, vmax = 0;
98  for (auto &topic : _topics_async) {
99  for (auto &query : topic.queries) {
100  query.points.clear();
101  for (auto &pair : query.query->data()) {
102  int64_t t = pair.first;
103  double v = pair.second;
104  query.points.emplace_back(t, v);
105  if (!init) {
106  init = true;
107  tmin = tmax = t;
108  vmin = vmax = v;
109  } else {
110  tmin = std::min(tmin, t);
111  tmax = std::max(tmax, t);
112  vmin = std::min(vmin, v);
113  vmax = std::max(vmax, v);
114  }
115  }
116  }
117  }
118 
119  QRectF canvas = painter->viewport();
120  painter->fillRect(canvas, toQColor(_style.backgroundColor));
121 
122  QRectF frame = canvas.marginsRemoved(QMarginsF(
123  _style.margins.left +
124  (_style.axes.y.label.empty()
125  ? 0
126  : (_style.axes.fontSize + _style.padding)) +
127  _style.padding * 2 + _style.ticks.length + _style.ticks.y.width,
128  _style.margins.top + _style.padding +
129  ((!_style.title.enable || _style.title.text.empty() ||
130  _style.title.fontSize == 0)
131  ? 0
132  : (_style.title.fontSize + _style.padding)),
133  _style.margins.right + _style.padding,
134  _style.margins.bottom +
135  (_style.axes.x.label.empty()
136  ? 0
137  : (_style.axes.fontSize + _style.padding)) +
138  _style.padding * 2 + _style.ticks.length + _style.ticks.fontSize));
139 
140  painter->setPen(QPen(toQColor(_style.foregroundColor), _style.frameWidth));
141  painter->drawRect(frame);
142 
143  painter->setPen(
144  QPen(toQColor(_style.foregroundColor), _style.axes.lineWidth));
145  painter->drawLine(frame.bottomLeft(), frame.bottomRight());
146  painter->drawLine(frame.bottomLeft(), frame.topLeft());
147 
148  if (!(!_style.title.enable || _style.title.text.empty() ||
149  _style.title.fontSize == 0)) {
150  QFont font;
151  font.setPixelSize(_style.title.fontSize);
152  painter->setFont(font);
153  painter->drawText(QRectF(frame.left(), _style.margins.top, frame.width(),
154  _style.title.fontSize + _style.padding * 2),
155  Qt::AlignCenter, _style.title.text.c_str());
156  }
157 
158  if (_style.axes.fontSize > 0) {
159  QFont font;
160  font.setPixelSize(_style.axes.fontSize);
161  painter->setFont(font);
162 
163  painter->drawText(
164  QRectF(frame.left(),
165  canvas.bottom() - _style.axes.fontSize - _style.padding * 2,
166  frame.width(), _style.axes.fontSize + _style.padding * 2),
167  Qt::AlignCenter, _style.axes.x.label.c_str());
168 
169  painter->save();
170  painter->translate(_style.margins.left, frame.bottom());
171  painter->rotate(-90);
172  painter->drawText(
173  QRectF(0, 0, frame.height(), _style.axes.fontSize + _style.padding * 2),
174  Qt::AlignCenter, _style.axes.y.label.c_str());
175  painter->restore();
176  }
177 
178  if (vmin == vmax) {
179  vmin -= 1e-6;
180  vmax += 1e-6;
181  }
182 
183  if (_bag_player) {
184  tmax = (_bag_player->startTime() + ros::Duration(_bag_player->time()))
185  .toNSec();
186  } else {
187  tmax = ros::Time::now().toNSec();
188  }
189 
190  tmin = tmax - std::max(int64_t(1000), int64_t(_duration * 1000000000));
191 
192  {
193  double vd = (vmax - vmin) * (1.0 / frame.height());
194  vmin -= vd * _style.spacing.bottom;
195  vmax += vd * _style.spacing.top;
196  }
197 
198  {
199  double vd = (tmax - tmin) * (1.0 / frame.width());
200  tmin -= vd * _style.spacing.left;
201  tmax += vd * _style.spacing.right;
202  }
203 
204  if (tmax != tmin && vmax != vmin) {
205 
206  QFont font;
207  font.setPixelSize(_style.ticks.fontSize);
208  painter->setFont(font);
209 
210  {
211  int64_t step = std::round(
212  stepSize((tmax - tmin) * (_style.ticks.x.stride * 1.0 /
213  std::max(1.0, 1.0 * frame.width()))));
214  for (int64_t x = (tmin + step - 1) / step * step; x <= tmax / step * step;
215  x += step) {
216  double fx = (x - tmin) * (1.0 / (tmax - tmin));
217  double px = fx * frame.width() + frame.left();
218  painter->setPen(
219  QPen(toQColor(_style.foregroundColor), _style.ticks.width));
220  painter->drawLine(px, frame.bottom(), px,
221  frame.bottom() + _style.ticks.length);
222  if (_style.grid.enable) {
223  painter->setPen(QPen(toQColor(_style.grid.color), _style.grid.width));
224  painter->drawLine(px, frame.bottom(), px, frame.top());
225  }
226  painter->setPen(QPen(toQColor(_style.foregroundColor)));
227  double w = step * 1.0 / (tmax - tmin) * frame.width();
228  painter->drawText(
229  QRectF(px - w * 0.5, frame.bottom() + _style.ticks.length, w,
230  _style.ticks.fontSize + _style.padding * 2),
231  Qt::AlignCenter,
232  QString::number((x % (1000000000l * 1000l)) * (1.0 / 1000000000),
233  'g', 2));
234  }
235  }
236 
237  {
238  double step =
239  stepSize((vmax - vmin) * (_style.ticks.y.stride * 1.0 /
240  std::max(1.0, 1.0 * frame.height())));
241  for (double y = vmin / step * step; y <= vmax / step * step; y += step) {
242  double fy = 1.0 - (y - vmin) * (1.0 / (vmax - vmin));
243  double py = fy * frame.height() + frame.top();
244  painter->setPen(
245  QPen(toQColor(_style.foregroundColor), _style.ticks.width));
246  painter->drawLine(frame.left(), py, frame.left() - _style.ticks.length,
247  py);
248  if (_style.grid.enable) {
249  painter->setPen(QPen(toQColor(_style.grid.color), _style.grid.width));
250  painter->drawLine(frame.left(), py, frame.right(), py);
251  }
252  painter->setPen(QPen(toQColor(_style.foregroundColor)));
253  double h = step * 1.0 / (vmax - vmin) * frame.height();
254  painter->drawText(
255  QRectF(frame.left() - _style.ticks.length - _style.ticks.y.width -
256  _style.padding * 2,
257  py - h * 0.5, _style.ticks.y.width + _style.padding, h),
258  Qt::AlignVCenter | Qt::AlignRight, QString::number(y, 'g', 3));
259  }
260  }
261 
262  double width = frame.width();
263  double height = frame.height();
264  for (auto &topic : _topics_async) {
265  for (auto &query : topic.queries) {
266  std::vector<QPointF> points;
267  for (auto &p : query.points) {
268  double fx = (p.first - tmin) * (1.0 / (tmax - tmin));
269  double fy = 1.0 - (p.second - vmin) * (1.0 / (vmax - vmin));
270  double px = fx * frame.width() + frame.left();
271  double py = fy * frame.height() + frame.top();
272  points.emplace_back(px, py);
273  }
274  painter->setPen(QPen(toQColor(query.color), _style.graphWidth));
275  painter->drawPolyline(points.data(), points.size());
276  }
277  }
278  }
279 }