draw_polygon_plugin.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2016, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
31 
32 // C++ standard libraries
33 #include <cstdio>
34 #include <vector>
35 
36 // QT libraries
37 #include <QDateTime>
38 #include <QDialog>
39 #include <QGLWidget>
40 #include <QMouseEvent>
41 #include <QPainter>
42 #include <QPalette>
43 
44 #include <opencv2/core/core.hpp>
45 
46 #include <geometry_msgs/Point32.h>
47 #include <geometry_msgs/PolygonStamped.h>
48 #include <ros/master.h>
51 
52 // Declare plugin
55 
56 namespace stu = swri_transform_util;
57 
58 namespace mapviz_plugins
59 {
60  DrawPolygonPlugin::DrawPolygonPlugin() :
61  config_widget_(new QWidget()),
62  map_canvas_(NULL),
63  selected_point_(-1),
64  is_mouse_down_(false),
65  max_ms_(Q_INT64_C(500)),
66  max_distance_(2.0)
67  {
68  ui_.setupUi(config_widget_);
69 
70  ui_.color->setColor(Qt::green);
71  // Set background white
72  QPalette p(config_widget_->palette());
73  p.setColor(QPalette::Background, Qt::white);
74  config_widget_->setPalette(p);
75  // Set status text red
76  QPalette p3(ui_.status->palette());
77  p3.setColor(QPalette::Text, Qt::red);
78  ui_.status->setPalette(p3);
79 
80  QObject::connect(ui_.selectframe, SIGNAL(clicked()), this,
81  SLOT(SelectFrame()));
82  QObject::connect(ui_.frame, SIGNAL(editingFinished()), this,
83  SLOT(FrameEdited()));
84  QObject::connect(ui_.publish, SIGNAL(clicked()), this,
85  SLOT(PublishPolygon()));
86  QObject::connect(ui_.clear, SIGNAL(clicked()), this,
87  SLOT(Clear()));
88  }
89 
91  {
92  if (map_canvas_)
93  {
94  map_canvas_->removeEventFilter(this);
95  }
96  }
97 
99  {
100  std::string frame = mapviz::SelectFrameDialog::selectFrame(tf_);
101  if (!frame.empty())
102  {
103  ui_.frame->setText(QString::fromStdString(frame));
104  FrameEdited();
105  }
106  }
107 
109  {
110  source_frame_ = ui_.frame->text().toStdString();
111  PrintWarning("Waiting for transform.");
112 
113  ROS_INFO("Setting target frame to to %s", source_frame_.c_str());
114 
115  initialized_ = true;
116  }
117 
119  {
120  if (polygon_topic_ != ui_.topic->text().toStdString())
121  {
122  polygon_topic_ = ui_.topic->text().toStdString();
124  polygon_pub_ = node_.advertise<geometry_msgs::PolygonStamped>(polygon_topic_, 1, true);
125  }
126 
127  geometry_msgs::PolygonStamped polygon;
128  polygon.header.stamp = ros::Time::now();
129  polygon.header.frame_id = ui_.frame->text().toStdString();
130 
131  for (const auto& vertex: vertices_)
132  {
133  geometry_msgs::Point32 point;
134  point.x = vertex.x();
135  point.y = vertex.y();
136  point.z = 0;
137  polygon.polygon.points.push_back(point);
138  }
139 
140  polygon_pub_.publish(polygon);
141  }
142 
144  {
145  vertices_.clear();
146  transformed_vertices_.clear();
147  }
148 
149  void DrawPolygonPlugin::PrintError(const std::string& message)
150  {
151  PrintErrorHelper(ui_.status, message, 1.0);
152  }
153 
154  void DrawPolygonPlugin::PrintInfo(const std::string& message)
155  {
156  PrintInfoHelper(ui_.status, message, 1.0);
157  }
158 
159  void DrawPolygonPlugin::PrintWarning(const std::string& message)
160  {
161  PrintWarningHelper(ui_.status, message, 1.0);
162  }
163 
164  QWidget* DrawPolygonPlugin::GetConfigWidget(QWidget* parent)
165  {
166  config_widget_->setParent(parent);
167 
168  return config_widget_;
169  }
170 
171  bool DrawPolygonPlugin::Initialize(QGLWidget* canvas)
172  {
173  map_canvas_ = static_cast<mapviz::MapCanvas*>(canvas);
174  map_canvas_->installEventFilter(this);
175 
176  initialized_ = true;
177  return true;
178  }
179 
180  bool DrawPolygonPlugin::eventFilter(QObject *object, QEvent* event)
181  {
182  switch (event->type())
183  {
184  case QEvent::MouseButtonPress:
185  return handleMousePress(static_cast<QMouseEvent*>(event));
186  case QEvent::MouseButtonRelease:
187  return handleMouseRelease(static_cast<QMouseEvent*>(event));
188  case QEvent::MouseMove:
189  return handleMouseMove(static_cast<QMouseEvent*>(event));
190  default:
191  return false;
192  }
193  }
194 
195  bool DrawPolygonPlugin::handleMousePress(QMouseEvent* event)
196  {
197  selected_point_ = -1;
198  int closest_point = 0;
199  double closest_distance = std::numeric_limits<double>::max();
200 
201  QPointF point = event->localPos();
203  std::string frame = ui_.frame->text().toStdString();
204  if (tf_manager_.GetTransform(target_frame_, frame, transform))
205  {
206  for (size_t i = 0; i < vertices_.size(); i++)
207  {
208  tf::Vector3 vertex = vertices_[i];
209  vertex = transform * vertex;
210 
211  QPointF transformed = map_canvas_->FixedFrameToMapGlCoord(QPointF(vertex.x(), vertex.y()));
212 
213  double distance = QLineF(transformed, point).length();
214 
215  if (distance < closest_distance)
216  {
217  closest_distance = distance;
218  closest_point = static_cast<int>(i);
219  }
220  }
221  }
222 
223  if (event->button() == Qt::LeftButton)
224  {
225  if (closest_distance < 15)
226  {
227  selected_point_ = closest_point;
228  return true;
229  }
230  else
231  {
232  is_mouse_down_ = true;
233  mouse_down_pos_ = event->localPos();
234  mouse_down_time_ = QDateTime::currentMSecsSinceEpoch();
235  return false;
236  }
237  }
238  else if (event->button() == Qt::RightButton)
239  {
240  if (closest_distance < 15)
241  {
242  vertices_.erase(vertices_.begin() + closest_point);
243  transformed_vertices_.resize(vertices_.size());
244  return true;
245  }
246  }
247 
248  return false;
249  }
250 
251  bool DrawPolygonPlugin::handleMouseRelease(QMouseEvent* event)
252  {
253  std::string frame = ui_.frame->text().toStdString();
254  if (selected_point_ >= 0 && static_cast<size_t>(selected_point_) < vertices_.size())
255  {
256  QPointF point = event->localPos();
258  if (tf_manager_.GetTransform(frame, target_frame_, transform))
259  {
260  QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point);
261  tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
262  position = transform * position;
263  vertices_[selected_point_].setX(position.x());
264  vertices_[selected_point_].setY(position.y());
265  }
266 
267  selected_point_ = -1;
268  return true;
269  }
270  else if (is_mouse_down_)
271  {
272  qreal distance = QLineF(mouse_down_pos_, event->localPos()).length();
273  qint64 msecsDiff = QDateTime::currentMSecsSinceEpoch() - mouse_down_time_;
274 
275  // Only fire the event if the mouse has moved less than the maximum distance
276  // and was held for shorter than the maximum time.. This prevents click
277  // events from being fired if the user is dragging the mouse across the map
278  // or just holding the cursor in place.
279  if (msecsDiff < max_ms_ && distance <= max_distance_)
280  {
281  QPointF point = event->localPos();
282 
283 
284  QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point);
285  ROS_INFO("mouse point at %f, %f -> %f, %f", point.x(), point.y(), transformed.x(), transformed.y());
286 
288  tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
289 
290  if (tf_manager_.GetTransform(frame, target_frame_, transform))
291  {
292  position = transform * position;
293  vertices_.push_back(position);
294  transformed_vertices_.resize(vertices_.size());
295  ROS_INFO("Adding vertex at %lf, %lf %s", position.x(), position.y(), frame.c_str());
296  }
297  }
298  }
299  is_mouse_down_ = false;
300 
301  return false;
302  }
303 
304  bool DrawPolygonPlugin::handleMouseMove(QMouseEvent* event)
305  {
306  if (selected_point_ >= 0 && static_cast<size_t>(selected_point_) < vertices_.size())
307  {
308  QPointF point = event->localPos();
310  std::string frame = ui_.frame->text().toStdString();
311  if (tf_manager_.GetTransform(frame, target_frame_, transform))
312  {
313  QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point);
314  tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
315  position = transform * position;
316  vertices_[selected_point_].setY(position.y());
317  vertices_[selected_point_].setX(position.x());
318  }
319 
320  return true;
321  }
322  return false;
323  }
324 
325  void DrawPolygonPlugin::Draw(double x, double y, double scale)
326  {
328  std::string frame = ui_.frame->text().toStdString();
329  if (!tf_manager_.GetTransform(target_frame_, frame, transform))
330  {
331  return;
332  }
333 
334  // Transform polygon
335  for (size_t i = 0; i < vertices_.size(); i++)
336  {
337  transformed_vertices_[i] = transform * vertices_[i];
338  }
339 
340  glLineWidth(1);
341  const QColor color = ui_.color->color();
342  glColor4d(color.redF(), color.greenF(), color.blueF(), 1.0);
343  glBegin(GL_LINE_STRIP);
344 
345  for (const auto& vertex: transformed_vertices_)
346  {
347  glVertex2d(vertex.x(), vertex.y());
348  }
349 
350  glEnd();
351 
352  glBegin(GL_LINES);
353 
354  glColor4d(color.redF(), color.greenF(), color.blueF(), 0.25);
355 
356  if (transformed_vertices_.size() > 2)
357  {
358  glVertex2d(transformed_vertices_.front().x(), transformed_vertices_.front().y());
359  glVertex2d(transformed_vertices_.back().x(), transformed_vertices_.back().y());
360  }
361 
362  glEnd();
363 
364  // Draw vertices
365  glPointSize(9);
366  glBegin(GL_POINTS);
367 
368  for (const auto& vertex: transformed_vertices_)
369  {
370  glVertex2d(vertex.x(), vertex.y());
371  }
372  glEnd();
373 
374 
375 
376  PrintInfo("OK");
377  }
378 
379  void DrawPolygonPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
380  {
381  if (node["frame"])
382  {
383  node["frame"] >> source_frame_;
384  ui_.frame->setText(source_frame_.c_str());
385  }
386 
387  if (node["polygon_topic"])
388  {
389  std::string polygon_topic;
390  node["polygon_topic"] >> polygon_topic;
391  ui_.topic->setText(polygon_topic.c_str());
392  }
393  if (node["color"])
394  {
395  std::string color;
396  node["color"] >> color;
397  ui_.color->setColor(QColor(color.c_str()));
398  }
399  }
400 
401  void DrawPolygonPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
402  {
403  std::string frame = ui_.frame->text().toStdString();
404  emitter << YAML::Key << "frame" << YAML::Value << frame;
405 
406  std::string polygon_topic = ui_.topic->text().toStdString();
407  emitter << YAML::Key << "polygon_topic" << YAML::Value << polygon_topic;
408 
409  std::string color = ui_.color->color().name().toStdString();
410  emitter << YAML::Key << "color" << YAML::Value << color;
411  }
412 }
#define NULL
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
QPointF MapGlCoordToFixedFrame(const QPointF &point)
swri_transform_util::TransformManager tf_manager_
ros::NodeHandle node_
void publish(const boost::shared_ptr< M > &message) const
void transform(Route &route, const swri_transform_util::Transform &transform, const std::string &target_frame)
void PrintWarning(const std::string &message)
std::vector< tf::Vector3 > transformed_vertices_
void LoadConfig(const YAML::Node &node, const std::string &path)
static void PrintWarningHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
static void PrintErrorHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void PrintInfo(const std::string &message)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
std::string target_frame_
static std::string selectFrame(boost::shared_ptr< tf::TransformListener > tf_listener, QWidget *parent=0)
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
std::string source_frame_
void PrintError(const std::string &message)
QWidget * GetConfigWidget(QWidget *parent)
QPointF FixedFrameToMapGlCoord(const QPointF &point)
#define ROS_INFO(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::vector< tf::Vector3 > vertices_
bool GetTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, Transform &transform) const
static Time now()
boost::shared_ptr< tf::TransformListener > tf_
bool eventFilter(QObject *object, QEvent *event)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void Draw(double x, double y, double scale)


mapviz_plugins
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 19:25:16