draw_polygon_plugin.cpp
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2016, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //
00028 // *****************************************************************************
00029 
00030 #include <mapviz_plugins/draw_polygon_plugin.h>
00031 
00032 // C++ standard libraries
00033 #include <cstdio>
00034 #include <vector>
00035 
00036 // QT libraries
00037 #include <QDateTime>
00038 #include <QDialog>
00039 #include <QGLWidget>
00040 #include <QMouseEvent>
00041 #include <QPainter>
00042 #include <QPalette>
00043 
00044 #include <opencv2/core/core.hpp>
00045 
00046 #include <geometry_msgs/Point32.h>
00047 #include <geometry_msgs/PolygonStamped.h>
00048 #include <ros/master.h>
00049 #include <mapviz/select_frame_dialog.h>
00050 #include <swri_transform_util/frames.h>
00051 
00052 // Declare plugin
00053 #include <pluginlib/class_list_macros.h>
00054 PLUGINLIB_EXPORT_CLASS(mapviz_plugins::DrawPolygonPlugin, mapviz::MapvizPlugin)
00055 
00056 namespace stu = swri_transform_util;
00057 
00058 namespace mapviz_plugins
00059 {
00060   DrawPolygonPlugin::DrawPolygonPlugin() :
00061     config_widget_(new QWidget()),
00062     map_canvas_(NULL),
00063     selected_point_(-1),
00064     is_mouse_down_(false),
00065     max_ms_(Q_INT64_C(500)),
00066     max_distance_(2.0)
00067   {
00068     ui_.setupUi(config_widget_);
00069 
00070     ui_.color->setColor(Qt::green);
00071     // Set background white
00072     QPalette p(config_widget_->palette());
00073     p.setColor(QPalette::Background, Qt::white);
00074     config_widget_->setPalette(p);
00075     // Set status text red
00076     QPalette p3(ui_.status->palette());
00077     p3.setColor(QPalette::Text, Qt::red);
00078     ui_.status->setPalette(p3);
00079 
00080     QObject::connect(ui_.selectframe, SIGNAL(clicked()), this,
00081                      SLOT(SelectFrame()));
00082     QObject::connect(ui_.frame, SIGNAL(editingFinished()), this,
00083                      SLOT(FrameEdited()));
00084     QObject::connect(ui_.publish, SIGNAL(clicked()), this,
00085                      SLOT(PublishPolygon()));
00086     QObject::connect(ui_.clear, SIGNAL(clicked()), this,
00087                      SLOT(Clear()));
00088   }
00089 
00090   DrawPolygonPlugin::~DrawPolygonPlugin()
00091   {
00092     if (map_canvas_)
00093     {
00094       map_canvas_->removeEventFilter(this);
00095     }
00096   }
00097 
00098   void DrawPolygonPlugin::SelectFrame()
00099   {
00100     std::string frame = mapviz::SelectFrameDialog::selectFrame(tf_);
00101     if (!frame.empty())
00102     {
00103       ui_.frame->setText(QString::fromStdString(frame));
00104       FrameEdited();
00105     }
00106   }
00107 
00108   void DrawPolygonPlugin::FrameEdited()
00109   {
00110     source_frame_ = ui_.frame->text().toStdString();
00111     PrintWarning("Waiting for transform.");
00112 
00113     ROS_INFO("Setting target frame to to %s", source_frame_.c_str());
00114 
00115     initialized_ = true;
00116   }
00117 
00118   void DrawPolygonPlugin::PublishPolygon()
00119   {
00120     if (polygon_topic_ != ui_.topic->text().toStdString())
00121     {
00122       polygon_topic_ = ui_.topic->text().toStdString();
00123       polygon_pub_.shutdown();
00124       polygon_pub_ = node_.advertise<geometry_msgs::PolygonStamped>(polygon_topic_, 1, true);
00125     }
00126 
00127     geometry_msgs::PolygonStamped polygon;
00128     polygon.header.stamp = ros::Time::now();
00129     polygon.header.frame_id = ui_.frame->text().toStdString();
00130 
00131     for (const auto& vertex: vertices_)
00132     {
00133       geometry_msgs::Point32 point;
00134       point.x = vertex.x();
00135       point.y = vertex.y();
00136       point.z = 0;
00137       polygon.polygon.points.push_back(point);
00138     }
00139 
00140     polygon_pub_.publish(polygon);
00141   }
00142 
00143   void DrawPolygonPlugin::Clear()
00144   {
00145     vertices_.clear();
00146     transformed_vertices_.clear();
00147   }
00148 
00149   void DrawPolygonPlugin::PrintError(const std::string& message)
00150   {
00151     PrintErrorHelper(ui_.status, message, 1.0);
00152   }
00153 
00154   void DrawPolygonPlugin::PrintInfo(const std::string& message)
00155   {
00156     PrintInfoHelper(ui_.status, message, 1.0);
00157   }
00158 
00159   void DrawPolygonPlugin::PrintWarning(const std::string& message)
00160   {
00161     PrintWarningHelper(ui_.status, message, 1.0);
00162   }
00163 
00164   QWidget* DrawPolygonPlugin::GetConfigWidget(QWidget* parent)
00165   {
00166     config_widget_->setParent(parent);
00167 
00168     return config_widget_;
00169   }
00170 
00171   bool DrawPolygonPlugin::Initialize(QGLWidget* canvas)
00172   {
00173     map_canvas_ = static_cast<mapviz::MapCanvas*>(canvas);
00174     map_canvas_->installEventFilter(this);
00175 
00176     initialized_ = true;
00177     return true;
00178   }
00179 
00180   bool DrawPolygonPlugin::eventFilter(QObject *object, QEvent* event)
00181   {
00182     switch (event->type())
00183     {
00184       case QEvent::MouseButtonPress:
00185         return handleMousePress(static_cast<QMouseEvent*>(event));
00186       case QEvent::MouseButtonRelease:
00187         return handleMouseRelease(static_cast<QMouseEvent*>(event));
00188       case QEvent::MouseMove:
00189         return handleMouseMove(static_cast<QMouseEvent*>(event));
00190       default:
00191         return false;
00192     }
00193   }
00194 
00195   bool DrawPolygonPlugin::handleMousePress(QMouseEvent* event)
00196   {
00197     selected_point_ = -1;
00198     int closest_point = 0;
00199     double closest_distance = std::numeric_limits<double>::max();
00200 
00201 #if QT_VERSION >= 0x050000
00202     QPointF point = event->localPos();
00203 #else
00204     QPointF point = event->posF();
00205 #endif
00206     stu::Transform transform;
00207     std::string frame = ui_.frame->text().toStdString();
00208     if (tf_manager_.GetTransform(target_frame_, frame, transform))
00209     {
00210       for (size_t i = 0; i < vertices_.size(); i++)
00211       {
00212         tf::Vector3 vertex = vertices_[i];
00213         vertex = transform * vertex;
00214 
00215         QPointF transformed = map_canvas_->FixedFrameToMapGlCoord(QPointF(vertex.x(), vertex.y()));
00216 
00217         double distance = QLineF(transformed, point).length();
00218 
00219         if (distance < closest_distance)
00220         {
00221           closest_distance = distance;
00222           closest_point = static_cast<int>(i);
00223         }
00224       }
00225     }
00226 
00227     if (event->button() == Qt::LeftButton)
00228     {
00229       if (closest_distance < 15)
00230       {
00231         selected_point_ = closest_point;
00232         return true;
00233       }
00234       else
00235       {
00236         is_mouse_down_ = true;
00237 #if QT_VERSION >= 0x050000
00238         mouse_down_pos_ = event->localPos();
00239 #else
00240         mouse_down_pos_ = event->posF();
00241 #endif
00242         mouse_down_time_ = QDateTime::currentMSecsSinceEpoch();
00243         return false;
00244       }
00245     }
00246     else if (event->button() == Qt::RightButton)
00247     {
00248       if (closest_distance < 15)
00249       {
00250         vertices_.erase(vertices_.begin() + closest_point);
00251         transformed_vertices_.resize(vertices_.size());
00252         return true;
00253       }
00254     }
00255 
00256     return false;
00257   }
00258 
00259   bool DrawPolygonPlugin::handleMouseRelease(QMouseEvent* event)
00260   {
00261     std::string frame = ui_.frame->text().toStdString();
00262     if (selected_point_ >= 0 && static_cast<size_t>(selected_point_) < vertices_.size())
00263     {
00264 #if QT_VERSION >= 0x050000
00265       QPointF point = event->localPos();
00266 #else
00267       QPointF point = event->posF();
00268 #endif
00269       stu::Transform transform;
00270       if (tf_manager_.GetTransform(frame, target_frame_, transform))
00271       {
00272         QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point);
00273         tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
00274         position = transform * position;
00275         vertices_[selected_point_].setX(position.x());
00276         vertices_[selected_point_].setY(position.y());
00277       }
00278 
00279       selected_point_ = -1;
00280       return true;
00281     }
00282     else if (is_mouse_down_)
00283     {
00284 #if QT_VERSION >= 0x050000
00285       qreal distance = QLineF(mouse_down_pos_, event->localPos()).length();
00286 #else
00287       qreal distance = QLineF(mouse_down_pos_, event->posF()).length();
00288 #endif
00289       qint64 msecsDiff = QDateTime::currentMSecsSinceEpoch() - mouse_down_time_;
00290 
00291       // Only fire the event if the mouse has moved less than the maximum distance
00292       // and was held for shorter than the maximum time..  This prevents click
00293       // events from being fired if the user is dragging the mouse across the map
00294       // or just holding the cursor in place.
00295       if (msecsDiff < max_ms_ && distance <= max_distance_)
00296       {
00297 #if QT_VERSION >= 0x050000
00298         QPointF point = event->localPos();
00299 #else
00300         QPointF point = event->posF();
00301 #endif
00302 
00303         QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point);
00304         ROS_INFO("mouse point at %f, %f -> %f, %f", point.x(), point.y(), transformed.x(), transformed.y());
00305 
00306         stu::Transform transform;
00307         tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
00308 
00309         if (tf_manager_.GetTransform(frame, target_frame_, transform))
00310         {
00311           position = transform * position;
00312           vertices_.push_back(position);
00313           transformed_vertices_.resize(vertices_.size());
00314           ROS_INFO("Adding vertex at %lf, %lf %s", position.x(), position.y(), frame.c_str());
00315         }
00316       }
00317     }
00318     is_mouse_down_ = false;
00319 
00320     return false;
00321   }
00322 
00323   bool DrawPolygonPlugin::handleMouseMove(QMouseEvent* event)
00324   {
00325     if (selected_point_ >= 0 && static_cast<size_t>(selected_point_) < vertices_.size())
00326     {
00327 #if QT_VERSION >= 0x050000
00328       QPointF point = event->localPos();
00329 #else
00330       QPointF point = event->posF();
00331 #endif
00332       stu::Transform transform;
00333       std::string frame = ui_.frame->text().toStdString();
00334       if (tf_manager_.GetTransform(frame, target_frame_, transform))
00335       {
00336         QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point);
00337         tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
00338         position = transform * position;
00339         vertices_[selected_point_].setY(position.y());
00340         vertices_[selected_point_].setX(position.x());
00341       }
00342 
00343       return true;
00344     }
00345     return false;
00346   }
00347 
00348   void DrawPolygonPlugin::Draw(double x, double y, double scale)
00349   {
00350     stu::Transform transform;
00351     std::string frame = ui_.frame->text().toStdString();
00352     if (!tf_manager_.GetTransform(target_frame_, frame, transform))
00353     {
00354       return;
00355     }
00356 
00357     // Transform polygon
00358     for (size_t i = 0; i < vertices_.size(); i++)
00359     {
00360       transformed_vertices_[i] = transform * vertices_[i];
00361     }
00362 
00363     glLineWidth(1);
00364     const QColor color = ui_.color->color();
00365     glColor4d(color.redF(), color.greenF(), color.blueF(), 1.0);
00366     glBegin(GL_LINE_STRIP);
00367 
00368     for (const auto& vertex: transformed_vertices_)
00369     {
00370       glVertex2d(vertex.x(), vertex.y());
00371     }
00372 
00373     glEnd();
00374 
00375     glBegin(GL_LINES);
00376 
00377     glColor4d(color.redF(), color.greenF(), color.blueF(), 0.25);
00378 
00379     if (transformed_vertices_.size() > 2)
00380     {
00381       glVertex2d(transformed_vertices_.front().x(), transformed_vertices_.front().y());
00382       glVertex2d(transformed_vertices_.back().x(), transformed_vertices_.back().y());
00383     }
00384 
00385     glEnd();
00386 
00387     // Draw vertices
00388     glPointSize(9);
00389     glBegin(GL_POINTS);
00390 
00391     for (const auto& vertex: transformed_vertices_)
00392     {
00393       glVertex2d(vertex.x(), vertex.y());
00394     }
00395     glEnd();
00396 
00397 
00398 
00399     PrintInfo("OK");
00400   }
00401 
00402   void DrawPolygonPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
00403   {
00404     if (node["frame"])
00405     {
00406       node["frame"] >> source_frame_;
00407       ui_.frame->setText(source_frame_.c_str());
00408     }
00409 
00410     if (node["polygon_topic"])
00411     {
00412       std::string polygon_topic;
00413       node["polygon_topic"] >> polygon_topic;
00414       ui_.topic->setText(polygon_topic.c_str());
00415     }
00416     if (node["color"])
00417     {
00418       std::string color;
00419       node["color"] >> color;
00420       ui_.color->setColor(QColor(color.c_str()));
00421     }
00422   }
00423 
00424   void DrawPolygonPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
00425   {
00426     std::string frame = ui_.frame->text().toStdString();
00427     emitter << YAML::Key << "frame" << YAML::Value << frame;
00428 
00429     std::string polygon_topic = ui_.topic->text().toStdString();
00430     emitter << YAML::Key << "polygon_topic" << YAML::Value << polygon_topic;
00431 
00432     std::string color = ui_.color->color().name().toStdString();
00433     emitter << YAML::Key << "color" << YAML::Value << color;
00434   }
00435 }


mapviz_plugins
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 18:51:07