40 #include <opencv2/imgproc/imgproc.hpp> 42 #include <QMessageBox> 51 setObjectName(
"ImageView");
65 ui_.image_frame->installEventFilter(
this);
68 ui_.topics_combo_box->setCurrentIndex(
ui_.topics_combo_box->findText(
""));
69 connect(
ui_.topics_combo_box, SIGNAL(currentIndexChanged(
int)),
this, SLOT(
onTopicChanged(
int)));
71 ui_.refresh_topics_push_button->setIcon(QIcon::fromTheme(
"view-refresh"));
72 connect(
ui_.refresh_topics_push_button, SIGNAL(pressed()),
this, SLOT(
updateTopicList()));
74 ui_.zoom_1_push_button->setIcon(QIcon::fromTheme(
"zoom-original"));
75 connect(
ui_.zoom_1_push_button, SIGNAL(toggled(
bool)),
this, SLOT(
onZoom1(
bool)));
77 connect(
ui_.dynamic_range_check_box, SIGNAL(toggled(
bool)),
this, SLOT(
onDynamicRange(
bool)));
82 if (watched ==
ui_.image_frame && event->type() == QEvent::Paint)
84 QPainter painter(
ui_.image_frame);
91 painter.drawImage(
ui_.image_frame->contentsRect(),
qimage_);
95 QLinearGradient gradient(0, 0,
ui_.image_frame->frameRect().width(),
ui_.image_frame->frameRect().height());
96 gradient.setColorAt(0, Qt::white);
97 gradient.setColorAt(1, Qt::black);
98 painter.setBrush(gradient);
99 painter.drawRect(0, 0,
ui_.image_frame->frameRect().width() + 1,
ui_.image_frame->frameRect().height() + 1);
104 return QObject::eventFilter(watched, event);
114 QString topic =
ui_.topics_combo_box->currentText();
116 instance_settings.
setValue(
"topic", topic);
117 instance_settings.
setValue(
"zoom1",
ui_.zoom_1_push_button->isChecked());
118 instance_settings.
setValue(
"dynamic_range",
ui_.dynamic_range_check_box->isChecked());
119 instance_settings.
setValue(
"max_range",
ui_.max_range_double_spin_box->value());
124 bool zoom1_checked = instance_settings.
value(
"zoom1",
false).toBool();
125 ui_.zoom_1_push_button->setChecked(zoom1_checked);
127 bool dynamic_range_checked = instance_settings.
value(
"dynamic_range",
false).toBool();
128 ui_.dynamic_range_check_box->setChecked(dynamic_range_checked);
130 double max_range = instance_settings.
value(
"max_range",
ui_.max_range_double_spin_box->value()).toDouble();
131 ui_.max_range_double_spin_box->setValue(max_range);
133 QString topic = instance_settings.
value(
"topic",
"").toString();
140 QSet<QString> message_types;
141 message_types.insert(
"sensor_msgs/Image");
144 QList<QString> transports;
147 for (std::vector<std::string>::const_iterator it = declared.begin(); it != declared.end(); it++)
150 QString transport = it->c_str();
153 QString prefix =
"image_transport/";
154 if (transport.startsWith(prefix))
156 transport = transport.mid(prefix.length());
158 transports.append(transport);
161 QString selected =
ui_.topics_combo_box->currentText();
164 QList<QString> topics =
getTopicList(message_types, transports);
167 ui_.topics_combo_box->clear();
168 for (QList<QString>::const_iterator it = topics.begin(); it != topics.end(); it++)
171 label.replace(
" ",
"/");
172 ui_.topics_combo_box->addItem(label, QVariant(*it));
184 QSet<QString> all_topics;
185 for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++)
187 all_topics.insert(it->name.c_str());
190 QList<QString> topics;
191 for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++)
193 if (message_types.contains(it->datatype.c_str()))
195 QString topic = it->name.c_str();
198 topics.append(topic);
202 for (QList<QString>::const_iterator jt = transports.begin(); jt != transports.end(); jt++)
204 if (all_topics.contains(topic +
"/" + *jt))
206 QString sub = topic +
" " + *jt;
218 int index =
ui_.topics_combo_box->findText(topic);
221 index =
ui_.topics_combo_box->findText(
"");
223 ui_.topics_combo_box->setCurrentIndex(index);
232 ui_.image_frame->update();
234 QStringList parts =
ui_.topics_combo_box->itemData(index).toString().split(
" ");
235 QString topic = parts.first();
236 QString transport = parts.length() == 2 ? parts.last() :
"raw";
238 if (!topic.isEmpty())
246 QMessageBox::warning(
widget_, tr(
"Loading image transport plugin failed"), e.what());
263 widget_->setMinimumSize(QSize(80, 60));
264 widget_->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX));
270 ui_.max_range_double_spin_box->setEnabled(!checked);
285 if (msg->encoding ==
"CV_8UC3")
289 }
else if (msg->encoding ==
"8UC1") {
292 }
else if (msg->encoding ==
"16UC1" || msg->encoding ==
"32FC1") {
295 double max =
ui_.max_range_double_spin_box->value();
296 if (msg->encoding ==
"16UC1") max *= 1000;
297 if (
ui_.dynamic_range_check_box->isChecked())
300 cv::minMaxLoc(cv_ptr->image, &min, &max);
307 cv::Mat img_scaled_8u;
308 cv::Mat(cv_ptr->image-min).convertTo(img_scaled_8u, CV_8UC1, 255. / (max - min));
311 qWarning(
"ImageView.callback_image() could not convert image from '%s' to 'rgb8' (%s)", msg->encoding.c_str(), e.what());
323 if (!
ui_.zoom_1_push_button->isEnabled())
325 ui_.zoom_1_push_button->setEnabled(
true);
328 ui_.image_frame->update();
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
virtual void initPlugin(qt_gui_cpp::PluginContext &context)
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 callbackImage(const sensor_msgs::Image::ConstPtr &msg)
virtual QList< QString > getTopicList(const QSet< QString > &message_types, const QList< QString > &transports)
image_transport::Subscriber subscriber_
virtual void onDynamicRange(bool checked)
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
QVariant value(const QString &key, const QVariant &defaultValue=QVariant()) const
void addWidget(QWidget *widget)
std::vector< TopicInfo > V_TopicInfo
virtual void onZoom1(bool checked)
virtual bool eventFilter(QObject *watched, QEvent *event)
virtual void onTopicChanged(int index)
virtual void shutdownPlugin()
std::vector< std::string > getDeclaredTransports() const
void setValue(const QString &key, const QVariant &value)
ros::NodeHandle & getNodeHandle() const
virtual void updateTopicList()
virtual void saveSettings(qt_gui_cpp::Settings &plugin_settings, qt_gui_cpp::Settings &instance_settings) const
virtual void selectTopic(const QString &topic)
virtual void restoreSettings(const qt_gui_cpp::Settings &plugin_settings, const qt_gui_cpp::Settings &instance_settings)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)