20 parent()->installEventFilter(
this);
26 parent()->removeEventFilter(
this);
32 if (event->type() == QEvent::MouseButtonPress || event->type() == QEvent::MouseMove)
34 QMouseEvent* me =
static_cast<QMouseEvent*
>(event);
35 QPointF windowPos = me->windowPos();
36 bool left_button = me->buttons() == Qt::LeftButton;
45 if (img_aspect > win_aspect)
50 int bias = int((
float(
win_height_) -
float(resized_img_height)) / 2.0);
51 pix_y = (float(windowPos.y()) - bias) /
float(resized_img_height) * float(
img_height_);
58 int bias = int((
float(
win_width_) -
float(resized_img_width)) / 2.0);
59 pix_x = (float(windowPos.x()) - bias) /
float(resized_img_width) * float(
img_width_);
63 if (pix_x >= 0 && pix_x < img_width_ && pix_y >= 0 && pix_y <
img_height_)
65 geometry_msgs::PointStamped point_msg;
67 point_msg.point.x = pix_x;
68 point_msg.point.y = pix_y;
73 return QObject::eventFilter(obj, event);
89 topic_ = topic.toStdString().append(
"/mouse_click");