pointcloud2_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 #include <map>
38 
39 // Boost libraries
40 #include <boost/algorithm/string.hpp>
41 
42 // QT libraries
43 #include <QColorDialog>
44 #include <QDialog>
45 #include <QGLWidget>
46 
47 // QT Autogenerated
48 #include "ui_topic_select.h"
49 
50 // ROS libraries
51 #include <ros/master.h>
54 
56 
57 // Declare plugin
59 
61 
62 namespace mapviz_plugins
63 {
64  PointCloud2Plugin::PointCloud2Plugin() :
65  config_widget_(new QWidget()),
66  topic_(""),
67  alpha_(1.0),
68  min_value_(0.0),
69  max_value_(100.0),
70  point_size_(3),
71  buffer_size_(1),
72  new_topic_(true),
73  has_message_(false),
74  num_of_feats_(0),
75  need_new_list_(true),
76  need_minmax_(false)
77  {
78  ui_.setupUi(config_widget_);
79 
80  // Set background white
81  QPalette p(config_widget_->palette());
82  p.setColor(QPalette::Background, Qt::white);
83  config_widget_->setPalette(p);
84 
85  // Set status text red
86  QPalette p3(ui_.status->palette());
87  p3.setColor(QPalette::Text, Qt::red);
88  ui_.status->setPalette(p3);
89 
90  // Initialize color selector colors
91  ui_.min_color->setColor(Qt::white);
92  ui_.max_color->setColor(Qt::black);
93  // Set color transformer choices
94  ui_.color_transformer->addItem(QString("Flat Color"), QVariant(0));
95 
96  QObject::connect(ui_.selecttopic,
97  SIGNAL(clicked()),
98  this,
99  SLOT(SelectTopic()));
100  QObject::connect(ui_.topic,
101  SIGNAL(editingFinished()),
102  this,
103  SLOT(TopicEdited()));
104  QObject::connect(ui_.alpha,
105  SIGNAL(valueChanged(double)),
106  this,
107  SLOT(AlphaEdited(double)));
108  QObject::connect(ui_.color_transformer,
109  SIGNAL(currentIndexChanged(int)),
110  this,
111  SLOT(ColorTransformerChanged(int)));
112  QObject::connect(ui_.max_color,
113  SIGNAL(colorEdited(
114  const QColor &)),
115  this,
116  SLOT(UpdateColors()));
117  QObject::connect(ui_.min_color,
118  SIGNAL(colorEdited(
119  const QColor &)),
120  this,
121  SLOT(UpdateColors()));
122  QObject::connect(ui_.minValue,
123  SIGNAL(valueChanged(double)),
124  this,
125  SLOT(MinValueChanged(double)));
126  QObject::connect(ui_.maxValue,
127  SIGNAL(valueChanged(double)),
128  this,
129  SLOT(MaxValueChanged(double)));
130  QObject::connect(ui_.bufferSize,
131  SIGNAL(valueChanged(int)),
132  this,
133  SLOT(BufferSizeChanged(int)));
134  QObject::connect(ui_.pointSize,
135  SIGNAL(valueChanged(int)),
136  this,
137  SLOT(PointSizeChanged(int)));
138  QObject::connect(ui_.use_rainbow,
139  SIGNAL(stateChanged(int)),
140  this,
141  SLOT(UseRainbowChanged(int)));
142  QObject::connect(ui_.unpack_rgb,
143  SIGNAL(stateChanged(int)),
144  this,
145  SLOT(UseRainbowChanged(int)));
146  QObject::connect(ui_.use_automaxmin,
147  SIGNAL(stateChanged(int)),
148  this,
149  SLOT(UseAutomaxminChanged(int)));
150  QObject::connect(ui_.max_color,
151  SIGNAL(colorEdited(
152  const QColor &)),
153  this,
154  SLOT(DrawIcon()));
155  QObject::connect(ui_.min_color,
156  SIGNAL(colorEdited(
157  const QColor &)),
158  this,
159  SLOT(DrawIcon()));
160  QObject::connect(this,
161  SIGNAL(TargetFrameChanged(const std::string&)),
162  this,
164 
165  PrintInfo("Constructed PointCloud2Plugin");
166  }
167 
169  {
170  }
171 
173  {
174  scans_.clear();
175  }
176 
178  {
179  if (icon_)
180  {
181  QPixmap icon(16, 16);
182  icon.fill(Qt::transparent);
183 
184  QPainter painter(&icon);
185  painter.setRenderHint(QPainter::Antialiasing, true);
186 
187  QPen pen;
188  pen.setWidth(4);
189  pen.setCapStyle(Qt::RoundCap);
190 
191  pen.setColor(ui_.min_color->color());
192  painter.setPen(pen);
193  painter.drawPoint(2, 13);
194 
195  pen.setColor(ui_.min_color->color());
196  painter.setPen(pen);
197  painter.drawPoint(4, 6);
198 
199  pen.setColor(ui_.max_color->color());
200  painter.setPen(pen);
201  painter.drawPoint(12, 9);
202 
203  pen.setColor(ui_.max_color->color());
204  painter.setPen(pen);
205  painter.drawPoint(13, 2);
206 
207  icon_->SetPixmap(icon);
208  }
209  }
210 
212  {
213  std::deque<Scan>::iterator scan_it = scans_.begin();
214  for (; scan_it != scans_.end(); ++scan_it)
215  {
216  scan_it->transformed = false;
217  }
218  }
219 
221  {
222  float val;
223  unsigned int color_transformer = static_cast<unsigned int>(ui_.color_transformer->currentIndex());
224  unsigned int transformer_index = color_transformer -1;
225  if (num_of_feats_ > 0 && color_transformer > 0)
226  {
227  val = point.features[transformer_index];
228  if (need_minmax_)
229  {
230  if (val > max_[transformer_index])
231  {
232  max_[transformer_index] = val;
233  }
234 
235  if (val < min_[transformer_index])
236  {
237  min_[transformer_index] = val;
238  }
239  }
240  }
241  else // No intensity or (color_transformer == COLOR_FLAT)
242  {
243  return ui_.min_color->color();
244  }
245 
246  if (ui_.unpack_rgb->isChecked())
247  {
248  uint8_t* pixelColor = reinterpret_cast<uint8_t*>(&val);
249  return QColor(pixelColor[2], pixelColor[1], pixelColor[0], 255);
250  }
251 
252  if (max_value_ > min_value_)
253  {
254  val = (val - min_value_) / (max_value_ - min_value_);
255  }
256  val = std::max(0.0f, std::min(val, 1.0f));
257 
258  if (ui_.use_automaxmin->isChecked())
259  {
260  max_value_ = max_[transformer_index];
261  min_value_ = min_[transformer_index];
262  }
263 
264  if (ui_.use_rainbow->isChecked())
265  { // Hue Interpolation
266 
267  int hue = (int)(val * 255.0);
268  return QColor::fromHsl(hue, 255, 127, 255);
269  }
270  else
271  {
272  const QColor min_color = ui_.min_color->color();
273  const QColor max_color = ui_.max_color->color();
274  // RGB Interpolation
275  int red, green, blue;
276  red = (int)(val * max_color.red() + ((1.0 - val) * min_color.red()));
277  green = (int)(val * max_color.green() + ((1.0 - val) * min_color.green()));
278  blue = (int)(val * max_color.blue() + ((1.0 - val) * min_color.blue()));
279  return QColor(red, green, blue, 255);
280  }
281  }
282 
283  inline int32_t findChannelIndex(const sensor_msgs::PointCloud2ConstPtr& cloud, const std::string& channel)
284  {
285  for (int32_t i = 0; static_cast<size_t>(i) < cloud->fields.size(); ++i)
286  {
287  if (cloud->fields[i].name == channel)
288  {
289  return i;
290  }
291  }
292 
293  return -1;
294  }
295 
297  {
298  {
299  QMutexLocker locker(&scan_mutex_);
300  std::deque<Scan>::iterator scan_it = scans_.begin();
301  for (; scan_it != scans_.end(); ++scan_it)
302  {
303  std::vector<StampedPoint>::iterator point_it = scan_it->points.begin();
304  for (; point_it != scan_it->points.end(); point_it++)
305  {
306  point_it->color = CalculateColor(*point_it);
307  }
308  }
309  }
310  canvas_->update();
311  }
312 
314  {
316  "sensor_msgs/PointCloud2");
317 
318  if (!topic.name.empty())
319  {
320  ui_.topic->setText(QString::fromStdString(topic.name));
321  TopicEdited();
322  }
323  }
324 
325 
327  {
328  std::string topic = ui_.topic->text().trimmed().toStdString();
329  if (topic != topic_)
330  {
331  initialized_ = false;
332  {
333  QMutexLocker locker(&scan_mutex_);
334  scans_.clear();
335  }
336  has_message_ = false;
337  PrintWarning("No messages received.");
338 
339  pc2_sub_.shutdown();
340 
341  topic_ = topic;
342  if (!topic.empty())
343  {
345  100,
347  this);
348  new_topic_ = true;
349  need_new_list_ = true;
350  max_.clear();
351  min_.clear();
352  ROS_INFO("Subscribing to %s", topic_.c_str());
353  }
354  }
355  }
356 
358  {
359  min_value_ = value;
360  UpdateColors();
361  }
362 
364  {
365  max_value_ = value;
366  UpdateColors();
367  }
368 
370  {
371  buffer_size_ = (size_t)value;
372 
373  if (buffer_size_ > 0)
374  {
375  QMutexLocker locker(&scan_mutex_);
376  while (scans_.size() > buffer_size_)
377  {
378  scans_.pop_front();
379  }
380  }
381 
382  canvas_->update();
383  }
384 
386  {
387  point_size_ = (size_t)value;
388 
389  canvas_->update();
390  }
391 
392  void PointCloud2Plugin::PointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr& msg)
393  {
394  if (!has_message_)
395  {
396  initialized_ = true;
397  has_message_ = true;
398  }
399 
400  // Note that unlike some plugins, this one does not store nor rely on the
401  // source_frame_ member variable. This one can potentially store many
402  // messages with different source frames, so we need to store and transform
403  // them individually.
404 
405  Scan scan;
406  {
407  // recycle already allocated memory, reusing an old scan
408  QMutexLocker locker(&scan_mutex_);
409  if (buffer_size_ > 0 )
410  {
411  if( scans_.size() >= buffer_size_)
412  {
413  scan = std::move( scans_.front() );
414  }
415  while (scans_.size() >= buffer_size_)
416  {
417  scans_.pop_front();
418  }
419  }
420  }
421 
422  scan.stamp = msg->header.stamp;
423  scan.color = QColor::fromRgbF(1.0f, 0.0f, 0.0f, 1.0f);
424  scan.source_frame = msg->header.frame_id;
425  scan.transformed = true;
426 
428  if (!GetTransform(scan.source_frame, msg->header.stamp, transform))
429  {
430  scan.transformed = false;
431  PrintError("No transform between " + scan.source_frame + " and " + target_frame_);
432  }
433 
434  int32_t xi = findChannelIndex(msg, "x");
435  int32_t yi = findChannelIndex(msg, "y");
436  int32_t zi = findChannelIndex(msg, "z");
437 
438  if (xi == -1 || yi == -1 || zi == -1)
439  {
440  return;
441  }
442 
443  if (new_topic_)
444  {
445  for (size_t i = 0; i < msg->fields.size(); ++i)
446  {
447  FieldInfo input;
448  std::string name = msg->fields[i].name;
449 
450  uint32_t offset_value = msg->fields[i].offset;
451  uint8_t datatype_value = msg->fields[i].datatype;
452  input.offset = offset_value;
453  input.datatype = datatype_value;
454  scan.new_features.insert(std::pair<std::string, FieldInfo>(name, input));
455  }
456 
457  new_topic_ = false;
458  num_of_feats_ = scan.new_features.size();
459 
460  max_.resize(num_of_feats_);
461  min_.resize(num_of_feats_);
462 
463  int label = 1;
464  if (need_new_list_)
465  {
466  int new_feature_index = ui_.color_transformer->currentIndex();
467  std::map<std::string, FieldInfo>::const_iterator it;
468  for (it = scan.new_features.begin(); it != scan.new_features.end(); ++it)
469  {
470  ui_.color_transformer->removeItem(static_cast<int>(num_of_feats_));
471  num_of_feats_--;
472  }
473 
474  for (it = scan.new_features.begin(); it != scan.new_features.end(); ++it)
475  {
476  std::string const field = it->first;
477  if (field == saved_color_transformer_)
478  {
479  // The very first time we see a new set of features, that means the
480  // plugin was just created; if we have a saved value, set the current
481  // index to that and clear the saved value.
482  new_feature_index = label;
484  }
485 
486  ui_.color_transformer->addItem(QString::fromStdString(field), QVariant(label));
487  num_of_feats_++;
488  label++;
489 
490  }
491  ui_.color_transformer->setCurrentIndex(new_feature_index);
492  need_new_list_ = false;
493  }
494  }
495 
496  if (!msg->data.empty())
497  {
498  const uint8_t* ptr = &msg->data.front();
499  const uint32_t point_step = msg->point_step;
500  const uint32_t xoff = msg->fields[xi].offset;
501  const uint32_t yoff = msg->fields[yi].offset;
502  const uint32_t zoff = msg->fields[zi].offset;
503  const size_t num_points = msg->data.size() / point_step;
504  const size_t num_features = scan.new_features.size();
505  scan.points.resize(num_points);
506 
507  std::vector<FieldInfo> field_infos;
508  field_infos.reserve(num_features);
509  for (auto it = scan.new_features.begin(); it != scan.new_features.end(); ++it)
510  {
511  field_infos.push_back(it->second);
512  }
513 
514  for (size_t i = 0; i < num_points; i++, ptr += point_step)
515  {
516  float x = *reinterpret_cast<const float*>(ptr + xoff);
517  float y = *reinterpret_cast<const float*>(ptr + yoff);
518  float z = *reinterpret_cast<const float*>(ptr + zoff);
519 
520  StampedPoint& point = scan.points[i];
521  point.point = tf::Point(x, y, z);
522 
523  point.features.resize(num_features);
524 
525  for (int count=0; count < field_infos.size(); count++)
526  {
527  point.features[count] = PointFeature(ptr, field_infos[count]);
528  }
529  if (scan.transformed)
530  {
531  point.transformed_point = transform * point.point;
532  }
533  point.color = CalculateColor(point);
534  }
535  }
536 
537  {
538  QMutexLocker locker(&scan_mutex_);
539  scans_.push_back( std::move(scan) );
540  }
541  new_topic_ = true;
542  canvas_->update();
543  }
544 
545  float PointCloud2Plugin::PointFeature(const uint8_t* data, const FieldInfo& feature_info)
546  {
547  switch (feature_info.datatype)
548  {
549  case 1:
550  return *reinterpret_cast<const int8_t*>(data + feature_info.offset);
551  case 2:
552  return *(data + feature_info.offset);
553  case 3:
554  return *reinterpret_cast<const int16_t*>(data + feature_info.offset);
555  case 4:
556  return *reinterpret_cast<const uint16_t*>(data + feature_info.offset);
557  case 5:
558  return *reinterpret_cast<const int32_t*>(data + feature_info.offset);
559  case 6:
560  return *reinterpret_cast<const uint32_t*>(data + feature_info.offset);
561  case 7:
562  return *reinterpret_cast<const float*>(data + feature_info.offset);
563  case 8:
564  return *reinterpret_cast<const double*>(data + feature_info.offset);
565  default:
566  ROS_WARN("Unknown data type in point: %d", feature_info.datatype);
567  return 0.0;
568  }
569  }
570 
571  void PointCloud2Plugin::PrintError(const std::string& message)
572  {
573  PrintErrorHelper(ui_.status, message);
574  }
575 
576  void PointCloud2Plugin::PrintInfo(const std::string& message)
577  {
578  PrintInfoHelper(ui_.status, message);
579  }
580 
581  void PointCloud2Plugin::PrintWarning(const std::string& message)
582  {
583  PrintWarningHelper(ui_.status, message);
584  }
585 
586  QWidget* PointCloud2Plugin::GetConfigWidget(QWidget* parent)
587  {
588  config_widget_->setParent(parent);
589 
590  return config_widget_;
591  }
592 
593  bool PointCloud2Plugin::Initialize(QGLWidget* canvas)
594  {
595  canvas_ = canvas;
596 
597  DrawIcon();
598 
599  return true;
600  }
601 
602  void PointCloud2Plugin::Draw(double x, double y, double scale)
603  {
604  glPointSize(point_size_);
605  glBegin(GL_POINTS);
606 
607  std::deque<Scan>::const_iterator scan_it;
608  std::vector<StampedPoint>::const_iterator point_it;
609  {
610  QMutexLocker locker(&scan_mutex_);
611 
612  for (scan_it = scans_.begin(); scan_it != scans_.end(); scan_it++)
613  {
614  if (scan_it->transformed)
615  {
616  for (point_it = scan_it->points.begin(); point_it != scan_it->points.end(); ++point_it)
617  {
618  glColor4d(
619  point_it->color.redF(),
620  point_it->color.greenF(),
621  point_it->color.blueF(),
622  alpha_);
623  glVertex2d(
624  point_it->transformed_point.getX(),
625  point_it->transformed_point.getY());
626  }
627  }
628  }
629  }
630 
631  glEnd();
632 
633  PrintInfo("OK");
634  }
635 
637  {
639  UpdateColors();
640  }
641 
643  {
644  need_minmax_ = check_state == Qt::Checked;
645  if( !need_minmax_ )
646  {
647  min_value_ = ui_.minValue->value();
648  max_value_ = ui_.maxValue->value();
649  }
650 
652  UpdateColors();
653  }
654 
656  {
657  {
658  QMutexLocker locker(&scan_mutex_);
659 
660  std::deque<Scan>::iterator scan_it = scans_.begin();
661  bool was_using_latest_transforms = use_latest_transforms_;
662  use_latest_transforms_ = false;
663  for (; scan_it != scans_.end(); ++scan_it)
664  {
665  Scan& scan = *scan_it;
666 
667  if (!scan_it->transformed)
668  {
670  if (GetTransform(scan.source_frame, scan.stamp, transform))
671  {
672  scan.transformed = true;
673  std::vector<StampedPoint>::iterator point_it = scan.points.begin();
674  for (; point_it != scan.points.end(); ++point_it)
675  {
676  point_it->transformed_point = transform * point_it->point;
677  }
678  }
679  else
680  {
681  ROS_WARN("Unable to get transform.");
682  scan.transformed = false;
683  }
684  }
685  }
686  use_latest_transforms_ = was_using_latest_transforms;
687  }
688  // Z color is based on transformed color, so it is dependent on the
689  // transform
690  if (ui_.color_transformer->currentIndex() == COLOR_Z)
691  {
692  UpdateColors();
693  }
694  }
695 
696  void PointCloud2Plugin::LoadConfig(const YAML::Node& node,
697  const std::string& path)
698  {
699  if (node["topic"])
700  {
701  std::string topic;
702  node["topic"] >> topic;
703  ui_.topic->setText(boost::trim_copy(topic).c_str());
704  TopicEdited();
705  }
706 
707  if (node["size"])
708  {
709  node["size"] >> point_size_;
710  ui_.pointSize->setValue(static_cast<int>(point_size_));
711  }
712 
713  if (node["buffer_size"])
714  {
715  node["buffer_size"] >> buffer_size_;
716  ui_.bufferSize->setValue(static_cast<int>(buffer_size_));
717  }
718 
719  if (node["color_transformer"])
720  {
721  node["color_transformer"] >> saved_color_transformer_;
722  }
723 
724  if (node["min_color"])
725  {
726  std::string min_color_str;
727  node["min_color"] >> min_color_str;
728  ui_.min_color->setColor(QColor(min_color_str.c_str()));
729  }
730 
731  if (node["max_color"])
732  {
733  std::string max_color_str;
734  node["max_color"] >> max_color_str;
735  ui_.max_color->setColor(QColor(max_color_str.c_str()));
736  }
737 
738  if (node["value_min"])
739  {
740  node["value_min"] >> min_value_;
741  ui_.minValue->setValue(min_value_);
742  }
743 
744  if (node["value_max"])
745  {
746  node["value_max"] >> max_value_;
747  ui_.maxValue->setValue(max_value_);
748  }
749 
750  if (node["alpha"])
751  {
752  node["alpha"] >> alpha_;
753  ui_.alpha->setValue(alpha_);
754  }
755 
756  if (node["use_rainbow"])
757  {
758  bool use_rainbow;
759  node["use_rainbow"] >> use_rainbow;
760  ui_.use_rainbow->setChecked(use_rainbow);
761  }
762 
763  if (node["unpack_rgb"])
764  {
765  bool unpack_rgb;
766  node["unpack_rgb"] >> unpack_rgb;
767  ui_.unpack_rgb->setChecked(unpack_rgb);
768  }
769 
770  // UseRainbowChanged must be called *before* ColorTransformerChanged
771  UseRainbowChanged(ui_.use_rainbow->checkState());
772 
773  if (node["use_automaxmin"])
774  {
775  bool use_automaxmin;
776  node["use_automaxmin"] >> use_automaxmin;
777  ui_.use_automaxmin->setChecked(use_automaxmin);
778  }
779  // UseRainbowChanged must be called *before* ColorTransformerChanged
780  UseAutomaxminChanged(ui_.use_automaxmin->checkState());
781  // ColorTransformerChanged will also update colors of all points
782  ColorTransformerChanged(ui_.color_transformer->currentIndex());
783  }
784 
786  {
787  ROS_DEBUG("Color transformer changed to %d", index);
789  UpdateColors();
790  }
791 
793  {
794  bool color_is_flat = ui_.color_transformer->currentIndex() == COLOR_FLAT;
795 
796  if (color_is_flat)
797  {
798  ui_.maxColorLabel->hide();
799  ui_.max_color->hide();
800  ui_.minColorLabel->hide();
801  ui_.min_max_color_widget->show();
802  ui_.min_max_value_widget->hide();
803  ui_.use_automaxmin->hide();
804  ui_.use_rainbow->hide();
805  }
806  else
807  {
808  ui_.maxColorLabel->show();
809  ui_.max_color->show();
810  ui_.minColorLabel->show();
811  ui_.min_max_color_widget->setVisible(!ui_.use_rainbow->isChecked());
812  ui_.min_max_value_widget->setVisible(!ui_.use_automaxmin->isChecked());
813  ui_.use_automaxmin->show();
814  ui_.use_rainbow->show();
815  }
816 
817  config_widget_->updateGeometry();
818  config_widget_->adjustSize();
819 
820  Q_EMIT SizeChanged();
821  }
822 
827  {
828  alpha_ = std::max(0.0f, std::min((float)value, 1.0f));
829  }
830 
831  void PointCloud2Plugin::SaveConfig(YAML::Emitter& emitter,
832  const std::string& path)
833  {
834  emitter << YAML::Key << "topic" <<
835  YAML::Value << boost::trim_copy(ui_.topic->text().toStdString());
836  emitter << YAML::Key << "size" <<
837  YAML::Value << ui_.pointSize->value();
838  emitter << YAML::Key << "buffer_size" <<
839  YAML::Value << ui_.bufferSize->value();
840  emitter << YAML::Key << "alpha" <<
841  YAML::Value << alpha_;
842  emitter << YAML::Key << "color_transformer" <<
843  YAML::Value << ui_.color_transformer->currentText().toStdString();
844  emitter << YAML::Key << "min_color" <<
845  YAML::Value << ui_.min_color->color().name().toStdString();
846  emitter << YAML::Key << "max_color" <<
847  YAML::Value << ui_.max_color->color().name().toStdString();
848  emitter << YAML::Key << "value_min" <<
849  YAML::Value << ui_.minValue->value();
850  emitter << YAML::Key << "value_max" <<
851  YAML::Value << ui_.maxValue->value();
852  emitter << YAML::Key << "use_rainbow" <<
853  YAML::Value << ui_.use_rainbow->isChecked();
854  emitter << YAML::Key << "use_automaxmin" <<
855  YAML::Value << ui_.use_automaxmin->isChecked();
856  emitter << YAML::Key << "unpack_rgb" <<
857  YAML::Value << ui_.unpack_rgb->isChecked();
858  }
859 }
860 
861 
bool GetTransform(const ros::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms=true)
string name
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
IconWidget * icon_
ros::NodeHandle node_
void transform(Route &route, const swri_transform_util::Transform &transform, const std::string &target_frame)
f
QColor CalculateColor(const StampedPoint &point)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void Draw(double x, double y, double scale)
int32_t findChannelIndex(const sensor_msgs::PointCloud2ConstPtr &cloud, const std::string &channel)
void PointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr &scan)
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_
tf::Vector3 Point
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void SetPixmap(QPixmap pixmap)
void PrintError(const std::string &message)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void PrintInfo(const std::string &message)
void LoadConfig(const YAML::Node &node, const std::string &path)
#define ROS_INFO(...)
void TargetFrameChanged(const std::string &target_frame)
TFSIMD_FORCE_INLINE const tfScalar & x() const
QWidget * GetConfigWidget(QWidget *parent)
TFSIMD_FORCE_INLINE const tfScalar & z() const
std::map< std::string, FieldInfo > new_features
float PointFeature(const uint8_t *, const FieldInfo &)
void UseAutomaxminChanged(int check_state)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void PrintWarning(const std::string &message)
#define ROS_DEBUG(...)


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