robot_image_plugin.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2014, 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 <algorithm>
35 #include <vector>
36 
37 // QT libraries
38 #include <QGLWidget>
39 #include <QPalette>
40 #include <QImage>
41 #include <QFileDialog>
42 
43 // ROS libraries
44 #include <ros/master.h>
45 
47 
48 // Declare plugin
51 
52 namespace mapviz_plugins
53 {
54  RobotImagePlugin::RobotImagePlugin() :
55  config_widget_(new QWidget()),
56  width_(1),
57  height_(1),
58  image_ratio_(1.0),
59  texture_loaded_(false),
60  transformed_(false)
61  {
62  ui_.setupUi(config_widget_);
63 
64  // Set background white
65  QPalette p(config_widget_->palette());
66  p.setColor(QPalette::Background, Qt::white);
67  config_widget_->setPalette(p);
68 
69  // Set status text red
70  QPalette p3(ui_.status->palette());
71  p3.setColor(QPalette::Text, Qt::red);
72  ui_.status->setPalette(p3);
73 
74  UpdateShape();
75 
76  QObject::connect(ui_.browse, SIGNAL(clicked()), this, SLOT(SelectFile()));
77  QObject::connect(ui_.selectframe, SIGNAL(clicked()), this, SLOT(SelectFrame()));
78  QObject::connect(ui_.frame, SIGNAL(editingFinished()), this, SLOT(FrameEdited()));
79  QObject::connect(ui_.width, SIGNAL(valueChanged(double)), this, SLOT(WidthChanged(double)));
80  QObject::connect(ui_.height, SIGNAL(valueChanged(double)), this, SLOT(HeightChanged(double)));
81  QObject::connect(ui_.ratio_equal, SIGNAL(toggled(bool)), this, SLOT(RatioEqualToggled(bool)));
82  QObject::connect(ui_.ratio_custom, SIGNAL(toggled(bool)), this, SLOT(RatioCustomToggled(bool)));
83  QObject::connect(ui_.ratio_original, SIGNAL(toggled(bool)), this, SLOT(RatioOriginalToggled(bool)));
84  }
85 
87  {
88  }
89 
91  {
92  QFileDialog dialog(config_widget_, "Select PNG Image");
93  dialog.setFileMode(QFileDialog::ExistingFile);
94  dialog.setNameFilter(tr("PNG Image Files (*.png)"));
95 
96  dialog.exec();
97 
98  if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
99  {
100  ui_.image->setText(dialog.selectedFiles().first());
101  filename_ = dialog.selectedFiles().first().toStdString();
102  LoadImage();
103  }
104  }
105 
107  {
108  std::string frame = mapviz::SelectFrameDialog::selectFrame(tf_);
109  if (!frame.empty())
110  {
111  ui_.frame->setText(QString::fromStdString(frame));
112  FrameEdited();
113  }
114  }
115 
117  {
118  source_frame_ = ui_.frame->text().toStdString();
119  PrintWarning("Waiting for transform.");
120 
121  ROS_INFO("Setting target frame to to %s", source_frame_.c_str());
122 
123  initialized_ = true;
124 
125  UpdateShape();
126  }
127 
129  {
130  width_ = value;
131  if( ui_.ratio_equal->isChecked()){
132  ui_.height->setValue( width_ );
133  }
134  else if( ui_.ratio_original->isChecked()){
135  ui_.height->setValue( width_ * image_ratio_ );
136  }
137  UpdateShape();
138  }
139 
141  {
142  height_ = value;
143  UpdateShape();
144  }
145 
147  {
148  if( toggled )
149  {
150  ui_.height->setValue(width_);
151  ui_.height->setEnabled(false);
152  UpdateShape();
153  }
154  }
155 
157  {
158  if( toggled )
159  {
160  ui_.height->setEnabled(true);
161  }
162  }
163 
165  {
166  if( toggled )
167  {
168  ui_.height->setValue(width_*image_ratio_);
169  ui_.height->setEnabled(false);
170  UpdateShape();
171  }
172  }
173 
175  {
176  top_left_ = tf::Point(-width_ / 2.0, height_ / 2.0, 0);
177  top_right_ = tf::Point(width_ / 2.0, height_ / 2.0, 0);
178  bottom_left_ = tf::Point(-width_ / 2.0, -height_/2.0, 0);
179  bottom_right_ = tf::Point(width_ / 2.0, -height_ / 2.0, 0);
180  }
181 
182  void RobotImagePlugin::PrintError(const std::string& message)
183  {
184  PrintErrorHelper(ui_.status, message);
185  }
186 
187  void RobotImagePlugin::PrintInfo(const std::string& message)
188  {
189  PrintInfoHelper(ui_.status, message);
190  }
191 
192  void RobotImagePlugin::PrintWarning(const std::string& message)
193  {
194  PrintWarningHelper(ui_.status, message);
195  }
196 
197  QWidget* RobotImagePlugin::GetConfigWidget(QWidget* parent)
198  {
199  config_widget_->setParent(parent);
200 
201  return config_widget_;
202  }
203 
204  bool RobotImagePlugin::Initialize(QGLWidget* canvas)
205  {
206  canvas_ = canvas;
207 
208  return true;
209  }
210 
211  void RobotImagePlugin::Draw(double x, double y, double scale)
212  {
214  {
215  glColor3f(1.0f, 1.0f, 1.0f);
216  glEnable(GL_TEXTURE_2D);
217  glBindTexture(GL_TEXTURE_2D, static_cast<GLuint>(texture_id_));
218 
219  glBegin(GL_QUADS);
220 
221  glTexCoord2f(0, 1); glVertex2d(top_left_transformed_.x(), top_left_transformed_.y());
222  glTexCoord2f(1, 1); glVertex2d(top_right_transformed_.x(), top_right_transformed_.y());
223  glTexCoord2f(1, 0); glVertex2d(bottom_right_transformed_.x(), bottom_right_transformed_.y());
224  glTexCoord2f(0, 0); glVertex2d(bottom_left_transformed_.x(), bottom_left_transformed_.y());
225 
226  glEnd();
227 
228  glDisable(GL_TEXTURE_2D);
229 
230  PrintInfo("OK");
231  }
232  }
233 
235  {
236  transformed_ = false;
237 
239  if (GetTransform(ros::Time(), transform))
240  {
241  top_left_transformed_ = transform * top_left_;
242  top_right_transformed_ = transform * top_right_;
245  transformed_ = true;
246  }
247  else
248  {
249  PrintError("No transform between " + source_frame_ + " and " + target_frame_);
250  }
251  }
252 
254  {
255  ROS_INFO("Loading image");
256  try
257  {
258  QImage nullImage;
259  image_ = nullImage;
260 
261  if (texture_loaded_)
262  {
263  GLuint ids[1];
264  ids[0] = static_cast<GLuint>(texture_id_);
265  glDeleteTextures(1, &ids[0]);
266  texture_loaded_ = false;
267  }
268 
269  if (image_.load(filename_.c_str()))
270  {
271  int width = image_.width();
272  int height = image_.height();
273  image_ratio_ = (double)height / (double)width;
274 
275  float max_dim = std::max(width, height);
276  dimension_ = static_cast<int>(std::pow(2, std::ceil(std::log(max_dim) / std::log(2.0f))));
277 
278  if (width != dimension_ || height != dimension_)
279  {
280  image_ = image_.scaled(dimension_, dimension_, Qt::IgnoreAspectRatio, Qt::FastTransformation);
281  }
282 
283  image_ = QGLWidget::convertToGLFormat(image_);
284 
285  GLuint ids[1];
286  glGenTextures(1, &ids[0]);
287  texture_id_ = ids[0];
288 
289  glBindTexture(GL_TEXTURE_2D, static_cast<GLuint>(texture_id_));
290  glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, dimension_, dimension_, 0, GL_RGBA, GL_UNSIGNED_BYTE, image_.bits());
291 
292  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);
293  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
294 
295  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
296  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
297 
298  texture_loaded_ = true;
299  if( ui_.ratio_original->isChecked() )
300  {
301  RatioOriginalToggled(true);
302  }
303  }
304  else
305  {
306  PrintError("Failed to load image.");
307  }
308  }
309  catch (const std::exception& e)
310  {
311  PrintError("Failed to load image. Exception occured.");
312  }
313  }
314 
315  void RobotImagePlugin::LoadConfig(const YAML::Node& node, const std::string& path)
316  {
317  if (node["frame"])
318  {
319  node["frame"] >> source_frame_;
320  ui_.frame->setText(source_frame_.c_str());
321  }
322 
323  if (node["image"])
324  {
325  node["image"] >> filename_;
326  ui_.image->setText(filename_.c_str());
327  }
328 
329  if (node["width"])
330  {
331  node["width"] >> width_;
332  ui_.width->setValue(width_);
333  }
334 
335  if (node["height"])
336  {
337  node["height"] >> height_;
338  ui_.height->setValue(height_);
339  }
340 
341  if (node["ratio"])
342  {
343  std::string value;
344  node["ratio"] >> value;
345  if(value == "equal")
346  {
347  ui_.ratio_equal->setChecked(true);
348  }
349  else if(value == "custom")
350  {
351  ui_.ratio_custom->setChecked(true);
352  }
353  else if(value == "original")
354  {
355  ui_.ratio_original->setChecked(true);
356  }
357  }
358 
359  UpdateShape();
360  LoadImage();
361  FrameEdited();
362  }
363 
364  void RobotImagePlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
365  {
366  emitter << YAML::Key << "frame" << YAML::Value << ui_.frame->text().toStdString();
367  emitter << YAML::Key << "image" << YAML::Value << ui_.image->text().toStdString();
368  emitter << YAML::Key << "width" << YAML::Value << width_;
369  emitter << YAML::Key << "height" << YAML::Value << height_;
370  if( ui_.ratio_custom->isChecked())
371  {
372  emitter << YAML::Key << "ratio" << YAML::Value << "custom";
373  }
374  else if( ui_.ratio_equal->isChecked())
375  {
376  emitter << YAML::Key << "ratio" << YAML::Value << "equal";
377  }
378  else if( ui_.ratio_original->isChecked())
379  {
380  emitter << YAML::Key << "ratio" << YAML::Value << "original";
381  }
382  }
383 }
384 
bool GetTransform(const ros::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms=true)
void PrintWarning(const std::string &message)
void transform(Route &route, const swri_transform_util::Transform &transform, const std::string &target_frame)
f
void PrintError(const std::string &message)
void SaveConfig(YAML::Emitter &emitter, 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)
QWidget * GetConfigWidget(QWidget *parent)
std::string target_frame_
void PrintInfo(const std::string &message)
static std::string selectFrame(boost::shared_ptr< tf::TransformListener > tf_listener, QWidget *parent=0)
tf::Vector3 Point
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void Draw(double x, double y, double scale)
std::string source_frame_
TFSIMD_FORCE_INLINE const tfScalar & x() const
#define ROS_INFO(...)
TFSIMD_FORCE_INLINE const tfScalar & y() const
boost::shared_ptr< tf::TransformListener > tf_
void LoadConfig(const YAML::Node &node, const std::string &path)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)


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