39 #include <boost/algorithm/string.hpp> 42 #include <QColorDialog> 47 #include "ui_topic_select.h" 62 LaserScanPlugin::LaserScanPlugin() :
63 config_widget_(new QWidget()),
77 p.setColor(QPalette::Background, Qt::white);
81 QPalette p3(
ui_.status->palette());
82 p3.setColor(QPalette::Text, Qt::red);
83 ui_.status->setPalette(p3);
86 ui_.min_color->setColor(Qt::white);
87 ui_.max_color->setColor(Qt::black);
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));
97 QObject::connect(
ui_.selecttopic,
101 QObject::connect(
ui_.topic,
102 SIGNAL(editingFinished()),
105 QObject::connect(
ui_.alpha,
106 SIGNAL(valueChanged(
double)),
109 QObject::connect(
ui_.color_transformer,
110 SIGNAL(currentIndexChanged(
int)),
113 QObject::connect(
ui_.max_color,
114 SIGNAL(colorEdited(
const QColor &)),
117 QObject::connect(
ui_.min_color,
118 SIGNAL(colorEdited(
const QColor &)),
121 QObject::connect(
ui_.minValue,
122 SIGNAL(valueChanged(
double)),
125 QObject::connect(
ui_.maxValue,
126 SIGNAL(valueChanged(
double)),
129 QObject::connect(
ui_.bufferSize,
130 SIGNAL(valueChanged(
int)),
133 QObject::connect(
ui_.pointSize,
134 SIGNAL(valueChanged(
int)),
137 QObject::connect(
ui_.use_rainbow,
138 SIGNAL(stateChanged(
int)),
142 QObject::connect(
ui_.max_color,
143 SIGNAL(colorEdited(
const QColor &)),
146 QObject::connect(
ui_.min_color,
147 SIGNAL(colorEdited(
const QColor &)),
151 PrintInfo(
"Constructed LaserScanPlugin");
167 QPixmap icon(16, 16);
168 icon.fill(Qt::transparent);
170 QPainter painter(&icon);
171 painter.setRenderHint(QPainter::Antialiasing,
true);
175 pen.setCapStyle(Qt::RoundCap);
177 pen.setColor(
ui_.min_color->color());
179 painter.drawPoint(2, 13);
181 pen.setColor(
ui_.min_color->color());
183 painter.drawPoint(4, 6);
185 pen.setColor(
ui_.max_color->color());
187 painter.drawPoint(12, 9);
189 pen.setColor(
ui_.max_color->color());
191 painter.drawPoint(13, 2);
201 int color_transformer =
ui_.color_transformer->currentIndex();
210 else if (color_transformer ==
COLOR_X)
214 else if (color_transformer ==
COLOR_Y)
218 else if (color_transformer ==
COLOR_Z)
224 return ui_.min_color->color();
228 val = std::max(0.0, std::min(val, 1.0));
229 if (
ui_.use_rainbow->isChecked())
232 int hue =
static_cast<int>(val * 255);
233 return QColor::fromHsl(hue, 255, 127, 255);
237 const QColor min_color =
ui_.min_color->color();
238 const QColor max_color =
ui_.max_color->color();
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);
250 std::deque<Scan>::iterator scan_it =
scans_.begin();
251 for (; scan_it !=
scans_.end(); ++scan_it)
253 std::vector<StampedPoint>::iterator point_it = scan_it->points.begin();
254 for (; point_it != scan_it->points.end(); point_it++)
256 point_it->color =
CalculateColor(*point_it, scan_it->has_intensity);
264 "sensor_msgs/LaserScan");
266 if (!topic.
name.empty())
268 ui_.topic->setText(QString::fromStdString(topic.
name));
275 std::string topic =
ui_.topic->text().trimmed().toStdString();
341 for (
size_t i = 0; i < msg->ranges.size(); i++)
343 double angle = msg->angle_min + msg->angle_increment * i;
364 scan.
stamp = msg->header.stamp;
365 scan.
color = QColor::fromRgbF(1.0
f, 0.0
f, 0.0
f, 1.0
f);
370 scan.
points.reserve( msg->ranges.size() );
382 for (
size_t i = 0; i < msg->ranges.size(); i++)
385 if (msg->ranges[i] > msg->range_max || msg->ranges[i] < msg->range_min)
393 point.
range = msg->ranges[i];
394 if (i < msg->intensities.size())
401 scan.
points.push_back(point);
451 std::deque<Scan>::const_iterator scan_it =
scans_.begin();
452 while (scan_it !=
scans_.end())
454 if (scan_it->transformed)
456 std::vector<StampedPoint>::const_iterator point_it = scan_it->points.begin();
457 for (; point_it != scan_it->points.end(); ++point_it)
460 point_it->color.redF(),
461 point_it->color.greenF(),
462 point_it->color.blueF(),
465 point_it->transformed_point.getX(),
466 point_it->transformed_point.getY());
479 if (check_state == Qt::Checked)
481 ui_.max_color->setVisible(
false);
482 ui_.min_color->setVisible(
false);
483 ui_.maxColorLabel->setVisible(
false);
484 ui_.minColorLabel->setVisible(
false);
488 ui_.max_color->setVisible(
true);
489 ui_.min_color->setVisible(
true);
490 ui_.maxColorLabel->setVisible(
true);
491 ui_.minColorLabel->setVisible(
true);
498 std::deque<Scan>::iterator scan_it =
scans_.begin();
499 for (; scan_it !=
scans_.end(); ++scan_it)
501 Scan& scan = *scan_it;
510 std::vector<StampedPoint>::iterator point_it = scan.
points.begin();
511 for (; point_it != scan.
points.end(); ++point_it)
513 point_it->transformed_point = transform * point_it->point;
524 if (
ui_.color_transformer->currentIndex() ==
COLOR_Z)
531 const std::string& path)
536 node[
"topic"] >> topic;
537 ui_.topic->setText(boost::trim_copy(topic).c_str());
544 ui_.pointSize->setValue(static_cast<int>(point_size_));
547 if (node[
"buffer_size"])
550 ui_.bufferSize->setValue(static_cast<int>(buffer_size_));
553 if (node[
"color_transformer"])
555 std::string color_transformer;
556 node[
"color_transformer"] >> color_transformer;
557 if (color_transformer ==
"Intensity")
559 else if (color_transformer ==
"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);
571 if (node[
"min_color"])
573 std::string min_color_str;
574 node[
"min_color"] >> min_color_str;
575 ui_.min_color->setColor(QColor(min_color_str.c_str()));
578 if (node[
"max_color"])
580 std::string max_color_str;
581 node[
"max_color"] >> max_color_str;
582 ui_.max_color->setColor(QColor(max_color_str.c_str()));
585 if (node[
"value_min"])
588 ui_.minValue->setValue(min_value_);
591 if (node[
"max_value"])
594 ui_.maxValue->setValue(max_value_);
600 ui_.alpha->setValue(alpha_);
603 if (node[
"use_rainbow"])
606 node[
"use_rainbow"] >> use_rainbow;
607 ui_.use_rainbow->setChecked(use_rainbow);
618 ROS_DEBUG(
"Color transformer changed to %d", index);
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);
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);
657 alpha_ = std::max(0.0
f, std::min((
float)val, 1.0
f));
661 const std::string& path)
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" <<
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();
virtual ~LaserScanPlugin()
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 PointSizeChanged(int value)
void laserScanCallback(const sensor_msgs::LaserScanConstPtr &scan)
std::vector< StampedPoint > points
void transform(Route &route, const swri_transform_util::Transform &transform, const std::string &target_frame)
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)
std::string source_frame_
static void PrintErrorHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void PrintWarning(const std::string &message)
std::string target_frame_
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 Draw(double x, double y, double scale)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void MinValueChanged(double value)
TFSIMD_FORCE_INLINE const tfScalar & z() const
std::deque< Scan > scans_
std::vector< double > precomputed_sin_
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE const tfScalar & x() const
void MaxValueChanged(double value)
void LoadConfig(const YAML::Node &node, const std::string &path)
ros::Subscriber laserscan_sub_
QColor CalculateColor(const StampedPoint &point, bool has_intensity)
void ColorTransformerChanged(int index)
void PrintInfo(const std::string &message)
void PrintError(const std::string &message)
bool Initialize(QGLWidget *canvas)
tf::Point transformed_point
void AlphaEdited(double val)
void updatePreComputedTriginometic(const sensor_msgs::LaserScanConstPtr &msg)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void BufferSizeChanged(int value)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void UseRainbowChanged(int check_state)
bool use_latest_transforms_