40 #include <QMouseEvent> 
   44 #include <opencv2/core/core.hpp> 
   46 #include <geometry_msgs/Point32.h> 
   47 #include <geometry_msgs/PolygonStamped.h> 
   61     config_widget_(new QWidget()),
 
   64     is_mouse_down_(false),
 
   65     max_ms_(Q_INT64_C(500)),
 
   70     ui_.color->setColor(Qt::green);
 
   73     p.setColor(QPalette::Background, Qt::white);
 
   76     QPalette p3(
ui_.status->palette());
 
   77     p3.setColor(QPalette::Text, Qt::red);
 
   78     ui_.status->setPalette(p3);
 
   80     QObject::connect(
ui_.selectframe, SIGNAL(clicked()), 
this,
 
   82     QObject::connect(
ui_.frame, SIGNAL(editingFinished()), 
this,
 
   84     QObject::connect(
ui_.publish, SIGNAL(clicked()), 
this,
 
   86     QObject::connect(
ui_.clear, SIGNAL(clicked()), 
this,
 
  103       ui_.frame->setText(QString::fromStdString(frame));
 
  127     geometry_msgs::PolygonStamped polygon;
 
  129     polygon.header.frame_id = 
ui_.frame->text().toStdString();
 
  133       geometry_msgs::Point32 point;
 
  134       point.x = vertex.x();
 
  135       point.y = vertex.y();
 
  137       polygon.polygon.points.push_back(point);
 
  182     switch (event->type())
 
  184       case QEvent::MouseButtonPress:
 
  186       case QEvent::MouseButtonRelease:
 
  188       case QEvent::MouseMove:
 
  199       ROS_DEBUG(
"Ignoring mouse press, since draw polygon plugin is hidden");
 
  204     int closest_point = 0;
 
  205     double closest_distance = std::numeric_limits<double>::max();
 
  207 #if QT_VERSION >= 0x050000 
  208     QPointF point = 
event->localPos();
 
  210     QPointF point = 
event->posF();
 
  213     std::string frame = 
ui_.frame->text().toStdString();
 
  216       for (
size_t i = 0; i < 
vertices_.size(); i++)
 
  223         double distance = QLineF(transformed, point).length();
 
  225         if (distance < closest_distance)
 
  227           closest_distance = distance;
 
  228           closest_point = 
static_cast<int>(i);
 
  233     if (event->button() == Qt::LeftButton)
 
  235       if (closest_distance < 15)
 
  243 #if QT_VERSION >= 0x050000 
  252     else if (event->button() == Qt::RightButton)
 
  254       if (closest_distance < 15)
 
  267     std::string frame = 
ui_.frame->text().toStdString();
 
  270 #if QT_VERSION >= 0x050000 
  271       QPointF point = 
event->localPos();
 
  273       QPointF point = 
event->posF();
 
  279         tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
 
  290 #if QT_VERSION >= 0x050000 
  303 #if QT_VERSION >= 0x050000 
  304         QPointF point = 
event->localPos();
 
  306         QPointF point = 
event->posF();
 
  310         ROS_INFO(
"mouse point at %f, %f -> %f, %f", point.x(), point.y(), transformed.x(), transformed.y());
 
  313         tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
 
  320           ROS_INFO(
"Adding vertex at %lf, %lf %s", position.x(), position.y(), frame.c_str());
 
  333 #if QT_VERSION >= 0x050000 
  334       QPointF point = 
event->localPos();
 
  336       QPointF point = 
event->posF();
 
  339       std::string frame = 
ui_.frame->text().toStdString();
 
  343         tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
 
  357     std::string frame = 
ui_.frame->text().toStdString();
 
  364     for (
size_t i = 0; i < 
vertices_.size(); i++)
 
  370     const QColor color = 
ui_.color->color();
 
  371     glColor4d(color.redF(), color.greenF(), color.blueF(), 1.0);
 
  372     glBegin(GL_LINE_STRIP);
 
  376       glVertex2d(vertex.x(), vertex.y());
 
  383     glColor4d(color.redF(), color.greenF(), color.blueF(), 0.25);
 
  399       glVertex2d(vertex.x(), vertex.y());
 
  416     if (node[
"polygon_topic"])
 
  418       std::string polygon_topic;
 
  419       node[
"polygon_topic"] >> polygon_topic;
 
  420       ui_.topic->setText(polygon_topic.c_str());
 
  425       node[
"color"] >> color;
 
  426       ui_.color->setColor(QColor(color.c_str()));
 
  432     std::string frame = 
ui_.frame->text().toStdString();
 
  433     emitter << YAML::Key << 
"frame" << YAML::Value << frame;
 
  435     std::string polygon_topic = 
ui_.topic->text().toStdString();
 
  436     emitter << YAML::Key << 
"polygon_topic" << YAML::Value << polygon_topic;
 
  438     std::string color = 
ui_.color->color().name().toStdString();
 
  439     emitter << YAML::Key << 
"color" << YAML::Value << color;