#include <route_plugin.h>

Public Types | |
| enum | DrawStyle { LINES = 0, POINTS = 1 } |
Public Member Functions | |
| void | Draw (double x, double y, double scale) |
| void | DrawRoute (const swri_route_util::Route &route) |
| void | DrawRoutePoint (const swri_route_util::RoutePoint &point) |
| void | DrawStopWaypoint (double x, double y) |
| QWidget * | GetConfigWidget (QWidget *parent) |
| bool | Initialize (QGLWidget *canvas) |
| void | LoadConfig (const YAML::Node &node, const std::string &path) |
| RoutePlugin () | |
| void | SaveConfig (YAML::Emitter &emitter, const std::string &path) |
| void | Shutdown () |
| void | Transform () |
| virtual | ~RoutePlugin () |
Protected Slots | |
| void | DrawIcon () |
| void | PositionTopicEdited () |
| void | SelectPositionTopic () |
| void | SelectTopic () |
| void | SetDrawStyle (QString style) |
| void | TopicEdited () |
Protected Member Functions | |
| void | PrintError (const std::string &message) |
| void | PrintInfo (const std::string &message) |
| void | PrintWarning (const std::string &message) |
Private Member Functions | |
| void | PositionCallback (const marti_nav_msgs::RoutePositionConstPtr &msg) |
| void | RouteCallback (const marti_nav_msgs::RouteConstPtr &msg) |
Private Attributes | |
| QWidget * | config_widget_ |
| DrawStyle | draw_style_ |
| ros::Subscriber | position_sub_ |
| std::string | position_topic_ |
| ros::Subscriber | route_sub_ |
| swri_route_util::Route | src_route_ |
| marti_nav_msgs::RoutePositionConstPtr | src_route_position_ |
| std::string | topic_ |
| Ui::route_config | ui_ |
Definition at line 57 of file route_plugin.h.
Definition at line 62 of file route_plugin.h.
Definition at line 65 of file route_plugin.cpp.
| mapviz_plugins::RoutePlugin::~RoutePlugin | ( | ) | [virtual] |
Definition at line 92 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::Draw | ( | double | x, |
| double | y, | ||
| double | scale | ||
| ) | [virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 277 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::DrawIcon | ( | ) | [protected, virtual, slot] |
Reimplemented from mapviz::MapvizPlugin.
Definition at line 96 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::DrawRoute | ( | const swri_route_util::Route & | route | ) |
Definition at line 346 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::DrawRoutePoint | ( | const swri_route_util::RoutePoint & | point | ) |
Definition at line 370 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::DrawStopWaypoint | ( | double | x, |
| double | y | ||
| ) |
Definition at line 325 of file route_plugin.cpp.
| QWidget * mapviz_plugins::RoutePlugin::GetConfigWidget | ( | QWidget * | parent | ) | [virtual] |
Reimplemented from mapviz::MapvizPlugin.
Definition at line 260 of file route_plugin.cpp.
| bool mapviz_plugins::RoutePlugin::Initialize | ( | QGLWidget * | canvas | ) | [virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 267 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::LoadConfig | ( | const YAML::Node & | node, |
| const std::string & | path | ||
| ) | [virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 394 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::PositionCallback | ( | const marti_nav_msgs::RoutePositionConstPtr & | msg | ) | [private] |
Definition at line 207 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::PositionTopicEdited | ( | ) | [protected, slot] |
Definition at line 188 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::PrintError | ( | const std::string & | message | ) | [protected, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 218 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::PrintInfo | ( | const std::string & | message | ) | [protected, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 232 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::PrintWarning | ( | const std::string & | message | ) | [protected, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 246 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::RouteCallback | ( | const marti_nav_msgs::RouteConstPtr & | msg | ) | [private] |
Definition at line 213 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::SaveConfig | ( | YAML::Emitter & | emitter, |
| const std::string & | path | ||
| ) | [virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 442 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::SelectPositionTopic | ( | ) | [protected, slot] |
Definition at line 154 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::SelectTopic | ( | ) | [protected, slot] |
Definition at line 140 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::SetDrawStyle | ( | QString | style | ) | [protected, slot] |
Definition at line 127 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::Shutdown | ( | ) | [inline, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 72 of file route_plugin.h.
| void mapviz_plugins::RoutePlugin::TopicEdited | ( | ) | [protected, slot] |
Definition at line 168 of file route_plugin.cpp.
| void mapviz_plugins::RoutePlugin::Transform | ( | ) | [inline, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 78 of file route_plugin.h.
QWidget* mapviz_plugins::RoutePlugin::config_widget_ [private] |
Definition at line 103 of file route_plugin.h.
Definition at line 105 of file route_plugin.h.
Definition at line 111 of file route_plugin.h.
std::string mapviz_plugins::RoutePlugin::position_topic_ [private] |
Definition at line 108 of file route_plugin.h.
Definition at line 110 of file route_plugin.h.
Definition at line 113 of file route_plugin.h.
marti_nav_msgs::RoutePositionConstPtr mapviz_plugins::RoutePlugin::src_route_position_ [private] |
Definition at line 114 of file route_plugin.h.
std::string mapviz_plugins::RoutePlugin::topic_ [private] |
Definition at line 107 of file route_plugin.h.
Ui::route_config mapviz_plugins::RoutePlugin::ui_ [private] |
Definition at line 102 of file route_plugin.h.