37 #include <QColorDialog> 
   54   config_widget_(new QWidget()),
 
   59   ui_.forward_color->setColor(QColor(0, 0, 255));
 
   60   ui_.reverse_color->setColor(QColor(255, 0, 0));
 
   66   p.setColor(QPalette::Background, Qt::white);
 
   69   QPalette p3(
ui_.status->palette());
 
   70   p3.setColor(QPalette::Text, Qt::red);
 
   71   ui_.status->setPalette(p3);
 
   74   QObject::connect(
ui_.select_topic, SIGNAL(clicked()),
 
   76   QObject::connect(
ui_.topic, SIGNAL(editingFinished()),
 
   79   QObject::connect(
ui_.history_size, SIGNAL(valueChanged(
int)),
 
   95   items_.set_capacity(
ui_.history_size->value());
 
  100   QColor color = in_reverse ? 
ui_.reverse_color->color() : 
ui_.forward_color->color();
 
  101   glColor3f(color.redF(), color.greenF(), color.blueF());
 
  105 void drawArrow(
const double x, 
const double y, 
const double yaw, 
const double L)
 
  107   double tip_x = x + std::cos(yaw)*L;
 
  108   double tip_y = y + std::sin(yaw)*L;
 
  110   double right_wing_x = tip_x + std::cos(yaw - M_PI*3.0/4.0)*L*0.25;
 
  111   double right_wing_y = tip_y + std::sin(yaw - M_PI*3.0/4.0)*L*0.25;
 
  113   double left_wing_x = tip_x + std::cos(yaw + M_PI*3.0/4.0)*L*0.25;
 
  114   double left_wing_y = tip_y + std::sin(yaw + M_PI*3.0/4.0)*L*0.25;
 
  119   glVertex2f(tip_x,tip_y);
 
  121   glVertex2f(tip_x,tip_y);
 
  122   glVertex2f(right_wing_x, right_wing_y);
 
  124   glVertex2f(tip_x, tip_y);
 
  125   glVertex2f(left_wing_x, left_wing_y);
 
  132   std::map<std::string, swri_transform_util::Transform> transforms;
 
  135   for (
size_t i = 0; i < 
items_.size(); i++)
 
  137     const auto& item = 
items_[i];
 
  139     std::string src_frame = item.header.frame_id.length() ? item.header.frame_id : 
target_frame_;
 
  140     if (transforms.count(src_frame) == 0)
 
  157     marti_nav_msgs::Path path = 
items_[i]; 
 
  160     for (
auto& pt: path.points)
 
  163       tf::Vector3 pt3(pt.x, pt.y, 0.0);
 
  174     if (
ui_.draw_lines->isChecked())
 
  176       glLineWidth(
ui_.line_width->value());
 
  180       glBegin(GL_LINE_STRIP);
 
  181       for (
auto const &point : path.points)
 
  183         glVertex2f(point.x, point.y);
 
  187     if (
ui_.draw_points->isChecked())
 
  189       glPointSize(2*
ui_.line_width->value() + 1);
 
  194       for (
auto const &point : path.points)
 
  196         glVertex2f(point.x, point.y);
 
  200     if (
ui_.draw_yaw->isChecked())
 
  202       glLineWidth(
ui_.line_width->value());
 
  205       for (
auto const &point : path.points)
 
  207         drawArrow(point.x, point.y, point.yaw, 
ui_.arrow_length->value());
 
  218   const YAML::Node& node,
 
  222   node[
"topic"] >> topic;
 
  223   ui_.topic->setText(topic.c_str());
 
  229     node[
"draw_lines"] >> val;
 
  230     ui_.draw_lines->setChecked(val);
 
  236     node[
"draw_points"] >> val;
 
  237     ui_.draw_points->setChecked(val);
 
  243     node[
"draw_yaw"] >> val;
 
  244     ui_.draw_yaw->setChecked(val);
 
  250     node[
"line_width"] >> val;
 
  251     ui_.line_width->setValue(val);
 
  257     node[
"arrow_length"] >> val;
 
  258     ui_.arrow_length->setValue(val);
 
  264     node[
"history_size"] >> val;
 
  265     ui_.arrow_length->setValue(val);
 
  271     node[
"forward_color"] >> color;
 
  272     ui_.forward_color->setColor(QColor(color.c_str()));
 
  278     node[
"reverse_color"] >> color;
 
  279     ui_.reverse_color->setColor(QColor(color.c_str()));
 
  284   YAML::Emitter& emitter, 
const std::string& )
 
  286   emitter << YAML::Key << 
"topic" 
  287           << YAML::Value << 
ui_.topic->text().toStdString();
 
  289   emitter << YAML::Key << 
"draw_lines" 
  290           << YAML::Value << 
ui_.draw_lines->isChecked();
 
  291   emitter << YAML::Key << 
"draw_points" 
  292           << YAML::Value << 
ui_.draw_points->isChecked();
 
  293   emitter << YAML::Key << 
"draw_yaw" 
  294           << YAML::Value << 
ui_.draw_yaw->isChecked();
 
  296   emitter << YAML::Key << 
"line_width" 
  297           << YAML::Value << 
ui_.line_width->value();
 
  298   emitter << YAML::Key << 
"arrow_length" 
  299           << YAML::Value << 
ui_.arrow_length->value();
 
  300   emitter << YAML::Key << 
"history_size" 
  301           << YAML::Value << 
ui_.history_size->value();
 
  303   emitter << YAML::Key << 
"forward_color" 
  304           << YAML::Value << 
ui_.forward_color->color().name().toStdString();
 
  305   emitter << YAML::Key << 
"reverse_color" 
  306           << YAML::Value << 
ui_.reverse_color->color().name().toStdString();
 
  318   if (message == 
ui_.status->text().toStdString())
 
  324   QPalette p(
ui_.status->palette());
 
  325   p.setColor(QPalette::Text, Qt::green);
 
  326   ui_.status->setPalette(p);
 
  327   ui_.status->setText(message.c_str());
 
  332   if (message == 
ui_.status->text().toStdString())
 
  338   QPalette p(
ui_.status->palette());
 
  339   p.setColor(QPalette::Text, Qt::darkYellow);
 
  340   ui_.status->setPalette(p);
 
  341   ui_.status->setText(message.c_str());
 
  346   if (message == 
ui_.status->text().toStdString())
 
  352   QPalette p(
ui_.status->palette());
 
  353   p.setColor(QPalette::Text, Qt::red);
 
  354   ui_.status->setPalette(p);
 
  355   ui_.status->setText(message.c_str());
 
  360   std::vector<std::string> supported_types;
 
  361   supported_types.push_back(
"marti_nav_msgs/Path");
 
  362   supported_types.push_back(
"marti_nav_msgs/PathPoint");
 
  366   if (!topic.
name.empty())
 
  368     ui_.topic->setText(QString::fromStdString(topic.
name));
 
  375   if (
ui_.topic->text().toStdString() != 
topic_)
 
  379     topic_ = 
ui_.topic->text().toStdString();
 
  392 #define IS_INSTANCE(msg, type) (msg->getDataType() == ros::message_traits::datatype<type>()) 
  396     marti_nav_msgs::PathConstPtr msg_typed = 
msg->instantiate<marti_nav_msgs::Path>();
 
  401     marti_nav_msgs::PathPointConstPtr msg_typed = 
msg->instantiate<marti_nav_msgs::PathPoint>();
 
  416   const marti_nav_msgs::Path &path)
 
  422   const marti_nav_msgs::PathPoint &point)
 
  424   marti_nav_msgs::Path segment;
 
  425   segment.in_reverse = 
false;
 
  426   segment.points.push_back(point);