TAMSVIZ
Visualization and annotation tool for ROS
imagewindow.cpp
1 // TAMSVIZ
2 // (c) 2020 Philipp Ruppel
3 
4 #include "imagewindow.h"
5 
6 #include "../core/bagplayer.h"
7 #include "../core/log.h"
8 #include "../core/workspace.h"
9 
10 #include <cv_bridge/cv_bridge.h>
11 #include <sensor_msgs/CompressedImage.h>
12 #include <sensor_msgs/Image.h>
13 
14 #include <QGraphicsScene>
15 #include <QGraphicsView>
16 
17 #include <condition_variable>
18 #include <mutex>
19 #include <thread>
20 
21 #include <opencv2/imgcodecs.hpp>
22 
23 struct AnnotationView : QGraphicsItem {
24  bool ok = false;
25  ImageWindow *_window = nullptr;
26  std::shared_ptr<AnnotationTrack> _track;
27  std::shared_ptr<AnnotationSpan> _span;
28  std::shared_ptr<ImageAnnotationBase> _annotation;
29  QPainterPath _visual;
30  QPainterPath _collider;
31  QColor _color;
32  bool _selected = false;
33  double _zoom_factor = 1.0;
34 
35  struct ControlPointHandle : QGraphicsEllipseItem {
36  AnnotationView *_parent = nullptr;
37  size_t _control_point_index = 0;
38  ControlPointHandle(AnnotationView *parent, size_t control_point_index)
39  : QGraphicsEllipseItem(parent), _parent(parent),
40  _control_point_index(control_point_index) {
41  double r = 5;
42  setRect(-r, -r, 2 * r, 2 * r);
43  setBrush(QBrush(Qt::white));
44  setPen(QPen(QBrush(Qt::black), 0));
45  setScale(1.0 / _parent->_zoom_factor);
46  }
47  void sync(const std::shared_ptr<Workspace> &ws) {
48  auto p = _parent->_annotation->controlPoints().at(_control_point_index);
49  setPos(p.x(), p.y());
50  }
51  virtual void mousePressEvent(QGraphicsSceneMouseEvent *event) override {
52  if (_parent->_window->annotation_type) {
53  return;
54  }
55  if (event->button() == Qt::LeftButton) {
56  event->accept();
57  }
58  }
59  virtual void mouseMoveEvent(QGraphicsSceneMouseEvent *event) override {
60  if (_parent->_window->annotation_type) {
61  return;
62  }
63  if (event->buttons() == Qt::LeftButton) {
64  event->accept();
65  setPos(pos() + (event->scenePos() - event->lastScenePos()));
66  LockScope ws;
67  auto p0 = _parent->_annotation->controlPoints();
68  for (size_t i = 0; i < _parent->control_point_handles.size(); i++) {
69  auto *h = _parent->control_point_handles.at(i);
70  _parent->_annotation->controlPoints().at(i) =
71  Eigen::Vector2d(h->pos().x(), h->pos().y());
72  }
73  _parent->_annotation->constrain();
74  _parent->sync(ws(), _parent->_zoom_factor);
75  _parent->updateShape();
76  _parent->_annotation->controlPoints() = p0;
77  }
78  }
79  virtual void mouseReleaseEvent(QGraphicsSceneMouseEvent *event) override {
80  if (_parent->_window->annotation_type) {
81  return;
82  }
83  if (event->button() == Qt::LeftButton) {
84  event->accept();
85  ActionScope ws("Edit Annotation");
86  for (size_t i = 0; i < _parent->control_point_handles.size(); i++) {
87  auto *h = _parent->control_point_handles.at(i);
88  _parent->_annotation->controlPoints().at(i) =
89  Eigen::Vector2d(h->pos().x(), h->pos().y());
90  }
91  _parent->_annotation->constrain();
92  ws->modified();
93  }
94  }
95  };
96  std::vector<ControlPointHandle *> control_point_handles;
97 
98  AnnotationView(ImageWindow *window, const std::shared_ptr<Workspace> &ws,
99  const std::shared_ptr<AnnotationTrack> &track,
100  const std::shared_ptr<AnnotationSpan> &span,
101  const std::shared_ptr<ImageAnnotationBase> &annotation) {
102  _window = window;
103  _track = track;
104  _span = span;
105  _annotation = annotation;
106  }
107  void updateShape() {
108  _annotation->render();
109  if (_annotation->shape) {
110  _visual = *_annotation->shape;
111  } else {
112  _visual = QPainterPath();
113  }
114  if (_annotation->controlPoints().size() == 1 && _annotation->complete) {
115  setPos(_annotation->controlPoints().front().x(),
116  _annotation->controlPoints().front().y());
117  _visual.translate(-_annotation->controlPoints().front().x(),
118  -_annotation->controlPoints().front().y());
119  setScale(1.0 / _zoom_factor);
120  _collider = QPainterPath();
121  _collider.addEllipse(_visual.boundingRect());
122  } else {
123  setPos(0, 0);
124  setScale(1);
125  _collider = _visual;
126  }
127  }
128  virtual void sync(const std::shared_ptr<Workspace> &ws, double zoom_factor) {
129  _zoom_factor = zoom_factor;
130 
131  updateShape();
132  _selected = ws->selection().contains(_annotation);
133 
134  if ((_window->annotation_type == nullptr && _selected &&
135  ws->selection().size() == 1 &&
136  _annotation->controlPoints().size() >= 2) ||
137  (_window->annotation_type != nullptr &&
138  _window->new_annotation == _annotation)) {
139  control_point_handles.resize(_annotation->controlPoints().size());
140  for (size_t i = 0; i < _annotation->controlPoints().size(); i++) {
141  auto &h = control_point_handles.at(i);
142  if (!h) {
143  h = new ControlPointHandle(this, i);
144  }
145  h->sync(ws);
146  }
147  } else {
148  for (auto *h : control_point_handles) {
149  delete h;
150  }
151  control_point_handles.clear();
152  }
153  _color = QColor::fromHsvF(_track->color(), 1, 1, 0.5);
154  }
155  virtual QRectF boundingRect() const override {
156  return _collider.boundingRect();
157  }
158  virtual void paint(QPainter *painter, const QStyleOptionGraphicsItem *option,
159  QWidget *widget) override {
160 
161  painter->setPen(QPen(QBrush(QColor(0, 0, 0, 255)), 0, Qt::SolidLine,
162  Qt::SquareCap, Qt::MiterJoin));
163  auto color = _color;
164  painter->setBrush(QBrush(color));
165  painter->drawPath(_visual);
166 
167  if (_selected && _window->annotation_type == nullptr) {
168 
169  painter->save();
170 
171  painter->setRenderHint(QPainter::Antialiasing, false);
172 
173  auto rect = boundingRect().marginsAdded(QMarginsF(4, 4, 4, 4));
174 
175  {
176  QRegion region;
177  auto r = rect.toRect();
178  auto d = r.size() * 0.75;
179  region += QRegion(r.translated(+d.width(), +d.height()));
180  region += QRegion(r.translated(+d.width(), -d.height()));
181  region += QRegion(r.translated(-d.width(), +d.height()));
182  region += QRegion(r.translated(-d.width(), -d.height()));
183  painter->setClipRegion(region);
184  }
185 
186  painter->setBrush(QBrush(Qt::transparent));
187 
188  painter->setPen(QPen(QBrush(Qt::white), 0, Qt::SolidLine, Qt::FlatCap,
189  Qt::MiterJoin));
190  painter->drawRect(rect);
191 
192  double m = 1.0 / painter->transform().m11();
193  rect = rect.marginsAdded(QMarginsF(m, m, m, m));
194  painter->setPen(QPen(QBrush(Qt::black), 0, Qt::SolidLine, Qt::FlatCap,
195  Qt::MiterJoin));
196  painter->drawRect(rect);
197 
198  painter->restore();
199  }
200  }
201  virtual QPainterPath shape() const override { return _collider; }
202  virtual void mousePressEvent(QGraphicsSceneMouseEvent *event) override {
203  if (_window->annotation_type) {
204  return;
205  }
206  if (event->button() == Qt::LeftButton) {
207  LockScope ws;
208  if (auto timeline = ws->document()->timeline()) {
209  if (_window->annotation_type == nullptr) {
210  event->accept();
211  if (event->modifiers() == Qt::ControlModifier) {
212  ws->selection().toggle(_annotation);
213  } else if (event->modifiers() == Qt::ShiftModifier) {
214  ws->selection().add(_annotation);
215  } else {
216  if (!ws->selection().contains(_annotation)) {
217  ws->selection() = _annotation;
218  }
219  }
220  ws->modified();
221  }
222  }
223  }
224  }
225  virtual void mouseMoveEvent(QGraphicsSceneMouseEvent *event) override {
226  if (_window->annotation_type) {
227  return;
228  }
229  if (event->buttons() == Qt::LeftButton) {
230  for (auto &p : _window->annotation_views) {
231  auto *view = p.second;
232  if (view->_selected) {
233  view->setPos(view->pos() +
234  (event->scenePos() - event->lastScenePos()));
235  }
236  }
237  }
238  }
239  virtual void mouseReleaseEvent(QGraphicsSceneMouseEvent *event) override {
240  if (_window->annotation_type) {
241  return;
242  }
243  if (event->button() == Qt::LeftButton) {
244  if (event->scenePos() != event->buttonDownScenePos(Qt::LeftButton)) {
245  ActionScope ws("Move Annotations");
246  auto delta =
247  (event->scenePos() - event->buttonDownScenePos(Qt::LeftButton));
248  for (auto &p : _window->annotation_views) {
249  auto *view = p.second;
250  if (view->_selected) {
251  auto annotation = p.first;
252  for (auto &point : annotation->controlPoints()) {
253  point.x() += delta.x();
254  point.y() += delta.y();
255  }
256  }
257  }
258  ws->modified();
259  }
260  }
261  }
262 };
263 
264 ImageWindow::ImageWindow() {
265 
266  {
267  auto *button = new FlatButton();
268  button->setSizePolicy(QSizePolicy::Minimum, QSizePolicy::Fixed);
269  QMenu *menu = new QMenu(this);
270  button->setMenu(menu);
271  button->setText("Image Topic");
272  addToolWidget(button);
273  connect(menu, &QMenu::aboutToShow, this, [this, menu]() {
274  menu->clear();
275  auto topics = LockScope()->listTopics({
276  "sensor_msgs/Image",
277  "sensor_msgs/CompressedImage",
278  });
279  if (topics.empty()) {
280  connect(menu->addAction("<no image topics found>"), &QAction::triggered,
281  this, [this](bool) {
282  ActionScope ws("Topic");
283  this->topic() = "";
284  ws->modified();
285  });
286  } else {
287  connect(menu->addAction("<none>"), &QAction::triggered, this,
288  [this](bool) {
289  ActionScope ws("Topic");
290  this->topic() = "";
291  ws->modified();
292  });
293  for (auto &topic : topics) {
294  connect(menu->addAction(topic.c_str()), &QAction::triggered, this,
295  [topic, this](bool) {
296  ActionScope ws("Topic");
297  this->topic() = topic;
298  ws->modified();
299  });
300  }
301  }
302  });
303  LockScope ws;
304  ws->modified.connect(button, [this, button]() {
305  LockScope ws;
306  button->setText(topic().empty() ? "Image Topic" : topic().c_str());
307  });
308  }
309 
310  {
311  auto *button = new FlatButton();
312  button->setSizePolicy(QSizePolicy::Minimum, QSizePolicy::Fixed);
313  QMenu *menu = new QMenu(this);
314  button->setMenu(menu);
315  addToolWidget(button);
316  {
317  QString label = "Select / Edit";
318  button->setText(label);
319  connect(menu->addAction(label), &QAction::triggered, this,
320  [label, button, this](bool checked) {
321  LockScope ws;
322  annotation_type = nullptr;
323  button->setText(label);
324  ws->modified();
325  });
326  }
327  for (auto &type : Type::find<ImageAnnotationBase>()->list()) {
328  if (!type->constructable()) {
329  continue;
330  }
331  QString label = type->name().c_str();
332  label = label.replace("ImageAnnotation", "");
333  connect(menu->addAction(label), &QAction::triggered, this,
334  [type, label, button, this](bool checked) {
335  LockScope ws;
336  annotation_type = type;
337  button->setText(label);
338  ws->modified();
339  });
340  }
341  }
342 
343  {
344  auto *button = new FlatButton();
345  button->setIcon(MATERIAL_ICON("zoom_out_map"));
346  button->setSizePolicy(QSizePolicy::Minimum, QSizePolicy::Fixed);
347  connect(button, &QPushButton::clicked, this, [this]() {
348  LockScope ws;
349  zoom() = 1.0;
350  center().x() = 0.5;
351  center().y() = 0.5;
352  ws->modified();
353  });
354  addToolWidgetRight(button);
355  }
356 
357  class MessageBuffer {
358  std::mutex _mutex;
359  std::shared_ptr<const Message> _image;
360  std::condition_variable _put_condition;
361  std::thread _worker;
362  QPixmap _pixmap;
363  bool _stop = false;
364  ros::Time _image_time, _pixmap_time;
365 
366  public:
367  Event<void()> ready;
368  MessageBuffer() {
369  _worker = std::thread([this]() {
370  while (true) {
371  std::shared_ptr<const Message> image;
372  {
373  std::unique_lock<std::mutex> lock(_mutex);
374  while (true) {
375  if (_stop) {
376  return;
377  }
378  if (_image) {
379  image = _image;
380  _image = nullptr;
381  break;
382  }
383  _put_condition.wait(lock);
384  }
385  }
386  if (image == nullptr) {
387  {
388  std::unique_lock<std::mutex> lock(_mutex);
389  _pixmap = QPixmap();
390  }
391  continue;
392  }
393 
394  /*
395  cv_bridge::CvImagePtr cv_ptr;
396  QImage::Format image_format;
397  try {
398  if (sensor_msgs::image_encodings::isColor(image->encoding)) {
399  LOG_DEBUG("color");
400  image_format = QImage::Format_RGBA8888;
401  cv_ptr = cv_bridge::toCvCopy(*image,
402  sensor_msgs::image_encodings::RGBA8);
403  } else {
404  LOG_DEBUG("grayscale");
405  image_format = QImage::Format_Grayscale8;
406  cv_ptr = cv_bridge::toCvCopy(*image,
407  sensor_msgs::image_encodings::MONO8);
408  }
409  } catch (cv_bridge::Exception &e) {
410  LOG_ERROR("cv_bridge exception: " << e.what());
411  {
412  std::unique_lock<std::mutex> lock(_mutex);
413  _pixmap = QPixmap();
414  }
415  ready();
416  continue;
417  }
418  if (cv_ptr->image.data == nullptr) {
419  {
420  std::unique_lock<std::mutex> lock(_mutex);
421  _pixmap = QPixmap();
422  }
423  ready();
424  continue;
425  }
426  cv::Mat mat = cv_ptr->image;
427  auto pixmap = QPixmap::fromImage(QImage(
428  (uchar *)mat.data, mat.cols, mat.rows, mat.step, image_format));
429  {
430  std::unique_lock<std::mutex> lock(_mutex);
431  _pixmap = pixmap;
432  _pixmap_time = _image_time;
433  }
434  */
435 
436  cv::Mat mat;
437 
438  if (auto img = image->instantiate<sensor_msgs::Image>()) {
439  cv_bridge::CvImagePtr cv_ptr;
440  try {
441  cv_ptr = cv_bridge::toCvCopy(*img);
442  } catch (cv_bridge::Exception &e) {
443  LOG_ERROR("cv_bridge exception: " << e.what());
444  {
445  std::unique_lock<std::mutex> lock(_mutex);
446  _pixmap = QPixmap();
447  }
448  ready();
449  continue;
450  }
451  mat = cv_ptr->image;
452  } else if (auto img =
453  image->instantiate<sensor_msgs::CompressedImage>()) {
454  mat = cv::imdecode(img->data, cv::IMREAD_UNCHANGED);
455  } else {
456  LOG_WARN("unsupported image message type" << image->type()->name());
457  continue;
458  }
459 
460  if (mat.empty()) {
461  LOG_WARN("failed to decode image");
462  continue;
463  }
464 
465  QImage qimage;
466  switch (mat.type()) {
467 
468  case CV_8UC1:
469  qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
470  QImage::Format_Grayscale8);
471  break;
472  case CV_16UC1:
473  mat.convertTo(mat, CV_8U, 1.0 / 256.0);
474  qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
475  QImage::Format_Grayscale8);
476  break;
477  case CV_32FC1:
478  mat.convertTo(mat, CV_8U, 255.0);
479  qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
480  QImage::Format_Grayscale8);
481  break;
482  case CV_64FC1:
483  mat.convertTo(mat, CV_8U, 255.0);
484  qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
485  QImage::Format_Grayscale8);
486  break;
487 
488  case CV_8UC3:
489  cv::cvtColor(mat, mat, cv::COLOR_BGR2RGB);
490  qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
491  QImage::Format_RGB888);
492  break;
493  case CV_16UC3:
494  cv::cvtColor(mat, mat, cv::COLOR_BGR2RGB);
495  mat.convertTo(mat, CV_8UC3, 1.0 / 256.0);
496  qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
497  QImage::Format_RGB888);
498  break;
499  case CV_32FC3:
500  cv::cvtColor(mat, mat, cv::COLOR_BGR2RGB);
501  mat.convertTo(mat, CV_8UC3, 255.0);
502  qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
503  QImage::Format_RGB888);
504  break;
505  case CV_64FC3:
506  cv::cvtColor(mat, mat, cv::COLOR_BGR2RGB);
507  mat.convertTo(mat, CV_8UC3, 255.0);
508  qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
509  QImage::Format_RGB888);
510  break;
511 
512  case CV_8UC4:
513  cv::cvtColor(mat, mat, cv::COLOR_BGRA2RGBA);
514  qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
515  QImage::Format_RGBA8888);
516  break;
517  case CV_16UC4:
518  cv::cvtColor(mat, mat, cv::COLOR_BGRA2RGBA);
519  mat.convertTo(mat, CV_8UC4, 1.0 / 256.0);
520  qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
521  QImage::Format_RGBA8888);
522  break;
523  case CV_32FC4:
524  cv::cvtColor(mat, mat, cv::COLOR_BGRA2RGBA);
525  mat.convertTo(mat, CV_8UC4, 255.0);
526  qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
527  QImage::Format_RGBA8888);
528  break;
529  case CV_64FC4:
530  cv::cvtColor(mat, mat, cv::COLOR_BGRA2RGBA);
531  mat.convertTo(mat, CV_8UC4, 255.0);
532  qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
533  QImage::Format_RGBA8888);
534  break;
535 
536  default:
537  LOG_WARN("image format not yet supported " << mat.type());
538  continue;
539  }
540  auto pixmap = QPixmap::fromImage(qimage);
541  {
542  std::unique_lock<std::mutex> lock(_mutex);
543  _pixmap = pixmap;
544  _pixmap_time = _image_time;
545  }
546  ready();
547  }
548  });
549  }
550  ~MessageBuffer() {
551  {
552  std::unique_lock<std::mutex> lock(_mutex);
553  _stop = true;
554  _put_condition.notify_one();
555  }
556  _worker.join();
557  }
558  void putImage(const std::shared_ptr<const Message> &msg) {
559  std::unique_lock<std::mutex> lock(_mutex);
560  _image = nullptr;
561  _image_time = ros::Time();
562  if (msg) {
563  _image = msg;
564  _image_time = msg->time();
565  _put_condition.notify_one();
566  }
567  _put_condition.notify_one();
568  }
569  void fetchPixmap(QPixmap *pixmap, ros::Time *time) {
570  std::unique_lock<std::mutex> lock(_mutex);
571  *pixmap = _pixmap;
572  *time = _pixmap_time;
573  }
574  };
575  std::shared_ptr<MessageBuffer> buffer = std::make_shared<MessageBuffer>();
576 
577  class GraphicsView : public QGraphicsView {
578  class GraphicsScene : public QGraphicsScene {
579  GraphicsView *_parent = nullptr;
580  QGraphicsRectItem *_selection_rect = nullptr;
581 
582  protected:
583  virtual void mousePressEvent(QGraphicsSceneMouseEvent *event) override {
584  QGraphicsScene::mousePressEvent(event);
585  if (event->button() == Qt::LeftButton) {
586  if (event->modifiers() == 0 && !event->isAccepted()) {
587  LockScope ws;
588  ws->selection().clear();
589  ws->modified();
590  }
591  event->accept();
592  }
593  }
594  virtual void mouseMoveEvent(QGraphicsSceneMouseEvent *event) override {
595  QGraphicsScene::mouseMoveEvent(event);
596  if (_parent->_parent->annotation_type == nullptr) {
597  if (event->buttons() == Qt::LeftButton && !event->isAccepted()) {
598  event->accept();
599  auto a = event->buttonDownScenePos(Qt::LeftButton);
600  auto b = event->scenePos();
601  _selection_rect->setRect(
602  std::min(a.x(), b.x()), std::min(a.y(), b.y()),
603  std::abs(a.x() - b.x()), std::abs(a.y() - b.y()));
604  if (_selection_rect->rect().width() > 1e-6 &&
605  _selection_rect->rect().height() > 1e-6) {
606  _selection_rect->show();
607  }
608  }
609  }
610  }
611  virtual void mouseReleaseEvent(QGraphicsSceneMouseEvent *event) override {
612  QGraphicsScene::mouseReleaseEvent(event);
613  if (event->button() == Qt::LeftButton && !event->isAccepted()) {
614  event->accept();
615  if (_selection_rect->isVisible()) {
616  LockScope ws;
617  QPainterPath selection_path;
618  selection_path.addRect(_selection_rect->rect());
619  for (auto &p : _parent->_parent->annotation_views) {
620  auto *view = p.second;
621  if (selection_path.intersects(
622  view->shape().translated(view->pos()))) {
623  ws->selection().add(p.first);
624  }
625  }
626  ws->modified();
627  _selection_rect->hide();
628  }
629  }
630  }
631 
632  public:
633  GraphicsScene(GraphicsView *parent)
634  : QGraphicsScene(parent), _parent(parent) {
635  _selection_rect = new QGraphicsRectItem();
636  _selection_rect->hide();
637  _selection_rect->setBrush(QBrush(Qt::transparent));
638  _selection_rect->setPen(QPen(QBrush(Qt::red), 0));
639  _selection_rect->setZValue(10);
640  addItem(_selection_rect);
641  }
642 
643  virtual void drawForeground(QPainter *painter,
644  const QRectF &rect) override {
645  QGraphicsScene::drawForeground(painter, rect);
646  painter->save();
647  painter->resetTransform();
648  _parent->_parent->paintAnnotationHUD(painter,
649  _parent->_parent->annotation_type);
650  painter->restore();
651  }
652  };
653  ImageWindow *_parent = nullptr;
654  std::shared_ptr<MessageBuffer> _buffer;
655  GraphicsScene *_scene = nullptr;
656  QPixmap _image_pixmap;
657  ros::Time _pixmap_time;
658  QGraphicsPixmapItem *_image_item = nullptr;
659  double windowScale() const {
660  return std::min(width() * 1.0 / std::max(1, _image_pixmap.width()),
661  height() * 1.0 / std::max(1, _image_pixmap.height()));
662  }
663  double zoomFactor() const { return windowScale() * _parent->zoom(); }
664 
665  private:
666  void sync() {
667  {
668  double s = 1000000;
669  scene()->setSceneRect(-s, -s, 2 * s, 2 * s);
670  }
671  _image_item->setPixmap(_image_pixmap);
672  {
673  LockScope ws;
674  {
675  resetTransform();
676  double zoom = zoomFactor();
677  scale(zoom, zoom);
678  centerOn(_parent->center().x() * _image_pixmap.width(),
679  _parent->center().y() * _image_pixmap.height());
680  }
681  for (auto &pair : _parent->annotation_views) {
682  pair.second->ok = false;
683  }
684  if (ws->player) {
685  if (auto timeline = ws->document()->timeline()) {
686  double current_time =
687  (_pixmap_time - ws->player->startTime()).toSec() + 1e-6;
688  for (auto &track_base : timeline->tracks()) {
689  if (auto track =
690  std::dynamic_pointer_cast<AnnotationTrack>(track_base)) {
691  if (auto branch = track->branch(ws(), false)) {
692  for (auto &span : branch->spans()) {
693  if (span->start() > current_time ||
694  span->start() + span->duration() <= current_time) {
695  continue;
696  }
697  for (auto &annotation_base : span->annotations()) {
698  if (auto annotation =
699  std::dynamic_pointer_cast<ImageAnnotationBase>(
700  annotation_base)) {
701  if (annotation->topic() != _parent->topic()) {
702  continue;
703  }
704  auto &view = _parent->annotation_views[annotation];
705  if (view == nullptr) {
706  view = new AnnotationView(_parent, ws(), track, span,
707  annotation);
708  scene()->addItem(view);
709  }
710  view->ok = true;
711  double zoom_factor = zoomFactor();
712  view->sync(ws(), zoom_factor);
713  }
714  }
715  }
716  }
717  }
718  }
719  }
720  }
721  if (auto annotation = _parent->new_annotation) {
722  auto &view = _parent->annotation_views[annotation];
723  view->ok = true;
724  double zoom_factor = zoomFactor();
725  view->sync(ws(), zoom_factor);
726  }
727  for (auto it = _parent->annotation_views.begin();
728  it != _parent->annotation_views.end();) {
729  if (it->second->ok) {
730  it++;
731  } else {
732  delete it->second;
733  it = _parent->annotation_views.erase(it);
734  }
735  }
736  }
737  update();
738  }
739 
740  protected:
741  virtual void resizeEvent(QResizeEvent *event) override {
742  QGraphicsView::resizeEvent(event);
743  sync();
744  }
745 
746  public:
747  GraphicsView(const std::shared_ptr<MessageBuffer> &buffer,
748  ImageWindow *parent)
749  : _buffer(buffer), _parent(parent) {
750  _scene = new GraphicsScene(this);
751  setViewport(new QOpenGLWidget(this));
752  setCacheMode(QGraphicsView::CacheNone);
753  setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
754  setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff);
755  setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff);
756  setRenderHints(QPainter::Antialiasing);
757  setMouseTracking(true);
758  setFocusPolicy(Qt::ClickFocus);
759  setScene(_scene);
760  _scene->setBackgroundBrush(Qt::black);
761  _image_item = new QGraphicsPixmapItem();
762  _image_item->setTransformationMode(Qt::SmoothTransformation);
763  _scene->addItem(_image_item);
764  buffer->ready.connect(this, [this]() {
765  // TODO: is this safe?
766  QObject o;
767  QObject::connect(&o, &QObject::destroyed, this, [this](QObject *o) {
768  _buffer->fetchPixmap(&_image_pixmap, &_pixmap_time);
769  sync();
770  });
771  });
772  LockScope()->modified.connect(this, [this]() { sync(); });
773  }
774  void focusOutEvent(QFocusEvent *event) {
775  QGraphicsView::focusOutEvent(event);
776  _parent->new_annotation = nullptr;
777  sync();
778  }
779  void wheelEvent(QWheelEvent *wheel) {
780  double degrees = wheel->angleDelta().y() * (1.0 / 8);
781  double exponent = degrees / 90;
782  double factor = std::pow(0.5, -exponent);
783  {
784  LockScope ws;
785  auto mouse_pos = mapToScene(_last_mouse_pos);
786  _parent->zoom() *= factor;
787  _parent->zoom() =
788  std::min(maxZoom(), std::max(minZoom(), _parent->zoom()));
789  sync();
790  auto d = (mouse_pos - mapToScene(_last_mouse_pos));
791  _parent->center().x() += d.x() / std::max(1, _image_pixmap.width());
792  _parent->center().y() += d.y() / std::max(1, _image_pixmap.height());
793  ws->modified();
794  }
795  }
796  QPoint _last_mouse_pos = QPoint(0, 0);
797  QPoint _middle_down_pos = QPoint(0, 0);
798  Eigen::Vector2d snap(const QPoint &p) {
799  if (_parent->new_annotation &&
800  _parent->new_annotation->controlPoints().size() > 2) {
801  auto q = _parent->new_annotation->controlPoints().front();
802  double distance = (mapFromScene(q.x(), q.y()) - p).manhattanLength();
803  if (distance <= 15) {
804  return q;
805  }
806  }
807  auto q = mapToScene(p);
808  return Eigen::Vector2d(q.x(), q.y());
809  }
810  virtual void mouseMoveEvent(QMouseEvent *event) override {
811  if (_parent->new_annotation) {
812  event->accept();
813  LockScope ws;
814  auto p = snap(event->pos());
815  _parent->new_annotation->controlPoints().back().x() = p.x();
816  _parent->new_annotation->controlPoints().back().y() = p.y();
817  _parent->new_annotation->constrain();
818  sync();
819  }
820  QGraphicsView::mouseMoveEvent(event);
821  event->accept();
822  if (event->buttons() == Qt::RightButton ||
823  event->buttons() == Qt::MiddleButton) {
824  LockScope ws;
825  auto d = mapToScene(event->pos()) - mapToScene(_last_mouse_pos);
826  _parent->center().x() -=
827  d.x() * 1.0 / std::max(1, _image_pixmap.width());
828  _parent->center().y() -=
829  d.y() * 1.0 / std::max(1, _image_pixmap.height());
830  ws->modified();
831  }
832 
833  _last_mouse_pos = event->pos();
834  }
835 
836  virtual void mousePressEvent(QMouseEvent *event) override {
837  if (_parent->new_annotation) {
838  event->accept();
839  }
840  QGraphicsView::mousePressEvent(event);
841  event->accept();
842  if (event->button() == Qt::MiddleButton) {
843  _middle_down_pos = event->pos();
844  }
845  if (event->button() == Qt::RightButton) {
846  if (_parent->new_annotation) {
847  _parent->new_annotation = nullptr;
848  sync();
849  }
850  }
851  if (event->button() == Qt::LeftButton) {
852  auto scene_pos = mapToScene(event->pos());
853  LockScope ws;
854  if (auto timeline = ws->document()->timeline()) {
855  if (ws->player) {
856  if (_parent->annotation_type) {
857  ActionScope ws("Annotate");
858  double current_time =
859  (_pixmap_time - ws->player->startTime()).toSec() + 1e-6;
860  std::shared_ptr<AnnotationTrack> current_track =
861  ws->currentAnnotationTrack().resolve(ws());
862  if (!current_track) {
863  for (auto &track_base : timeline->tracks()) {
864  if (auto track = std::dynamic_pointer_cast<AnnotationTrack>(
865  track_base)) {
866  if (auto branch = track->branch(ws(), false)) {
867  for (auto &span : branch->spans()) {
868  if (span->start() <= current_time &&
869  span->start() + span->duration() >= current_time) {
870  current_track = track;
871  break;
872  }
873  }
874  if (current_track) {
875  break;
876  }
877  }
878  }
879  }
880  }
881  if (!current_track) {
882  for (auto &track_base : timeline->tracks()) {
883  if (auto track = std::dynamic_pointer_cast<AnnotationTrack>(
884  track_base)) {
885  current_track = track;
886  break;
887  }
888  }
889  }
890  if (!current_track) {
891  timeline->tracks().push_back(
892  current_track = std::make_shared<AnnotationTrack>());
893  }
894  ws->currentAnnotationTrack() = current_track;
895  std::shared_ptr<AnnotationSpan> current_span;
896  if (auto branch = current_track->branch(ws(), false)) {
897  for (auto &span : branch->spans()) {
898  if (span->start() <= current_time &&
899  span->start() + span->duration() >= current_time) {
900  current_span = span;
901  break;
902  }
903  }
904  }
905  if (current_span == nullptr) {
906  current_span = std::make_shared<AnnotationSpan>();
907  current_span->start() = current_time;
908  current_span->duration() = 0.1;
909  {
910  double start = 0;
911  double duration = 0;
912  if (ws->player->findMessageTimeSpan(
913  _parent->topic(), current_time, &start, &duration)) {
914  current_span->start() = start;
915  current_span->duration() = duration;
916  }
917  }
918  current_track->branch(ws(), true)
919  ->spans()
920  .push_back(current_span);
921  }
922  ws->selection() = current_span;
923  _parent->new_annotation_span = current_span;
924  if (!_parent->new_annotation) {
925  _parent->new_annotation =
926  _parent->annotation_type
927  ->instantiate<ImageAnnotationBase>();
928  _parent->new_annotation->topic() = _parent->topic();
929  _parent->new_annotation->controlPoints().emplace_back(
930  scene_pos.x(), scene_pos.y());
931  _parent->new_annotation->constrain();
932  _parent->new_annotation->render();
933  auto &view = _parent->annotation_views[_parent->new_annotation];
934  view =
935  new AnnotationView(_parent, ws(), current_track,
936  current_span, _parent->new_annotation);
937  scene()->addItem(view);
938  }
939  if (_parent->new_annotation->complete) {
940  ActionScope ws("New Annotation");
941  if (_parent->new_annotation->controlPoints().size() >= 2 &&
942  _parent->new_annotation->controlPoints().front() ==
943  _parent->new_annotation->controlPoints().back()) {
944  _parent->new_annotation->controlPoints().pop_back();
945  }
946  current_span->annotations().push_back(_parent->new_annotation);
947  ws->selection() = _parent->new_annotation;
948  _parent->new_annotation = nullptr;
949  } else {
950  auto point = snap(event->pos());
951  _parent->new_annotation->controlPoints().emplace_back(point);
952  _parent->new_annotation->constrain();
953  }
954  ws->modified();
955  }
956  }
957  }
958  }
959  _last_mouse_pos = event->pos();
960  }
961  virtual void mouseReleaseEvent(QMouseEvent *event) override {
962  if (_parent->new_annotation) {
963  {
964  LockScope ws;
965  _parent->new_annotation->render();
966  if (_parent->new_annotation->complete &&
967  _parent->new_annotation->controlPoints().size() == 2) {
968  auto a = _parent->new_annotation->controlPoints().at(0);
969  auto b = _parent->new_annotation->controlPoints().at(1);
970  double distance =
971  (mapFromScene(a.x(), a.y()) - mapFromScene(b.x(), b.y()))
972  .manhattanLength();
973  LOG_DEBUG("diagonal " << distance);
974  if (distance > 15) {
975  ActionScope ws("New Annotation");
976  _parent->new_annotation_span->annotations().push_back(
977  _parent->new_annotation);
978  ws->selection() = _parent->new_annotation;
979  _parent->new_annotation = nullptr;
980  ws->modified();
981  }
982  }
983  }
984  event->accept();
985  }
986  QGraphicsView::mouseReleaseEvent(event);
987  event->accept();
988  _last_mouse_pos = event->pos();
989  }
990  };
991 
992  auto *view = new GraphicsView(buffer, this);
993  setContentWidget(view);
994 
995  {
996  LockScope ws;
997  ws->modified.connect(this, [this, buffer]() {
998  LockScope ws;
999  if (topic().empty()) {
1000  subscriber = nullptr;
1001  buffer->putImage(nullptr);
1002  } else {
1003  if (!subscriber || subscriber->topic()->name() != topic()) {
1004  buffer->putImage(nullptr);
1005  subscriber = std::make_shared<Subscriber<Message>>(
1006  topic(), shared_from_this(),
1007  [buffer](const std::shared_ptr<const Message> &msg) {
1008  // LOG_DEBUG("image " << msg->time());
1009  buffer->putImage(msg);
1010  });
1011  }
1012  }
1013  });
1014  }
1015 }