40 #include <QMouseEvent> 
   43 #include <QStaticText> 
   45 #include <opencv2/core/core.hpp> 
   53 #include <marti_nav_msgs/PlanRoute.h> 
   59 namespace mnm = marti_nav_msgs;
 
   66     config_widget_(new QWidget()),
 
   68     failed_service_(false),
 
   70     is_mouse_down_(false),
 
   71     max_ms_(Q_INT64_C(500)),
 
   76     ui_.color->setColor(Qt::green);
 
   79     p.setColor(QPalette::Background, Qt::white);
 
   82     QPalette p3(
ui_.status->palette());
 
   83     p3.setColor(QPalette::Text, Qt::red);
 
   84     ui_.status->setPalette(p3);
 
   85     QObject::connect(
ui_.service, SIGNAL(editingFinished()), 
this,
 
   87     QObject::connect(
ui_.publish, SIGNAL(clicked()), 
this,
 
   89     QObject::connect(
ui_.clear, SIGNAL(clicked()), 
this,
 
   91     QObject::connect(
this,
 
  135     bool start_from_vehicle = 
ui_.start_from_vehicle->isChecked();
 
  141     std::string service = 
ui_.service->text().toStdString();
 
  144     mnm::PlanRoute plan_route;
 
  145     plan_route.request.header.frame_id = stu::_wgs84_frame;
 
  147     plan_route.request.plan_from_vehicle = 
static_cast<unsigned char>(start_from_vehicle);
 
  150     if (client.
call(plan_route))
 
  152       if (plan_route.response.success)
 
  154         route_preview_ = boost::make_shared<sru::Route>(plan_route.response.route);
 
  216     switch (event->type())
 
  218       case QEvent::MouseButtonPress:
 
  220       case QEvent::MouseButtonRelease:
 
  222       case QEvent::MouseMove:
 
  232     int closest_point = 0;
 
  233     double closest_distance = std::numeric_limits<double>::max();
 
  235 #if QT_VERSION >= 0x050000 
  236     QPointF point = 
event->localPos();
 
  238     QPointF point = 
event->posF();
 
  243       for (
size_t i = 0; i < 
waypoints_.size(); i++)
 
  245         tf::Vector3 waypoint(
 
  253         double distance = QLineF(transformed, point).length();
 
  255         if (distance < closest_distance)
 
  257           closest_distance = distance;
 
  258           closest_point = 
static_cast<int>(i);
 
  263     if (event->button() == Qt::LeftButton)
 
  265       if (closest_distance < 15)
 
  273 #if QT_VERSION >= 0x050000 
  282     else if (event->button() == Qt::RightButton)
 
  284       if (closest_distance < 15)
 
  297 #if QT_VERSION >= 0x050000 
  298     QPointF point = 
event->localPos();
 
  300     QPointF point = 
event->posF();
 
  308         tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
 
  332         tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
 
  337           geometry_msgs::Pose pose;
 
  338           pose.position.x = position.x();
 
  339           pose.position.y = position.y();
 
  354 #if QT_VERSION >= 0x050000 
  355       QPointF point = 
event->localPos();
 
  357       QPointF point = 
event->posF();
 
  363         tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
 
  388           const QColor color = 
ui_.color->color();
 
  389           glColor4d(color.redF(), color.greenF(), color.blueF(), 1.0);
 
  390           glBegin(GL_LINE_STRIP);
 
  392           for (
size_t i = 0; i < route.
points.size(); i++)
 
  394             glVertex2d(route.
points[i].position().x(), route.
points[i].position().y());
 
  406       glColor4f(0.0, 1.0, 1.0, 1.0);
 
  409       for (
size_t i = 0; i < 
waypoints_.size(); i++)
 
  413         glVertex2d(point.x(), point.y());
 
  426     painter->resetTransform();
 
  428     QPen pen(QBrush(QColor(Qt::darkCyan).darker()), 1);
 
  429     painter->setPen(pen);
 
  430     painter->setFont(QFont(
"DejaVu Sans Mono", 7));
 
  435       for (
size_t i = 0; i < 
waypoints_.size(); i++)
 
  440         QPointF corner(gl_point.x() - 20, gl_point.y() - 20);
 
  441         QRectF rect(corner, QSizeF(40, 40));
 
  442         painter->drawText(rect, Qt::AlignHCenter | Qt::AlignVCenter, QString::fromStdString(boost::lexical_cast<std::string>(i + 1)));
 
  451     if (node[
"route_topic"])
 
  453       std::string route_topic;
 
  454       node[
"route_topic"] >> route_topic;
 
  455       ui_.topic->setText(route_topic.c_str());
 
  460       node[
"color"] >> color;
 
  461       ui_.color->setColor(QColor(color.c_str()));
 
  466       node[
"service"] >> service;
 
  467       ui_.service->setText(service.c_str());
 
  469     if (node[
"start_from_vehicle"])
 
  471       bool start_from_vehicle;
 
  472       node[
"start_from_vehicle"] >> start_from_vehicle;
 
  473       ui_.start_from_vehicle->setChecked(start_from_vehicle);
 
  481     std::string route_topic = 
ui_.topic->text().toStdString();
 
  482     emitter << YAML::Key << 
"route_topic" << YAML::Value << route_topic;
 
  484     std::string color = 
ui_.color->color().name().toStdString();
 
  485     emitter << YAML::Key << 
"color" << YAML::Value << color;
 
  487     std::string service = 
ui_.service->text().toStdString();
 
  488     emitter << YAML::Key << 
"service" << YAML::Value << service;
 
  490     bool start_from_vehicle = 
ui_.start_from_vehicle->isChecked();
 
  491     emitter << YAML::Key << 
"start_from_vehicle" << YAML::Value << start_from_vehicle;