42 #include <opencv2/core/core.hpp> 
   52 #include <marti_nav_msgs/Route.h> 
   68     ui_.color->setColor(Qt::green);
 
   71     p.setColor(QPalette::Background, Qt::white);
 
   74     QPalette p3(
ui_.status->palette());
 
   75     p3.setColor(QPalette::Text, Qt::red);
 
   76     ui_.status->setPalette(p3);
 
   77     QObject::connect(
ui_.selecttopic, SIGNAL(clicked()), 
this,
 
   79     QObject::connect(
ui_.topic, SIGNAL(editingFinished()), 
this,
 
   81     QObject::connect(
ui_.selectpositiontopic, SIGNAL(clicked()), 
this,
 
   83     QObject::connect(
ui_.positiontopic, SIGNAL(editingFinished()), 
this,
 
   85     QObject::connect(
ui_.drawstyle, SIGNAL(activated(QString)), 
this,
 
   87     QObject::connect(
ui_.color, SIGNAL(colorEdited(
const QColor&)), 
this,
 
  100       icon.fill(Qt::transparent);
 
  102       QPainter painter(&icon);
 
  103       painter.setRenderHint(QPainter::Antialiasing, 
true);
 
  105       QPen pen(
ui_.color->color());
 
  110         pen.setCapStyle(Qt::RoundCap);
 
  112         painter.drawPoint(8, 8);
 
  117         pen.setCapStyle(Qt::FlatCap);
 
  119         painter.drawLine(1, 14, 14, 1);
 
  128     if (style == 
"lines")
 
  132     else if (style == 
"points")
 
  144     if (topic.
name.empty())
 
  149     ui_.topic->setText(QString::fromStdString(topic.
name));
 
  158     if (topic.
name.empty())
 
  163     ui_.positiontopic->setText(QString::fromStdString(topic.
name));
 
  169     std::string topic = 
ui_.topic->text().trimmed().toStdString();
 
  189     std::string topic = 
ui_.positiontopic->text().trimmed().toStdString();
 
  207       const marti_nav_msgs::RoutePositionConstPtr& msg)
 
  258     if (route.
header.frame_id.empty())
 
  260       route.
header.frame_id = 
"/wgs84";
 
  271     sru::projectToXY(route);
 
  272     sru::fillOrientations(route);
 
  286         PrintError(
"Failed to find route position in route.");
 
  300     const double S = a * 2.414213562373095;
 
  304     glColor3f(1.0, 0.0, 0.0);
 
  306     glVertex2d(x + S / 2.0, y - a / 2.0);
 
  307     glVertex2d(x + S / 2.0, y + a / 2.0);
 
  308     glVertex2d(x + a / 2.0, y + S / 2.0);
 
  309     glVertex2d(x - a / 2.0, y + S / 2.0);
 
  310     glVertex2d(x - S / 2.0, y + a / 2.0);
 
  311     glVertex2d(x - S / 2.0, y - a / 2.0);
 
  312     glVertex2d(x - a / 2.0, y - S / 2.0);
 
  313     glVertex2d(x + a / 2.0, y - S / 2.0);
 
  320     const QColor color = 
ui_.color->color();
 
  321     glColor4d(color.redF(), color.greenF(), color.blueF(), 1.0);
 
  326       glBegin(GL_LINE_STRIP);
 
  334     for (
size_t i = 0; i < route.
points.size(); i++)
 
  336       glVertex2d(route.
points[i].position().x(),
 
  337                  route.
points[i].position().y());
 
  344     const double arrow_size = 
ui_.iconsize->value();
 
  346     tf::Vector3 v1(arrow_size, 0.0, 0.0);
 
  347     tf::Vector3 v2(0.0, arrow_size / 2.0, 0.0);
 
  348     tf::Vector3 v3(0.0, -arrow_size / 2.0, 0.0);
 
  356     const QColor color = 
ui_.positioncolor->color();
 
  359     glColor4d(color.redF(), color.greenF(), color.blueF(), 1.0);
 
  360     glVertex2d(v1.x(), v1.y());
 
  361     glVertex2d(v2.x(), v2.y());
 
  362     glVertex2d(v3.x(), v3.y());
 
  370       std::string route_topic;
 
  371       node[
"topic"] >> route_topic;
 
  372       ui_.topic->setText(route_topic.c_str());
 
  377       node[
"color"] >> color;
 
  378       ui_.color->setColor(QColor(color.c_str()));
 
  380     if (node[
"postopic"])
 
  382       std::string pos_topic;
 
  383       node[
"postopic"] >> pos_topic;
 
  384       ui_.positiontopic->setText(pos_topic.c_str());
 
  386     if (node[
"poscolor"])
 
  388       std::string poscolor;
 
  389       node[
"poscolor"] >> poscolor;
 
  390       ui_.positioncolor->setColor(QColor(poscolor.c_str()));
 
  393     if (node[
"draw_style"])
 
  395       std::string draw_style;
 
  396       node[
"draw_style"] >> draw_style;
 
  398       if (draw_style == 
"lines")
 
  401         ui_.drawstyle->setCurrentIndex(0);
 
  403       else if (draw_style == 
"points")
 
  406         ui_.drawstyle->setCurrentIndex(1);
 
  416     std::string route_topic = 
ui_.topic->text().toStdString();
 
  417     emitter << YAML::Key << 
"topic" << YAML::Value << route_topic;
 
  419     std::string color = 
ui_.color->color().name().toStdString();
 
  420     emitter << YAML::Key << 
"color" << YAML::Value << color;
 
  422     std::string pos_topic = 
ui_.positiontopic->text().toStdString();
 
  423     emitter << YAML::Key << 
"postopic" << YAML::Value << pos_topic;
 
  425     std::string pos_color = 
ui_.positioncolor->color().name().toStdString();
 
  426     emitter << YAML::Key << 
"poscolor" << YAML::Value << pos_color;
 
  428     std::string draw_style = 
ui_.drawstyle->currentText().toStdString();
 
  429     emitter << YAML::Key << 
"draw_style" << YAML::Value << draw_style;