42 #include <opencv2/core/core.hpp> 
   53 #include <marti_nav_msgs/Plan.h> 
   69     ui_.color->setColor(Qt::green);
 
   72     p.setColor(QPalette::Background, Qt::white);
 
   75     QPalette p3(
ui_.status->palette());
 
   76     p3.setColor(QPalette::Text, Qt::red);
 
   77     ui_.status->setPalette(p3);
 
   78     QObject::connect(
ui_.selecttopic, SIGNAL(clicked()), 
this,
 
   80     QObject::connect(
ui_.topic, SIGNAL(editingFinished()), 
this,
 
   82     QObject::connect(
ui_.selectpositiontopic, SIGNAL(clicked()), 
this,
 
   84     QObject::connect(
ui_.positiontopic, SIGNAL(editingFinished()), 
this,
 
   86     QObject::connect(
ui_.drawstyle, SIGNAL(activated(QString)), 
this,
 
   88     QObject::connect(
ui_.color, SIGNAL(colorEdited(
const QColor&)), 
this,
 
  100       QPixmap icon(16, 16);
 
  101       icon.fill(Qt::transparent);
 
  103       QPainter painter(&icon);
 
  104       painter.setRenderHint(QPainter::Antialiasing, 
true);
 
  106       QPen pen(
ui_.color->color());
 
  111         pen.setCapStyle(Qt::RoundCap);
 
  113         painter.drawPoint(8, 8);
 
  118         pen.setCapStyle(Qt::FlatCap);
 
  120         painter.drawLine(1, 14, 14, 1);
 
  129     if (style == 
"lines")
 
  133     else if (style == 
"points")
 
  137     else if (style == 
"points and lines")
 
  149     if (topic.
name.empty())
 
  154     ui_.topic->setText(QString::fromStdString(topic.
name));
 
  163     if (topic.
name.empty())
 
  168     ui_.positiontopic->setText(QString::fromStdString(topic.
name));
 
  174     std::string topic = 
ui_.topic->text().trimmed().toStdString();
 
  194     std::string topic = 
ui_.positiontopic->text().trimmed().toStdString();
 
  212       const marti_nav_msgs::PlanTrackConstPtr& msg)
 
  263     if (route.header.frame_id.empty())
 
  265       route.header.frame_id = 
"/wgs84";
 
  276     sru::projectToXY(route);
 
  277     sru::fillOrientations(route);
 
  284       marti_nav_msgs::PlanPoint point;
 
  292         PrintError(
"Failed to find plan position in plan.");
 
  306     const double S = a * 2.414213562373095;
 
  310     glColor3f(1.0, 0.0, 0.0);
 
  312     glVertex2d(x + S / 2.0, y - a / 2.0);
 
  313     glVertex2d(x + S / 2.0, y + a / 2.0);
 
  314     glVertex2d(x + a / 2.0, y + S / 2.0);
 
  315     glVertex2d(x - a / 2.0, y + S / 2.0);
 
  316     glVertex2d(x - S / 2.0, y + a / 2.0);
 
  317     glVertex2d(x - S / 2.0, y - a / 2.0);
 
  318     glVertex2d(x - a / 2.0, y - S / 2.0);
 
  319     glVertex2d(x + a / 2.0, y - S / 2.0);
 
  326     const QColor color = 
ui_.color->color();
 
  327     glColor4d(color.redF(), color.greenF(), color.blueF(), 1.0);
 
  332       glBegin(GL_LINE_STRIP);
 
  333       for (
size_t i = 0; i < route.points.size(); i++)
 
  335         glVertex2d(route.points[i].x,
 
  345       for (
size_t i = 0; i < route.points.size(); i++)
 
  347         glVertex2d(route.points[i].x,
 
  356     const double arrow_size = 
ui_.iconsize->value();
 
  358     tf::Vector3 v1(arrow_size, 0.0, 0.0);
 
  359     tf::Vector3 v2(0.0, arrow_size / 2.0, 0.0);
 
  360     tf::Vector3 v3(0.0, -arrow_size / 2.0, 0.0);
 
  363     tf::Vector3 p(point.x, point.y, point.z);
 
  370     const QColor color = 
ui_.positioncolor->color();
 
  373     glColor4d(color.redF(), color.greenF(), color.blueF(), 1.0);
 
  374     glVertex2d(v1.x(), v1.y());
 
  375     glVertex2d(v2.x(), v2.y());
 
  376     glVertex2d(v3.x(), v3.y());
 
  384       std::string route_topic;
 
  385       node[
"topic"] >> route_topic;
 
  386       ui_.topic->setText(route_topic.c_str());
 
  391       node[
"color"] >> color;
 
  392       ui_.color->setColor(QColor(color.c_str()));
 
  394     if (node[
"postopic"])
 
  396       std::string pos_topic;
 
  397       node[
"postopic"] >> pos_topic;
 
  398       ui_.positiontopic->setText(pos_topic.c_str());
 
  400     if (node[
"poscolor"])
 
  402       std::string poscolor;
 
  403       node[
"poscolor"] >> poscolor;
 
  404       ui_.positioncolor->setColor(QColor(poscolor.c_str()));
 
  407     if (node[
"draw_style"])
 
  409       std::string draw_style;
 
  410       node[
"draw_style"] >> draw_style;
 
  412       if (draw_style == 
"lines")
 
  415         ui_.drawstyle->setCurrentIndex(0);
 
  417       else if (draw_style == 
"points")
 
  420         ui_.drawstyle->setCurrentIndex(1);
 
  422       else if (draw_style == 
"points and lines")
 
  425         ui_.drawstyle->setCurrentIndex(2);
 
  435     std::string route_topic = 
ui_.topic->text().toStdString();
 
  436     emitter << YAML::Key << 
"topic" << YAML::Value << route_topic;
 
  438     std::string color = 
ui_.color->color().name().toStdString();
 
  439     emitter << YAML::Key << 
"color" << YAML::Value << color;
 
  441     std::string pos_topic = 
ui_.positiontopic->text().toStdString();
 
  442     emitter << YAML::Key << 
"postopic" << YAML::Value << pos_topic;
 
  444     std::string pos_color = 
ui_.positioncolor->color().name().toStdString();
 
  445     emitter << YAML::Key << 
"poscolor" << YAML::Value << pos_color;
 
  447     std::string draw_style = 
ui_.drawstyle->currentText().toStdString();
 
  448     emitter << YAML::Key << 
"draw_style" << YAML::Value << draw_style;