4 #include "imagewindow.h" 6 #include "../core/bagplayer.h" 7 #include "../core/log.h" 8 #include "../core/workspace.h" 10 #include <cv_bridge/cv_bridge.h> 11 #include <sensor_msgs/CompressedImage.h> 12 #include <sensor_msgs/Image.h> 14 #include <QGraphicsScene> 15 #include <QGraphicsView> 17 #include <condition_variable> 21 #include <opencv2/imgcodecs.hpp> 26 std::shared_ptr<AnnotationTrack> _track;
27 std::shared_ptr<AnnotationSpan> _span;
28 std::shared_ptr<ImageAnnotationBase> _annotation;
30 QPainterPath _collider;
32 bool _selected =
false;
33 double _zoom_factor = 1.0;
37 size_t _control_point_index = 0;
39 : QGraphicsEllipseItem(parent), _parent(parent),
40 _control_point_index(control_point_index) {
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);
47 void sync(
const std::shared_ptr<Workspace> &ws) {
48 auto p = _parent->_annotation->controlPoints().at(_control_point_index);
51 virtual void mousePressEvent(QGraphicsSceneMouseEvent *event)
override {
52 if (_parent->_window->annotation_type) {
55 if (event->button() == Qt::LeftButton) {
59 virtual void mouseMoveEvent(QGraphicsSceneMouseEvent *event)
override {
60 if (_parent->_window->annotation_type) {
63 if (event->buttons() == Qt::LeftButton) {
65 setPos(pos() + (event->scenePos() -
event->lastScenePos()));
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());
73 _parent->_annotation->constrain();
74 _parent->sync(ws(), _parent->_zoom_factor);
75 _parent->updateShape();
76 _parent->_annotation->controlPoints() = p0;
79 virtual void mouseReleaseEvent(QGraphicsSceneMouseEvent *event)
override {
80 if (_parent->_window->annotation_type) {
83 if (event->button() == Qt::LeftButton) {
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());
91 _parent->_annotation->constrain();
96 std::vector<ControlPointHandle *> control_point_handles;
99 const std::shared_ptr<AnnotationTrack> &track,
100 const std::shared_ptr<AnnotationSpan> &span,
101 const std::shared_ptr<ImageAnnotationBase> &annotation) {
105 _annotation = annotation;
108 _annotation->render();
109 if (_annotation->shape) {
110 _visual = *_annotation->shape;
112 _visual = QPainterPath();
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());
128 virtual void sync(
const std::shared_ptr<Workspace> &ws,
double zoom_factor) {
129 _zoom_factor = zoom_factor;
132 _selected = ws->selection().contains(_annotation);
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);
148 for (
auto *h : control_point_handles) {
151 control_point_handles.clear();
153 _color = QColor::fromHsvF(_track->color(), 1, 1, 0.5);
155 virtual QRectF boundingRect()
const override {
156 return _collider.boundingRect();
158 virtual void paint(QPainter *painter,
const QStyleOptionGraphicsItem *option,
159 QWidget *widget)
override {
161 painter->setPen(QPen(QBrush(QColor(0, 0, 0, 255)), 0, Qt::SolidLine,
162 Qt::SquareCap, Qt::MiterJoin));
164 painter->setBrush(QBrush(color));
165 painter->drawPath(_visual);
167 if (_selected && _window->annotation_type ==
nullptr) {
171 painter->setRenderHint(QPainter::Antialiasing,
false);
173 auto rect = boundingRect().marginsAdded(QMarginsF(4, 4, 4, 4));
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);
186 painter->setBrush(QBrush(Qt::transparent));
188 painter->setPen(QPen(QBrush(Qt::white), 0, Qt::SolidLine, Qt::FlatCap,
190 painter->drawRect(rect);
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,
196 painter->drawRect(rect);
201 virtual QPainterPath shape()
const override {
return _collider; }
202 virtual void mousePressEvent(QGraphicsSceneMouseEvent *event)
override {
203 if (_window->annotation_type) {
206 if (event->button() == Qt::LeftButton) {
208 if (
auto timeline = ws->document()->timeline()) {
209 if (_window->annotation_type ==
nullptr) {
211 if (event->modifiers() == Qt::ControlModifier) {
212 ws->selection().toggle(_annotation);
213 }
else if (event->modifiers() == Qt::ShiftModifier) {
214 ws->selection().add(_annotation);
216 if (!ws->selection().contains(_annotation)) {
217 ws->selection() = _annotation;
225 virtual void mouseMoveEvent(QGraphicsSceneMouseEvent *event)
override {
226 if (_window->annotation_type) {
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()));
239 virtual void mouseReleaseEvent(QGraphicsSceneMouseEvent *event)
override {
240 if (_window->annotation_type) {
243 if (event->button() == Qt::LeftButton) {
244 if (event->scenePos() !=
event->buttonDownScenePos(Qt::LeftButton)) {
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();
264 ImageWindow::ImageWindow() {
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]() {
277 "sensor_msgs/CompressedImage",
279 if (topics.empty()) {
280 connect(menu->addAction(
"<no image topics found>"), &QAction::triggered,
287 connect(menu->addAction(
"<none>"), &QAction::triggered,
this,
293 for (
auto &topic : topics) {
294 connect(menu->addAction(topic.c_str()), &QAction::triggered,
this,
295 [topic,
this](
bool) {
297 this->topic() = topic;
304 ws->modified.connect(button, [
this, button]() {
306 button->setText(topic().empty() ?
"Image Topic" : topic().c_str());
312 button->setSizePolicy(QSizePolicy::Minimum, QSizePolicy::Fixed);
313 QMenu *menu =
new QMenu(
this);
314 button->setMenu(menu);
315 addToolWidget(button);
317 QString label =
"Select / Edit";
318 button->setText(label);
319 connect(menu->addAction(label), &QAction::triggered,
this,
320 [label, button,
this](
bool checked) {
322 annotation_type =
nullptr;
323 button->setText(label);
327 for (
auto &type : Type::find<ImageAnnotationBase>()->list()) {
328 if (!type->constructable()) {
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) {
336 annotation_type = type;
337 button->setText(label);
345 button->setIcon(MATERIAL_ICON(
"zoom_out_map"));
346 button->setSizePolicy(QSizePolicy::Minimum, QSizePolicy::Fixed);
347 connect(button, &QPushButton::clicked,
this, [
this]() {
354 addToolWidgetRight(button);
357 class MessageBuffer {
359 std::shared_ptr<const Message> _image;
360 std::condition_variable _put_condition;
364 ros::Time _image_time, _pixmap_time;
369 _worker = std::thread([
this]() {
371 std::shared_ptr<const Message> image;
373 std::unique_lock<std::mutex> lock(_mutex);
383 _put_condition.wait(lock);
386 if (image ==
nullptr) {
388 std::unique_lock<std::mutex> lock(_mutex);
438 if (
auto img = image->instantiate<sensor_msgs::Image>()) {
439 cv_bridge::CvImagePtr cv_ptr;
441 cv_ptr = cv_bridge::toCvCopy(*img);
442 }
catch (cv_bridge::Exception &e) {
443 LOG_ERROR(
"cv_bridge exception: " << e.what());
445 std::unique_lock<std::mutex> lock(_mutex);
452 }
else if (
auto img =
453 image->instantiate<sensor_msgs::CompressedImage>()) {
454 mat = cv::imdecode(img->data, cv::IMREAD_UNCHANGED);
456 LOG_WARN(
"unsupported image message type" << image->type()->name());
461 LOG_WARN(
"failed to decode image");
466 switch (mat.type()) {
469 qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
470 QImage::Format_Grayscale8);
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);
478 mat.convertTo(mat, CV_8U, 255.0);
479 qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
480 QImage::Format_Grayscale8);
483 mat.convertTo(mat, CV_8U, 255.0);
484 qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
485 QImage::Format_Grayscale8);
489 cv::cvtColor(mat, mat, cv::COLOR_BGR2RGB);
490 qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
491 QImage::Format_RGB888);
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);
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);
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);
513 cv::cvtColor(mat, mat, cv::COLOR_BGRA2RGBA);
514 qimage = QImage((uchar *)mat.data, mat.cols, mat.rows, mat.step,
515 QImage::Format_RGBA8888);
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);
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);
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);
537 LOG_WARN(
"image format not yet supported " << mat.type());
540 auto pixmap = QPixmap::fromImage(qimage);
542 std::unique_lock<std::mutex> lock(_mutex);
544 _pixmap_time = _image_time;
552 std::unique_lock<std::mutex> lock(_mutex);
554 _put_condition.notify_one();
558 void putImage(
const std::shared_ptr<const Message> &msg) {
559 std::unique_lock<std::mutex> lock(_mutex);
561 _image_time = ros::Time();
564 _image_time = msg->time();
565 _put_condition.notify_one();
567 _put_condition.notify_one();
569 void fetchPixmap(QPixmap *pixmap, ros::Time *time) {
570 std::unique_lock<std::mutex> lock(_mutex);
572 *time = _pixmap_time;
575 std::shared_ptr<MessageBuffer> buffer = std::make_shared<MessageBuffer>();
577 class GraphicsView :
public QGraphicsView {
578 class GraphicsScene :
public QGraphicsScene {
579 GraphicsView *_parent =
nullptr;
580 QGraphicsRectItem *_selection_rect =
nullptr;
583 virtual void mousePressEvent(QGraphicsSceneMouseEvent *event)
override {
584 QGraphicsScene::mousePressEvent(event);
585 if (event->button() == Qt::LeftButton) {
586 if (event->modifiers() == 0 && !
event->isAccepted()) {
588 ws->selection().clear();
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()) {
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();
611 virtual void mouseReleaseEvent(QGraphicsSceneMouseEvent *event)
override {
612 QGraphicsScene::mouseReleaseEvent(event);
613 if (event->button() == Qt::LeftButton && !
event->isAccepted()) {
615 if (_selection_rect->isVisible()) {
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);
627 _selection_rect->hide();
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);
643 virtual void drawForeground(QPainter *painter,
644 const QRectF &rect)
override {
645 QGraphicsScene::drawForeground(painter, rect);
647 painter->resetTransform();
648 _parent->_parent->paintAnnotationHUD(painter,
649 _parent->_parent->annotation_type);
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()));
663 double zoomFactor()
const {
return windowScale() * _parent->zoom(); }
669 scene()->setSceneRect(-s, -s, 2 * s, 2 * s);
671 _image_item->setPixmap(_image_pixmap);
676 double zoom = zoomFactor();
678 centerOn(_parent->center().x() * _image_pixmap.width(),
679 _parent->center().y() * _image_pixmap.height());
681 for (
auto &pair : _parent->annotation_views) {
682 pair.second->ok =
false;
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()) {
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) {
697 for (
auto &annotation_base : span->annotations()) {
698 if (
auto annotation =
699 std::dynamic_pointer_cast<ImageAnnotationBase>(
701 if (annotation->topic() != _parent->topic()) {
704 auto &view = _parent->annotation_views[annotation];
705 if (view ==
nullptr) {
708 scene()->addItem(view);
711 double zoom_factor = zoomFactor();
712 view->sync(ws(), zoom_factor);
721 if (
auto annotation = _parent->new_annotation) {
722 auto &view = _parent->annotation_views[annotation];
724 double zoom_factor = zoomFactor();
725 view->sync(ws(), zoom_factor);
727 for (
auto it = _parent->annotation_views.begin();
728 it != _parent->annotation_views.end();) {
729 if (it->second->ok) {
733 it = _parent->annotation_views.erase(it);
741 virtual void resizeEvent(QResizeEvent *event)
override {
742 QGraphicsView::resizeEvent(event);
747 GraphicsView(
const std::shared_ptr<MessageBuffer> &buffer,
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);
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]() {
767 QObject::connect(&o, &QObject::destroyed,
this, [
this](QObject *o) {
768 _buffer->fetchPixmap(&_image_pixmap, &_pixmap_time);
772 LockScope()->modified.connect(
this, [
this]() { sync(); });
774 void focusOutEvent(QFocusEvent *event) {
775 QGraphicsView::focusOutEvent(event);
776 _parent->new_annotation =
nullptr;
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);
785 auto mouse_pos = mapToScene(_last_mouse_pos);
786 _parent->zoom() *= factor;
788 std::min(maxZoom(), std::max(minZoom(), _parent->zoom()));
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());
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) {
807 auto q = mapToScene(p);
808 return Eigen::Vector2d(q.x(), q.y());
810 virtual void mouseMoveEvent(QMouseEvent *event)
override {
811 if (_parent->new_annotation) {
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();
820 QGraphicsView::mouseMoveEvent(event);
822 if (event->buttons() == Qt::RightButton ||
823 event->buttons() == Qt::MiddleButton) {
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());
833 _last_mouse_pos =
event->pos();
836 virtual void mousePressEvent(QMouseEvent *event)
override {
837 if (_parent->new_annotation) {
840 QGraphicsView::mousePressEvent(event);
842 if (event->button() == Qt::MiddleButton) {
843 _middle_down_pos =
event->pos();
845 if (event->button() == Qt::RightButton) {
846 if (_parent->new_annotation) {
847 _parent->new_annotation =
nullptr;
851 if (event->button() == Qt::LeftButton) {
852 auto scene_pos = mapToScene(event->pos());
854 if (
auto timeline = ws->document()->timeline()) {
856 if (_parent->annotation_type) {
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>(
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;
881 if (!current_track) {
882 for (
auto &track_base : timeline->tracks()) {
883 if (
auto track = std::dynamic_pointer_cast<AnnotationTrack>(
885 current_track = track;
890 if (!current_track) {
891 timeline->tracks().push_back(
892 current_track = std::make_shared<AnnotationTrack>());
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) {
905 if (current_span ==
nullptr) {
906 current_span = std::make_shared<AnnotationSpan>();
907 current_span->start() = current_time;
908 current_span->duration() = 0.1;
912 if (ws->player->findMessageTimeSpan(
913 _parent->topic(), current_time, &start, &duration)) {
914 current_span->start() = start;
915 current_span->duration() = duration;
918 current_track->branch(ws(),
true)
920 .push_back(current_span);
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
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];
936 current_span, _parent->new_annotation);
937 scene()->addItem(view);
939 if (_parent->new_annotation->complete) {
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();
946 current_span->annotations().push_back(_parent->new_annotation);
947 ws->selection() = _parent->new_annotation;
948 _parent->new_annotation =
nullptr;
950 auto point = snap(event->pos());
951 _parent->new_annotation->controlPoints().emplace_back(point);
952 _parent->new_annotation->constrain();
959 _last_mouse_pos =
event->pos();
961 virtual void mouseReleaseEvent(QMouseEvent *event)
override {
962 if (_parent->new_annotation) {
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);
971 (mapFromScene(a.x(), a.y()) - mapFromScene(b.x(), b.y()))
973 LOG_DEBUG(
"diagonal " << distance);
976 _parent->new_annotation_span->annotations().push_back(
977 _parent->new_annotation);
978 ws->selection() = _parent->new_annotation;
979 _parent->new_annotation =
nullptr;
986 QGraphicsView::mouseReleaseEvent(event);
988 _last_mouse_pos =
event->pos();
992 auto *view =
new GraphicsView(buffer,
this);
993 setContentWidget(view);
997 ws->modified.connect(
this, [
this, buffer]() {
999 if (topic().empty()) {
1000 subscriber =
nullptr;
1001 buffer->putImage(
nullptr);
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) {
1009 buffer->putImage(msg);