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/robot_image_plugin.h>
00031
00032
00033 #include <cstdio>
00034 #include <algorithm>
00035 #include <vector>
00036
00037
00038 #include <QGLWidget>
00039 #include <QPalette>
00040 #include <QImage>
00041 #include <QFileDialog>
00042
00043
00044 #include <ros/master.h>
00045
00046 #include <mapviz/select_frame_dialog.h>
00047
00048
00049 #include <pluginlib/class_list_macros.h>
00050 PLUGINLIB_EXPORT_CLASS(mapviz_plugins::RobotImagePlugin, mapviz::MapvizPlugin)
00051
00052 namespace mapviz_plugins
00053 {
00054 RobotImagePlugin::RobotImagePlugin() :
00055 config_widget_(new QWidget()),
00056 width_(2.0),
00057 height_(1.0),
00058 offset_x_(0.0),
00059 offset_y_(0.0),
00060 texture_loaded_(false),
00061 transformed_(false)
00062 {
00063 ui_.setupUi(config_widget_);
00064
00065
00066 QPalette p(config_widget_->palette());
00067 p.setColor(QPalette::Background, Qt::white);
00068 config_widget_->setPalette(p);
00069
00070
00071 QPalette p3(ui_.status->palette());
00072 p3.setColor(QPalette::Text, Qt::red);
00073 ui_.status->setPalette(p3);
00074
00075 UpdateShape();
00076
00077 QObject::connect(ui_.browse, SIGNAL(clicked()), this, SLOT(SelectFile()));
00078 QObject::connect(ui_.selectframe, SIGNAL(clicked()), this, SLOT(SelectFrame()));
00079 QObject::connect(ui_.frame, SIGNAL(editingFinished()), this, SLOT(FrameEdited()));
00080 QObject::connect(ui_.width, SIGNAL(valueChanged(double)), this, SLOT(WidthChanged(double)));
00081 QObject::connect(ui_.height, SIGNAL(valueChanged(double)), this, SLOT(HeightChanged(double)));
00082 QObject::connect(ui_.offset_x, SIGNAL(valueChanged(double)), this, SLOT(OffsetXChanged(double)));
00083 QObject::connect(ui_.offset_y, SIGNAL(valueChanged(double)), this, SLOT(OffsetYChanged(double)));
00084
00085 ui_.offset_x->setMinimum(-99.99);
00086 ui_.offset_y->setMinimum(-99.99);
00087 }
00088
00089 RobotImagePlugin::~RobotImagePlugin()
00090 {
00091 }
00092
00093 void RobotImagePlugin::SelectFile()
00094 {
00095 QFileDialog dialog(config_widget_, "Select PNG Image");
00096 dialog.setFileMode(QFileDialog::ExistingFile);
00097 dialog.setNameFilter(tr("PNG Image Files (*.png)"));
00098
00099 dialog.exec();
00100
00101 if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
00102 {
00103 ui_.image->setText(dialog.selectedFiles().first());
00104 filename_ = dialog.selectedFiles().first().toStdString();
00105 LoadImage();
00106 }
00107 }
00108
00109 void RobotImagePlugin::SelectFrame()
00110 {
00111 std::string frame = mapviz::SelectFrameDialog::selectFrame(tf_);
00112 if (!frame.empty())
00113 {
00114 ui_.frame->setText(QString::fromStdString(frame));
00115 FrameEdited();
00116 }
00117 }
00118
00119 void RobotImagePlugin::FrameEdited()
00120 {
00121 source_frame_ = ui_.frame->text().toStdString();
00122 PrintWarning("Waiting for transform.");
00123
00124 ROS_INFO("Setting target frame to to %s", source_frame_.c_str());
00125
00126 initialized_ = true;
00127
00128 UpdateShape();
00129 }
00130
00131 void RobotImagePlugin::WidthChanged(double value)
00132 {
00133 width_ = value;
00134 UpdateShape();
00135 }
00136
00137 void RobotImagePlugin::HeightChanged(double value)
00138 {
00139 height_ = value;
00140 UpdateShape();
00141 }
00142
00143 void RobotImagePlugin::OffsetXChanged(double value)
00144 {
00145 offset_x_ = value;
00146 UpdateShape();
00147 }
00148
00149 void RobotImagePlugin::OffsetYChanged(double value)
00150 {
00151 offset_y_ = value;
00152 UpdateShape();
00153 }
00154
00155 void RobotImagePlugin::UpdateShape()
00156 {
00157 double hw = 0.5*width_;
00158 double hh = 0.5*height_;
00159 top_left_ = tf::Point(offset_x_ - hw, offset_y_ + hh, 0);
00160 top_right_ = tf::Point(offset_x_ + hw, offset_y_ + hh, 0);
00161 bottom_left_ = tf::Point(offset_x_ - hw, offset_y_ - hh, 0);
00162 bottom_right_ = tf::Point(offset_x_ + hw, offset_y_ - hh, 0);
00163 }
00164
00165 void RobotImagePlugin::PrintError(const std::string& message)
00166 {
00167 PrintErrorHelper(ui_.status, message);
00168 }
00169
00170 void RobotImagePlugin::PrintInfo(const std::string& message)
00171 {
00172 PrintInfoHelper(ui_.status, message);
00173 }
00174
00175 void RobotImagePlugin::PrintWarning(const std::string& message)
00176 {
00177 PrintWarningHelper(ui_.status, message);
00178 }
00179
00180 QWidget* RobotImagePlugin::GetConfigWidget(QWidget* parent)
00181 {
00182 config_widget_->setParent(parent);
00183
00184 return config_widget_;
00185 }
00186
00187 bool RobotImagePlugin::Initialize(QGLWidget* canvas)
00188 {
00189 canvas_ = canvas;
00190
00191 return true;
00192 }
00193
00194 void RobotImagePlugin::Draw(double x, double y, double scale)
00195 {
00196 if (texture_loaded_ && transformed_)
00197 {
00198 glColor3f(1.0f, 1.0f, 1.0f);
00199 glEnable(GL_TEXTURE_2D);
00200 glBindTexture(GL_TEXTURE_2D, static_cast<GLuint>(texture_id_));
00201
00202 glBegin(GL_QUADS);
00203
00204
00205 glTexCoord2f(0, 1); glVertex2d(top_left_transformed_.x(), top_left_transformed_.y());
00206 glTexCoord2f(1, 1); glVertex2d(top_right_transformed_.x(), top_right_transformed_.y());
00207 glTexCoord2f(1, 0); glVertex2d(bottom_right_transformed_.x(), bottom_right_transformed_.y());
00208 glTexCoord2f(0, 0); glVertex2d(bottom_left_transformed_.x(), bottom_left_transformed_.y());
00209
00210 glEnd();
00211
00212 glDisable(GL_TEXTURE_2D);
00213
00214 PrintInfo("OK");
00215 }
00216 }
00217
00218 void RobotImagePlugin::Transform()
00219 {
00220 transformed_ = false;
00221
00222 swri_transform_util::Transform transform;
00223 if (GetTransform(ros::Time(), transform))
00224 {
00225 top_left_transformed_ = transform * top_left_;
00226 top_right_transformed_ = transform * top_right_;
00227 bottom_left_transformed_ = transform * bottom_left_;
00228 bottom_right_transformed_ = transform * bottom_right_;
00229 transformed_ = true;
00230 }
00231 else
00232 {
00233 PrintError("No transform between " + source_frame_ + " and " + target_frame_);
00234 }
00235 }
00236
00237 void RobotImagePlugin::LoadImage()
00238 {
00239 ROS_INFO("Loading image");
00240 try
00241 {
00242 QImage nullImage;
00243 image_ = nullImage;
00244
00245 if (texture_loaded_)
00246 {
00247 GLuint ids[1];
00248 ids[0] = static_cast<GLuint>(texture_id_);
00249 glDeleteTextures(1, &ids[0]);
00250 texture_loaded_ = false;
00251 }
00252
00253 if (image_.load(filename_.c_str()))
00254 {
00255 int width = image_.width();
00256 int height = image_.height();
00257
00258 float max_dim = std::max(width, height);
00259 dimension_ = static_cast<int>(std::pow(2, std::ceil(std::log(max_dim) / std::log(2.0f))));
00260
00261 if (width != dimension_ || height != dimension_)
00262 {
00263 image_ = image_.scaled(dimension_, dimension_, Qt::IgnoreAspectRatio, Qt::FastTransformation);
00264 }
00265
00266 image_ = QGLWidget::convertToGLFormat(image_);
00267
00268 GLuint ids[1];
00269 glGenTextures(1, &ids[0]);
00270 texture_id_ = ids[0];
00271
00272 glBindTexture(GL_TEXTURE_2D, static_cast<GLuint>(texture_id_));
00273 glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, dimension_, dimension_, 0, GL_RGBA, GL_UNSIGNED_BYTE, image_.bits());
00274
00275 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);
00276 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
00277
00278 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
00279 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
00280
00281 texture_loaded_ = true;
00282 }
00283 else
00284 {
00285 PrintError("Failed to load image.");
00286 }
00287 }
00288 catch (const std::exception& e)
00289 {
00290 PrintError("Failed to load image. Exception occured.");
00291 }
00292 }
00293
00294 void RobotImagePlugin::LoadConfig(const YAML::Node& node, const std::string& path)
00295 {
00296 if (node["frame"])
00297 {
00298 node["frame"] >> source_frame_;
00299 ui_.frame->setText(source_frame_.c_str());
00300 }
00301
00302 if (node["image"])
00303 {
00304 node["image"] >> filename_;
00305 ui_.image->setText(filename_.c_str());
00306 }
00307
00308 if (node["width"])
00309 {
00310 node["width"] >> width_;
00311 ui_.width->setValue(width_);
00312 }
00313
00314 if (node["height"])
00315 {
00316 node["height"] >> height_;
00317 ui_.height->setValue(height_);
00318 }
00319
00320 if (node["offset_x"])
00321 {
00322 node["offset_x"] >> offset_x_;
00323 ui_.offset_x->setValue(offset_x_);
00324 }
00325
00326 if (node["offset_y"])
00327 {
00328 node["offset_y"] >> offset_y_;
00329 ui_.offset_y->setValue(offset_y_);
00330 }
00331
00332 UpdateShape();
00333 LoadImage();
00334 FrameEdited();
00335 }
00336
00337 void RobotImagePlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
00338 {
00339 emitter << YAML::Key << "frame" << YAML::Value << ui_.frame->text().toStdString();
00340 emitter << YAML::Key << "image" << YAML::Value << ui_.image->text().toStdString();
00341 emitter << YAML::Key << "width" << YAML::Value << width_;
00342 emitter << YAML::Key << "height" << YAML::Value << height_;
00343 emitter << YAML::Key << "offset_x" << YAML::Value << offset_x_;
00344 emitter << YAML::Key << "offset_y" << YAML::Value << offset_y_;
00345 }
00346 }
00347