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
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <mapviz_plugins/path_plugin.h>
00031
00032
00033 #include <cstdio>
00034 #include <vector>
00035
00036
00037 #include <QDialog>
00038 #include <QGLWidget>
00039
00040
00041 #include <ros/master.h>
00042
00043 #include <mapviz/select_topic_dialog.h>
00044
00045
00046 #include <pluginlib/class_list_macros.h>
00047 PLUGINLIB_EXPORT_CLASS(mapviz_plugins::PathPlugin, mapviz::MapvizPlugin)
00048
00049 namespace mapviz_plugins
00050 {
00051 PathPlugin::PathPlugin() : config_widget_(new QWidget())
00052 {
00053 ui_.setupUi(config_widget_);
00054 ui_.path_color->setColor(Qt::green);
00055
00056
00057 QPalette p(config_widget_->palette());
00058 p.setColor(QPalette::Background, Qt::white);
00059 config_widget_->setPalette(p);
00060
00061
00062 QPalette p3(ui_.status->palette());
00063 p3.setColor(QPalette::Text, Qt::red);
00064 ui_.status->setPalette(p3);
00065
00066 connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic()));
00067 connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited()));
00068 connect(ui_.path_color, SIGNAL(colorEdited(const QColor&)), this,
00069 SLOT(SetColor(const QColor&)));
00070 }
00071
00072 PathPlugin::~PathPlugin()
00073 {
00074 }
00075
00076 void PathPlugin::SelectTopic()
00077 {
00078 ros::master::TopicInfo topic =
00079 mapviz::SelectTopicDialog::selectTopic("nav_msgs/Path");
00080
00081 if (!topic.name.empty())
00082 {
00083 ui_.topic->setText(QString::fromStdString(topic.name));
00084 TopicEdited();
00085 }
00086 }
00087
00088 void PathPlugin::TopicEdited()
00089 {
00090 std::string topic = ui_.topic->text().trimmed().toStdString();
00091 if (topic != topic_)
00092 {
00093 initialized_ = false;
00094 points_.clear();
00095 has_message_ = false;
00096 PrintWarning("No messages received.");
00097
00098 path_sub_.shutdown();
00099
00100 topic_ = topic;
00101 if (!topic.empty())
00102 {
00103 path_sub_ = node_.subscribe(topic_, 1, &PathPlugin::pathCallback, this);
00104
00105 ROS_INFO("Subscribing to %s", topic_.c_str());
00106 }
00107 }
00108 }
00109
00110 void PathPlugin::pathCallback(const nav_msgs::PathConstPtr& path)
00111 {
00112 if (!has_message_)
00113 {
00114 initialized_ = true;
00115 has_message_ = true;
00116 }
00117
00118 points_.clear();
00119
00120 for (unsigned int i = 0; i < path->poses.size(); i++)
00121 {
00122 StampedPoint stamped_point;
00123 stamped_point.stamp = path->header.stamp;
00124 stamped_point.source_frame = path->header.frame_id;
00125 stamped_point.point = tf::Point(path->poses[i].pose.position.x,
00126 path->poses[i].pose.position.y, 0);
00127
00128 points_.push_back(stamped_point);
00129 }
00130 }
00131
00132 void PathPlugin::PrintError(const std::string& message)
00133 {
00134 PrintErrorHelper(ui_.status, message);
00135 }
00136
00137 void PathPlugin::PrintInfo(const std::string& message)
00138 {
00139 PrintInfoHelper(ui_.status, message);
00140 }
00141
00142 void PathPlugin::PrintWarning(const std::string& message)
00143 {
00144 PrintWarningHelper(ui_.status, message);
00145 }
00146
00147 QWidget* PathPlugin::GetConfigWidget(QWidget* parent)
00148 {
00149 config_widget_->setParent(parent);
00150
00151 return config_widget_;
00152 }
00153
00154 bool PathPlugin::Initialize(QGLWidget* canvas)
00155 {
00156 canvas_ = canvas;
00157 DrawIcon();
00158 return true;
00159 }
00160
00161 void PathPlugin::Draw(double x, double y, double scale)
00162 {
00163 bool lines;
00164 bool points;
00165 QColor old_color = ui_.path_color->color();
00166 draw_style_ = LINES;
00167 lines = DrawPoints(scale);
00168 color_ = color_.dark(200);
00169 draw_style_ = POINTS;
00170 points = DrawPoints(scale);
00171 color_ = old_color;
00172 if (lines && points)
00173 {
00174 PrintInfo("OK");
00175 }
00176 }
00177
00178 void PathPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
00179 {
00180 if (swri_yaml_util::FindValue(node, "color"))
00181 {
00182 std::string topic;
00183 node["topic"] >> topic;
00184 ui_.topic->setText(topic.c_str());
00185 TopicEdited();
00186 }
00187
00188 if (swri_yaml_util::FindValue(node, "color"))
00189 {
00190 std::string color;
00191 node["color"] >> color;
00192 SetColor(QColor(color.c_str()));
00193 ui_.path_color->setColor(color_);
00194 }
00195 }
00196
00197 void PathPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
00198 {
00199 std::string topic = ui_.topic->text().toStdString();
00200 emitter << YAML::Key << "topic" << YAML::Value << topic;
00201
00202 std::string color = ui_.path_color->color().name().toStdString();
00203 emitter << YAML::Key << "color" << YAML::Value << color;
00204 }
00205 }