navsat_plugin.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (C) 2013 All Right Reserved, Southwest Research Institute® (SwRI®)
4 //
5 // Contract No. 10-58058A
6 // Contractor Southwest Research Institute® (SwRI®)
7 // Address 6220 Culebra Road, San Antonio, Texas 78228-0510
8 // Contact Steve Dellenback <sdellenback@swri.org> (210) 522-3914
9 //
10 // This code was developed as part of an internal research project fully funded
11 // by Southwest Research Institute®.
12 //
13 // THIS CODE AND INFORMATION ARE PROVIDED "AS IS" WITHOUT WARRANTY OF ANY
14 // KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE
15 // IMPLIED WARRANTIES OF MERCHANTABILITY AND/OR FITNESS FOR A
16 // PARTICULAR PURPOSE.
17 //
18 // *****************************************************************************
19 
21 
22 // C++ standard libraries
23 #include <cstdio>
24 #include <vector>
25 
26 // QT libraries
27 #include <QDialog>
28 #include <QGLWidget>
29 #include <QPalette>
30 
31 #include <opencv2/core/core.hpp>
32 
33 // ROS libraries
34 #include <ros/master.h>
35 
38 
40 
41 // Declare plugin
44 
45 namespace mapviz_plugins
46 {
47  NavSatPlugin::NavSatPlugin() : config_widget_(new QWidget())
48  {
49  ui_.setupUi(config_widget_);
50 
51  ui_.color->setColor(Qt::green);
52 
53  // Set background white
54  QPalette p(config_widget_->palette());
55  p.setColor(QPalette::Background, Qt::white);
56  config_widget_->setPalette(p);
57 
58  // Set status text red
59  QPalette p3(ui_.status->palette());
60  p3.setColor(QPalette::Text, Qt::red);
61  ui_.status->setPalette(p3);
62 
63  QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this,
64  SLOT(SelectTopic()));
65  QObject::connect(ui_.topic, SIGNAL(editingFinished()), this,
66  SLOT(TopicEdited()));
67  QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this,
68  SLOT(PositionToleranceChanged(double)));
69  QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this,
70  SLOT(BufferSizeChanged(int)));
71  QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this,
72  SLOT(SetDrawStyle(QString)));
73  QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this,
74  SLOT(SetColor(const QColor&)));
75  }
76 
78  {
79  }
80 
82  {
84  mapviz::SelectTopicDialog::selectTopic("sensor_msgs/NavSatFix");
85 
86  if (!topic.name.empty())
87  {
88  ui_.topic->setText(QString::fromStdString(topic.name));
89  TopicEdited();
90  }
91  }
92 
94  {
95  std::string topic = ui_.topic->text().trimmed().toStdString();
96  if (topic != topic_)
97  {
98  initialized_ = false;
99  points_.clear();
100  has_message_ = false;
101  PrintWarning("No messages received.");
102 
104  topic_ = topic;
105  if (!topic.empty())
106  {
108 
109  ROS_INFO("Subscribing to %s", topic_.c_str());
110  }
111  }
112  }
113 
115  const sensor_msgs::NavSatFixConstPtr navsat)
116  {
118  {
119  return;
120  }
121  if (!has_message_)
122  {
123  initialized_ = true;
124  has_message_ = true;
125  }
126 
127  StampedPoint stamped_point;
128  stamped_point.stamp = navsat->header.stamp;
129 
130  double x;
131  double y;
132  local_xy_util_.ToLocalXy(navsat->latitude, navsat->longitude, x, y);
133 
134  stamped_point.point = tf::Point(x, y, navsat->altitude);
135 
136  stamped_point.orientation = tf::createQuaternionFromYaw(0.0);
137 
138  stamped_point.source_frame = local_xy_util_.Frame();
139 
140  if (points_.empty() ||
141  stamped_point.point.distance(points_.back().point) >=
143  {
144  points_.push_back(stamped_point);
145  }
146 
147  if (buffer_size_ > 0)
148  {
149  while (static_cast<int>(points_.size()) > buffer_size_)
150  {
151  points_.pop_front();
152  }
153  }
154 
155  cur_point_ = stamped_point;
156  }
157 
158  void NavSatPlugin::PrintError(const std::string& message)
159  {
160  PrintErrorHelper(ui_.status, message);
161  }
162 
163  void NavSatPlugin::PrintInfo(const std::string& message)
164  {
165  PrintInfoHelper(ui_.status, message);
166  }
167 
168  void NavSatPlugin::PrintWarning(const std::string& message)
169  {
170  PrintWarningHelper(ui_.status, message);
171  }
172 
173  QWidget* NavSatPlugin::GetConfigWidget(QWidget* parent)
174  {
175  config_widget_->setParent(parent);
176 
177  return config_widget_;
178  }
179 
180  bool NavSatPlugin::Initialize(QGLWidget* canvas)
181  {
182  canvas_ = canvas;
183  SetColor(ui_.color->color());
184  return true;
185  }
186 
187  void NavSatPlugin::Draw(double x, double y, double scale)
188  {
189  if (DrawPoints(scale))
190  {
191  PrintInfo("OK");
192  }
193  }
194 
195  void NavSatPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
196  {
197  if (node["topic"])
198  {
199  std::string topic;
200  node["topic"] >> topic;
201  ui_.topic->setText(topic.c_str());
202  }
203 
204  if (node["color"])
205  {
206  std::string color;
207  node["color"] >> color;
208  SetColor(QColor(color.c_str()));
209  ui_.color->setColor(color_);
210  }
211 
212  if (node["draw_style"])
213  {
214  std::string draw_style;
215  node["draw_style"] >> draw_style;
216 
217  if (draw_style == "lines")
218  {
219  draw_style_ = LINES;
220  ui_.drawstyle->setCurrentIndex(0);
221  }
222  else if (draw_style == "points")
223  {
225  ui_.drawstyle->setCurrentIndex(1);
226  }
227  }
228 
229  if (node["position_tolerance"])
230  {
231  node["position_tolerance"] >> position_tolerance_;
232  ui_.positiontolerance->setValue(position_tolerance_);
233  }
234 
235  if (node["buffer_size"])
236  {
237  node["buffer_size"] >> buffer_size_;
238  ui_.buffersize->setValue(buffer_size_);
239  }
240 
241  TopicEdited();
242  }
243 
244  void NavSatPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
245  {
246  std::string topic = ui_.topic->text().toStdString();
247  emitter << YAML::Key << "topic" << YAML::Value << topic;
248 
249  std::string color = ui_.color->color().name().toStdString();
250  emitter << YAML::Key << "color" << YAML::Value << color;
251 
252  std::string draw_style = ui_.drawstyle->currentText().toStdString();
253  emitter << YAML::Key << "draw_style" << YAML::Value << draw_style;
254 
255  emitter << YAML::Key << "position_tolerance" <<
256  YAML::Value << position_tolerance_;
257 
258  emitter << YAML::Key << "buffer_size" << YAML::Value << buffer_size_;
259  }
260 }
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
void PrintInfo(const std::string &message)
ros::NodeHandle node_
virtual void PositionToleranceChanged(double value)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static void PrintWarningHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
static void PrintErrorHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
QWidget * GetConfigWidget(QWidget *parent)
swri_transform_util::LocalXyWgs84Util local_xy_util_
Definition: navsat_plugin.h:85
tf::Vector3 Point
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
TFSIMD_FORCE_INLINE const tfScalar & y() const
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void Draw(double x, double y, double scale)
bool ToLocalXy(double latitude, double longitude, double &x, double &y) const
static Quaternion createQuaternionFromYaw(double yaw)
void NavSatFixCallback(const sensor_msgs::NavSatFixConstPtr navsat)
#define ROS_INFO(...)
TFSIMD_FORCE_INLINE const tfScalar & x() const
virtual void SetColor(const QColor &color)
void PrintWarning(const std::string &message)
void LoadConfig(const YAML::Node &node, const std::string &path)
bool Initialize(QGLWidget *canvas)
virtual void SetDrawStyle(QString style)
void PrintError(const std::string &message)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)


mapviz_plugins
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 19:25:16