43 #include <opencv2/imgproc/imgproc.hpp>
54 config_widget_(new QWidget()),
61 transport_(
"default"),
66 original_aspect_ratio_(1.0)
72 p.setColor(QPalette::Background, Qt::white);
76 QPalette p3(
ui_.status->palette());
77 p3.setColor(QPalette::Text, Qt::red);
78 ui_.status->setPalette(p3);
80 QObject::connect(
ui_.selecttopic, SIGNAL(clicked()),
this, SLOT(
SelectTopic()));
81 QObject::connect(
ui_.topic, SIGNAL(editingFinished()),
this, SLOT(
TopicEdited()));
82 QObject::connect(
ui_.anchor, SIGNAL(activated(QString)),
this, SLOT(
SetAnchor(QString)));
83 QObject::connect(
ui_.units, SIGNAL(activated(QString)),
this, SLOT(
SetUnits(QString)));
84 QObject::connect(
ui_.offsetx, SIGNAL(valueChanged(
int)),
this, SLOT(
SetOffsetX(
int)));
85 QObject::connect(
ui_.offsety, SIGNAL(valueChanged(
int)),
this, SLOT(
SetOffsetY(
int)));
86 QObject::connect(
ui_.width, SIGNAL(valueChanged(
double)),
this, SLOT(
SetWidth(
double)));
87 QObject::connect(
ui_.height, SIGNAL(valueChanged(
double)),
this, SLOT(
SetHeight(
double)));
89 QObject::connect(
ui_.keep_ratio, SIGNAL(toggled(
bool)),
this, SLOT(
KeepRatioChanged(
bool)));
90 QObject::connect(
ui_.transport_combo_box, SIGNAL(activated(
const QString&)),
92 QObject::connect(
ui_.rotation, SIGNAL(activated(QString)),
this, SLOT(
SetRotation(QString)));
94 ui_.width->setKeyboardTracking(
false);
95 ui_.height->setKeyboardTracking(
false);
124 if (anchor ==
"top left")
128 else if (anchor ==
"top center")
132 else if (anchor ==
"top right")
136 else if (anchor ==
"center left")
140 else if (anchor ==
"center")
144 else if (anchor ==
"center right")
148 else if (anchor ==
"bottom left")
152 else if (anchor ==
"bottom center")
156 else if (anchor ==
"bottom right")
165 ui_.width->setMaximum(10000);
166 ui_.height->setMaximum(10000);
168 if (units ==
"pixels")
170 ui_.width->setDecimals(0);
171 ui_.height->setDecimals(0);
175 ui_.width->setSuffix(
" px");
176 ui_.height->setSuffix(
" px");
178 else if (units ==
"percent")
180 ui_.width->setDecimals(1);
181 ui_.height->setDecimals(1);
185 ui_.width->setSuffix(
" %");
186 ui_.height->setSuffix(
" %");
193 ui_.width->setMaximum(100);
194 ui_.height->setMaximum(100);
225 if ((rotation ==
"90°") || (rotation ==
"90"))
229 else if ((rotation ==
"180°") || (rotation ==
"180"))
233 else if ((rotation ==
"270°") || (rotation ==
"270"))
235 rotation_ = cv::ROTATE_90_COUNTERCLOCKWISE;
244 ui_.height->setEnabled( !checked );
263 "sensor_msgs/Image");
265 if(topic.
name.empty())
271 if (!topic.
name.empty())
273 ui_.topic->setText(QString::fromStdString(topic.
name));
280 std::string topic =
ui_.topic->text().trimmed().toStdString();
318 ROS_DEBUG(
"Setting transport to %s on %s.",
358 if(
ui_.keep_ratio->isChecked() )
365 ui_.height->setValue(height);
414 if (image ==
NULL || image->cols == 0 || image->rows == 0)
420 switch (image->channels())
423 format = GL_LUMINANCE;
426 format = GL_LUMINANCE_ALPHA;
435 glPixelZoom(1.0
f, -1.0
f);
436 glPixelStorei(GL_UNPACK_ALIGNMENT, 1);
437 glDrawPixels(image->cols, image->rows, format, GL_UNSIGNED_BYTE, image->ptr());
438 glPixelStorei(GL_UNPACK_ALIGNMENT, 4);
460 if(
ui_.keep_ratio->isChecked() )
472 if(
rotation_ >= cv::ROTATE_90_CLOCKWISE &&
rotation_ <= cv::ROTATE_90_COUNTERCLOCKWISE){
494 x_pos = (
canvas_->width() - width) / 2.0 + x_offset;
499 x_pos =
canvas_->width() - width - x_offset;
505 y_pos = (
canvas_->height() - height) / 2.0 + y_offset;
509 x_pos = (
canvas_->width() - width) / 2.0 + x_offset;
510 y_pos = (
canvas_->height() - height) / 2.0 + y_offset;
514 x_pos =
canvas_->width() - width - x_offset;
515 y_pos = (
canvas_->height() - height) / 2.0 + y_offset;
520 y_pos =
canvas_->height() - height - y_offset;
524 x_pos = (
canvas_->width() - width) / 2.0 + x_offset;
525 y_pos =
canvas_->height() - height - y_offset;
529 x_pos =
canvas_->width() - width - x_offset;
530 y_pos =
canvas_->height() - height - y_offset;
533 glMatrixMode(GL_PROJECTION);
538 glRasterPos2d(x_pos, y_pos);
553 if (node[
"image_transport"])
556 int index =
ui_.transport_combo_box->findText( QString::fromStdString(
transport_) );
559 ui_.transport_combo_box->setCurrentIndex(index);
563 ROS_WARN(
"Saved image transport %s is unavailable.",
571 node[
"topic"] >> topic;
572 ui_.topic->setText(topic.c_str());
579 node[
"anchor"] >> anchor;
580 ui_.anchor->setCurrentIndex(
ui_.anchor->findText(anchor.c_str()));
584 if (node[
"rotation"])
586 std::string rotation;
587 node[
"rotation"] >> rotation;
588 ui_.rotation->setCurrentIndex(
ui_.rotation->findText(rotation.c_str()));
595 node[
"units"] >> units;
596 ui_.units->setCurrentIndex(
ui_.units->findText(units.c_str()));
600 if (node[
"offset_x"])
606 if (node[
"offset_y"])
624 if (node[
"keep_ratio"])
627 node[
"keep_ratio"] >> keep;
628 ui_.keep_ratio->setChecked( keep );
634 emitter << YAML::Key <<
"topic" << YAML::Value <<
ui_.topic->text().toStdString();
637 emitter << YAML::Key <<
"offset_x" << YAML::Value <<
offset_x_;
638 emitter << YAML::Key <<
"offset_y" << YAML::Value <<
offset_y_;
639 emitter << YAML::Key <<
"width" << YAML::Value <<
width_;
640 emitter << YAML::Key <<
"height" << YAML::Value <<
height_;
641 emitter << YAML::Key <<
"keep_ratio" << YAML::Value <<
ui_.keep_ratio->isChecked();
642 emitter << YAML::Key <<
"image_transport" << YAML::Value <<
transport_;
648 std::string anchor_string =
"top left";
652 anchor_string =
"top left";
656 anchor_string =
"top center";
660 anchor_string =
"top right";
664 anchor_string =
"center left";
666 else if (anchor ==
CENTER)
668 anchor_string =
"center";
672 anchor_string =
"center right";
676 anchor_string =
"bottom left";
680 anchor_string =
"bottom center";
684 anchor_string =
"bottom right";
687 return anchor_string;
692 std::string units_string =
"pixels";
696 units_string =
"pixels";
700 units_string =
"percent";
708 std::string rotation_string =
"0°";
710 if (rotation == cv::ROTATE_90_CLOCKWISE) { rotation_string =
"90°"; }
711 else if (rotation == cv::ROTATE_180) { rotation_string =
"180°"; }
712 else if (rotation == cv::ROTATE_90_COUNTERCLOCKWISE) { rotation_string =
"270°"; }
714 return rotation_string;
724 snprintf(buf,
sizeof(buf),
"image_%llu", (
unsigned long long)
ros::WallTime::now().toNSec());
736 Q_FOREACH (
const std::string& transport, transports)
738 QString qtransport = QString::fromStdString(transport).replace(
"image_transport/",
"");
739 ui_.transport_combo_box->addItem(qtransport);