41     config_widget_(new QWidget()),
 
   43     is_mouse_down_(false),
 
   44     monitoring_action_state_(false)
 
   50     p.setColor(QPalette::Background, Qt::white);
 
   54     ui_.status->setText(
"OK");
 
   55     QPalette p3(
ui_.status->palette());
 
   56     p3.setColor(QPalette::Text, Qt::green);
 
   57     ui_.status->setPalette(p3);
 
   59     QObject::connect(
ui_.pushButtonPose, SIGNAL(toggled(
bool)),
 
   62     QObject::connect(
ui_.topic, SIGNAL(textEdited(
const QString&)),
 
  111     switch (event->type())
 
  113     case QEvent::MouseButtonPress:
 
  115     case QEvent::MouseButtonRelease:
 
  117     case QEvent::MouseMove:
 
  126   ui_.pushButtonPose->setEnabled( 
true );
 
  132     bool pose_checked = 
ui_.pushButtonPose->isChecked();
 
  139     if (event->button() == Qt::LeftButton)
 
  143 #if QT_VERSION >= 0x050000 
  157 #if QT_VERSION >= 0x050000 
  177     bool pose_checked = 
ui_.pushButtonPose->isChecked();
 
  188       geometry_msgs::PoseWithCovarianceStamped pose;
 
  195       pose.pose.pose.position.z = 0.0;
 
  200       std::string output_frame = 
ui_.outputframe->currentText().toStdString();
 
  203         pose.header.frame_id = output_frame;
 
  204         tf::Vector3 pose_oframe = 
transform * tf::Vector3(pose.pose.pose.position.x,
 
  205                                                           pose.pose.pose.position.y, 0);
 
  206         pose.pose.pose.position.x = pose_oframe.x();
 
  207         pose.pose.pose.position.y = pose_oframe.y();
 
  213         std::stringstream ss;
 
  215            << 
" to frame " << output_frame;
 
  221         std::stringstream ss;
 
  222         ss << 
"Attempting to publish to " <<  
ui_.topic->text().toStdString().c_str()
 
  223            << 
" but it's not set up...";
 
  227       std::stringstream ss;
 
  228       ss << 
"Pose published to topic: " <<  
ui_.topic->text().toStdString().c_str()
 
  229          << 
" in frame " << pose.header.frame_id;
 
  232       ui_.pushButtonPose->setChecked(
false);
 
  240     std::array<QPointF, 7> arrow_points;
 
  241     arrow_points[0] = QPointF(10, 0);
 
  242     arrow_points[1] = QPointF(6, -2.5);
 
  243     arrow_points[2] = QPointF(6.5, -1);
 
  244     arrow_points[3] = QPointF(0, -1);
 
  245     arrow_points[4] = QPointF(0, 1);
 
  246     arrow_points[5] = QPointF(6.5, 1);
 
  247     arrow_points[6] = QPointF(6, 2.5);
 
  251         QPointF transformed_points[7];
 
  252         for (
size_t i=0; i<7; i++ )
 
  254             tf::Vector3 point(arrow_points[i].x(), arrow_points[i].y(), 0);
 
  260         glColor3f(0.1, 0.9, 0.1);
 
  262         glBegin(GL_TRIANGLE_FAN);
 
  263         for (
const QPointF& point: transformed_points )
 
  265             glVertex2d(point.x(), point.y());
 
  269         glColor3f(0.0, 0.6, 0.0);
 
  270         glBegin(GL_LINE_LOOP);
 
  271         for (
const QPointF& point: transformed_points )
 
  273             glVertex2d(point.x(), point.y());
 
  285       node[
"topic"] >> tmp;
 
  286       ui_.topic->setText(QString(tmp.c_str()));
 
  292       node[
"output_frame"] >> tmp;
 
  293       ui_.outputframe->addItem(QString(tmp.c_str()));
 
  300     emitter << YAML::Key << 
"topic" << YAML::Value << 
ui_.topic->text().toStdString();
 
  301     emitter << YAML::Key << 
"output_frame" << YAML::Value << 
ui_.outputframe->currentText().toStdString();
 
  308       QPixmap cursor_pixmap = QPixmap(
":/images/green-arrow.png");
 
  309       QApplication::setOverrideCursor(QCursor(cursor_pixmap));
 
  313       QApplication::restoreOverrideCursor();
 
  321     std::stringstream ss;
 
  322     ss << 
"Publishing points to topic: " << topic.toStdString().c_str();
 
  325     if (!topic.isEmpty())
 
  333     std::vector<std::string> frames;
 
  334     tf_->getFrameStrings(frames);
 
  336     bool supports_wgs84 = 
tf_manager_->SupportsTransform(
 
  345     if (
ui_.outputframe->count() >= 0 &&
 
  346         static_cast<size_t>(
ui_.outputframe->count()) == frames.size())
 
  348       bool changed = 
false;
 
  349       for (
size_t i = 0; i < frames.size(); i++)
 
  351         if (frames[i] != 
ui_.outputframe->itemText(
static_cast<int>(i)).toStdString())
 
  361     std::string output_frame = 
ui_.outputframe->currentText().toStdString();
 
  363     ui_.outputframe->clear();
 
  364     for (
size_t i = 0; i < frames.size(); i++)
 
  366       ui_.outputframe->addItem(frames[i].c_str());
 
  369     if (output_frame != 
"")
 
  372       int index = 
ui_.outputframe->findText(output_frame.c_str());
 
  375         ui_.outputframe->addItem(output_frame.c_str());
 
  379       index = 
ui_.outputframe->findText(output_frame.c_str());
 
  380       ui_.outputframe->setCurrentIndex(index);
 
  386       int index = 
ui_.outputframe->findText(QString(
"map"));
 
  387       ui_.outputframe->setCurrentIndex(index);