41 #include <opencv2/imgproc/imgproc.hpp> 43 #include <QMessageBox> 55 setObjectName(
"ImageEnhancer");
69 ui_.image_frame->installEventFilter(
this);
72 ui_.topics_combo_box->setCurrentIndex(
ui_.topics_combo_box->findText(
""));
73 connect(
ui_.topics_combo_box, SIGNAL(currentIndexChanged(
int)),
this, SLOT(
onTopicChanged(
int)));
75 ui_.refresh_topics_push_button->setIcon(QIcon::fromTheme(
"view-refresh"));
76 connect(
ui_.refresh_topics_push_button, SIGNAL(pressed()),
this, SLOT(
updateTopicList()));
78 connect(
ui_.dynamic_range_check_box, SIGNAL(toggled(
bool)),
this, SLOT(
onDynamicRange(
bool)));
81 connect(
ui_.image_frame, SIGNAL(selectionInProgress(QPoint,QPoint)),
this, SLOT(
onSelectionInProgress(QPoint,QPoint)));
82 connect(
ui_.image_frame, SIGNAL(selectionFinished(QPoint,QPoint)),
this, SLOT(
onSelectionFinished(QPoint,QPoint)));
87 if (watched ==
ui_.image_frame && event->type() == QEvent::Paint)
89 QPainter painter(
ui_.image_frame);
92 ui_.image_frame->resizeToFitAspectRatio();
97 painter.drawImage(
ui_.image_frame->contentsRect(),
qimage_);
101 QLinearGradient gradient(0, 0,
ui_.image_frame->frameRect().width(),
ui_.image_frame->frameRect().height());
102 gradient.setColorAt(0, Qt::white);
103 gradient.setColorAt(1, Qt::black);
104 painter.setBrush(gradient);
105 painter.drawRect(0, 0,
ui_.image_frame->frameRect().width() + 1,
ui_.image_frame->frameRect().height() + 1);
111 painter.setPen(Qt::red);
112 painter.drawRect(rect);
115 ui_.image_frame->update();
120 return QObject::eventFilter(watched, event);
130 QString topic =
ui_.topics_combo_box->currentText();
132 instance_settings.
setValue(
"topic", topic);
133 instance_settings.
setValue(
"dynamic_range",
ui_.dynamic_range_check_box->isChecked());
134 instance_settings.
setValue(
"max_range",
ui_.max_range_double_spin_box->value());
139 bool dynamic_range_checked = instance_settings.
value(
"dynamic_range",
false).toBool();
140 ui_.dynamic_range_check_box->setChecked(dynamic_range_checked);
142 double max_range = instance_settings.
value(
"max_range",
ui_.max_range_double_spin_box->value()).toDouble();
143 ui_.max_range_double_spin_box->setValue(max_range);
145 QString topic = instance_settings.
value(
"topic",
"").toString();
152 QSet<QString> message_types;
153 message_types.insert(
"sensor_msgs/Image");
156 QList<QString> transports;
159 for (std::vector<std::string>::const_iterator it = declared.begin(); it != declared.end(); it++)
162 QString transport = it->c_str();
165 QString prefix =
"image_transport/";
166 if (transport.startsWith(prefix))
168 transport = transport.mid(prefix.length());
170 transports.append(transport);
173 QString selected =
ui_.topics_combo_box->currentText();
176 QList<QString> topics =
getTopicList(message_types, transports);
179 ui_.topics_combo_box->clear();
180 for (QList<QString>::const_iterator it = topics.begin(); it != topics.end(); it++)
183 label.replace(
" ",
"/");
184 ui_.topics_combo_box->addItem(label, QVariant(*it));
196 QSet<QString> all_topics;
197 for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++)
199 all_topics.insert(it->name.c_str());
202 QList<QString> topics;
203 for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++)
205 if (message_types.contains(it->datatype.c_str()))
207 QString topic = it->name.c_str();
210 topics.append(topic);
214 for (QList<QString>::const_iterator jt = transports.begin(); jt != transports.end(); jt++)
216 if (all_topics.contains(topic +
"/" + *jt))
218 QString sub = topic +
" " + *jt;
230 int index =
ui_.topics_combo_box->findText(topic);
233 index =
ui_.topics_combo_box->findText(
"");
235 ui_.topics_combo_box->setCurrentIndex(index);
244 ui_.image_frame->update();
246 QStringList parts =
ui_.topics_combo_box->itemData(index).toString().split(
" ");
247 QString topic = parts.first();
248 QString transport = parts.length() == 2 ? parts.last() :
"raw";
250 if (!topic.isEmpty())
258 QMessageBox::warning(
widget_, tr(
"Loading image transport plugin failed"), e.what());
271 ui_.image_frame->setInnerFrameFixedSize(
qimage_.size());
276 ui_.image_frame->setInnerFrameMinimumSize(QSize(80, 60));
277 ui_.image_frame->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX));
278 widget_->setMinimumSize(QSize(80, 60));
279 widget_->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX));
288 int tl_x = std::min(p1.x(), p2.x());
289 int tl_y = std::min(p1.y(), p2.y());
304 int tl_x = p1.x() < p2.x() ? p1.x() : p2.x();
305 int tl_y = p1.y() < p2.y() ? p1.y() : p2.y();
321 int max_x =
ui_.image_frame->width();
324 int max_y =
ui_.image_frame->height();
326 p.setX(std::min(std::max(p.x(),min_x),max_x));
327 p.setY(std::min(std::max(p.y(),min_y),max_y));
332 ui_.max_range_double_spin_box->setEnabled(!checked);
349 if (msg->encoding ==
"CV_8UC3")
353 }
else if (msg->encoding ==
"8UC1") {
356 }
else if (msg->encoding ==
"16UC1" || msg->encoding ==
"32FC1") {
359 double max =
ui_.max_range_double_spin_box->value();
360 if (msg->encoding ==
"16UC1") max *= 1000;
361 if (
ui_.dynamic_range_check_box->isChecked())
364 cv::minMaxLoc(cv_ptr->image, &min, &max);
371 cv::Mat img_scaled_8u;
372 cv::Mat(cv_ptr->image-min).convertTo(img_scaled_8u, CV_8UC1, 255. / (max - min));
375 qWarning(
"ImageEnhancer.callback_image() could not convert image from '%s' to 'rgb8' (%s)", msg->encoding.c_str(), e.what());
390 ui_.image_frame->setInnerFrameMinimumSize(QSize(80, 60));
391 ui_.image_frame->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX));
392 widget_->setMinimumSize(QSize(80, 60));
393 widget_->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX));
virtual void saveSettings(qt_gui_cpp::Settings &plugin_settings, qt_gui_cpp::Settings &instance_settings) const
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
virtual void onSelectionFinished(QPoint p1, QPoint p2)
virtual void shutdownPlugin()
virtual void updateTopicList()
virtual void initPlugin(qt_gui_cpp::PluginContext &context)
virtual void onZoom1(bool checked)
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
virtual void selectTopic(const QString &topic)
QVariant value(const QString &key, const QVariant &defaultValue=QVariant()) const
image_transport::Subscriber subscriber_
void addWidget(QWidget *widget)
std::vector< TopicInfo > V_TopicInfo
virtual void onDynamicRange(bool checked)
std::vector< std::string > getDeclaredTransports() const
void setValue(const QString &key, const QVariant &value)
virtual bool eventFilter(QObject *watched, QEvent *event)
ros::NodeHandle & getNodeHandle() const
virtual void callbackImage(const sensor_msgs::Image::ConstPtr &msg)
virtual void restoreSettings(const qt_gui_cpp::Settings &plugin_settings, const qt_gui_cpp::Settings &instance_settings)
Ui::ImageEnhancerWidget ui_
virtual void enforceSelectionConstraints(QPoint &p)
virtual QList< QString > getTopicList(const QSet< QString > &message_types, const QList< QString > &transports)
virtual void onSelectionInProgress(QPoint p1, QPoint p2)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void onTopicChanged(int index)
virtual void onRemoveSelection()
QPoint selection_top_left_