textured_marker_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 <cmath>
34 #include <cstdio>
35 #include <vector>
36 
37 // Boost libraries
38 #include <boost/algorithm/string.hpp>
39 
40 // QT libraries
41 #include <QDialog>
42 #include <QGLWidget>
43 
44 // ROS libraries
45 #include <ros/master.h>
47 
49 
51 
52 // Declare plugin
55 
56 namespace mapviz_plugins
57 {
58  TexturedMarkerPlugin::TexturedMarkerPlugin() :
59  config_widget_(new QWidget()),
60  is_marker_array_(false),
61  alphaVal_(1.0f) // Initialize the alpha value to default
62  {
63  ui_.setupUi(config_widget_);
64 
65  // Set background white
66  QPalette p(config_widget_->palette());
67  p.setColor(QPalette::Background, Qt::white);
68  config_widget_->setPalette(p);
69 
70  // Set status text red
71  QPalette p3(ui_.status->palette());
72  p3.setColor(QPalette::Text, Qt::red);
73  ui_.status->setPalette(p3);
74 
75  QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic()));
76  QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited()));
77  QObject::connect(ui_.clear, SIGNAL(clicked()), this, SLOT(ClearHistory()));
78  QObject::connect(ui_.alphaSlide, SIGNAL(valueChanged(int)), this, SLOT(SetAlphaLevel(int)));
79 
80  // By using a signal/slot connection, we ensure that we only generate GL textures on the
81  // main thread in case a non-main thread handles the ROS callbacks.
82  qRegisterMetaType<marti_visualization_msgs::TexturedMarkerConstPtr>("TexturedMarkerConstPtr");
83  qRegisterMetaType<marti_visualization_msgs::TexturedMarkerArrayConstPtr>("TexturedMarkerArrayConstPtr");
84 
85  QObject::connect(this,
86  SIGNAL(MarkerReceived(const marti_visualization_msgs::TexturedMarkerConstPtr)),
87  this,
88  SLOT(ProcessMarker(const marti_visualization_msgs::TexturedMarkerConstPtr)));
89  QObject::connect(this,
90  SIGNAL(MarkersReceived(const marti_visualization_msgs::TexturedMarkerArrayConstPtr)),
91  this,
92  SLOT(ProcessMarkers(const marti_visualization_msgs::TexturedMarkerArrayConstPtr)));
93  }
94 
96  {
97  }
98 
100  {
101  ROS_DEBUG("TexturedMarkerPlugin::ClearHistory()");
102  markers_.clear();
103  }
104 
105  // TODO could instead use the value() function on alphaSlide when needed, assuming value is always good
106  // Modify min and max values by adjusting textured_marker_config.ui
108  {
109  int max = ui_.alphaSlide->maximum();
110  int min = ui_.alphaSlide->minimum();
111 
112  if(max < 1
113  || min < 0
114  || alpha > max
115  || alpha < min) // ignore negative min and max
116  {
117  alphaVal_ = 1.0f;
118  PrintWarning("Invalid alpha input.");
119  }
120  else
121  {
122  alphaVal_ = (static_cast<float>(alpha) / max); // Ex. convert int in range 0-100 to float in range 0-1
123  ROS_INFO("Adjusting alpha value to: %f", alphaVal_);
124  }
125  }
126 
128  {
130  "marti_visualization_msgs/TexturedMarker",
131  "marti_visualization_msgs/TexturedMarkerArray");
132 
133  if (!topic.name.empty())
134  {
135  ui_.topic->setText(QString::fromStdString(topic.name));
136 
137  if (topic.datatype == "marti_visualization_msgs/TexturedMarkerArray")
138  {
139  is_marker_array_ = true;
140  }
141 
142  TopicEdited();
143  }
144  }
145 
147  {
148  std::string topic = ui_.topic->text().trimmed().toStdString();
149  if (topic != topic_)
150  {
151  initialized_ = false;
152  markers_.clear();
153  has_message_ = false;
154  PrintWarning("No messages received.");
155 
157 
158  topic_ = topic;
159  if (!topic.empty())
160  {
161  if (is_marker_array_)
162  {
164  }
165  else
166  {
168  }
169 
170  ROS_INFO("Subscribing to %s", topic_.c_str());
171  }
172  }
173  }
174 
175  void TexturedMarkerPlugin::ProcessMarker(const marti_visualization_msgs::TexturedMarkerConstPtr marker)
176  {
177  ProcessMarker(*marker);
178  }
179 
180  void TexturedMarkerPlugin::ProcessMarker(const marti_visualization_msgs::TexturedMarker& marker)
181  {
182  if (!has_message_)
183  {
184  initialized_ = true;
185  has_message_ = true;
186  }
187 
188  // Note that unlike some plugins, this one does not store nor rely on the
189  // source_frame_ member variable. This one can potentially store many
190  // messages with different source frames, so we need to store and transform
191  // them individually.
192 
193  if (marker.action == marti_visualization_msgs::TexturedMarker::ADD)
194  {
195  MarkerData& markerData = markers_[marker.ns][marker.id];
196  markerData.stamp = marker.header.stamp;
197 
198  markerData.transformed = true;
199  markerData.alpha_ = marker.alpha;
200  markerData.source_frame_ = marker.header.frame_id;
201 
203  if (!GetTransform(markerData.source_frame_, marker.header.stamp, transform))
204  {
205  markerData.transformed = false;
206  PrintError("No transform between " + markerData.source_frame_ + " and " + target_frame_);
207  }
208 
209  // Handle lifetime parameter
210  ros::Duration lifetime = marker.lifetime;
211  if (lifetime.isZero())
212  {
213  markerData.expire_time = ros::TIME_MAX;
214  }
215  else
216  {
217  // Temporarily add 5 seconds to fix some existing markers.
218  markerData.expire_time = ros::Time::now() + lifetime + ros::Duration(5);
219  }
220 
221  tf::Transform offset(
223  marker.pose.orientation.x,
224  marker.pose.orientation.y,
225  marker.pose.orientation.z,
226  marker.pose.orientation.w),
227  tf::Vector3(
228  marker.pose.position.x,
229  marker.pose.position.y,
230  marker.pose.position.z));
231 
232  double right = marker.image.width * marker.resolution / 2.0;
233  double left = -right;
234  double top = marker.image.height * marker.resolution / 2.0;
235  double bottom = -top;
236 
237  tf::Vector3 top_left(left, top, 0);
238  tf::Vector3 top_right(right, top, 0);
239  tf::Vector3 bottom_left(left, bottom, 0);
240  tf::Vector3 bottom_right(right, bottom, 0);
241 
242  top_left = offset * top_left;
243  top_right = offset * top_right;
244  bottom_left = offset * bottom_left;
245  bottom_right = offset * bottom_right;
246 
247  markerData.quad_.clear();
248  markerData.quad_.push_back(top_left);
249  markerData.quad_.push_back(top_right);
250  markerData.quad_.push_back(bottom_right);
251 
252  markerData.quad_.push_back(top_left);
253  markerData.quad_.push_back(bottom_right);
254  markerData.quad_.push_back(bottom_left);
255 
256  markerData.transformed_quad_.clear();
257  for (size_t i = 0; i < markerData.quad_.size(); i++)
258  {
259  markerData.transformed_quad_.push_back(transform * markerData.quad_[i]);
260  }
261 
262  int32_t max_dimension = std::max(marker.image.height, marker.image.width);
263  int32_t new_size = 1;
264  while (new_size < max_dimension)
265  new_size = new_size << 1;
266 
267  if (new_size != markerData.texture_size_ || markerData.encoding_ != marker.image.encoding)
268  {
269  markerData.texture_size_ = new_size;
270 
271  markerData.encoding_ = marker.image.encoding;
272 
273  GLuint ids[1];
274 
275  // Free the current texture.
276  if (markerData.texture_id_ != -1)
277  {
278  ids[0] = static_cast<GLuint>(markerData.texture_id_);
279  glDeleteTextures(1, &ids[0]);
280  }
281 
282  // Get a new texture id.
283  glGenTextures(1, &ids[0]);
284  markerData.texture_id_ = ids[0];
285 
286  // Bind the texture with the correct size and null memory.
287  glBindTexture(GL_TEXTURE_2D, static_cast<GLuint>(markerData.texture_id_));
288 
289  glPixelStorei(GL_UNPACK_ALIGNMENT, 1);
290 
291  size_t bpp = 0;
293  {
294  bpp = 4;
295  markerData.texture_.resize(static_cast<size_t>(markerData.texture_size_ * markerData.texture_size_ * 4));
296  }
297  else if (markerData.encoding_ == sensor_msgs::image_encodings::BGR8)
298  {
299  bpp = 3;
300  markerData.texture_.resize(static_cast<size_t>(markerData.texture_size_ * markerData.texture_size_ * 3));
301  }
302  else if (markerData.encoding_ == sensor_msgs::image_encodings::MONO8)
303  {
304  bpp = 1;
305  markerData.texture_.resize(static_cast<size_t>(markerData.texture_size_ * markerData.texture_size_));
306  }
307  else
308  {
309  ROS_WARN("Unsupported encoding: %s", markerData.encoding_.c_str());
310  }
311 
312  size_t expected = marker.image.height*marker.image.width*bpp;
313  if (markerData.texture_.size() > 0 && marker.image.data.size() < expected)
314  {
315  ROS_ERROR("TexturedMarker image had expected data size %zu but only got %zu. Dropping message.", expected, marker.image.data.size());
316  return;
317  }
318 
319  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
320  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
321 
322  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
323  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
324 
325  glTexEnvf( GL_TEXTURE_ENV, GL_TEXTURE_ENV_MODE, GL_MODULATE );
326 
327  glBindTexture(GL_TEXTURE_2D, 0);
328 
329  glPixelStorei(GL_UNPACK_ALIGNMENT, 4);
330  }
331 
332  glBindTexture(GL_TEXTURE_2D, static_cast<GLuint>(markerData.texture_id_));
333 
335  {
336  for (size_t row = 0; row < marker.image.height; row++)
337  {
338  for (size_t col = 0; col < marker.image.width; col++)
339  {
340  size_t src_index = (row * marker.image.width + col) * 4;
341  size_t dst_index = (row * markerData.texture_size_ + col) * 4;
342 
343  markerData.texture_[dst_index + 0] = marker.image.data[src_index + 0];
344  markerData.texture_[dst_index + 1] = marker.image.data[src_index + 1];
345  markerData.texture_[dst_index + 2] = marker.image.data[src_index + 2];
346  markerData.texture_[dst_index + 3] = marker.image.data[src_index + 3];
347  }
348  }
349 
350  glTexImage2D(
351  GL_TEXTURE_2D,
352  0,
353  GL_RGBA,
354  markerData.texture_size_,
355  markerData.texture_size_,
356  0,
357  GL_BGRA,
358  GL_UNSIGNED_BYTE,
359  markerData.texture_.data());
360  }
361  else if (markerData.encoding_ == sensor_msgs::image_encodings::BGR8)
362  {
363  for (size_t row = 0; row < marker.image.height; row++)
364  {
365  for (size_t col = 0; col < marker.image.width; col++)
366  {
367  size_t src_index = (row * marker.image.width + col) * 3;
368  size_t dst_index = (row * markerData.texture_size_ + col) * 3;
369 
370  markerData.texture_[dst_index + 0] = marker.image.data[src_index + 0];
371  markerData.texture_[dst_index + 1] = marker.image.data[src_index + 1];
372  markerData.texture_[dst_index + 2] = marker.image.data[src_index + 2];
373  }
374  }
375 
376  glTexImage2D(
377  GL_TEXTURE_2D,
378  0,
379  GL_RGB,
380  markerData.texture_size_,
381  markerData.texture_size_,
382  0,
383  GL_BGR,
384  GL_UNSIGNED_BYTE,
385  markerData.texture_.data());
386  }
387  else if (markerData.encoding_ == sensor_msgs::image_encodings::MONO8)
388  {
389  for (size_t row = 0; row < marker.image.height; row++)
390  {
391  for (size_t col = 0; col < marker.image.width; col++)
392  {
393  size_t src_index = row * marker.image.width + col;
394  size_t dst_index = row * markerData.texture_size_ + col;
395 
396  markerData.texture_[dst_index] = marker.image.data[src_index];
397  }
398  }
399 
400  glTexImage2D(
401  GL_TEXTURE_2D,
402  0,
403  GL_LUMINANCE,
404  markerData.texture_size_,
405  markerData.texture_size_,
406  0,
407  GL_LUMINANCE,
408  GL_UNSIGNED_BYTE,
409  markerData.texture_.data());
410  }
411 
412  glBindTexture(GL_TEXTURE_2D, 0);
413 
414  markerData.texture_x_ = static_cast<float>(marker.image.width) / static_cast<float>(markerData.texture_size_);
415  markerData.texture_y_ = static_cast<float>(marker.image.height) / static_cast<float>(markerData.texture_size_);
416  }
417  else
418  {
419  markers_[marker.ns].erase(marker.id);
420  }
421  }
422 
423  void TexturedMarkerPlugin::ProcessMarkers(const marti_visualization_msgs::TexturedMarkerArrayConstPtr markers)
424  {
425  for (unsigned int i = 0; i < markers->markers.size(); i++)
426  {
427  ProcessMarker(markers->markers[i]);
428  }
429  }
430 
431 
432  void TexturedMarkerPlugin::MarkerCallback(const marti_visualization_msgs::TexturedMarkerConstPtr marker)
433  {
434  Q_EMIT MarkerReceived(marker);
435  }
436 
437  void TexturedMarkerPlugin::MarkerArrayCallback(const marti_visualization_msgs::TexturedMarkerArrayConstPtr markers)
438  {
439  Q_EMIT MarkersReceived(markers);
440  }
441 
442  void TexturedMarkerPlugin::PrintError(const std::string& message)
443  {
444  PrintErrorHelper(ui_.status, message);
445  }
446 
447  void TexturedMarkerPlugin::PrintInfo(const std::string& message)
448  {
449  PrintInfoHelper(ui_.status, message);
450  }
451 
452  void TexturedMarkerPlugin::PrintWarning(const std::string& message)
453  {
454  PrintWarningHelper(ui_.status, message);
455  }
456 
457  QWidget* TexturedMarkerPlugin::GetConfigWidget(QWidget* parent)
458  {
459  config_widget_->setParent(parent);
460 
461  return config_widget_;
462  }
463 
464  bool TexturedMarkerPlugin::Initialize(QGLWidget* canvas)
465  {
466  canvas_ = canvas;
467 
468  return true;
469  }
470 
471  void TexturedMarkerPlugin::Draw(double x, double y, double scale)
472  {
473  ros::Time now = ros::Time::now();
474 
475  float alphaVal = alphaVal_; // Set all markers to same alpha value
476 
477  std::map<std::string, std::map<int, MarkerData> >::iterator nsIter;
478  for (nsIter = markers_.begin(); nsIter != markers_.end(); ++nsIter)
479  {
480  std::map<int, MarkerData>::iterator markerIter;
481  for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end(); ++markerIter)
482  {
483  MarkerData& marker = markerIter->second;
484  marker.alpha_ = alphaVal; // Update current marker's alpha value
485 
486  if (marker.expire_time > now)
487  {
488  if (marker.transformed)
489  {
490  glEnable(GL_TEXTURE_2D);
491 
492  glBindTexture(GL_TEXTURE_2D, static_cast<GLuint>(marker.texture_id_));
493 
494  glBegin(GL_TRIANGLES);
495 
496  glColor4f(1.0f, 1.0f, 1.0f, marker.alpha_);
497 
498  double marker_x = marker.texture_x_;
499  double marker_y = marker.texture_y_;
500 
501  glTexCoord2d(0, 0); glVertex2d(marker.transformed_quad_[0].x(), marker.transformed_quad_[0].y());
502  glTexCoord2d(marker_x, 0); glVertex2d(marker.transformed_quad_[1].x(), marker.transformed_quad_[1].y());
503  glTexCoord2d(marker_x, marker_y); glVertex2d(marker.transformed_quad_[2].x(), marker.transformed_quad_[2].y());
504 
505  glTexCoord2d(0, 0); glVertex2d(marker.transformed_quad_[3].x(), marker.transformed_quad_[3].y());
506  glTexCoord2d(marker_x, marker_y); glVertex2d(marker.transformed_quad_[4].x(), marker.transformed_quad_[4].y());
507  glTexCoord2d(0, marker_y); glVertex2d(marker.transformed_quad_[5].x(), marker.transformed_quad_[5].y());
508 
509  glEnd();
510 
511  glBindTexture(GL_TEXTURE_2D, 0);
512 
513  glDisable(GL_TEXTURE_2D);
514 
515  PrintInfo("OK");
516  }
517  }
518  }
519  }
520  }
521 
523  {
524  std::map<std::string, std::map<int, MarkerData> >::iterator nsIter;
525  for (nsIter = markers_.begin(); nsIter != markers_.end(); ++nsIter)
526  {
527  std::map<int, MarkerData>::iterator markerIter;
528  for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end(); ++markerIter)
529  {
531  if (GetTransform(markerIter->second.source_frame_, markerIter->second.stamp, transform))
532  {
533  markerIter->second.transformed_quad_.clear();
534  for (size_t i = 0; i < markerIter->second.quad_.size(); i++)
535  {
536  markerIter->second.transformed_quad_.push_back(transform * markerIter->second.quad_[i]);
537  }
538  }
539  }
540  }
541  }
542 
543  void TexturedMarkerPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
544  {
545  if (node["topic"])
546  {
547  std::string topic;
548  node["topic"] >> topic;
549  ui_.topic->setText(boost::trim_copy(topic).c_str());
550  }
551 
552  if (node["is_marker_array"])
553  {
554  node["is_marker_array"] >> is_marker_array_;
555  }
556 
557  TopicEdited();
558  }
559 
560  void TexturedMarkerPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
561  {
562  emitter << YAML::Key << "topic" << YAML::Value << boost::trim_copy(ui_.topic->text().toStdString());
563  emitter << YAML::Key << "is_marker_array" << YAML::Value << is_marker_array_;
564  }
565 }
566 
bool GetTransform(const ros::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms=true)
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
void MarkersReceived(const marti_visualization_msgs::TexturedMarkerArrayConstPtr markers)
void PrintInfo(const std::string &message)
ros::NodeHandle node_
void MarkerArrayCallback(const marti_visualization_msgs::TexturedMarkerArrayConstPtr markers)
void ProcessMarkers(const marti_visualization_msgs::TexturedMarkerArrayConstPtr markers)
void transform(Route &route, const swri_transform_util::Transform &transform, const std::string &target_frame)
f
void LoadConfig(const YAML::Node &node, const std::string &path)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
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)
std::string target_frame_
#define ROS_WARN(...)
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void PrintError(const std::string &message)
std::map< std::string, std::map< int, MarkerData > > markers_
void MarkerCallback(const marti_visualization_msgs::TexturedMarkerConstPtr marker)
void PrintWarning(const std::string &message)
#define ROS_INFO(...)
void MarkerReceived(const marti_visualization_msgs::TexturedMarkerConstPtr marker)
ROSTIME_DECL const Time TIME_MAX
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
int min(int a, int b)
static Time now()
void ProcessMarker(const marti_visualization_msgs::TexturedMarkerConstPtr marker)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
void Draw(double x, double y, double scale)
#define ROS_DEBUG(...)


mapviz_plugins
Author(s): Marc Alban
autogenerated on Fri Mar 19 2021 02:44:32