Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 #include <mapviz_plugins/navsat_plugin.h>
00021
00022
00023 #include <cstdio>
00024 #include <vector>
00025
00026
00027 #include <QDialog>
00028 #include <QGLWidget>
00029 #include <QPalette>
00030
00031 #include <opencv2/core/core.hpp>
00032
00033
00034 #include <ros/master.h>
00035
00036 #include <swri_image_util/geometry_util.h>
00037 #include <swri_transform_util/transform_util.h>
00038
00039 #include <mapviz/select_topic_dialog.h>
00040
00041
00042 #include <pluginlib/class_list_macros.h>
00043 PLUGINLIB_EXPORT_CLASS(mapviz_plugins::NavSatPlugin, mapviz::MapvizPlugin)
00044
00045 namespace mapviz_plugins
00046 {
00047 NavSatPlugin::NavSatPlugin() : config_widget_(new QWidget())
00048 {
00049 ui_.setupUi(config_widget_);
00050
00051 ui_.color->setColor(Qt::green);
00052
00053
00054 QPalette p(config_widget_->palette());
00055 p.setColor(QPalette::Background, Qt::white);
00056 config_widget_->setPalette(p);
00057
00058
00059 QPalette p3(ui_.status->palette());
00060 p3.setColor(QPalette::Text, Qt::red);
00061 ui_.status->setPalette(p3);
00062
00063 QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this,
00064 SLOT(SelectTopic()));
00065 QObject::connect(ui_.topic, SIGNAL(editingFinished()), this,
00066 SLOT(TopicEdited()));
00067 QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this,
00068 SLOT(PositionToleranceChanged(double)));
00069 QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this,
00070 SLOT(BufferSizeChanged(int)));
00071 QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this,
00072 SLOT(SetDrawStyle(QString)));
00073 QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this,
00074 SLOT(SetColor(const QColor&)));
00075 }
00076
00077 NavSatPlugin::~NavSatPlugin()
00078 {
00079 }
00080
00081 void NavSatPlugin::SelectTopic()
00082 {
00083 ros::master::TopicInfo topic =
00084 mapviz::SelectTopicDialog::selectTopic("sensor_msgs/NavSatFix");
00085
00086 if (!topic.name.empty())
00087 {
00088 ui_.topic->setText(QString::fromStdString(topic.name));
00089 TopicEdited();
00090 }
00091 }
00092
00093 void NavSatPlugin::TopicEdited()
00094 {
00095 std::string topic = ui_.topic->text().trimmed().toStdString();
00096 if (topic != topic_)
00097 {
00098 initialized_ = false;
00099 points_.clear();
00100 has_message_ = false;
00101 PrintWarning("No messages received.");
00102
00103 navsat_sub_.shutdown();
00104 topic_ = topic;
00105 if (!topic.empty())
00106 {
00107 navsat_sub_ = node_.subscribe(topic_, 1, &NavSatPlugin::NavSatFixCallback, this);
00108
00109 ROS_INFO("Subscribing to %s", topic_.c_str());
00110 }
00111 }
00112 }
00113
00114 void NavSatPlugin::NavSatFixCallback(
00115 const sensor_msgs::NavSatFixConstPtr navsat)
00116 {
00117 if (!local_xy_util_.Initialized())
00118 {
00119 return;
00120 }
00121 if (!has_message_)
00122 {
00123 initialized_ = true;
00124 has_message_ = true;
00125 }
00126
00127 StampedPoint stamped_point;
00128 stamped_point.stamp = navsat->header.stamp;
00129
00130 double x;
00131 double y;
00132 local_xy_util_.ToLocalXy(navsat->latitude, navsat->longitude, x, y);
00133
00134 stamped_point.point = tf::Point(x, y, navsat->altitude);
00135
00136 stamped_point.orientation = tf::createQuaternionFromYaw(0.0);
00137
00138 stamped_point.source_frame = local_xy_util_.Frame();
00139
00140 if (points_.empty() ||
00141 stamped_point.point.distance(points_.back().point) >=
00142 position_tolerance_)
00143 {
00144 points_.push_back(stamped_point);
00145 }
00146
00147 if (buffer_size_ > 0)
00148 {
00149 while (static_cast<int>(points_.size()) > buffer_size_)
00150 {
00151 points_.pop_front();
00152 }
00153 }
00154
00155 cur_point_ = stamped_point;
00156 }
00157
00158 void NavSatPlugin::PrintError(const std::string& message)
00159 {
00160 PrintErrorHelper(ui_.status, message);
00161 }
00162
00163 void NavSatPlugin::PrintInfo(const std::string& message)
00164 {
00165 PrintInfoHelper(ui_.status, message);
00166 }
00167
00168 void NavSatPlugin::PrintWarning(const std::string& message)
00169 {
00170 PrintWarningHelper(ui_.status, message);
00171 }
00172
00173 QWidget* NavSatPlugin::GetConfigWidget(QWidget* parent)
00174 {
00175 config_widget_->setParent(parent);
00176
00177 return config_widget_;
00178 }
00179
00180 bool NavSatPlugin::Initialize(QGLWidget* canvas)
00181 {
00182 canvas_ = canvas;
00183 SetColor(ui_.color->color());
00184 return true;
00185 }
00186
00187 void NavSatPlugin::Draw(double x, double y, double scale)
00188 {
00189 if (DrawPoints(scale))
00190 {
00191 PrintInfo("OK");
00192 }
00193 }
00194
00195 void NavSatPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
00196 {
00197 if (node["topic"])
00198 {
00199 std::string topic;
00200 node["topic"] >> topic;
00201 ui_.topic->setText(topic.c_str());
00202 }
00203
00204 if (node["color"])
00205 {
00206 std::string color;
00207 node["color"] >> color;
00208 SetColor(QColor(color.c_str()));
00209 ui_.color->setColor(color_);
00210 }
00211
00212 if (node["draw_style"])
00213 {
00214 std::string draw_style;
00215 node["draw_style"] >> draw_style;
00216
00217 if (draw_style == "lines")
00218 {
00219 draw_style_ = LINES;
00220 ui_.drawstyle->setCurrentIndex(0);
00221 }
00222 else if (draw_style == "points")
00223 {
00224 draw_style_ = POINTS;
00225 ui_.drawstyle->setCurrentIndex(1);
00226 }
00227 }
00228
00229 if (node["position_tolerance"])
00230 {
00231 node["position_tolerance"] >> position_tolerance_;
00232 ui_.positiontolerance->setValue(position_tolerance_);
00233 }
00234
00235 if (node["buffer_size"])
00236 {
00237 node["buffer_size"] >> buffer_size_;
00238 ui_.buffersize->setValue(buffer_size_);
00239 }
00240
00241 TopicEdited();
00242 }
00243
00244 void NavSatPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
00245 {
00246 std::string topic = ui_.topic->text().toStdString();
00247 emitter << YAML::Key << "topic" << YAML::Value << topic;
00248
00249 std::string color = ui_.color->color().name().toStdString();
00250 emitter << YAML::Key << "color" << YAML::Value << color;
00251
00252 std::string draw_style = ui_.drawstyle->currentText().toStdString();
00253 emitter << YAML::Key << "draw_style" << YAML::Value << draw_style;
00254
00255 emitter << YAML::Key << "position_tolerance" <<
00256 YAML::Value << position_tolerance_;
00257
00258 emitter << YAML::Key << "buffer_size" << YAML::Value << buffer_size_;
00259 }
00260 }