gps_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 
39 
40 // Declare plugin
43 
44 namespace mapviz_plugins
45 {
46  GpsPlugin::GpsPlugin() : config_widget_(new QWidget())
47  {
48  ui_.setupUi(config_widget_);
49 
50  ui_.color->setColor(Qt::green);
51 
52  // Set background white
53  QPalette p(config_widget_->palette());
54  p.setColor(QPalette::Background, Qt::white);
55  config_widget_->setPalette(p);
56 
57  // Set status text red
58  QPalette p3(ui_.status->palette());
59  p3.setColor(QPalette::Text, Qt::red);
60  ui_.status->setPalette(p3);
61 
62  QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this,
63  SLOT(SelectTopic()));
64  QObject::connect(ui_.topic, SIGNAL(editingFinished()), this,
65  SLOT(TopicEdited()));
66  QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this,
67  SLOT(PositionToleranceChanged(double)));
68  QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this,
69  SLOT(BufferSizeChanged(int)));
70  QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this,
71  SLOT(SetDrawStyle(QString)));
72  QObject::connect(ui_.static_arrow_sizes, SIGNAL(clicked(bool)),
73  this, SLOT(SetStaticArrowSizes(bool)));
74  QObject::connect(ui_.arrow_size, SIGNAL(valueChanged(int)),
75  this, SLOT(SetArrowSize(int)));
76  QObject::connect(ui_.use_latest_transforms, SIGNAL(clicked(bool)),
77  this, SLOT(SetUseLatestTransforms(bool)));
78  QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this,
79  SLOT(SetColor(const QColor&)));
80  QObject::connect(ui_.show_laps, SIGNAL(toggled(bool)), this,
81  SLOT(LapToggled(bool)));
82  QObject::connect(ui_.buttonResetBuffer, SIGNAL(pressed()), this,
83  SLOT(ClearPoints()));
84  }
85 
87  {
88  }
89 
91  {
93  mapviz::SelectTopicDialog::selectTopic("gps_common/GPSFix");
94 
95  if (!topic.name.empty())
96  {
97  ui_.topic->setText(QString::fromStdString(topic.name));
98  TopicEdited();
99  }
100  }
101 
103  {
104  std::string topic = ui_.topic->text().trimmed().toStdString();
105  if (topic != topic_)
106  {
107  initialized_ = false;
108  ClearPoints();
109  has_message_ = false;
110  PrintWarning("No messages received.");
111 
112  gps_sub_.shutdown();
113 
114  topic_ = topic;
115  if (!topic.empty())
116  {
118 
119  ROS_INFO("Subscribing to %s", topic_.c_str());
120  }
121  }
122  }
123 
124  void GpsPlugin::GPSFixCallback(const gps_common::GPSFixConstPtr& gps)
125  {
126  if (!tf_manager_->LocalXyUtil()->Initialized())
127  {
128  return;
129  }
130  if (!has_message_)
131  {
132  initialized_ = true;
133  has_message_ = true;
134  }
135 
136  StampedPoint stamped_point;
137  stamped_point.stamp = gps->header.stamp;
138  stamped_point.source_frame = tf_manager_->LocalXyUtil()->Frame();
139  double x;
140  double y;
141  tf_manager_->LocalXyUtil()->ToLocalXy(gps->latitude, gps->longitude, x, y);
142 
143  stamped_point.point = tf::Point(x, y, gps->altitude);
144 
145  // The GPS "track" is in degrees, but createQuaternionFromYaw expects
146  // radians.
147  // Furthermore, the track rotates in the opposite direction and is also
148  // offset by 90 degrees, so all of that has to be compensated for.
149  stamped_point.orientation =
150  tf::createQuaternionFromYaw((-gps->track * (M_PI / 180.0)) + M_PI_2);
151 
152  pushPoint( std::move( stamped_point) );
153  }
154 
155  void GpsPlugin::PrintError(const std::string& message)
156  {
157  PrintErrorHelper(ui_.status, message);
158  }
159 
160  void GpsPlugin::PrintInfo(const std::string& message)
161  {
162  PrintInfoHelper(ui_.status, message);
163  }
164 
165  void GpsPlugin::PrintWarning(const std::string& message)
166  {
167  PrintWarningHelper(ui_.status, message);
168  }
169 
170  QWidget* GpsPlugin::GetConfigWidget(QWidget* parent)
171  {
172  config_widget_->setParent(parent);
173 
174  return config_widget_;
175  }
176 
177  bool GpsPlugin::Initialize(QGLWidget* canvas)
178  {
179  canvas_ = canvas;
180  SetColor(ui_.color->color());
181 
182  return true;
183  }
184 
185  void GpsPlugin::Draw(double x, double y, double scale)
186  {
187  if (DrawPoints(scale))
188  {
189  PrintInfo("OK");
190  }
191  }
192 
193  void GpsPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
194  {
195  if (node["topic"])
196  {
197  std::string topic;
198  node["topic"] >> topic;
199  ui_.topic->setText(topic.c_str());
200  }
201 
202  if (node["color"])
203  {
204  std::string color;
205  node["color"] >> color;
206  QColor qcolor(color.c_str());
207  SetColor(qcolor);
208  ui_.color->setColor(qcolor);
209  }
210 
211  if (node["draw_style"])
212  {
213  std::string draw_style;
214  node["draw_style"] >> draw_style;
215 
216  if (draw_style == "lines")
217  {
218  ui_.drawstyle->setCurrentIndex(0);
219  SetDrawStyle( LINES );
220  }
221  else if (draw_style == "points")
222  {
223  ui_.drawstyle->setCurrentIndex(1);
224  SetDrawStyle( POINTS );
225  }
226  else if (draw_style == "arrows")
227  {
228  ui_.drawstyle->setCurrentIndex(2);
229  SetDrawStyle( ARROWS );
230  }
231  }
232 
233  if (node["position_tolerance"])
234  {
235  double position_tolerance;
236  node["position_tolerance"] >> position_tolerance;
237  ui_.positiontolerance->setValue(position_tolerance);
238  PositionToleranceChanged(position_tolerance);
239  }
240 
241  if (node["buffer_size"])
242  {
243  double buffer_size;
244  node["buffer_size"] >> buffer_size;
245  ui_.buffersize->setValue(buffer_size);
246  BufferSizeChanged(buffer_size);
247  }
248 
249  if (node["show_laps"])
250  {
251  bool show_laps = false;
252  node["show_laps"] >> show_laps;
253  ui_.show_laps->setChecked(show_laps);
254  LapToggled(show_laps);
255  }
256 
257  if (node["static_arrow_sizes"])
258  {
259  bool static_arrow_sizes = node["static_arrow_sizes"].as<bool>();
260  ui_.static_arrow_sizes->setChecked(static_arrow_sizes);
261  SetStaticArrowSizes(static_arrow_sizes);
262  }
263 
264  if (node["arrow_size"])
265  {
266  int arrow_size = node["arrow_size"].as<int>();
267  ui_.arrow_size->setValue(arrow_size);
268  SetArrowSize(arrow_size);
269  }
270 
271  if (node["use_latest_transforms"])
272  {
273  bool use_latest_transforms = node["use_latest_transforms"].as<bool>();
274  ui_.use_latest_transforms->setChecked(use_latest_transforms);
275  SetUseLatestTransforms(use_latest_transforms);
276  }
277 
278  TopicEdited();
279  }
280 
281  void GpsPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
282  {
283  std::string topic = ui_.topic->text().toStdString();
284  emitter << YAML::Key << "topic" << YAML::Value << topic;
285 
286  emitter << YAML::Key << "color" << YAML::Value
287  << ui_.color->color().name().toStdString();
288 
289  std::string draw_style = ui_.drawstyle->currentText().toStdString();
290  emitter << YAML::Key << "draw_style" << YAML::Value << draw_style;
291 
292  emitter << YAML::Key << "position_tolerance" <<
293  YAML::Value << positionTolerance();
294 
295  emitter << YAML::Key << "buffer_size" << YAML::Value << bufferSize();
296 
297  bool show_laps = ui_.show_laps->isChecked();
298  emitter << YAML::Key << "show_laps" << YAML::Value << show_laps;
299 
300  emitter << YAML::Key << "static_arrow_sizes" << YAML::Value << ui_.static_arrow_sizes->isChecked();
301 
302  emitter << YAML::Key << "arrow_size" << YAML::Value << ui_.arrow_size->value();
303 
304  emitter << YAML::Key << "use_latest_transforms" << YAML::Value << ui_.use_latest_transforms->isChecked();
305  }
306 }
mapviz_plugins::GpsPlugin::PrintWarning
void PrintWarning(const std::string &message)
Definition: gps_plugin.cpp:165
mapviz_plugins::PointDrawingPlugin::StampedPoint
Definition: point_drawing_plugin.h:56
mapviz_plugins::PointDrawingPlugin::LapToggled
virtual void LapToggled(bool checked)
Definition: point_drawing_plugin.cpp:160
tf::createQuaternionFromYaw
static Quaternion createQuaternionFromYaw(double yaw)
select_topic_dialog.h
mapviz_plugins::PointDrawingPlugin::DrawPoints
virtual bool DrawPoints(double scale)
Definition: point_drawing_plugin.cpp:258
mapviz_plugins::PointDrawingPlugin::ClearPoints
void ClearPoints()
Definition: point_drawing_plugin.cpp:218
mapviz_plugins::GpsPlugin::PrintError
void PrintError(const std::string &message)
Definition: gps_plugin.cpp:155
mapviz_plugins::PointDrawingPlugin::BufferSizeChanged
virtual void BufferSizeChanged(int value)
Definition: point_drawing_plugin.cpp:245
mapviz_plugins::GpsPlugin::ui_
Ui::gps_config ui_
Definition: gps_plugin.h:80
mapviz::MapvizPlugin::PrintErrorHelper
static void PrintErrorHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
mapviz_plugins::PointDrawingPlugin::SetColor
virtual void SetColor(const QColor &color)
Definition: point_drawing_plugin.cpp:405
mapviz_plugins::GpsPlugin::SaveConfig
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
Definition: gps_plugin.cpp:281
mapviz_plugins::GpsPlugin::LoadConfig
void LoadConfig(const YAML::Node &node, const std::string &path)
Definition: gps_plugin.cpp:193
geometry_util.h
ros::Subscriber::shutdown
void shutdown()
mapviz_plugins::PointDrawingPlugin::SetStaticArrowSizes
virtual void SetStaticArrowSizes(bool isChecked)
Definition: point_drawing_plugin.cpp:149
mapviz_plugins::PointDrawingPlugin::SetUseLatestTransforms
virtual void SetUseLatestTransforms(bool checked)
Definition: point_drawing_plugin.cpp:175
mapviz_plugins::PointDrawingPlugin::pushPoint
void pushPoint(StampedPoint point)
Definition: point_drawing_plugin.cpp:198
mapviz_plugins::PointDrawingPlugin::StampedPoint::source_frame
std::string source_frame
Definition: point_drawing_plugin.h:66
mapviz_plugins::PointDrawingPlugin::positionTolerance
double positionTolerance() const
Definition: point_drawing_plugin.cpp:235
mapviz_plugins::GpsPlugin::topic_
std::string topic_
Definition: gps_plugin.h:83
mapviz_plugins::GpsPlugin
Definition: gps_plugin.h:50
class_list_macros.h
mapviz_plugins::PointDrawingPlugin::LINES
@ LINES
Definition: point_drawing_plugin.h:76
tf::Point
tf::Vector3 Point
transform_util.h
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mapviz_plugins::GpsPlugin::config_widget_
QWidget * config_widget_
Definition: gps_plugin.h:81
mapviz_plugins::PointDrawingPlugin::PositionToleranceChanged
virtual void PositionToleranceChanged(double value)
Definition: point_drawing_plugin.cpp:155
mapviz_plugins::GpsPlugin::~GpsPlugin
virtual ~GpsPlugin()
Definition: gps_plugin.cpp:86
mapviz_plugins::GpsPlugin::Draw
void Draw(double x, double y, double scale)
Definition: gps_plugin.cpp:185
mapviz::MapvizPlugin::PrintWarningHelper
static void PrintWarningHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
mapviz_plugins::PointDrawingPlugin::bufferSize
double bufferSize() const
Definition: point_drawing_plugin.cpp:223
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
mapviz_plugins::GpsPlugin::has_message_
bool has_message_
Definition: gps_plugin.h:86
mapviz_plugins::PointDrawingPlugin::POINTS
@ POINTS
Definition: point_drawing_plugin.h:77
mapviz::MapvizPlugin::PrintInfoHelper
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
mapviz::MapvizPlugin::canvas_
QGLWidget * canvas_
mapviz_plugins::GpsPlugin::PrintInfo
void PrintInfo(const std::string &message)
Definition: gps_plugin.cpp:160
mapviz_plugins::PointDrawingPlugin::StampedPoint::orientation
tf::Quaternion orientation
Definition: point_drawing_plugin.h:61
mapviz_plugins::GpsPlugin::GetConfigWidget
QWidget * GetConfigWidget(QWidget *parent)
Definition: gps_plugin.cpp:170
mapviz_plugins::GpsPlugin::gps_sub_
ros::Subscriber gps_sub_
Definition: gps_plugin.h:85
mapviz_plugins::PointDrawingPlugin::ARROWS
@ ARROWS
Definition: point_drawing_plugin.h:78
mapviz_plugins::PointDrawingPlugin::SetArrowSize
virtual void SetArrowSize(int arrowSize)
Definition: point_drawing_plugin.cpp:119
mapviz_plugins::PointDrawingPlugin::SetDrawStyle
virtual void SetDrawStyle(QString style)
Definition: point_drawing_plugin.cpp:125
mapviz_plugins::GpsPlugin::GpsPlugin
GpsPlugin()
Definition: gps_plugin.cpp:46
gps_plugin.h
mapviz::MapvizPlugin::tf_manager_
swri_transform_util::TransformManagerPtr tf_manager_
mapviz_plugins::PointDrawingPlugin::StampedPoint::stamp
ros::Time stamp
Definition: point_drawing_plugin.h:68
mapviz::MapvizPlugin
mapviz::MapvizPlugin::initialized_
bool initialized_
mapviz_plugins::GpsPlugin::SelectTopic
void SelectTopic()
Definition: gps_plugin.cpp:90
mapviz_plugins::GpsPlugin::GPSFixCallback
void GPSFixCallback(const gps_common::GPSFixConstPtr &gps)
Definition: gps_plugin.cpp:124
ROS_INFO
#define ROS_INFO(...)
ros::master::TopicInfo
mapviz_plugins::PointDrawingPlugin::StampedPoint::point
tf::Point point
Definition: point_drawing_plugin.h:60
mapviz_plugins
Definition: attitude_indicator_plugin.h:61
master.h
mapviz::MapvizPlugin::node_
ros::NodeHandle node_
mapviz_plugins::GpsPlugin::TopicEdited
void TopicEdited()
Definition: gps_plugin.cpp:102
mapviz::SelectTopicDialog::selectTopic
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
ros::master::TopicInfo::name
std::string name
mapviz_plugins::GpsPlugin::Initialize
bool Initialize(QGLWidget *canvas)
Definition: gps_plugin.cpp:177


mapviz_plugins
Author(s): Marc Alban
autogenerated on Wed Jan 17 2024 03:27:49