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/grid_plugin.h>
00031
00032
00033 #include <cstdio>
00034 #include <vector>
00035
00036 #include <boost/lexical_cast.hpp>
00037
00038
00039 #include <QGLWidget>
00040 #include <QPalette>
00041
00042 #include <mapviz/select_frame_dialog.h>
00043
00044
00045 #include <pluginlib/class_list_macros.h>
00046 PLUGINLIB_EXPORT_CLASS(mapviz_plugins::GridPlugin, mapviz::MapvizPlugin)
00047
00048 namespace mapviz_plugins
00049 {
00050 GridPlugin::GridPlugin() :
00051 config_widget_(new QWidget()),
00052 alpha_(1.0),
00053 top_left_(0, 0, 0),
00054 size_(1),
00055 rows_(1),
00056 columns_(1),
00057 transformed_(false)
00058 {
00059 ui_.setupUi(config_widget_);
00060
00061 ui_.color->setColor(Qt::red);
00062
00063
00064 QPalette p(config_widget_->palette());
00065 p.setColor(QPalette::Background, Qt::white);
00066 config_widget_->setPalette(p);
00067
00068
00069 QPalette p3(ui_.status->palette());
00070 p3.setColor(QPalette::Text, Qt::red);
00071 ui_.status->setPalette(p3);
00072
00073 QObject::connect(ui_.select_frame, SIGNAL(clicked()), this, SLOT(SelectFrame()));
00074 QObject::connect(ui_.frame, SIGNAL(textEdited(const QString&)), this, SLOT(FrameEdited()));
00075 QObject::connect(ui_.alpha, SIGNAL(valueChanged(double)), this, SLOT(SetAlpha(double)));
00076 QObject::connect(ui_.x, SIGNAL(valueChanged(double)), this, SLOT(SetX(double)));
00077 QObject::connect(ui_.y, SIGNAL(valueChanged(double)), this, SLOT(SetY(double)));
00078 QObject::connect(ui_.size, SIGNAL(valueChanged(double)), this, SLOT(SetSize(double)));
00079 QObject::connect(ui_.rows, SIGNAL(valueChanged(int)), this, SLOT(SetRows(int)));
00080 QObject::connect(ui_.columns, SIGNAL(valueChanged(int)), this, SLOT(SetColumns(int)));
00081 connect(ui_.color, SIGNAL(colorEdited(const QColor &)), this, SLOT(DrawIcon()));
00082 }
00083
00084 GridPlugin::~GridPlugin()
00085 {
00086 Shutdown();
00087 }
00088
00089 void GridPlugin::Shutdown()
00090 {
00091 }
00092
00093 void GridPlugin::DrawIcon()
00094 {
00095 if (icon_)
00096 {
00097 QPixmap icon(16, 16);
00098 icon.fill(Qt::transparent);
00099
00100 QPainter painter(&icon);
00101 painter.setRenderHint(QPainter::Antialiasing, true);
00102
00103 QPen pen(QColor(ui_.color->color()));
00104
00105 pen.setWidth(2);
00106 pen.setCapStyle(Qt::SquareCap);
00107 painter.setPen(pen);
00108
00109 painter.drawLine(2, 2, 14, 2);
00110 painter.drawLine(2, 2, 2, 14);
00111 painter.drawLine(14, 2, 14, 14);
00112 painter.drawLine(2, 14, 14, 14);
00113 painter.drawLine(8, 2, 8, 14);
00114 painter.drawLine(2, 8, 14, 8);
00115
00116 icon_->SetPixmap(icon);
00117 }
00118 }
00119
00120 void GridPlugin::SetAlpha(double alpha)
00121 {
00122 alpha_ = alpha;
00123 }
00124
00125 void GridPlugin::SetX(double x)
00126 {
00127 top_left_.setX(x);
00128
00129 RecalculateGrid();
00130 }
00131
00132 void GridPlugin::SetY(double y)
00133 {
00134 top_left_.setY(y);
00135
00136 RecalculateGrid();
00137 }
00138
00139 void GridPlugin::SetSize(double size)
00140 {
00141 size_ = size;
00142
00143 RecalculateGrid();
00144 }
00145
00146 void GridPlugin::SetRows(int rows)
00147 {
00148 rows_ = rows;
00149
00150 RecalculateGrid();
00151 }
00152
00153 void GridPlugin::SetColumns(int columns)
00154 {
00155 columns_ = columns;
00156
00157 RecalculateGrid();
00158 }
00159
00160 void GridPlugin::SelectFrame()
00161 {
00162 std::string frame = mapviz::SelectFrameDialog::selectFrame(tf_);
00163 if (!frame.empty())
00164 {
00165 ui_.frame->setText(QString::fromStdString(frame));
00166 FrameEdited();
00167 }
00168 }
00169
00170 void GridPlugin::FrameEdited()
00171 {
00172 source_frame_ = ui_.frame->text().toStdString();
00173
00174 initialized_ = true;
00175
00176 RecalculateGrid();
00177 }
00178
00179 void GridPlugin::PrintError(const std::string& message)
00180 {
00181 PrintErrorHelper(ui_.status, message);
00182 }
00183
00184 void GridPlugin::PrintInfo(const std::string& message)
00185 {
00186 PrintInfoHelper(ui_.status, message);
00187 }
00188
00189 void GridPlugin::PrintWarning(const std::string& message)
00190 {
00191 PrintWarningHelper(ui_.status, message);
00192 }
00193
00194 QWidget* GridPlugin::GetConfigWidget(QWidget* parent)
00195 {
00196 config_widget_->setParent(parent);
00197
00198 return config_widget_;
00199 }
00200
00201 bool GridPlugin::Initialize(QGLWidget* canvas)
00202 {
00203 canvas_ = canvas;
00204
00205 DrawIcon();
00206
00207 return true;
00208 }
00209
00210 void GridPlugin::Draw(double x, double y, double scale)
00211 {
00212 if (transformed_)
00213 {
00214 QColor color = ui_.color->color();
00215
00216 glLineWidth(3);
00217 glColor4d(color.redF(), color.greenF(), color.blueF(), alpha_);
00218 glBegin(GL_LINES);
00219
00220 std::list<tf::Point>::iterator transformed_left_it = transformed_left_points_.begin();
00221 std::list<tf::Point>::iterator transformed_right_it = transformed_right_points_.begin();
00222 for (; transformed_left_it != transformed_left_points_.end(); ++transformed_left_it)
00223 {
00224 glVertex2d(transformed_left_it->getX(), transformed_left_it->getY());
00225 glVertex2d(transformed_right_it->getX(), transformed_right_it->getY());
00226
00227 ++transformed_right_it;
00228 }
00229
00230 std::list<tf::Point>::iterator transformed_top_it = transformed_top_points_.begin();
00231 std::list<tf::Point>::iterator transformed_bottom_it = transformed_bottom_points_.begin();
00232 for (; transformed_top_it != transformed_top_points_.end(); ++transformed_top_it)
00233 {
00234 glVertex2d(transformed_top_it->getX(), transformed_top_it->getY());
00235 glVertex2d(transformed_bottom_it->getX(), transformed_bottom_it->getY());
00236
00237 ++transformed_bottom_it;
00238 }
00239
00240 glEnd();
00241
00242 PrintInfo("OK");
00243 }
00244 }
00245
00246 void GridPlugin::RecalculateGrid()
00247 {
00248 transformed_ = false;
00249
00250 left_points_.clear();
00251 right_points_.clear();
00252 top_points_.clear();
00253 bottom_points_.clear();
00254
00255 transformed_left_points_.clear();
00256 transformed_right_points_.clear();
00257 transformed_top_points_.clear();
00258 transformed_bottom_points_.clear();
00259
00260
00261 for (int c = 0; c <= columns_; c++)
00262 {
00263 tf::Point top_point(top_left_.getX() + c * size_, top_left_.getY(), 0);
00264 top_points_.push_back(top_point);
00265 transformed_top_points_.push_back(transform_ * top_point);
00266
00267 tf::Point bottom_point(top_left_.getX() + c * size_, top_left_.getY() + size_ * rows_, 0);
00268 bottom_points_.push_back(bottom_point);
00269 transformed_bottom_points_.push_back(transform_ * bottom_point);
00270 }
00271
00272
00273 for (int r = 0; r <= rows_; r++)
00274 {
00275 tf::Point left_point(top_left_.getX(), top_left_.getY() + r * size_, 0);
00276 left_points_.push_back(left_point);
00277 transformed_left_points_.push_back(transform_ * left_point);
00278
00279 tf::Point right_point(top_left_.getX() + size_ * columns_, top_left_.getY() + r * size_, 0);
00280 right_points_.push_back(right_point);
00281 transformed_right_points_.push_back(transform_ * right_point);
00282 }
00283 }
00284
00285 void GridPlugin::Transform()
00286 {
00287 transformed_ = false;
00288
00289 if (GetTransform(ros::Time(), transform_))
00290 {
00291 Transform(left_points_, transformed_left_points_);
00292 Transform(right_points_, transformed_right_points_);
00293 Transform(top_points_, transformed_top_points_);
00294 Transform(bottom_points_, transformed_bottom_points_);
00295
00296 transformed_ = true;
00297 }
00298 }
00299
00300 void GridPlugin::Transform(std::list<tf::Point>& src, std::list<tf::Point>& dst)
00301 {
00302 std::list<tf::Point>::iterator points_it = src.begin();
00303 std::list<tf::Point>::iterator transformed_it = dst.begin();
00304 for (; points_it != src.end() && transformed_it != dst.end(); ++points_it)
00305 {
00306 (*transformed_it) = transform_ * (*points_it);
00307
00308 ++transformed_it;
00309 }
00310 }
00311
00312 void GridPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
00313 {
00314 if (node["color"])
00315 {
00316 std::string color;
00317 node["color"] >> color;
00318 ui_.color->setColor(QColor(color.c_str()));
00319 }
00320
00321 if (node["frame"])
00322 {
00323 std::string frame;
00324 node["frame"] >> frame;
00325 ui_.frame->setText(QString::fromStdString(frame));
00326 }
00327
00328 if (node["x"])
00329 {
00330 float x = 0;
00331 node["x"] >> x;
00332 ui_.x->setValue(x);
00333 }
00334
00335 if (node["y"])
00336 {
00337 float y = 0;
00338 node["y"] >> y;
00339 ui_.y->setValue(y);
00340 }
00341
00342 if (node["alpha"])
00343 {
00344 node["alpha"] >> alpha_;
00345 ui_.alpha->setValue(alpha_);
00346 }
00347
00348 if (node["size"])
00349 {
00350 node["size"] >> size_;
00351 ui_.size->setValue(size_);
00352 }
00353
00354 if (node["rows"])
00355 {
00356 node["rows"] >> rows_;
00357 ui_.rows->setValue(rows_);
00358 }
00359
00360 if (node["columns"])
00361 {
00362 node["columns"] >> columns_;
00363 ui_.columns->setValue(columns_);
00364 }
00365
00366 FrameEdited();
00367 }
00368
00369 void GridPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
00370 {
00371 emitter << YAML::Key << "color" << YAML::Value << ui_.color->color().name().toStdString();
00372
00373 emitter << YAML::Key << "alpha" << YAML::Value << alpha_;
00374
00375 std::string frame = ui_.frame->text().toStdString();
00376 emitter << YAML::Key << "frame" << YAML::Value << frame;
00377
00378 emitter << YAML::Key << "x" << YAML::Value << top_left_.getX();
00379 emitter << YAML::Key << "y" << YAML::Value << top_left_.getY();
00380 emitter << YAML::Key << "size" << YAML::Value << size_;
00381 emitter << YAML::Key << "rows" << YAML::Value << rows_;
00382 emitter << YAML::Key << "columns" << YAML::Value << columns_;
00383 }
00384 }
00385