laserscan_plugin.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2015, 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 <algorithm>
36 #include <vector>
37 
38 // Boost libraries
39 #include <boost/algorithm/string.hpp>
40 
41 // QT libraries
42 #include <QColorDialog>
43 #include <QDialog>
44 #include <QGLWidget>
45 
46 // QT Autogenerated
47 #include "ui_topic_select.h"
48 
49 // ROS libraries
50 #include <ros/master.h>
53 
55 
56 // Declare plugin
59 
60 namespace mapviz_plugins
61 {
62  LaserScanPlugin::LaserScanPlugin() :
63  config_widget_(new QWidget()),
64  topic_(""),
65  alpha_(1.0),
66  min_value_(0.0),
67  max_value_(100.0),
68  point_size_(3),
69  prev_ranges_size_(0),
70  prev_angle_min_(0.0),
71  prev_increment_(0.0)
72  {
73  ui_.setupUi(config_widget_);
74 
75  // Set background white
76  QPalette p(config_widget_->palette());
77  p.setColor(QPalette::Background, Qt::white);
78  config_widget_->setPalette(p);
79 
80  // Set status text red
81  QPalette p3(ui_.status->palette());
82  p3.setColor(QPalette::Text, Qt::red);
83  ui_.status->setPalette(p3);
84 
85  // Initialize color selector colors
86  ui_.min_color->setColor(Qt::white);
87  ui_.max_color->setColor(Qt::black);
88 
89  // Set color transformer choices
90  ui_.color_transformer->addItem(QString("Flat Color"), QVariant(0));
91  ui_.color_transformer->addItem(QString("Intensity"), QVariant(1));
92  ui_.color_transformer->addItem(QString("Range"), QVariant(2));
93  ui_.color_transformer->addItem(QString("X Axis"), QVariant(3));
94  ui_.color_transformer->addItem(QString("Y Axis"), QVariant(4));
95  ui_.color_transformer->addItem(QString("Z Axis"), QVariant(5));
96 
97  QObject::connect(ui_.selecttopic,
98  SIGNAL(clicked()),
99  this,
100  SLOT(SelectTopic()));
101  QObject::connect(ui_.topic,
102  SIGNAL(editingFinished()),
103  this,
104  SLOT(TopicEdited()));
105  QObject::connect(ui_.alpha,
106  SIGNAL(valueChanged(double)),
107  this,
108  SLOT(AlphaEdited(double)));
109  QObject::connect(ui_.color_transformer,
110  SIGNAL(currentIndexChanged(int)),
111  this,
112  SLOT(ColorTransformerChanged(int)));
113  QObject::connect(ui_.max_color,
114  SIGNAL(colorEdited(const QColor &)),
115  this,
116  SLOT(UpdateColors()));
117  QObject::connect(ui_.min_color,
118  SIGNAL(colorEdited(const QColor &)),
119  this,
120  SLOT(UpdateColors()));
121  QObject::connect(ui_.minValue,
122  SIGNAL(valueChanged(double)),
123  this,
124  SLOT(MinValueChanged(double)));
125  QObject::connect(ui_.maxValue,
126  SIGNAL(valueChanged(double)),
127  this,
128  SLOT(MaxValueChanged(double)));
129  QObject::connect(ui_.bufferSize,
130  SIGNAL(valueChanged(int)),
131  this,
132  SLOT(BufferSizeChanged(int)));
133  QObject::connect(ui_.pointSize,
134  SIGNAL(valueChanged(int)),
135  this,
136  SLOT(PointSizeChanged(int)));
137  QObject::connect(ui_.use_rainbow,
138  SIGNAL(stateChanged(int)),
139  this,
140  SLOT(UseRainbowChanged(int)));
141 
142  QObject::connect(ui_.max_color,
143  SIGNAL(colorEdited(const QColor &)),
144  this,
145  SLOT(DrawIcon()));
146  QObject::connect(ui_.min_color,
147  SIGNAL(colorEdited(const QColor &)),
148  this,
149  SLOT(DrawIcon()));
150 
151  PrintInfo("Constructed LaserScanPlugin");
152  }
153 
155  {
156  }
157 
159  {
160  scans_.clear();
161  }
162 
164  {
165  if (icon_)
166  {
167  QPixmap icon(16, 16);
168  icon.fill(Qt::transparent);
169 
170  QPainter painter(&icon);
171  painter.setRenderHint(QPainter::Antialiasing, true);
172 
173  QPen pen;
174  pen.setWidth(4);
175  pen.setCapStyle(Qt::RoundCap);
176 
177  pen.setColor(ui_.min_color->color());
178  painter.setPen(pen);
179  painter.drawPoint(2, 13);
180 
181  pen.setColor(ui_.min_color->color());
182  painter.setPen(pen);
183  painter.drawPoint(4, 6);
184 
185  pen.setColor(ui_.max_color->color());
186  painter.setPen(pen);
187  painter.drawPoint(12, 9);
188 
189  pen.setColor(ui_.max_color->color());
190  painter.setPen(pen);
191  painter.drawPoint(13, 2);
192 
193  icon_->SetPixmap(icon);
194  }
195  }
196 
198  bool has_intensity)
199  {
200  double val;
201  int color_transformer = ui_.color_transformer->currentIndex();
202  if (color_transformer == COLOR_RANGE)
203  {
204  val = point.range;
205  }
206  else if (color_transformer == COLOR_INTENSITY && has_intensity)
207  {
208  val = point.intensity;
209  }
210  else if (color_transformer == COLOR_X)
211  {
212  val = point.point.x();
213  }
214  else if (color_transformer == COLOR_Y)
215  {
216  val = point.point.y();
217  }
218  else if (color_transformer == COLOR_Z)
219  {
220  val = point.transformed_point.z();
221  }
222  else // No intensity or (color_transformer == COLOR_FLAT)
223  {
224  return ui_.min_color->color();
225  }
226  if (max_value_ > min_value_)
227  val = (val - min_value_) / (max_value_ - min_value_);
228  val = std::max(0.0, std::min(val, 1.0));
229  if (ui_.use_rainbow->isChecked())
230  {
231  // Hue Interpolation
232  int hue = static_cast<int>(val * 255);
233  return QColor::fromHsl(hue, 255, 127, 255);
234  }
235  else
236  {
237  const QColor min_color = ui_.min_color->color();
238  const QColor max_color = ui_.max_color->color();
239  // RGB Interpolation
240  int red, green, blue;
241  red = static_cast<int>(val * max_color.red() + ((1.0 - val) * min_color.red()));
242  green = static_cast<int>(val * max_color.green() + ((1.0 - val) * min_color.green()));
243  blue = static_cast<int>(val * max_color.blue() + ((1.0 - val) * min_color.blue()));
244  return QColor(red, green, blue, 255);
245  }
246  }
247 
249  {
250  std::deque<Scan>::iterator scan_it = scans_.begin();
251  for (; scan_it != scans_.end(); ++scan_it)
252  {
253  std::vector<StampedPoint>::iterator point_it = scan_it->points.begin();
254  for (; point_it != scan_it->points.end(); point_it++)
255  {
256  point_it->color = CalculateColor(*point_it, scan_it->has_intensity);
257  }
258  }
259  }
260 
262  {
264  "sensor_msgs/LaserScan");
265 
266  if (!topic.name.empty())
267  {
268  ui_.topic->setText(QString::fromStdString(topic.name));
269  TopicEdited();
270  }
271  }
272 
274  {
275  std::string topic = ui_.topic->text().trimmed().toStdString();
276  if (topic != topic_)
277  {
278  initialized_ = false;
279  scans_.clear();
280  has_message_ = false;
281  PrintWarning("No messages received.");
282 
284 
285  topic_ = topic;
286  if (!topic.empty())
287  {
289  100,
291  this);
292 
293  ROS_INFO("Subscribing to %s", topic_.c_str());
294  }
295  }
296  }
297 
299  {
300  min_value_ = value;
301  UpdateColors();
302  }
303 
305  {
306  max_value_ = value;
307  UpdateColors();
308  }
309 
311  {
312  buffer_size_ = static_cast<size_t>(value);
313 
314  if (buffer_size_ > 0)
315  {
316  while (scans_.size() > buffer_size_)
317  {
318  scans_.pop_front();
319  }
320  }
321  }
322 
324  {
325  point_size_ = static_cast<size_t>(value);
326  }
327 
328  void LaserScanPlugin::updatePreComputedTriginometic(const sensor_msgs::LaserScanConstPtr& msg)
329  {
330  if( msg->ranges.size() != prev_ranges_size_ ||
331  msg->angle_min != prev_angle_min_ ||
332  msg->angle_increment != prev_increment_ )
333  {
334  prev_ranges_size_ = msg->ranges.size();
335  prev_angle_min_ = msg->angle_min;
336  prev_increment_ = msg->angle_increment;
337 
338  precomputed_cos_.resize( msg->ranges.size() );
339  precomputed_sin_.resize( msg->ranges.size() );
340 
341  for (size_t i = 0; i < msg->ranges.size(); i++)
342  {
343  double angle = msg->angle_min + msg->angle_increment * i;
344  precomputed_cos_[i] = cos(angle);
345  precomputed_sin_[i] = sin(angle);
346  }
347  }
348  }
349 
350  void LaserScanPlugin::laserScanCallback(const sensor_msgs::LaserScanConstPtr& msg)
351  {
352  if (!has_message_)
353  {
354  initialized_ = true;
355  has_message_ = true;
356  }
357 
358  // Note that unlike some plugins, this one does not store nor rely on the
359  // source_frame_ member variable. This one can potentially store many
360  // messages with different source frames, so we need to store and transform
361  // them individually.
362 
363  Scan scan;
364  scan.stamp = msg->header.stamp;
365  scan.color = QColor::fromRgbF(1.0f, 0.0f, 0.0f, 1.0f);
366  scan.source_frame_ = msg->header.frame_id;
367  scan.transformed = true;
368  scan.has_intensity = !msg->intensities.empty();
369 
370  scan.points.reserve( msg->ranges.size() );
371 
373  if (!GetTransform(scan.source_frame_, msg->header.stamp, transform))
374  {
375  scan.transformed = false;
376  PrintError("No transform between " + source_frame_ + " and " + target_frame_);
377  }
378  double x, y;
379 
381 
382  for (size_t i = 0; i < msg->ranges.size(); i++)
383  {
384  // Discard the point if it's out of range
385  if (msg->ranges[i] > msg->range_max || msg->ranges[i] < msg->range_min)
386  {
387  continue;
388  }
389  StampedPoint point;
390  x = precomputed_cos_[i] * msg->ranges[i];
391  y = precomputed_sin_[i] * msg->ranges[i];
392  point.point = tf::Point(x, y, 0.0f);
393  point.range = msg->ranges[i];
394  if (i < msg->intensities.size())
395  point.intensity = msg->intensities[i];
396  if (scan.transformed)
397  {
398  point.transformed_point = transform * point.point;
399  }
400  point.color = CalculateColor(point, scan.has_intensity);
401  scan.points.push_back(point);
402  }
403  scans_.push_back(scan);
404 
405  // If there are more items in the scan buffer than buffer_size_, remove them
406  if (buffer_size_ > 0)
407  {
408  while (scans_.size() > buffer_size_)
409  {
410  scans_.pop_front();
411  }
412  }
413  }
414 
415  void LaserScanPlugin::PrintError(const std::string& message)
416  {
417  PrintErrorHelper(ui_.status, message);
418  }
419 
420  void LaserScanPlugin::PrintInfo(const std::string& message)
421  {
422  PrintInfoHelper(ui_.status, message);
423  }
424 
425  void LaserScanPlugin::PrintWarning(const std::string& message)
426  {
427  PrintWarningHelper(ui_.status, message);
428  }
429 
430  QWidget* LaserScanPlugin::GetConfigWidget(QWidget* parent)
431  {
432  config_widget_->setParent(parent);
433 
434  return config_widget_;
435  }
436 
437  bool LaserScanPlugin::Initialize(QGLWidget* canvas)
438  {
439  canvas_ = canvas;
440 
441  DrawIcon();
442 
443  return true;
444  }
445 
446  void LaserScanPlugin::Draw(double x, double y, double scale)
447  {
448  glPointSize(point_size_);
449  glBegin(GL_POINTS);
450 
451  std::deque<Scan>::const_iterator scan_it = scans_.begin();
452  while (scan_it != scans_.end())
453  {
454  if (scan_it->transformed)
455  {
456  std::vector<StampedPoint>::const_iterator point_it = scan_it->points.begin();
457  for (; point_it != scan_it->points.end(); ++point_it)
458  {
459  glColor4d(
460  point_it->color.redF(),
461  point_it->color.greenF(),
462  point_it->color.blueF(),
463  alpha_);
464  glVertex2d(
465  point_it->transformed_point.getX(),
466  point_it->transformed_point.getY());
467  }
468  }
469  ++scan_it;
470  }
471 
472  glEnd();
473 
474  PrintInfo("OK");
475  }
476 
478  {
479  if (check_state == Qt::Checked)
480  {
481  ui_.max_color->setVisible(false);
482  ui_.min_color->setVisible(false);
483  ui_.maxColorLabel->setVisible(false);
484  ui_.minColorLabel->setVisible(false);
485  }
486  else
487  {
488  ui_.max_color->setVisible(true);
489  ui_.min_color->setVisible(true);
490  ui_.maxColorLabel->setVisible(true);
491  ui_.minColorLabel->setVisible(true);
492  }
493  UpdateColors();
494  }
495 
497  {
498  std::deque<Scan>::iterator scan_it = scans_.begin();
499  for (; scan_it != scans_.end(); ++scan_it)
500  {
501  Scan& scan = *scan_it;
502 
504 
505  bool was_using_latest_transforms = this->use_latest_transforms_;
506  this->use_latest_transforms_ = false;
507  if (GetTransform(scan.source_frame_, scan.stamp, transform))
508  {
509  scan.transformed = true;
510  std::vector<StampedPoint>::iterator point_it = scan.points.begin();
511  for (; point_it != scan.points.end(); ++point_it)
512  {
513  point_it->transformed_point = transform * point_it->point;
514  }
515  }
516  else
517  {
518  scan.transformed = false;
519  }
520  this->use_latest_transforms_ = was_using_latest_transforms;
521  }
522  // Z color is based on transformed color, so it is dependent on the
523  // transform
524  if (ui_.color_transformer->currentIndex() == COLOR_Z)
525  {
526  UpdateColors();
527  }
528  }
529 
530  void LaserScanPlugin::LoadConfig(const YAML::Node& node,
531  const std::string& path)
532  {
533  if (node["topic"])
534  {
535  std::string topic;
536  node["topic"] >> topic;
537  ui_.topic->setText(boost::trim_copy(topic).c_str());
538  TopicEdited();
539  }
540 
541  if (node["size"])
542  {
543  node["size"] >> point_size_;
544  ui_.pointSize->setValue(static_cast<int>(point_size_));
545  }
546 
547  if (node["buffer_size"])
548  {
549  node["buffer_size"] >> buffer_size_;
550  ui_.bufferSize->setValue(static_cast<int>(buffer_size_));
551  }
552 
553  if (node["color_transformer"])
554  {
555  std::string color_transformer;
556  node["color_transformer"] >> color_transformer;
557  if (color_transformer == "Intensity")
558  ui_.color_transformer->setCurrentIndex(COLOR_INTENSITY);
559  else if (color_transformer == "Range")
560  ui_.color_transformer->setCurrentIndex(COLOR_RANGE);
561  else if (color_transformer == "X Axis")
562  ui_.color_transformer->setCurrentIndex(COLOR_X);
563  else if (color_transformer == "Y Axis")
564  ui_.color_transformer->setCurrentIndex(COLOR_Y);
565  else if (color_transformer == "Z Axis")
566  ui_.color_transformer->setCurrentIndex(COLOR_Z);
567  else
568  ui_.color_transformer->setCurrentIndex(COLOR_FLAT);
569  }
570 
571  if (node["min_color"])
572  {
573  std::string min_color_str;
574  node["min_color"] >> min_color_str;
575  ui_.min_color->setColor(QColor(min_color_str.c_str()));
576  }
577 
578  if (node["max_color"])
579  {
580  std::string max_color_str;
581  node["max_color"] >> max_color_str;
582  ui_.max_color->setColor(QColor(max_color_str.c_str()));
583  }
584 
585  if (node["value_min"])
586  {
587  node["value_min"] >> min_value_;
588  ui_.minValue->setValue(min_value_);
589  }
590 
591  if (node["max_value"])
592  {
593  node["value_max"] >> max_value_;
594  ui_.maxValue->setValue(max_value_);
595  }
596 
597  if (node["alpha"])
598  {
599  node["alpha"] >> alpha_;
600  ui_.alpha->setValue(alpha_);
601  }
602 
603  if (node["use_rainbow"])
604  {
605  bool use_rainbow;
606  node["use_rainbow"] >> use_rainbow;
607  ui_.use_rainbow->setChecked(use_rainbow);
608  }
609 
610  // UseRainbowChanged must be called *before* ColorTransformerChanged
611  UseRainbowChanged(ui_.use_rainbow->checkState());
612  // ColorTransformerChanged will also update colors of all points
613  ColorTransformerChanged(ui_.color_transformer->currentIndex());
614  }
615 
617  {
618  ROS_DEBUG("Color transformer changed to %d", index);
619  switch (index)
620  {
621  case COLOR_FLAT:
622  ui_.min_color->setVisible(true);
623  ui_.max_color->setVisible(false);
624  ui_.maxColorLabel->setVisible(false);
625  ui_.minColorLabel->setVisible(false);
626  ui_.minValueLabel->setVisible(false);
627  ui_.maxValueLabel->setVisible(false);
628  ui_.minValue->setVisible(false);
629  ui_.maxValue->setVisible(false);
630  ui_.use_rainbow->setVisible(false);
631  break;
632  case COLOR_INTENSITY: // Intensity
633  case COLOR_RANGE: // Range
634  case COLOR_X: // X Axis
635  case COLOR_Y: // Y Axis
636  case COLOR_Z: // Z axis
637  default:
638  ui_.min_color->setVisible(!ui_.use_rainbow->isChecked());
639  ui_.max_color->setVisible(!ui_.use_rainbow->isChecked());
640  ui_.maxColorLabel->setVisible(!ui_.use_rainbow->isChecked());
641  ui_.minColorLabel->setVisible(!ui_.use_rainbow->isChecked());
642  ui_.minValueLabel->setVisible(true);
643  ui_.maxValueLabel->setVisible(true);
644  ui_.minValue->setVisible(true);
645  ui_.maxValue->setVisible(true);
646  ui_.use_rainbow->setVisible(true);
647  break;
648  }
649  UpdateColors();
650  }
651 
656  {
657  alpha_ = std::max(0.0f, std::min((float)val, 1.0f));
658  }
659 
660  void LaserScanPlugin::SaveConfig(YAML::Emitter& emitter,
661  const std::string& path)
662  {
663  emitter << YAML::Key << "topic" <<
664  YAML::Value << boost::trim_copy(ui_.topic->text().toStdString());
665  emitter << YAML::Key << "size" <<
666  YAML::Value << ui_.pointSize->value();
667  emitter << YAML::Key << "buffer_size" <<
668  YAML::Value << ui_.bufferSize->value();
669  emitter << YAML::Key << "alpha" <<
670  YAML::Value << alpha_;
671  emitter << YAML::Key << "color_transformer" <<
672  YAML::Value << ui_.color_transformer->currentText().toStdString();
673  emitter << YAML::Key << "min_color" <<
674  YAML::Value << ui_.min_color->color().name().toStdString();
675  emitter << YAML::Key << "max_color" <<
676  YAML::Value << ui_.max_color->color().name().toStdString();
677  emitter << YAML::Key << "value_min" <<
678  YAML::Value << ui_.minValue->text().toDouble();
679  emitter << YAML::Key << "value_max" <<
680  YAML::Value << ui_.maxValue->text().toDouble();
681  emitter << YAML::Key << "use_rainbow" <<
682  YAML::Value << ui_.use_rainbow->isChecked();
683  }
684 }
685 
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 laserScanCallback(const sensor_msgs::LaserScanConstPtr &scan)
IconWidget * icon_
ros::NodeHandle node_
std::vector< StampedPoint > points
void transform(Route &route, const swri_transform_util::Transform &transform, const std::string &target_frame)
f
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)
void PrintWarning(const std::string &message)
std::string target_frame_
tf::Vector3 Point
TFSIMD_FORCE_INLINE const tfScalar & y() const
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
QWidget * GetConfigWidget(QWidget *parent)
std::vector< double > precomputed_cos_
std::string source_frame_
void SetPixmap(QPixmap pixmap)
void Draw(double x, double y, double scale)
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
#define ROS_INFO(...)
std::vector< double > precomputed_sin_
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE const tfScalar & x() const
void LoadConfig(const YAML::Node &node, const std::string &path)
QColor CalculateColor(const StampedPoint &point, bool has_intensity)
void PrintInfo(const std::string &message)
void PrintError(const std::string &message)
bool Initialize(QGLWidget *canvas)
void updatePreComputedTriginometic(const sensor_msgs::LaserScanConstPtr &msg)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void UseRainbowChanged(int check_state)
#define ROS_DEBUG(...)


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