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 #include <mapviz_plugins/image_plugin.h>
00031
00032
00033 #include <cstdio>
00034 #include <vector>
00035
00036
00037 #include <QDialog>
00038 #include <QGLWidget>
00039
00040
00041 #include <ros/master.h>
00042 #include <sensor_msgs/image_encodings.h>
00043 #include <opencv2/imgproc/imgproc.hpp>
00044
00045 #include <mapviz/select_topic_dialog.h>
00046
00047
00048 #include <pluginlib/class_list_macros.h>
00049 PLUGINLIB_EXPORT_CLASS(mapviz_plugins::ImagePlugin, mapviz::MapvizPlugin)
00050
00051 namespace mapviz_plugins
00052 {
00053 ImagePlugin::ImagePlugin() :
00054 config_widget_(new QWidget()),
00055 anchor_(TOP_LEFT),
00056 units_(PIXELS),
00057 offset_x_(0),
00058 offset_y_(0),
00059 width_(320),
00060 height_(240),
00061 transport_("default"),
00062 has_image_(false),
00063 last_width_(0),
00064 last_height_(0),
00065 original_aspect_ratio_(1.0)
00066 {
00067 ui_.setupUi(config_widget_);
00068
00069
00070 QPalette p(config_widget_->palette());
00071 p.setColor(QPalette::Background, Qt::white);
00072 config_widget_->setPalette(p);
00073
00074
00075 QPalette p3(ui_.status->palette());
00076 p3.setColor(QPalette::Text, Qt::red);
00077 ui_.status->setPalette(p3);
00078
00079 QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic()));
00080 QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited()));
00081 QObject::connect(ui_.anchor, SIGNAL(activated(QString)), this, SLOT(SetAnchor(QString)));
00082 QObject::connect(ui_.units, SIGNAL(activated(QString)), this, SLOT(SetUnits(QString)));
00083 QObject::connect(ui_.offsetx, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetX(int)));
00084 QObject::connect(ui_.offsety, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetY(int)));
00085 QObject::connect(ui_.width, SIGNAL(valueChanged(double)), this, SLOT(SetWidth(double)));
00086 QObject::connect(ui_.height, SIGNAL(valueChanged(double)), this, SLOT(SetHeight(double)));
00087 QObject::connect(this,SIGNAL(VisibleChanged(bool)),this,SLOT(SetSubscription(bool)));
00088 QObject::connect(ui_.keep_ratio, SIGNAL(toggled(bool)), this, SLOT(KeepRatioChanged(bool)));
00089 QObject::connect(ui_.transport_combo_box, SIGNAL(activated(const QString&)),
00090 this, SLOT(SetTransport(const QString&)));
00091
00092 ui_.width->setKeyboardTracking(false);
00093 ui_.height->setKeyboardTracking(false);
00094 }
00095
00096 ImagePlugin::~ImagePlugin()
00097 {
00098 }
00099
00100 void ImagePlugin::SetOffsetX(int offset)
00101 {
00102 offset_x_ = offset;
00103 }
00104
00105 void ImagePlugin::SetOffsetY(int offset)
00106 {
00107 offset_y_ = offset;
00108 }
00109
00110 void ImagePlugin::SetWidth(double width)
00111 {
00112 width_ = width;
00113 }
00114
00115 void ImagePlugin::SetHeight(double height)
00116 {
00117 height_ = height;
00118 }
00119
00120 void ImagePlugin::SetAnchor(QString anchor)
00121 {
00122 if (anchor == "top left")
00123 {
00124 anchor_ = TOP_LEFT;
00125 }
00126 else if (anchor == "top center")
00127 {
00128 anchor_ = TOP_CENTER;
00129 }
00130 else if (anchor == "top right")
00131 {
00132 anchor_ = TOP_RIGHT;
00133 }
00134 else if (anchor == "center left")
00135 {
00136 anchor_ = CENTER_LEFT;
00137 }
00138 else if (anchor == "center")
00139 {
00140 anchor_ = CENTER;
00141 }
00142 else if (anchor == "center right")
00143 {
00144 anchor_ = CENTER_RIGHT;
00145 }
00146 else if (anchor == "bottom left")
00147 {
00148 anchor_ = BOTTOM_LEFT;
00149 }
00150 else if (anchor == "bottom center")
00151 {
00152 anchor_ = BOTTOM_CENTER;
00153 }
00154 else if (anchor == "bottom right")
00155 {
00156 anchor_ = BOTTOM_RIGHT;
00157 }
00158 }
00159
00160 void ImagePlugin::SetUnits(QString units)
00161 {
00162
00163 ui_.width->setMaximum(10000);
00164 ui_.height->setMaximum(10000);
00165
00166 if (units == "pixels")
00167 {
00168 ui_.width->setDecimals(0);
00169 ui_.height->setDecimals(0);
00170 units_ = PIXELS;
00171 width_ = width_ * double(canvas_->width()) / 100.0;
00172 height_ = height_ * double(canvas_->height()) / 100.0;
00173 ui_.width->setSuffix(" px");
00174 ui_.height->setSuffix(" px");
00175 }
00176 else if (units == "percent")
00177 {
00178 ui_.width->setDecimals(1);
00179 ui_.height->setDecimals(1);
00180 units_ = PERCENT;
00181 width_ = width_ * 100.0 / double(canvas_->width());
00182 height_ = height_ * 100.0 / double(canvas_->height());
00183 ui_.width->setSuffix(" %");
00184 ui_.height->setSuffix(" %");
00185 }
00186 ui_.width->setValue( width_ );
00187 ui_.height->setValue( height_ );
00188
00189 if( units_ == PERCENT)
00190 {
00191 ui_.width->setMaximum(100);
00192 ui_.height->setMaximum(100);
00193 }
00194
00195 }
00196 void ImagePlugin::SetSubscription(bool visible)
00197 {
00198 if(topic_.empty())
00199 {
00200 return;
00201 }
00202 else if(!visible)
00203 {
00204 image_sub_.shutdown();
00205 ROS_INFO("Dropped subscription to %s", topic_.c_str());
00206 }
00207 else
00208 {
00209 image_transport::ImageTransport it(local_node_);
00210 image_sub_ = it.subscribe(topic_, 1, &ImagePlugin::imageCallback, this);
00211
00212 ROS_INFO("Subscribing to %s", topic_.c_str());
00213 }
00214 }
00215
00216 void ImagePlugin::SetTransport(const QString& transport)
00217 {
00218 ROS_INFO("Changing image_transport to %s.", transport.toStdString().c_str());
00219 transport_ = transport;
00220 TopicEdited();
00221 }
00222
00223 void ImagePlugin::KeepRatioChanged(bool checked)
00224 {
00225 ui_.height->setEnabled( !checked );
00226 if( checked )
00227 {
00228 ui_.height->setValue( width_ * original_aspect_ratio_ );
00229 }
00230 }
00231
00232 void ImagePlugin::Resubscribe()
00233 {
00234 if (transport_ == QString::fromStdString("default"))
00235 {
00236 force_resubscribe_ = true;
00237 TopicEdited();
00238 }
00239 }
00240
00241 void ImagePlugin::SelectTopic()
00242 {
00243 ros::master::TopicInfo topic = mapviz::SelectTopicDialog::selectTopic(
00244 "sensor_msgs/Image");
00245
00246 if(topic.name.empty())
00247 {
00248 topic.name.clear();
00249 TopicEdited();
00250
00251 }
00252 if (!topic.name.empty())
00253 {
00254 ui_.topic->setText(QString::fromStdString(topic.name));
00255 TopicEdited();
00256 }
00257 }
00258
00259 void ImagePlugin::TopicEdited()
00260 {
00261 std::string topic = ui_.topic->text().trimmed().toStdString();
00262 if(!this->Visible())
00263 {
00264 PrintWarning("Topic is Hidden");
00265 initialized_ = false;
00266 has_message_ = false;
00267 if (!topic.empty())
00268 {
00269 topic_ = topic;
00270 }
00271 image_sub_.shutdown();
00272 return;
00273 }
00274
00275
00276 if (force_resubscribe_ ||
00277 topic != topic_ ||
00278 image_sub_.getTransport() != transport_.toStdString())
00279 {
00280 force_resubscribe_ = false;
00281 initialized_ = false;
00282 has_message_ = false;
00283 topic_ = topic;
00284 PrintWarning("No messages received.");
00285
00286 image_sub_.shutdown();
00287
00288 if (!topic_.empty())
00289 {
00290 boost::shared_ptr<image_transport::ImageTransport> it;
00291 if (transport_ == QString::fromStdString("default"))
00292 {
00293 ROS_DEBUG("Using default transport.");
00294 it = boost::make_shared<image_transport::ImageTransport>(node_);
00295 image_sub_ = it->subscribe(topic_, 1, &ImagePlugin::imageCallback, this);
00296 }
00297 else
00298 {
00299 ROS_DEBUG("Setting transport to %s on %s.",
00300 transport_.toStdString().c_str(), local_node_.getNamespace().c_str());
00301
00302 local_node_.setParam("image_transport", transport_.toStdString());
00303 it = boost::make_shared<image_transport::ImageTransport>(local_node_);
00304 image_sub_ = it->subscribe(topic_, 1, &ImagePlugin::imageCallback, this,
00305 image_transport::TransportHints(transport_.toStdString(),
00306 ros::TransportHints(),
00307 local_node_));
00308 }
00309
00310 ROS_INFO("Subscribing to %s", topic_.c_str());
00311 }
00312 }
00313 }
00314
00315 void ImagePlugin::imageCallback(const sensor_msgs::ImageConstPtr& image)
00316 {
00317 if (!has_message_)
00318 {
00319 initialized_ = true;
00320 has_message_ = true;
00321 }
00322
00323 image_ = *image;
00324
00325 try
00326 {
00327 cv_image_ = cv_bridge::toCvCopy(image, sensor_msgs::image_encodings::BGR8);
00328 }
00329 catch (const cv_bridge::Exception& e)
00330 {
00331 PrintError(e.what());
00332 return;
00333 }
00334
00335 last_width_ = 0;
00336 last_height_ = 0;
00337 original_aspect_ratio_ = (double)image->height / (double)image->width;
00338
00339 if( ui_.keep_ratio->isChecked() )
00340 {
00341 double height = width_ * original_aspect_ratio_;
00342 if (units_ == PERCENT)
00343 {
00344 height *= (double)canvas_->width() / (double)canvas_->height();
00345 }
00346 ui_.height->setValue(height);
00347 }
00348
00349 has_image_ = true;
00350 }
00351
00352 void ImagePlugin::PrintError(const std::string& message)
00353 {
00354 PrintErrorHelper(ui_.status, message);
00355 }
00356
00357 void ImagePlugin::PrintInfo(const std::string& message)
00358 {
00359 PrintInfoHelper(ui_.status, message);
00360 }
00361
00362 void ImagePlugin::PrintWarning(const std::string& message)
00363 {
00364 PrintWarningHelper(ui_.status, message);
00365 }
00366
00367 QWidget* ImagePlugin::GetConfigWidget(QWidget* parent)
00368 {
00369 config_widget_->setParent(parent);
00370
00371 return config_widget_;
00372 }
00373
00374 bool ImagePlugin::Initialize(QGLWidget* canvas)
00375 {
00376 canvas_ = canvas;
00377
00378 return true;
00379 }
00380
00381 void ImagePlugin::ScaleImage(double width, double height)
00382 {
00383 if (!has_image_)
00384 {
00385 return;
00386 }
00387
00388 cv::resize(cv_image_->image, scaled_image_, cvSize2D32f(width, height), 0, 0, CV_INTER_AREA);
00389 }
00390
00391 void ImagePlugin::DrawIplImage(cv::Mat *image)
00392 {
00393
00394
00395 if (image == NULL || image->cols == 0 || image->rows == 0)
00396 {
00397 return;
00398 }
00399
00400 GLenum format;
00401 switch (image->channels())
00402 {
00403 case 1:
00404 format = GL_LUMINANCE;
00405 break;
00406 case 2:
00407 format = GL_LUMINANCE_ALPHA;
00408 break;
00409 case 3:
00410 format = GL_BGR;
00411 break;
00412 default:
00413 return;
00414 }
00415
00416 glPixelZoom(1.0f, -1.0f);
00417 glPixelStorei(GL_UNPACK_ALIGNMENT, 1);
00418 glDrawPixels(image->cols, image->rows, format, GL_UNSIGNED_BYTE, image->ptr());
00419
00420 PrintInfo("OK");
00421 }
00422
00423 void ImagePlugin::Draw(double x, double y, double scale)
00424 {
00425
00426 double x_offset = offset_x_;
00427 double y_offset = offset_y_;
00428 double width = width_;
00429 double height = height_;
00430
00431 if (units_ == PERCENT)
00432 {
00433 x_offset = offset_x_ * canvas_->width() / 100.0;
00434 y_offset = offset_y_ * canvas_->height() / 100.0;
00435 width = width_ * canvas_->width() / 100.0;
00436 height = height_ * canvas_->height() / 100.0;
00437 }
00438
00439 if( ui_.keep_ratio->isChecked() )
00440 {
00441 height = original_aspect_ratio_ * width;
00442 }
00443
00444
00445 if (width != last_width_ || height != last_height_)
00446 {
00447 ScaleImage(width, height);
00448 }
00449
00450
00451 double x_pos = 0;
00452 double y_pos = 0;
00453 if (anchor_ == TOP_LEFT)
00454 {
00455 x_pos = x_offset;
00456 y_pos = y_offset;
00457 }
00458 else if (anchor_ == TOP_CENTER)
00459 {
00460 x_pos = (canvas_->width() - width) / 2.0 + x_offset;
00461 y_pos = y_offset;
00462 }
00463 else if (anchor_ == TOP_RIGHT)
00464 {
00465 x_pos = canvas_->width() - width - x_offset;
00466 y_pos = y_offset;
00467 }
00468 else if (anchor_ == CENTER_LEFT)
00469 {
00470 x_pos = x_offset;
00471 y_pos = (canvas_->height() - height) / 2.0 + y_offset;
00472 }
00473 else if (anchor_ == CENTER)
00474 {
00475 x_pos = (canvas_->width() - width) / 2.0 + x_offset;
00476 y_pos = (canvas_->height() - height) / 2.0 + y_offset;
00477 }
00478 else if (anchor_ == CENTER_RIGHT)
00479 {
00480 x_pos = canvas_->width() - width - x_offset;
00481 y_pos = (canvas_->height() - height) / 2.0 + y_offset;
00482 }
00483 else if (anchor_ == BOTTOM_LEFT)
00484 {
00485 x_pos = x_offset;
00486 y_pos = canvas_->height() - height - y_offset;
00487 }
00488 else if (anchor_ == BOTTOM_CENTER)
00489 {
00490 x_pos = (canvas_->width() - width) / 2.0 + x_offset;
00491 y_pos = canvas_->height() - height - y_offset;
00492 }
00493 else if (anchor_ == BOTTOM_RIGHT)
00494 {
00495 x_pos = canvas_->width() - width - x_offset;
00496 y_pos = canvas_->height() - height - y_offset;
00497 }
00498
00499 glMatrixMode(GL_PROJECTION);
00500 glPushMatrix();
00501 glLoadIdentity();
00502 glOrtho(0, canvas_->width(), canvas_->height(), 0, -0.5f, 0.5f);
00503
00504 glRasterPos2d(x_pos, y_pos);
00505
00506 DrawIplImage(&scaled_image_);
00507
00508 glPopMatrix();
00509
00510 last_width_ = width;
00511 last_height_ = height;
00512 }
00513
00514 void ImagePlugin::LoadConfig(const YAML::Node& node, const std::string& path)
00515 {
00516
00517
00518
00519 if (node["image_transport"])
00520 {
00521 std::string transport;
00522 node["image_transport"] >> transport;
00523 transport_ = QString::fromStdString(transport);
00524 int index = ui_.transport_combo_box->findText(transport_);
00525 if (index != -1)
00526 {
00527 ui_.transport_combo_box->setCurrentIndex(index);
00528 }
00529 else
00530 {
00531 ROS_WARN("Saved image transport %s is unavailable.",
00532 transport_.toStdString().c_str());
00533 }
00534 }
00535
00536 if (node["topic"])
00537 {
00538 std::string topic;
00539 node["topic"] >> topic;
00540 ui_.topic->setText(topic.c_str());
00541 TopicEdited();
00542 }
00543
00544 if (node["anchor"])
00545 {
00546 std::string anchor;
00547 node["anchor"] >> anchor;
00548 ui_.anchor->setCurrentIndex(ui_.anchor->findText(anchor.c_str()));
00549 SetAnchor(anchor.c_str());
00550 }
00551
00552 if (node["units"])
00553 {
00554 std::string units;
00555 node["units"] >> units;
00556 ui_.units->setCurrentIndex(ui_.units->findText(units.c_str()));
00557 SetUnits(units.c_str());
00558 }
00559
00560 if (node["offset_x"])
00561 {
00562 node["offset_x"] >> offset_x_;
00563 ui_.offsetx->setValue(offset_x_);
00564 }
00565
00566 if (node["offset_y"])
00567 {
00568 node["offset_y"] >> offset_y_;
00569 ui_.offsety->setValue(offset_y_);
00570 }
00571
00572 if (node["width"])
00573 {
00574 node["width"] >> width_;
00575 ui_.width->setValue(width_);
00576 }
00577
00578 if (node["height"])
00579 {
00580 node["height"] >> height_;
00581 ui_.height->setValue(height_);
00582 }
00583
00584 if (node["keep_ratio"])
00585 {
00586 bool keep;
00587 node["keep_ratio"] >> keep;
00588 ui_.keep_ratio->setChecked( keep );
00589 }
00590 }
00591
00592 void ImagePlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
00593 {
00594 emitter << YAML::Key << "topic" << YAML::Value << ui_.topic->text().toStdString();
00595 emitter << YAML::Key << "anchor" << YAML::Value << AnchorToString(anchor_);
00596 emitter << YAML::Key << "units" << YAML::Value << UnitsToString(units_);
00597 emitter << YAML::Key << "offset_x" << YAML::Value << offset_x_;
00598 emitter << YAML::Key << "offset_y" << YAML::Value << offset_y_;
00599 emitter << YAML::Key << "width" << YAML::Value << width_;
00600 emitter << YAML::Key << "height" << YAML::Value << height_;
00601 emitter << YAML::Key << "keep_ratio" << YAML::Value << ui_.keep_ratio->isChecked();
00602 emitter << YAML::Key << "image_transport" << YAML::Value << transport_.toStdString();
00603 }
00604
00605 std::string ImagePlugin::AnchorToString(Anchor anchor)
00606 {
00607 std::string anchor_string = "top left";
00608
00609 if (anchor == TOP_LEFT)
00610 {
00611 anchor_string = "top left";
00612 }
00613 else if (anchor == TOP_CENTER)
00614 {
00615 anchor_string = "top center";
00616 }
00617 else if (anchor == TOP_RIGHT)
00618 {
00619 anchor_string = "top right";
00620 }
00621 else if (anchor == CENTER_LEFT)
00622 {
00623 anchor_string = "center left";
00624 }
00625 else if (anchor == CENTER)
00626 {
00627 anchor_string = "center";
00628 }
00629 else if (anchor == CENTER_RIGHT)
00630 {
00631 anchor_string = "center right";
00632 }
00633 else if (anchor == BOTTOM_LEFT)
00634 {
00635 anchor_string = "bottom left";
00636 }
00637 else if (anchor == BOTTOM_CENTER)
00638 {
00639 anchor_string = "bottom center";
00640 }
00641 else if (anchor == BOTTOM_RIGHT)
00642 {
00643 anchor_string = "bottom right";
00644 }
00645
00646 return anchor_string;
00647 }
00648
00649 std::string ImagePlugin::UnitsToString(Units units)
00650 {
00651 std::string units_string = "pixels";
00652
00653 if (units == PIXELS)
00654 {
00655 units_string = "pixels";
00656 }
00657 else if (units == PERCENT)
00658 {
00659 units_string = "percent";
00660 }
00661
00662 return units_string;
00663 }
00664
00665 void ImagePlugin::CreateLocalNode()
00666 {
00667
00668
00669
00670
00671 char buf[200];
00672 snprintf(buf, sizeof(buf), "image_%llu", (unsigned long long)ros::WallTime::now().toNSec());
00673 local_node_ = ros::NodeHandle(node_, buf);
00674 }
00675
00676 void ImagePlugin::SetNode(const ros::NodeHandle& node)
00677 {
00678 node_ = node;
00679
00680
00681
00682 image_transport::ImageTransport it(node_);
00683 std::vector<std::string> transports = it.getLoadableTransports();
00684 Q_FOREACH (const std::string& transport, transports)
00685 {
00686 QString qtransport = QString::fromStdString(transport).replace("image_transport/", "");
00687 ui_.transport_combo_box->addItem(qtransport);
00688 }
00689
00690 CreateLocalNode();
00691 }
00692 }
00693