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


mapviz_plugins
Author(s): Marc Alban
autogenerated on Wed Jan 17 2024 03:27:49