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_.use_latest_transforms, SIGNAL(clicked(bool)),
68  this, SLOT(SetUseLatestTransforms(bool)));
69  QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this,
70  SLOT(PositionToleranceChanged(double)));
71  QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this,
72  SLOT(BufferSizeChanged(int)));
73  QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this,
74  SLOT(SetDrawStyle(QString)));
75  QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this,
76  SLOT(SetColor(const QColor&)));
77  QObject::connect(ui_.buttonResetBuffer, SIGNAL(pressed()), this,
78  SLOT(ClearPoints()));
79  }
80 
82  {
83  }
84 
86  {
88  mapviz::SelectTopicDialog::selectTopic("sensor_msgs/NavSatFix");
89 
90  if (!topic.name.empty())
91  {
92  ui_.topic->setText(QString::fromStdString(topic.name));
93  TopicEdited();
94  }
95  }
96 
98  {
99  std::string topic = ui_.topic->text().trimmed().toStdString();
100  if (topic != topic_)
101  {
102  initialized_ = false;
103  ClearPoints();
104  has_message_ = false;
105  PrintWarning("No messages received.");
106 
108  topic_ = topic;
109  if (!topic.empty())
110  {
112 
113  ROS_INFO("Subscribing to %s", topic_.c_str());
114  }
115  }
116  }
117 
119  const sensor_msgs::NavSatFixConstPtr navsat)
120  {
121  if (!tf_manager_->LocalXyUtil()->Initialized())
122  {
123  return;
124  }
125  if (!has_message_)
126  {
127  initialized_ = true;
128  has_message_ = true;
129  }
130 
131  StampedPoint stamped_point;
132  stamped_point.stamp = navsat->header.stamp;
133 
134  double x;
135  double y;
136  tf_manager_->LocalXyUtil()->ToLocalXy(navsat->latitude, navsat->longitude, x, y);
137 
138  stamped_point.point = tf::Point(x, y, navsat->altitude);
139  stamped_point.orientation = tf::createQuaternionFromYaw(0.0);
140  stamped_point.source_frame = tf_manager_->LocalXyUtil()->Frame();
141 
142  pushPoint( std::move(stamped_point ) );
143  }
144 
145  void NavSatPlugin::PrintError(const std::string& message)
146  {
147  PrintErrorHelper(ui_.status, message);
148  }
149 
150  void NavSatPlugin::PrintInfo(const std::string& message)
151  {
152  PrintInfoHelper(ui_.status, message);
153  }
154 
155  void NavSatPlugin::PrintWarning(const std::string& message)
156  {
157  PrintWarningHelper(ui_.status, message);
158  }
159 
160  QWidget* NavSatPlugin::GetConfigWidget(QWidget* parent)
161  {
162  config_widget_->setParent(parent);
163 
164  return config_widget_;
165  }
166 
167  bool NavSatPlugin::Initialize(QGLWidget* canvas)
168  {
169  canvas_ = canvas;
170  SetColor(ui_.color->color());
171  return true;
172  }
173 
174  void NavSatPlugin::Draw(double x, double y, double scale)
175  {
176  if (DrawPoints(scale))
177  {
178  PrintInfo("OK");
179  }
180  }
181 
182  void NavSatPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
183  {
184  if (node["topic"])
185  {
186  std::string topic;
187  node["topic"] >> topic;
188  ui_.topic->setText(topic.c_str());
189  }
190 
191  if (node["color"])
192  {
193  std::string color;
194  node["color"] >> color;
195  QColor qcolor(color.c_str());
196  SetColor(qcolor);
197  ui_.color->setColor(qcolor);
198  }
199 
200  if (node["draw_style"])
201  {
202  std::string draw_style;
203  node["draw_style"] >> draw_style;
204 
205  if (draw_style == "lines")
206  {
207  ui_.drawstyle->setCurrentIndex(0);
208  SetDrawStyle( LINES );
209  }
210  else if (draw_style == "points")
211  {
212  ui_.drawstyle->setCurrentIndex(1);
213  SetDrawStyle( POINTS );
214  }
215  }
216 
217  if (node["use_latest_transforms"])
218  {
219  bool use_latest_transforms = node["use_latest_transforms"].as<bool>();
220  ui_.use_latest_transforms->setChecked(use_latest_transforms);
221  SetUseLatestTransforms(use_latest_transforms);
222  }
223 
224  if (node["position_tolerance"])
225  {
226  double position_tolerance;
227  node["position_tolerance"] >> position_tolerance;
228  ui_.positiontolerance->setValue(position_tolerance);
229  PositionToleranceChanged(position_tolerance);
230  }
231 
232  if (node["buffer_size"])
233  {
234  double buffer_size;
235  node["buffer_size"] >> buffer_size;
236  ui_.buffersize->setValue(buffer_size);
237  BufferSizeChanged(buffer_size);
238  }
239 
240  TopicEdited();
241  }
242 
243  void NavSatPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
244  {
245  std::string topic = ui_.topic->text().toStdString();
246  emitter << YAML::Key << "topic" << YAML::Value << topic;
247 
248  std::string color = ui_.color->color().name().toStdString();
249  emitter << YAML::Key << "color" << YAML::Value << color;
250 
251  std::string draw_style = ui_.drawstyle->currentText().toStdString();
252  emitter << YAML::Key << "draw_style" << YAML::Value << draw_style;
253 
254  emitter << YAML::Key << "use_latest_transforms" << YAML::Value << ui_.use_latest_transforms->isChecked();
255 
256  emitter << YAML::Key << "position_tolerance" <<
257  YAML::Value << positionTolerance();
258 
259  emitter << YAML::Key << "buffer_size" << YAML::Value << bufferSize();
260  }
261 }
mapviz_plugins::NavSatPlugin::topic_
std::string topic_
Definition: navsat_plugin.h:80
mapviz_plugins::PointDrawingPlugin::StampedPoint
Definition: point_drawing_plugin.h:56
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::NavSatPlugin
Definition: navsat_plugin.h:47
mapviz_plugins::NavSatPlugin::Initialize
bool Initialize(QGLWidget *canvas)
Definition: navsat_plugin.cpp:167
mapviz_plugins::PointDrawingPlugin::BufferSizeChanged
virtual void BufferSizeChanged(int value)
Definition: point_drawing_plugin.cpp:245
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::NavSatPlugin::NavSatFixCallback
void NavSatFixCallback(const sensor_msgs::NavSatFixConstPtr navsat)
Definition: navsat_plugin.cpp:118
geometry_util.h
ros::Subscriber::shutdown
void shutdown()
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::NavSatPlugin::navsat_sub_
ros::Subscriber navsat_sub_
Definition: navsat_plugin.h:82
mapviz_plugins::NavSatPlugin::has_message_
bool has_message_
Definition: navsat_plugin.h:83
mapviz_plugins::NavSatPlugin::NavSatPlugin
NavSatPlugin()
Definition: navsat_plugin.cpp:47
mapviz_plugins::NavSatPlugin::LoadConfig
void LoadConfig(const YAML::Node &node, const std::string &path)
Definition: navsat_plugin.cpp:182
class_list_macros.h
mapviz_plugins::NavSatPlugin::config_widget_
QWidget * config_widget_
Definition: navsat_plugin.h:78
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::NavSatPlugin::PrintWarning
void PrintWarning(const std::string &message)
Definition: navsat_plugin.cpp:155
mapviz_plugins::NavSatPlugin::GetConfigWidget
QWidget * GetConfigWidget(QWidget *parent)
Definition: navsat_plugin.cpp:160
mapviz_plugins::PointDrawingPlugin::PositionToleranceChanged
virtual void PositionToleranceChanged(double value)
Definition: point_drawing_plugin.cpp:155
mapviz_plugins::NavSatPlugin::SelectTopic
void SelectTopic()
Definition: navsat_plugin.cpp:85
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::NavSatPlugin::ui_
Ui::navsat_config ui_
Definition: navsat_plugin.h:77
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::PointDrawingPlugin::StampedPoint::orientation
tf::Quaternion orientation
Definition: point_drawing_plugin.h:61
mapviz_plugins::NavSatPlugin::~NavSatPlugin
virtual ~NavSatPlugin()
Definition: navsat_plugin.cpp:81
mapviz_plugins::PointDrawingPlugin::SetDrawStyle
virtual void SetDrawStyle(QString style)
Definition: point_drawing_plugin.cpp:125
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_plugins::NavSatPlugin::Draw
void Draw(double x, double y, double scale)
Definition: navsat_plugin.cpp:174
mapviz_plugins::NavSatPlugin::PrintError
void PrintError(const std::string &message)
Definition: navsat_plugin.cpp:145
mapviz::MapvizPlugin
mapviz_plugins::NavSatPlugin::TopicEdited
void TopicEdited()
Definition: navsat_plugin.cpp:97
mapviz::MapvizPlugin::initialized_
bool initialized_
navsat_plugin.h
ROS_INFO
#define ROS_INFO(...)
ros::master::TopicInfo
mapviz_plugins::NavSatPlugin::SaveConfig
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
Definition: navsat_plugin.cpp:243
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::SelectTopicDialog::selectTopic
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
ros::master::TopicInfo::name
std::string name
mapviz_plugins::NavSatPlugin::PrintInfo
void PrintInfo(const std::string &message)
Definition: navsat_plugin.cpp:150


mapviz_plugins
Author(s): Marc Alban
autogenerated on Sun Sep 8 2024 02:27:14