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/odometry_plugin.h>
00031
00032
00033 #include <cstdio>
00034 #include <vector>
00035
00036
00037 #include <QDialog>
00038 #include <QGLWidget>
00039 #include <QPainter>
00040 #include <QPalette>
00041
00042 #include <opencv2/core/core.hpp>
00043
00044
00045 #include <ros/master.h>
00046
00047 #include <swri_image_util/geometry_util.h>
00048 #include <swri_transform_util/transform_util.h>
00049 #include <mapviz/select_topic_dialog.h>
00050
00051
00052 #include <pluginlib/class_list_macros.h>
00053 PLUGINLIB_DECLARE_CLASS(mapviz_plugins,
00054 odometry,
00055 mapviz_plugins::OdometryPlugin,
00056 mapviz::MapvizPlugin);
00057
00058 namespace mapviz_plugins
00059 {
00060 OdometryPlugin::OdometryPlugin() : config_widget_(new QWidget())
00061 {
00062 ui_.setupUi(config_widget_);
00063 covariance_checked_ = ui_.show_covariance->isChecked();
00064 ui_.color->setColor(Qt::green);
00065
00066
00067 QPalette p(config_widget_->palette());
00068 p.setColor(QPalette::Background, Qt::white);
00069 config_widget_->setPalette(p);
00070
00071
00072 QPalette p3(ui_.status->palette());
00073 p3.setColor(QPalette::Text, Qt::red);
00074 ui_.status->setPalette(p3);
00075
00076 QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this,
00077 SLOT(SelectTopic()));
00078 QObject::connect(ui_.topic, SIGNAL(editingFinished()), this,
00079 SLOT(TopicEdited()));
00080 QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this,
00081 SLOT(PositionToleranceChanged(double)));
00082 QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this,
00083 SLOT(BufferSizeChanged(int)));
00084 QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this,
00085 SLOT(SetDrawStyle(QString)));
00086 QObject::connect(ui_.static_arrow_sizes, SIGNAL(clicked(bool)),
00087 this, SLOT(SetStaticArrowSizes(bool)));
00088 QObject::connect(ui_.arrow_size, SIGNAL(valueChanged(int)),
00089 this, SLOT(SetArrowSize(int)));
00090 connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this,
00091 SLOT(SetColor(const QColor&)));
00092 }
00093
00094 OdometryPlugin::~OdometryPlugin()
00095 {
00096 }
00097
00098 void OdometryPlugin::SelectTopic()
00099 {
00100 ros::master::TopicInfo topic =
00101 mapviz::SelectTopicDialog::selectTopic("nav_msgs/Odometry");
00102
00103 if (!topic.name.empty())
00104 {
00105 ui_.topic->setText(QString::fromStdString(topic.name));
00106 TopicEdited();
00107 }
00108 }
00109
00110 void OdometryPlugin::TopicEdited()
00111 {
00112 std::string topic = ui_.topic->text().trimmed().toStdString();
00113 if (topic != topic_)
00114 {
00115 initialized_ = false;
00116 points_.clear();
00117 has_message_ = false;
00118 PrintWarning("No messages received.");
00119
00120 odometry_sub_.shutdown();
00121
00122 topic_ = topic;
00123 if (!topic.empty())
00124 {
00125 odometry_sub_ = node_.subscribe(
00126 topic_, 1, &OdometryPlugin::odometryCallback, this);
00127
00128 ROS_INFO("Subscribing to %s", topic_.c_str());
00129 }
00130 }
00131 }
00132
00133 void OdometryPlugin::odometryCallback(
00134 const nav_msgs::OdometryConstPtr odometry)
00135 {
00136 if (!has_message_)
00137 {
00138 initialized_ = true;
00139 has_message_ = true;
00140 }
00141
00142
00143
00144
00145
00146 StampedPoint stamped_point;
00147 stamped_point.stamp = odometry->header.stamp;
00148 stamped_point.source_frame = odometry->header.frame_id;
00149
00150 stamped_point.point = tf::Point(odometry->pose.pose.position.x,
00151 odometry->pose.pose.position.y,
00152 odometry->pose.pose.position.z);
00153
00154 stamped_point.orientation = tf::Quaternion(
00155 odometry->pose.pose.orientation.x,
00156 odometry->pose.pose.orientation.y,
00157 odometry->pose.pose.orientation.z,
00158 odometry->pose.pose.orientation.w);
00159
00160 if (points_.empty() ||
00161 stamped_point.point.distance(points_.back().point) >=
00162 position_tolerance_)
00163 {
00164 points_.push_back(stamped_point);
00165 }
00166
00167 if (buffer_size_ > 0)
00168 {
00169 while (static_cast<int>(points_.size()) > buffer_size_)
00170 {
00171 points_.pop_front();
00172 }
00173 }
00174
00175 cur_point_ = stamped_point;
00176 covariance_checked_ = ui_.show_covariance->isChecked();
00177 lap_checked_ = ui_.show_laps->isChecked();
00178
00179 if (covariance_checked_)
00180 {
00181 tf::Matrix3x3 tf_cov =
00182 swri_transform_util::GetUpperLeft(odometry->pose.covariance);
00183
00184 if (tf_cov[0][0] < 100000 && tf_cov[1][1] < 100000)
00185 {
00186 cv::Mat cov_matrix_3d(3, 3, CV_32FC1);
00187 for (int32_t r = 0; r < 3; r++)
00188 {
00189 for (int32_t c = 0; c < 3; c++)
00190 {
00191 cov_matrix_3d.at<float>(r, c) = tf_cov[r][c];
00192 }
00193 }
00194
00195 cv::Mat cov_matrix_2d =
00196 swri_image_util::ProjectEllipsoid(cov_matrix_3d);
00197
00198 if (!cov_matrix_2d.empty())
00199 {
00200 cur_point_.cov_points = swri_image_util::GetEllipsePoints(
00201 cov_matrix_2d, cur_point_.point, 3, 32);
00202
00203 cur_point_.transformed_cov_points = cur_point_.cov_points;
00204 }
00205 else
00206 {
00207 ROS_ERROR("Failed to project x, y, z covariance to xy-plane.");
00208 }
00209 }
00210 }
00211 }
00212
00213 void OdometryPlugin::PrintError(const std::string& message)
00214 {
00215 if (message == ui_.status->text().toStdString())
00216 {
00217 return;
00218 }
00219
00220 ROS_ERROR("Error: %s", message.c_str());
00221 QPalette p(ui_.status->palette());
00222 p.setColor(QPalette::Text, Qt::red);
00223 ui_.status->setPalette(p);
00224 ui_.status->setText(message.c_str());
00225 }
00226
00227 void OdometryPlugin::PrintInfo(const std::string& message)
00228 {
00229 if (message == ui_.status->text().toStdString())
00230 {
00231 return;
00232 }
00233
00234 ROS_INFO("%s", message.c_str());
00235 QPalette p(ui_.status->palette());
00236 p.setColor(QPalette::Text, Qt::green);
00237 ui_.status->setPalette(p);
00238 ui_.status->setText(message.c_str());
00239 }
00240
00241 void OdometryPlugin::PrintWarning(const std::string& message)
00242 {
00243 if (message == ui_.status->text().toStdString())
00244 {
00245 return;
00246 }
00247
00248 ROS_WARN("%s", message.c_str());
00249 QPalette p(ui_.status->palette());
00250 p.setColor(QPalette::Text, Qt::darkYellow);
00251 ui_.status->setPalette(p);
00252 ui_.status->setText(message.c_str());
00253 }
00254
00255 QWidget* OdometryPlugin::GetConfigWidget(QWidget* parent)
00256 {
00257 config_widget_->setParent(parent);
00258
00259 return config_widget_;
00260 }
00261
00262 bool OdometryPlugin::Initialize(QGLWidget* canvas)
00263 {
00264 canvas_ = canvas;
00265 SetColor(ui_.color->color());
00266
00267 return true;
00268 }
00269
00270 void OdometryPlugin::Draw(double x, double y, double scale)
00271 {
00272 if (ui_.show_covariance->isChecked())
00273 {
00274 DrawCovariance();
00275 }
00276 if (DrawPoints(scale))
00277 {
00278 PrintInfo("OK");
00279 }
00280 }
00281
00282 void OdometryPlugin::DrawCovariance()
00283 {
00284 glLineWidth(4);
00285
00286 if (cur_point_.transformed && !cur_point_.transformed_cov_points.empty())
00287 {
00288 glBegin(GL_LINE_STRIP);
00289
00290 for (uint32_t i = 0; i < cur_point_.transformed_cov_points.size(); i++)
00291 {
00292 glVertex2d(cur_point_.transformed_cov_points[i].getX(),
00293 cur_point_.transformed_cov_points[i].getY());
00294 }
00295
00296 glVertex2d(cur_point_.transformed_cov_points.front().getX(),
00297 cur_point_.transformed_cov_points.front().getY());
00298
00299 glEnd();
00300 }
00301 }
00302
00303 void OdometryPlugin::LoadConfig(const YAML::Node& node,
00304 const std::string& path)
00305 {
00306 if (node["topic"])
00307 {
00308 std::string topic;
00309 node["topic"] >> topic;
00310 ui_.topic->setText(topic.c_str());
00311 }
00312
00313 if (node["color"])
00314 {
00315 std::string color;
00316 node["color"] >> color;
00317 SetColor(QColor(color.c_str()));
00318 ui_.color->setColor(color_);
00319 }
00320
00321 if (node["draw_style"])
00322 {
00323 std::string draw_style;
00324 node["draw_style"] >> draw_style;
00325
00326 if (draw_style == "lines")
00327 {
00328 draw_style_ = LINES;
00329 ui_.drawstyle->setCurrentIndex(0);
00330 }
00331 else if (draw_style == "points")
00332 {
00333 draw_style_ = POINTS;
00334 ui_.drawstyle->setCurrentIndex(1);
00335 }
00336 else if (draw_style == "arrows")
00337 {
00338 draw_style_ = ARROWS;
00339 ui_.drawstyle->setCurrentIndex(2);
00340 }
00341 }
00342
00343 if (node["position_tolerance"])
00344 {
00345 node["position_tolerance"] >> position_tolerance_;
00346 ui_.positiontolerance->setValue(position_tolerance_);
00347 }
00348
00349 if (node["buffer_size"])
00350 {
00351 node["buffer_size"] >> buffer_size_;
00352 ui_.buffersize->setValue(buffer_size_);
00353 }
00354
00355 if (node["show_covariance"])
00356 {
00357 bool show_covariance = false;
00358 node["show_covariance"] >> show_covariance;
00359 ui_.show_covariance->setChecked(show_covariance);
00360 }
00361 if (node["show_laps"])
00362 {
00363 bool show_laps = false;
00364 node["show_laps"] >> show_laps;
00365 ui_.show_laps->setChecked(show_laps);
00366 }
00367
00368 if (node["static_arrow_sizes"])
00369 {
00370 bool static_arrow_sizes = node["static_arrow_sizes"].as<bool>();
00371 ui_.static_arrow_sizes->setChecked(static_arrow_sizes);
00372 SetStaticArrowSizes(static_arrow_sizes);
00373 }
00374
00375 if (node["arrow_size"])
00376 {
00377 ui_.arrow_size->setValue(node["arrow_size"].as<int>());
00378 }
00379
00380 TopicEdited();
00381 }
00382
00383 void OdometryPlugin::SaveConfig(YAML::Emitter& emitter,
00384 const std::string& path)
00385 {
00386 std::string topic = ui_.topic->text().toStdString();
00387 emitter << YAML::Key << "topic" << YAML::Value << topic;
00388
00389 std::string color = ui_.color->color().name().toStdString();
00390 emitter << YAML::Key << "color" << YAML::Value << color;
00391
00392 std::string draw_style = ui_.drawstyle->currentText().toStdString();
00393 emitter << YAML::Key << "draw_style" << YAML::Value << draw_style;
00394
00395 emitter << YAML::Key << "position_tolerance" <<
00396 YAML::Value << position_tolerance_;
00397 if (!lap_checked_)
00398 {
00399 emitter << YAML::Key << "buffer_size" << YAML::Value << buffer_size_;
00400 }
00401 else
00402 {
00403 emitter << YAML::Key << "buffer_size" << YAML::Value << buffer_holder_;
00404 }
00405 bool show_laps = ui_.show_laps->isChecked();
00406 emitter << YAML::Key << "show_laps" << YAML::Value << show_laps;
00407
00408 bool show_covariance = ui_.show_covariance->isChecked();
00409 emitter << YAML::Key << "show_covariance" << YAML::Value << show_covariance;
00410
00411 emitter << YAML::Key << "static_arrow_sizes" << YAML::Value << ui_.static_arrow_sizes->isChecked();
00412
00413 emitter << YAML::Key << "arrow_size" << YAML::Value << ui_.arrow_size->value();
00414 }
00415 }