6 #include "../core/profiler.h" 8 #include <sensor_msgs/JointState.h> 9 #include <std_msgs/Float64.h> 10 #include <tf2_msgs/TFMessage.h> 12 inline QColor toQColor(
const Color3 &c) {
13 return QColor::fromRgbF(c.r(), c.g(), c.b());
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];
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();
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();
33 topic_display.subscriber = topic_renderer.subscriber;
34 topic_renderer.subscriber->duration(display->duration());
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);
52 PlotRenderer::PlotRenderer(
const std::shared_ptr<PlotDisplay> &display) {
53 _data->display = display;
54 auto *data = _data.get();
55 LockScope()->modified.connect(_data, [data]() {
62 void PlotRenderer::renderSync() {
63 PROFILER(
"PlotRenderer sync");
65 _duration = _data->display->duration();
67 _style = _data->display->style();
71 _topics_async = _data->topics;
75 inline double stepSize(
double diff) {
76 static std::vector<double> steps = {
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)) {
90 return std::pow(10.0, std::floor(lg) + step);
93 void PlotRenderer::renderAsync(QPainter *painter) {
94 PROFILER(
"PlotRenderer async");
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);
110 tmin = std::min(tmin, t);
111 tmax = std::max(tmax, t);
112 vmin = std::min(vmin, v);
113 vmax = std::max(vmax, v);
119 QRectF canvas = painter->viewport();
120 painter->fillRect(canvas, toQColor(_style.backgroundColor));
122 QRectF frame = canvas.marginsRemoved(QMarginsF(
123 _style.margins.left +
124 (_style.axes.y.label.empty()
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)
132 : (_style.title.fontSize + _style.padding)),
133 _style.margins.right + _style.padding,
134 _style.margins.bottom +
135 (_style.axes.x.label.empty()
137 : (_style.axes.fontSize + _style.padding)) +
138 _style.padding * 2 + _style.ticks.length + _style.ticks.fontSize));
140 painter->setPen(QPen(toQColor(_style.foregroundColor), _style.frameWidth));
141 painter->drawRect(frame);
144 QPen(toQColor(_style.foregroundColor), _style.axes.lineWidth));
145 painter->drawLine(frame.bottomLeft(), frame.bottomRight());
146 painter->drawLine(frame.bottomLeft(), frame.topLeft());
148 if (!(!_style.title.enable || _style.title.text.empty() ||
149 _style.title.fontSize == 0)) {
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());
158 if (_style.axes.fontSize > 0) {
160 font.setPixelSize(_style.axes.fontSize);
161 painter->setFont(font);
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());
170 painter->translate(_style.margins.left, frame.bottom());
171 painter->rotate(-90);
173 QRectF(0, 0, frame.height(), _style.axes.fontSize + _style.padding * 2),
174 Qt::AlignCenter, _style.axes.y.label.c_str());
184 tmax = (_bag_player->startTime() + ros::Duration(_bag_player->time()))
187 tmax = ros::Time::now().toNSec();
190 tmin = tmax - std::max(int64_t(1000), int64_t(_duration * 1000000000));
193 double vd = (vmax - vmin) * (1.0 / frame.height());
194 vmin -= vd * _style.spacing.bottom;
195 vmax += vd * _style.spacing.top;
199 double vd = (tmax - tmin) * (1.0 / frame.width());
200 tmin -= vd * _style.spacing.left;
201 tmax += vd * _style.spacing.right;
204 if (tmax != tmin && vmax != vmin) {
207 font.setPixelSize(_style.ticks.fontSize);
208 painter->setFont(font);
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;
216 double fx = (x - tmin) * (1.0 / (tmax - tmin));
217 double px = fx * frame.width() + frame.left();
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());
226 painter->setPen(QPen(toQColor(_style.foregroundColor)));
227 double w = step * 1.0 / (tmax - tmin) * frame.width();
229 QRectF(px - w * 0.5, frame.bottom() + _style.ticks.length, w,
230 _style.ticks.fontSize + _style.padding * 2),
232 QString::number((x % (1000000000l * 1000l)) * (1.0 / 1000000000),
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();
245 QPen(toQColor(_style.foregroundColor), _style.ticks.width));
246 painter->drawLine(frame.left(), py, frame.left() - _style.ticks.length,
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);
252 painter->setPen(QPen(toQColor(_style.foregroundColor)));
253 double h = step * 1.0 / (vmax - vmin) * frame.height();
255 QRectF(frame.left() - _style.ticks.length - _style.ticks.y.width -
257 py - h * 0.5, _style.ticks.y.width + _style.padding, h),
258 Qt::AlignVCenter | Qt::AlignRight, QString::number(y,
'g', 3));
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);
274 painter->setPen(QPen(toQColor(query.color), _style.graphWidth));
275 painter->drawPolyline(points.data(), points.size());