marti_nav_path_plugin.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2021, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
31 
32 #include <string>
33 #include <vector>
34 
35 #include <QObject>
36 #include <QColor>
37 #include <QColorDialog>
38 #include <QDialog>
39 #include <QPalette>
40 #include <QWidget>
41 #include <QGLWidget>
42 
43 #include <ros/ros.h>
44 #include <ros/master.h>
45 
47 
49 
50 namespace mapviz_plugins
51 {
53  :
54  config_widget_(new QWidget()),
55  topic_("")
56 {
57  ui_.setupUi(config_widget_);
58 
59  ui_.forward_color->setColor(QColor(0, 0, 255));
60  ui_.reverse_color->setColor(QColor(255, 0, 0));
61 
63 
64  // Set background white
65  QPalette p(config_widget_->palette());
66  p.setColor(QPalette::Background, Qt::white);
67  config_widget_->setPalette(p);
68 
69  QPalette p3(ui_.status->palette());
70  p3.setColor(QPalette::Text, Qt::red);
71  ui_.status->setPalette(p3);
72 
73  // Connect slots
74  QObject::connect(ui_.select_topic, SIGNAL(clicked()),
75  this, SLOT(selectTopic()));
76  QObject::connect(ui_.topic, SIGNAL(editingFinished()),
77  this, SLOT(topicEdited()));
78 
79  QObject::connect(ui_.history_size, SIGNAL(valueChanged(int)),
80  this, SLOT(historyChanged()));
81 }
82 
83 bool MartiNavPathPlugin::Initialize(QGLWidget* canvas)
84 {
85  canvas_ = canvas;
86  return true;
87 }
88 
90 {
91 }
92 
94 {
95  items_.set_capacity(ui_.history_size->value());
96 }
97 
98 void MartiNavPathPlugin::setColorForDirection(const bool in_reverse)
99 {
100  QColor color = in_reverse ? ui_.reverse_color->color() : ui_.forward_color->color();
101  glColor3f(color.redF(), color.greenF(), color.blueF());
102 }
103 
104 static inline
105 void drawArrow(const double x, const double y, const double yaw, const double L)
106 {
107  double tip_x = x + std::cos(yaw)*L;
108  double tip_y = y + std::sin(yaw)*L;
109 
110  double right_wing_x = tip_x + std::cos(yaw - M_PI*3.0/4.0)*L*0.25;
111  double right_wing_y = tip_y + std::sin(yaw - M_PI*3.0/4.0)*L*0.25;
112 
113  double left_wing_x = tip_x + std::cos(yaw + M_PI*3.0/4.0)*L*0.25;
114  double left_wing_y = tip_y + std::sin(yaw + M_PI*3.0/4.0)*L*0.25;
115 
116  glBegin(GL_LINES);
117 
118  glVertex2f(x,y);
119  glVertex2f(tip_x,tip_y);
120 
121  glVertex2f(tip_x,tip_y);
122  glVertex2f(right_wing_x, right_wing_y);
123 
124  glVertex2f(tip_x, tip_y);
125  glVertex2f(left_wing_x, left_wing_y);
126 
127  glEnd();
128 }
129 
130 void MartiNavPathPlugin::Draw(double /*x*/, double /*y*/, double /*scale*/)
131 {
132  std::map<std::string, swri_transform_util::Transform> transforms;
133  PrintInfo("Ok");
134 
135  for (size_t i = 0; i < items_.size(); i++)
136  {
137  const auto& item = items_[i];
138 
139  std::string src_frame = item.header.frame_id.length() ? item.header.frame_id : target_frame_;
140  if (transforms.count(src_frame) == 0)
141  {
143  if (tf_manager_->GetTransform(target_frame_, src_frame, ros::Time(), transform))
144  {
145  transforms[src_frame] = transform;
146  }
147  else
148  {
149  ROS_ERROR("Failed to get transform from %s to %s", src_frame.c_str(), target_frame_.c_str());
150  PrintError("Failed to get transform from " + src_frame + " to " + target_frame_);
151  continue;
152  }
153  }
154 
155  const swri_transform_util::Transform &transform = transforms[src_frame];
156 
157  marti_nav_msgs::Path path = items_[i]; //mutable copy
158 
159  // transform the points
160  for (auto& pt: path.points)
161  {
162  // transform position
163  tf::Vector3 pt3(pt.x, pt.y, 0.0);
164  pt3 = transform*pt3;
165  pt.x = pt3.x();
166  pt.y = pt3.y();
167 
168  // transform yaw
170  q = transform*q;
171  pt.yaw = tf::getYaw(q);
172  }
173 
174  if (ui_.draw_lines->isChecked())
175  {
176  glLineWidth(ui_.line_width->value());
177 
178  setColorForDirection(path.in_reverse);
179 
180  glBegin(GL_LINE_STRIP);
181  for (auto const &point : path.points)
182  {
183  glVertex2f(point.x, point.y);
184  }
185  glEnd();
186  }
187  if (ui_.draw_points->isChecked())
188  {
189  glPointSize(2*ui_.line_width->value() + 1);
190 
191  setColorForDirection(path.in_reverse);
192 
193  glBegin(GL_POINTS);
194  for (auto const &point : path.points)
195  {
196  glVertex2f(point.x, point.y);
197  }
198  glEnd();
199  }
200  if (ui_.draw_yaw->isChecked())
201  {
202  glLineWidth(ui_.line_width->value());
203 
204  setColorForDirection(path.in_reverse);
205  for (auto const &point : path.points)
206  {
207  drawArrow(point.x, point.y, point.yaw, ui_.arrow_length->value());
208  }
209  }
210  }
211 }
212 
214 {
215 }
216 
218  const YAML::Node& node,
219  const std::string& /*path*/)
220 {
221  std::string topic;
222  node["topic"] >> topic;
223  ui_.topic->setText(topic.c_str());
224  topicEdited();
225 
226  if (swri_yaml_util::FindValue(node, "draw_lines"))
227  {
228  bool val;
229  node["draw_lines"] >> val;
230  ui_.draw_lines->setChecked(val);
231  }
232 
233  if (swri_yaml_util::FindValue(node, "draw_points"))
234  {
235  bool val;
236  node["draw_points"] >> val;
237  ui_.draw_points->setChecked(val);
238  }
239 
240  if (swri_yaml_util::FindValue(node, "draw_yaw"))
241  {
242  bool val;
243  node["draw_yaw"] >> val;
244  ui_.draw_yaw->setChecked(val);
245  }
246 
247  if (swri_yaml_util::FindValue(node, "line_width"))
248  {
249  double val;
250  node["line_width"] >> val;
251  ui_.line_width->setValue(val);
252  }
253 
254  if (swri_yaml_util::FindValue(node, "arrow_length"))
255  {
256  double val;
257  node["arrow_length"] >> val;
258  ui_.arrow_length->setValue(val);
259  }
260 
261  if (swri_yaml_util::FindValue(node, "history_size"))
262  {
263  int val;
264  node["history_size"] >> val;
265  ui_.arrow_length->setValue(val);
266  }
267 
268  if (swri_yaml_util::FindValue(node, "forward_color"))
269  {
270  std::string color;
271  node["forward_color"] >> color;
272  ui_.forward_color->setColor(QColor(color.c_str()));
273  }
274 
275  if (swri_yaml_util::FindValue(node, "reverse_color"))
276  {
277  std::string color;
278  node["reverse_color"] >> color;
279  ui_.reverse_color->setColor(QColor(color.c_str()));
280  }
281 }
282 
284  YAML::Emitter& emitter, const std::string& /*path*/)
285 {
286  emitter << YAML::Key << "topic"
287  << YAML::Value << ui_.topic->text().toStdString();
288 
289  emitter << YAML::Key << "draw_lines"
290  << YAML::Value << ui_.draw_lines->isChecked();
291  emitter << YAML::Key << "draw_points"
292  << YAML::Value << ui_.draw_points->isChecked();
293  emitter << YAML::Key << "draw_yaw"
294  << YAML::Value << ui_.draw_yaw->isChecked();
295 
296  emitter << YAML::Key << "line_width"
297  << YAML::Value << ui_.line_width->value();
298  emitter << YAML::Key << "arrow_length"
299  << YAML::Value << ui_.arrow_length->value();
300  emitter << YAML::Key << "history_size"
301  << YAML::Value << ui_.history_size->value();
302 
303  emitter << YAML::Key << "forward_color"
304  << YAML::Value << ui_.forward_color->color().name().toStdString();
305  emitter << YAML::Key << "reverse_color"
306  << YAML::Value << ui_.reverse_color->color().name().toStdString();
307 }
308 
309 QWidget* MartiNavPathPlugin::GetConfigWidget(QWidget* parent)
310 {
311  config_widget_->setParent(parent);
312 
313  return config_widget_;
314 }
315 
316 void MartiNavPathPlugin::PrintInfo(const std::string& message)
317 {
318  if (message == ui_.status->text().toStdString())
319  {
320  return;
321  }
322 
323  ROS_INFO("%s", message.c_str());
324  QPalette p(ui_.status->palette());
325  p.setColor(QPalette::Text, Qt::green);
326  ui_.status->setPalette(p);
327  ui_.status->setText(message.c_str());
328 }
329 
330 void MartiNavPathPlugin::PrintWarning(const std::string& message)
331 {
332  if (message == ui_.status->text().toStdString())
333  {
334  return;
335  }
336 
337  ROS_WARN("%s", message.c_str());
338  QPalette p(ui_.status->palette());
339  p.setColor(QPalette::Text, Qt::darkYellow);
340  ui_.status->setPalette(p);
341  ui_.status->setText(message.c_str());
342 }
343 
344 void MartiNavPathPlugin::PrintError(const std::string& message)
345 {
346  if (message == ui_.status->text().toStdString())
347  {
348  return;
349  }
350 
351  ROS_ERROR("Error: %s", message.c_str());
352  QPalette p(ui_.status->palette());
353  p.setColor(QPalette::Text, Qt::red);
354  ui_.status->setPalette(p);
355  ui_.status->setText(message.c_str());
356 }
357 
359 {
360  std::vector<std::string> supported_types;
361  supported_types.push_back("marti_nav_msgs/Path");
362  supported_types.push_back("marti_nav_msgs/PathPoint");
363 
365 
366  if (!topic.name.empty())
367  {
368  ui_.topic->setText(QString::fromStdString(topic.name));
369  topicEdited();
370  }
371 }
372 
374 {
375  if (ui_.topic->text().toStdString() != topic_)
376  {
377  initialized_ = true;
378  items_.clear();
379  topic_ = ui_.topic->text().toStdString();
380 
383 
384  ROS_INFO("Subscribing to %s", topic_.c_str());
385  PrintWarning("No messages received.");
386  }
387 }
388 
391 {
392 #define IS_INSTANCE(msg, type) (msg->getDataType() == ros::message_traits::datatype<type>())
393 
394  if (IS_INSTANCE(msg, marti_nav_msgs::Path))
395  {
396  marti_nav_msgs::PathConstPtr msg_typed = msg->instantiate<marti_nav_msgs::Path>();
397  handlePath(*msg_typed);
398  }
399  else if (IS_INSTANCE(msg, marti_nav_msgs::PathPoint))
400  {
401  marti_nav_msgs::PathPointConstPtr msg_typed = msg->instantiate<marti_nav_msgs::PathPoint>();
402  handlePathPoint(*msg_typed);
403  }
404  else
405  {
406  ROS_ERROR_THROTTLE(1.0, "Unknown message type: %s", msg->getDataType().c_str());
407  return;
408  }
409 
410  canvas_->update();
411 
412 #undef IS_INSTANCE
413 }
414 
416  const marti_nav_msgs::Path &path)
417 {
418  items_.push_back(path);
419 }
420 
422  const marti_nav_msgs::PathPoint &point)
423 {
424  marti_nav_msgs::Path segment;
425  segment.in_reverse = false;// no inherent direction for a point, just pick one
426  segment.points.push_back(point);
427  handlePath(segment);
428 }
429 } // namespace mapviz_plugins
430 
431 // Register nodelet plugin
433 PLUGINLIB_EXPORT_CLASS( //NOLINT
ROS_ERROR_THROTTLE
#define ROS_ERROR_THROTTLE(period,...)
mapviz_plugins::MartiNavPathPlugin::SaveConfig
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
Definition: marti_nav_path_plugin.cpp:283
tf::createQuaternionFromYaw
static Quaternion createQuaternionFromYaw(double yaw)
mapviz_plugins::MartiNavPathPlugin::config_widget_
QWidget * config_widget_
Definition: marti_nav_path_plugin.h:60
select_topic_dialog.h
msg
msg
mapviz_plugins::MartiNavPathPlugin::Draw
void Draw(double x, double y, double scale)
Definition: marti_nav_path_plugin.cpp:130
swri_yaml_util::FindValue
bool FindValue(const YAML::Node &node, const std::string &name)
mapviz_plugins::MartiNavPathPlugin::Shutdown
void Shutdown()
Definition: marti_nav_path_plugin.cpp:89
boost::shared_ptr< ShapeShifter const >
mapviz_plugins::MartiNavPathPlugin::historyChanged
void historyChanged()
Definition: marti_nav_path_plugin.cpp:93
mapviz_plugins::MartiNavPathPlugin::PrintError
void PrintError(const std::string &message)
Definition: marti_nav_path_plugin.cpp:344
ros.h
marti_nav_path_plugin.h
mapviz_plugins::MartiNavPathPlugin::selectTopic
void selectTopic()
Definition: marti_nav_path_plugin.cpp:358
mapviz_plugins::MartiNavPathPlugin::setColorForDirection
void setColorForDirection(const bool in_reverse)
Definition: marti_nav_path_plugin.cpp:98
mapviz_plugins::MartiNavPathPlugin::handlePath
void handlePath(const marti_nav_msgs::Path &path)
Definition: marti_nav_path_plugin.cpp:415
mapviz_plugins::MartiNavPathPlugin::handlePathPoint
void handlePathPoint(const marti_nav_msgs::PathPoint &pt)
Definition: marti_nav_path_plugin.cpp:421
mapviz_plugins::MartiNavPathPlugin::topicEdited
void topicEdited()
Definition: marti_nav_path_plugin.cpp:373
mapviz_plugins::MartiNavPathPlugin::topic_
std::string topic_
Definition: marti_nav_path_plugin.h:61
class_list_macros.h
tf::getYaw
static double getYaw(const geometry_msgs::Quaternion &msg_q)
transform
void transform(marti_nav_msgs::Path &path, const swri_transform_util::Transform &transform, const std::string &target_frame)
mapviz_plugins::MartiNavPathPlugin::PrintWarning
void PrintWarning(const std::string &message)
Definition: marti_nav_path_plugin.cpp:330
yaml_util.h
mapviz_plugins::MartiNavPathPlugin::PrintInfo
void PrintInfo(const std::string &message)
Definition: marti_nav_path_plugin.cpp:316
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mapviz_plugins::MartiNavPathPlugin::messageCallback
void messageCallback(const topic_tools::ShapeShifter::ConstPtr &msg)
Definition: marti_nav_path_plugin.cpp:389
swri_transform_util::Transform
ROS_WARN
#define ROS_WARN(...)
mapviz_plugins::MartiNavPathPlugin::ui_
Ui::marti_nav_path_config ui_
Definition: marti_nav_path_plugin.h:59
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::MartiNavPathPlugin::LoadConfig
void LoadConfig(const YAML::Node &node, const std::string &path)
Definition: marti_nav_path_plugin.cpp:217
IS_INSTANCE
#define IS_INSTANCE(msg, type)
mapviz_plugins::drawArrow
static void drawArrow(const double x, const double y, const double yaw, const double L)
Definition: marti_nav_path_plugin.cpp:105
mapviz_plugins::MartiNavPathPlugin::subscriber_
ros::Subscriber subscriber_
Definition: marti_nav_path_plugin.h:63
mapviz_plugins::MartiNavPathPlugin::GetConfigWidget
QWidget * GetConfigWidget(QWidget *parent)
Definition: marti_nav_path_plugin.cpp:309
mapviz_plugins::MartiNavPathPlugin::Initialize
bool Initialize(QGLWidget *canvas)
Definition: marti_nav_path_plugin.cpp:83
mapviz::MapvizPlugin::canvas_
QGLWidget * canvas_
mapviz_plugins::MartiNavPathPlugin::Transform
void Transform()
Definition: marti_nav_path_plugin.cpp:213
ros::Time
mapviz::MapvizPlugin::target_frame_
std::string target_frame_
mapviz_plugins::MartiNavPathPlugin::MartiNavPathPlugin
MartiNavPathPlugin()
Definition: marti_nav_path_plugin.cpp:52
ROS_ERROR
#define ROS_ERROR(...)
mapviz::MapvizPlugin::tf_manager_
swri_transform_util::TransformManagerPtr tf_manager_
mapviz::MapvizPlugin
mapviz::MapvizPlugin::initialized_
bool initialized_
topic_tools::ShapeShifter
ROS_INFO
#define ROS_INFO(...)
ros::master::TopicInfo
mapviz_plugins
Definition: attitude_indicator_plugin.h:61
mapviz_plugins::MartiNavPathPlugin
Definition: marti_nav_path_plugin.h:55
master.h
mapviz::MapvizPlugin::node_
ros::NodeHandle node_
mapviz_plugins::MartiNavPathPlugin::items_
boost::circular_buffer< marti_nav_msgs::Path > items_
Definition: marti_nav_path_plugin.h:65
tf::Quaternion
mapviz::SelectTopicDialog::selectTopic
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
ros::master::TopicInfo::name
std::string name


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