40 #include <boost/algorithm/string.hpp> 43 #include <QColorDialog> 48 #include "ui_topic_select.h" 64 PointCloud2Plugin::PointCloud2Plugin() :
65 config_widget_(new QWidget()),
82 p.setColor(QPalette::Background, Qt::white);
86 QPalette p3(
ui_.status->palette());
87 p3.setColor(QPalette::Text, Qt::red);
88 ui_.status->setPalette(p3);
91 ui_.min_color->setColor(Qt::white);
92 ui_.max_color->setColor(Qt::black);
94 ui_.color_transformer->addItem(QString(
"Flat Color"), QVariant(0));
96 QObject::connect(
ui_.selecttopic,
100 QObject::connect(
ui_.topic,
101 SIGNAL(editingFinished()),
104 QObject::connect(
ui_.alpha,
105 SIGNAL(valueChanged(
double)),
108 QObject::connect(
ui_.color_transformer,
109 SIGNAL(currentIndexChanged(
int)),
112 QObject::connect(
ui_.max_color,
117 QObject::connect(
ui_.min_color,
122 QObject::connect(
ui_.minValue,
123 SIGNAL(valueChanged(
double)),
126 QObject::connect(
ui_.maxValue,
127 SIGNAL(valueChanged(
double)),
130 QObject::connect(
ui_.bufferSize,
131 SIGNAL(valueChanged(
int)),
134 QObject::connect(
ui_.pointSize,
135 SIGNAL(valueChanged(
int)),
138 QObject::connect(
ui_.use_rainbow,
139 SIGNAL(stateChanged(
int)),
142 QObject::connect(
ui_.unpack_rgb,
143 SIGNAL(stateChanged(
int)),
146 QObject::connect(
ui_.use_automaxmin,
147 SIGNAL(stateChanged(
int)),
150 QObject::connect(
ui_.max_color,
155 QObject::connect(
ui_.min_color,
160 QObject::connect(
this,
165 PrintInfo(
"Constructed PointCloud2Plugin");
181 QPixmap icon(16, 16);
182 icon.fill(Qt::transparent);
184 QPainter painter(&icon);
185 painter.setRenderHint(QPainter::Antialiasing,
true);
189 pen.setCapStyle(Qt::RoundCap);
191 pen.setColor(
ui_.min_color->color());
193 painter.drawPoint(2, 13);
195 pen.setColor(
ui_.min_color->color());
197 painter.drawPoint(4, 6);
199 pen.setColor(
ui_.max_color->color());
201 painter.drawPoint(12, 9);
203 pen.setColor(
ui_.max_color->color());
205 painter.drawPoint(13, 2);
213 std::deque<Scan>::iterator scan_it =
scans_.begin();
214 for (; scan_it !=
scans_.end(); ++scan_it)
216 scan_it->transformed =
false;
223 unsigned int color_transformer =
static_cast<unsigned int>(
ui_.color_transformer->currentIndex());
224 unsigned int transformer_index = color_transformer -1;
227 val = point.
features[transformer_index];
230 if (val >
max_[transformer_index])
232 max_[transformer_index] = val;
235 if (val <
min_[transformer_index])
237 min_[transformer_index] = val;
243 return ui_.min_color->color();
246 if (
ui_.unpack_rgb->isChecked())
248 uint8_t* pixelColor =
reinterpret_cast<uint8_t*
>(&val);
249 return QColor(pixelColor[2], pixelColor[1], pixelColor[0], 255);
256 val = std::max(0.0
f, std::min(val, 1.0
f));
258 if (
ui_.use_automaxmin->isChecked())
264 if (
ui_.use_rainbow->isChecked())
267 int hue = (int)(val * 255.0);
268 return QColor::fromHsl(hue, 255, 127, 255);
272 const QColor min_color =
ui_.min_color->color();
273 const QColor max_color =
ui_.max_color->color();
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);
283 inline int32_t
findChannelIndex(
const sensor_msgs::PointCloud2ConstPtr& cloud,
const std::string& channel)
285 for (int32_t i = 0;
static_cast<size_t>(i) < cloud->fields.size(); ++i)
287 if (cloud->fields[i].name == channel)
300 std::deque<Scan>::iterator scan_it =
scans_.begin();
301 for (; scan_it !=
scans_.end(); ++scan_it)
303 std::vector<StampedPoint>::iterator point_it = scan_it->points.begin();
304 for (; point_it != scan_it->points.end(); point_it++)
316 "sensor_msgs/PointCloud2");
318 if (!topic.
name.empty())
320 ui_.topic->setText(QString::fromStdString(topic.
name));
328 std::string topic =
ui_.topic->text().trimmed().toStdString();
413 scan = std::move(
scans_.front() );
422 scan.
stamp = msg->header.stamp;
423 scan.
color = QColor::fromRgbF(1.0
f, 0.0
f, 0.0
f, 1.0
f);
438 if (xi == -1 || yi == -1 || zi == -1)
445 for (
size_t i = 0; i < msg->fields.size(); ++i)
448 std::string
name = msg->fields[i].name;
450 uint32_t offset_value = msg->fields[i].offset;
451 uint8_t datatype_value = msg->fields[i].datatype;
452 input.
offset = offset_value;
454 scan.
new_features.insert(std::pair<std::string, FieldInfo>(name, input));
466 int new_feature_index =
ui_.color_transformer->currentIndex();
467 std::map<std::string, FieldInfo>::const_iterator it;
476 std::string
const field = it->first;
482 new_feature_index = label;
486 ui_.color_transformer->addItem(QString::fromStdString(field), QVariant(label));
491 ui_.color_transformer->setCurrentIndex(new_feature_index);
496 if (!msg->data.empty())
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;
505 scan.
points.resize(num_points);
507 std::vector<FieldInfo> field_infos;
508 field_infos.reserve(num_features);
511 field_infos.push_back(it->second);
514 for (
size_t i = 0; i < num_points; i++, ptr += point_step)
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);
523 point.
features.resize(num_features);
525 for (
int count=0; count < field_infos.size(); count++)
539 scans_.push_back( std::move(scan) );
550 return *
reinterpret_cast<const int8_t*
>(data + feature_info.
offset);
552 return *(data + feature_info.
offset);
554 return *
reinterpret_cast<const int16_t*
>(data + feature_info.
offset);
556 return *
reinterpret_cast<const uint16_t*
>(data + feature_info.
offset);
558 return *
reinterpret_cast<const int32_t*
>(data + feature_info.
offset);
560 return *
reinterpret_cast<const uint32_t*
>(data + feature_info.
offset);
562 return *
reinterpret_cast<const float*
>(data + feature_info.
offset);
564 return *
reinterpret_cast<const double*
>(data + feature_info.
offset);
607 std::deque<Scan>::const_iterator scan_it;
608 std::vector<StampedPoint>::const_iterator point_it;
612 for (scan_it =
scans_.begin(); scan_it !=
scans_.end(); scan_it++)
614 if (scan_it->transformed)
616 for (point_it = scan_it->points.begin(); point_it != scan_it->points.end(); ++point_it)
619 point_it->color.redF(),
620 point_it->color.greenF(),
621 point_it->color.blueF(),
624 point_it->transformed_point.getX(),
625 point_it->transformed_point.getY());
660 std::deque<Scan>::iterator scan_it =
scans_.begin();
663 for (; scan_it !=
scans_.end(); ++scan_it)
665 Scan& scan = *scan_it;
667 if (!scan_it->transformed)
673 std::vector<StampedPoint>::iterator point_it = scan.
points.begin();
674 for (; point_it != scan.
points.end(); ++point_it)
676 point_it->transformed_point = transform * point_it->point;
681 ROS_WARN(
"Unable to get transform.");
690 if (
ui_.color_transformer->currentIndex() ==
COLOR_Z)
697 const std::string& path)
702 node[
"topic"] >> topic;
703 ui_.topic->setText(boost::trim_copy(topic).c_str());
710 ui_.pointSize->setValue(static_cast<int>(point_size_));
713 if (node[
"buffer_size"])
716 ui_.bufferSize->setValue(static_cast<int>(buffer_size_));
719 if (node[
"color_transformer"])
724 if (node[
"min_color"])
726 std::string min_color_str;
727 node[
"min_color"] >> min_color_str;
728 ui_.min_color->setColor(QColor(min_color_str.c_str()));
731 if (node[
"max_color"])
733 std::string max_color_str;
734 node[
"max_color"] >> max_color_str;
735 ui_.max_color->setColor(QColor(max_color_str.c_str()));
738 if (node[
"value_min"])
741 ui_.minValue->setValue(min_value_);
744 if (node[
"value_max"])
747 ui_.maxValue->setValue(max_value_);
753 ui_.alpha->setValue(alpha_);
756 if (node[
"use_rainbow"])
759 node[
"use_rainbow"] >> use_rainbow;
760 ui_.use_rainbow->setChecked(use_rainbow);
763 if (node[
"unpack_rgb"])
766 node[
"unpack_rgb"] >> unpack_rgb;
767 ui_.unpack_rgb->setChecked(unpack_rgb);
773 if (node[
"use_automaxmin"])
776 node[
"use_automaxmin"] >> use_automaxmin;
777 ui_.use_automaxmin->setChecked(use_automaxmin);
787 ROS_DEBUG(
"Color transformer changed to %d", index);
794 bool color_is_flat =
ui_.color_transformer->currentIndex() ==
COLOR_FLAT;
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();
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();
828 alpha_ = std::max(0.0
f, std::min((
float)value, 1.0
f));
832 const std::string& path)
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" <<
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();
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 ResetTransformedPointClouds()
void AlphaEdited(double new_value)
void transform(Route &route, const swri_transform_util::Transform &transform, const std::string &target_frame)
bool Initialize(QGLWidget *canvas)
std::vector< double > max_
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)
void UpdateMinMaxWidgets()
int32_t findChannelIndex(const sensor_msgs::PointCloud2ConstPtr &cloud, const std::string &channel)
void PointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr &scan)
void ColorTransformerChanged(int index)
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_
TFSIMD_FORCE_INLINE const tfScalar & y() const
void MaxValueChanged(double value)
void BufferSizeChanged(int value)
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
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)
void PointSizeChanged(int value)
void MinValueChanged(double value)
void TargetFrameChanged(const std::string &target_frame)
virtual ~PointCloud2Plugin()
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::vector< float > features
QWidget * GetConfigWidget(QWidget *parent)
std::vector< StampedPoint > points
TFSIMD_FORCE_INLINE const tfScalar & z() const
std::map< std::string, FieldInfo > new_features
float PointFeature(const uint8_t *, const FieldInfo &)
tf::Point transformed_point
Ui::PointCloud2_config ui_
std::vector< double > min_
void UseAutomaxminChanged(int check_state)
std::deque< Scan > scans_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void UseRainbowChanged(int check_state)
void PrintWarning(const std::string &message)
bool use_latest_transforms_
std::string saved_color_transformer_