00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include <rqt_ptam/remote_ptam.h>
00035
00036 #include <pluginlib/class_list_macros.h>
00037 #include <ros/master.h>
00038 #include <sensor_msgs/image_encodings.h>
00039 #include <std_msgs/String.h>
00040
00041 #include <cv_bridge/cv_bridge.h>
00042 #include <opencv2/imgproc/imgproc.hpp>
00043
00044 #include <QMessageBox>
00045 #include <QPainter>
00046 #include <QKeyEvent>
00047
00048 namespace rqt_ptam {
00049
00050 RemotePTAM::RemotePTAM()
00051 : rqt_gui_cpp::Plugin()
00052 , widget_(0)
00053 {
00054 setObjectName("RemotePTAM");
00055 }
00056
00057 void RemotePTAM::initPlugin(qt_gui_cpp::PluginContext& context)
00058 {
00059 widget_ = new QWidget();
00060 ui_.setupUi(widget_);
00061
00062 if (context.serialNumber() > 1)
00063 {
00064 widget_->setWindowTitle(widget_->windowTitle() + " (" + QString::number(context.serialNumber()) + ")");
00065 }
00066 context.addWidget(widget_);
00067
00068 ui_.image_frame->installEventFilter(this);
00069
00070
00071
00072 updateNamespaceList();
00073 ui_.topics_combo_box->setCurrentIndex(ui_.topics_combo_box->findText(""));
00074 connect(ui_.topics_combo_box, SIGNAL(currentIndexChanged(int)), this, SLOT(onNamespaceChanged(int)));
00075
00076 ui_.refresh_topics_push_button->setIcon(QIcon::fromTheme("view-refresh"));
00077 connect(ui_.refresh_topics_push_button, SIGNAL(pressed()), this, SLOT(updateNamespaceList()));
00078
00079 ui_.zoom_1_push_button->setIcon(QIcon::fromTheme("zoom-original"));
00080 connect(ui_.zoom_1_push_button, SIGNAL(toggled(bool)), this, SLOT(onZoom1(bool)));
00081
00082 connect(ui_.subscribe_check_box, SIGNAL(toggled(bool)), this, SLOT(onSubscribe(bool)));
00083
00084 connect(ui_.space_push_button, SIGNAL(pressed()), this, SLOT(onSpace()));
00085
00086 connect(ui_.reset_push_button, SIGNAL(pressed()), this, SLOT(onReset()));
00087
00088 std::cout<<"test\n";
00089 }
00090
00091 bool RemotePTAM::eventFilter(QObject* watched, QEvent* event)
00092 {
00093 if (watched == ui_.image_frame && event->type() == QEvent::Paint)
00094 {
00095 QPainter painter(ui_.image_frame);
00096 if (!qimage_.isNull())
00097 {
00098 ui_.image_frame->resizeToFitAspectRatio();
00099
00100
00101
00102 qimage_mutex_.lock();
00103 painter.drawImage(ui_.image_frame->contentsRect(), qimage_);
00104 qimage_mutex_.unlock();
00105 } else {
00106
00107 QLinearGradient gradient(0, 0, ui_.image_frame->frameRect().width(), ui_.image_frame->frameRect().height());
00108 gradient.setColorAt(0, Qt::white);
00109 gradient.setColorAt(1, Qt::black);
00110 painter.setBrush(gradient);
00111 painter.drawRect(0, 0, ui_.image_frame->frameRect().width() + 1, ui_.image_frame->frameRect().height() + 1);
00112 }
00113 return false;
00114 }
00115 else if(event->type() == QEvent::KeyPress){
00116 QKeyEvent *key = static_cast<QKeyEvent *>(event);
00117 if(key->key() == Qt::Key_Space)
00118 onSpace();
00119 else if(key->key() == Qt::Key_R)
00120 onReset();
00121 }
00122
00123 return QObject::eventFilter(watched, event);
00124 }
00125
00126 void RemotePTAM::shutdownPlugin()
00127 {
00128 subscriber_.shutdown();
00129 cmd_pub_.shutdown();
00130 }
00131
00132 void RemotePTAM::saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const
00133 {
00134 QString topic = ui_.topics_combo_box->currentText();
00135
00136 instance_settings.setValue("topic", topic);
00137 instance_settings.setValue("zoom1", ui_.zoom_1_push_button->isChecked());
00138 }
00139
00140 void RemotePTAM::restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings)
00141 {
00142 bool zoom1_checked = instance_settings.value("zoom1", false).toBool();
00143 ui_.zoom_1_push_button->setChecked(zoom1_checked);
00144
00145 QString topic = instance_settings.value("topic", "").toString();
00146
00147 selectTopic(topic);
00148 }
00149
00150 void RemotePTAM::updateNamespaceList()
00151 {
00152 QSet<QString> message_types;
00153 QList<QString> transports;
00154 message_types.insert("ptam_com/ptam_info");
00155
00156 QString selected = ui_.topics_combo_box->currentText();
00157
00158
00159 QList<QString> topics = getTopicList(message_types, transports);
00160 topics.append("");
00161 qSort(topics);
00162 ui_.topics_combo_box->clear();
00163 for (QList<QString>::const_iterator it = topics.begin(); it != topics.end(); it++)
00164 {
00165
00166 QString label(*it);
00167 label.replace(" ", "/");
00168 label.replace("/info", "");
00169
00170
00171 ui_.topics_combo_box->addItem(label, QVariant(label));
00172 }
00173
00174
00175 selectTopic(selected);
00176 }
00177
00178 QList<QString> RemotePTAM::getTopicList(const QSet<QString>& message_types, const QList<QString>& transports)
00179 {
00180 ros::master::V_TopicInfo topic_info;
00181 ros::master::getTopics(topic_info);
00182
00183 QSet<QString> all_topics;
00184 for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++)
00185 {
00186 all_topics.insert(it->name.c_str());
00187 }
00188
00189 QList<QString> topics;
00190 for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++)
00191 {
00192 if (message_types.contains(it->datatype.c_str()))
00193 {
00194 QString topic = it->name.c_str();
00195
00196
00197 topics.append(topic);
00198
00199
00200
00201 for (QList<QString>::const_iterator jt = transports.begin(); jt != transports.end(); jt++)
00202 {
00203 if (all_topics.contains(topic + "/" + *jt))
00204 {
00205 QString sub = topic + " " + *jt;
00206 topics.append(sub);
00207
00208 }
00209 }
00210 }
00211 }
00212 return topics;
00213 }
00214
00215 void RemotePTAM::selectTopic(const QString& topic)
00216 {
00217 int index = ui_.topics_combo_box->findText(topic);
00218 if (index == -1)
00219 {
00220 index = ui_.topics_combo_box->findText("");
00221 }
00222 ui_.topics_combo_box->setCurrentIndex(index);
00223 }
00224
00225 void RemotePTAM::onNamespaceChanged(int index)
00226 {
00227 subscriber_.shutdown();
00228
00229
00230 qimage_ = QImage();
00231 ui_.image_frame->update();
00232
00233 QStringList parts = ui_.topics_combo_box->itemData(index).toString().split(" ");
00234 QString topic = parts.first();
00235
00236 std::cout<<"topic"<<topic.toStdString()<<std::endl;
00237
00238 ros::NodeHandle nh = getNodeHandle();
00239
00240 if (!topic.isEmpty())
00241 {
00242
00243 cmd_pub_ = nh.advertise<std_msgs::String>(topic.toStdString() + "/key_pressed", 10);
00244 image_transport::ImageTransport it(nh);
00245 try {
00246 subscriber_ = it.subscribe(topic.toStdString() + "/preview", 1, &RemotePTAM::callbackImage, this);
00247
00248 } catch (image_transport::TransportLoadException& e) {
00249 QMessageBox::warning(widget_, tr("Loading image transport plugin failed"), e.what());
00250 }
00251 }
00252 }
00253
00254 void RemotePTAM::onZoom1(bool checked)
00255 {
00256 if (checked)
00257 {
00258 if (qimage_.isNull())
00259 {
00260 return;
00261 }
00262 ui_.image_frame->setInnerFrameFixedSize(qimage_.size());
00263 widget_->resize(ui_.image_frame->size());
00264 widget_->setMinimumSize(widget_->sizeHint());
00265 widget_->setMaximumSize(widget_->sizeHint());
00266 } else {
00267 ui_.image_frame->setInnerFrameMinimumSize(QSize(80, 60));
00268 ui_.image_frame->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX));
00269 widget_->setMinimumSize(QSize(80, 60));
00270 widget_->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX));
00271 }
00272 }
00273
00274 void RemotePTAM::onSubscribe(bool checked)
00275 {
00276
00277 }
00278
00279 void RemotePTAM::callbackImage(const sensor_msgs::Image::ConstPtr& msg)
00280 {
00281 try
00282 {
00283
00284 cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::RGB8);
00285 conversion_mat_ = cv_ptr->image;
00286 }
00287 catch (cv_bridge::Exception& e)
00288 {
00289 ROS_WARN_STREAM("image conversion failed. Reason: "<< e.what());
00290 }
00291
00292
00293 QImage image(conversion_mat_.data, conversion_mat_.cols, conversion_mat_.rows, QImage::Format_RGB888);
00294 qimage_mutex_.lock();
00295 qimage_ = image.copy();
00296 qimage_mutex_.unlock();
00297
00298 ui_.image_frame->setAspectRatio(qimage_.width(), qimage_.height());
00299 if (!ui_.zoom_1_push_button->isEnabled())
00300 {
00301 ui_.zoom_1_push_button->setEnabled(true);
00302 onZoom1(ui_.zoom_1_push_button->isChecked());
00303 }
00304 ui_.image_frame->update();
00305 }
00306
00307 void RemotePTAM::onReset()
00308 {
00309 std::cout << "Sending \"r\" to ptam" << std::endl;
00310 std_msgs::StringPtr msg(new std_msgs::String);
00311 msg->data = "r";
00312 cmd_pub_.publish(msg);
00313 }
00314
00315 void RemotePTAM::onSpace()
00316 {
00317 std::cout << "Sending \"Space\" to ptam" << std::endl;
00318 std_msgs::StringPtr msg(new std_msgs::String);
00319 msg->data = "Space";
00320 cmd_pub_.publish(msg);
00321 }
00322
00323
00324 }
00325
00326 PLUGINLIB_EXPORT_CLASS(rqt_ptam::RemotePTAM, rqt_gui_cpp::Plugin)