#include <plan_route_plugin.h>

Public Member Functions | |
| void | Draw (double x, double y, double scale) |
| QWidget * | GetConfigWidget (QWidget *parent) |
| bool | Initialize (QGLWidget *canvas) |
| void | LoadConfig (const YAML::Node &node, const std::string &path) |
| void | Paint (QPainter *painter, double x, double y, double scale) |
| PlanRoutePlugin () | |
| void | SaveConfig (YAML::Emitter &emitter, const std::string &path) |
| void | Shutdown () |
| bool | SupportsPainting () |
| void | Transform () |
| virtual | ~PlanRoutePlugin () |
Protected Slots | |
| void | Clear () |
| void | PlanRoute () |
| void | PublishRoute () |
Protected Member Functions | |
| bool | eventFilter (QObject *object, QEvent *event) |
| bool | handleMouseMove (QMouseEvent *) |
| bool | handleMousePress (QMouseEvent *) |
| bool | handleMouseRelease (QMouseEvent *) |
| void | PrintError (const std::string &message) |
| void | PrintInfo (const std::string &message) |
| void | PrintWarning (const std::string &message) |
Private Member Functions | |
| void | Retry (const ros::TimerEvent &e) |
Private Attributes | |
| QWidget * | config_widget_ |
| bool | failed_service_ |
| bool | is_mouse_down_ |
| mapviz::MapCanvas * | map_canvas_ |
| qreal | max_distance_ |
| qint64 | max_ms_ |
| QPointF | mouse_down_pos_ |
| qint64 | mouse_down_time_ |
| ros::Timer | retry_timer_ |
| swri_route_util::RoutePtr | route_preview_ |
| ros::Publisher | route_pub_ |
| std::string | route_topic_ |
| int | selected_point_ |
| Ui::plan_route_config | ui_ |
| std::vector< geometry_msgs::Pose > | waypoints_ |
Definition at line 61 of file plan_route_plugin.h.
Definition at line 65 of file plan_route_plugin.cpp.
| mapviz_plugins::PlanRoutePlugin::~PlanRoutePlugin | ( | ) | [virtual] |
Definition at line 93 of file plan_route_plugin.cpp.
| void mapviz_plugins::PlanRoutePlugin::Clear | ( | ) | [protected, slot] |
Definition at line 159 of file plan_route_plugin.cpp.
| void mapviz_plugins::PlanRoutePlugin::Draw | ( | double | x, |
| double | y, | ||
| double | scale | ||
| ) | [virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 359 of file plan_route_plugin.cpp.
| bool mapviz_plugins::PlanRoutePlugin::eventFilter | ( | QObject * | object, |
| QEvent * | event | ||
| ) | [protected] |
Definition at line 198 of file plan_route_plugin.cpp.
| QWidget * mapviz_plugins::PlanRoutePlugin::GetConfigWidget | ( | QWidget * | parent | ) | [virtual] |
Reimplemented from mapviz::MapvizPlugin.
Definition at line 180 of file plan_route_plugin.cpp.
| bool mapviz_plugins::PlanRoutePlugin::handleMouseMove | ( | QMouseEvent * | event | ) | [protected] |
Definition at line 334 of file plan_route_plugin.cpp.
| bool mapviz_plugins::PlanRoutePlugin::handleMousePress | ( | QMouseEvent * | event | ) | [protected] |
Definition at line 213 of file plan_route_plugin.cpp.
| bool mapviz_plugins::PlanRoutePlugin::handleMouseRelease | ( | QMouseEvent * | event | ) | [protected] |
Definition at line 279 of file plan_route_plugin.cpp.
| bool mapviz_plugins::PlanRoutePlugin::Initialize | ( | QGLWidget * | canvas | ) | [virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 187 of file plan_route_plugin.cpp.
| void mapviz_plugins::PlanRoutePlugin::LoadConfig | ( | const YAML::Node & | node, |
| const std::string & | path | ||
| ) | [virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 433 of file plan_route_plugin.cpp.
| void mapviz_plugins::PlanRoutePlugin::Paint | ( | QPainter * | painter, |
| double | x, | ||
| double | y, | ||
| double | scale | ||
| ) | [virtual] |
Reimplemented from mapviz::MapvizPlugin.
Definition at line 407 of file plan_route_plugin.cpp.
| void mapviz_plugins::PlanRoutePlugin::PlanRoute | ( | ) | [protected, slot] |
Definition at line 116 of file plan_route_plugin.cpp.
| void mapviz_plugins::PlanRoutePlugin::PrintError | ( | const std::string & | message | ) | [protected, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 165 of file plan_route_plugin.cpp.
| void mapviz_plugins::PlanRoutePlugin::PrintInfo | ( | const std::string & | message | ) | [protected, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 170 of file plan_route_plugin.cpp.
| void mapviz_plugins::PlanRoutePlugin::PrintWarning | ( | const std::string & | message | ) | [protected, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 175 of file plan_route_plugin.cpp.
| void mapviz_plugins::PlanRoutePlugin::PublishRoute | ( | ) | [protected, slot] |
Definition at line 101 of file plan_route_plugin.cpp.
| void mapviz_plugins::PlanRoutePlugin::Retry | ( | const ros::TimerEvent & | e | ) | [private] |
Definition at line 154 of file plan_route_plugin.cpp.
| void mapviz_plugins::PlanRoutePlugin::SaveConfig | ( | YAML::Emitter & | emitter, |
| const std::string & | path | ||
| ) | [virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 463 of file plan_route_plugin.cpp.
| void mapviz_plugins::PlanRoutePlugin::Shutdown | ( | ) | [inline, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 71 of file plan_route_plugin.h.
| bool mapviz_plugins::PlanRoutePlugin::SupportsPainting | ( | ) | [inline, virtual] |
Reimplemented from mapviz::MapvizPlugin.
Definition at line 85 of file plan_route_plugin.h.
| void mapviz_plugins::PlanRoutePlugin::Transform | ( | ) | [inline, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 78 of file plan_route_plugin.h.
QWidget* mapviz_plugins::PlanRoutePlugin::config_widget_ [private] |
Definition at line 108 of file plan_route_plugin.h.
bool mapviz_plugins::PlanRoutePlugin::failed_service_ [private] |
Definition at line 116 of file plan_route_plugin.h.
bool mapviz_plugins::PlanRoutePlugin::is_mouse_down_ [private] |
Definition at line 122 of file plan_route_plugin.h.
Definition at line 109 of file plan_route_plugin.h.
qreal mapviz_plugins::PlanRoutePlugin::max_distance_ [private] |
Definition at line 127 of file plan_route_plugin.h.
qint64 mapviz_plugins::PlanRoutePlugin::max_ms_ [private] |
Definition at line 126 of file plan_route_plugin.h.
QPointF mapviz_plugins::PlanRoutePlugin::mouse_down_pos_ [private] |
Definition at line 123 of file plan_route_plugin.h.
qint64 mapviz_plugins::PlanRoutePlugin::mouse_down_time_ [private] |
Definition at line 124 of file plan_route_plugin.h.
Definition at line 114 of file plan_route_plugin.h.
Definition at line 117 of file plan_route_plugin.h.
Definition at line 113 of file plan_route_plugin.h.
std::string mapviz_plugins::PlanRoutePlugin::route_topic_ [private] |
Definition at line 111 of file plan_route_plugin.h.
int mapviz_plugins::PlanRoutePlugin::selected_point_ [private] |
Definition at line 121 of file plan_route_plugin.h.
Ui::plan_route_config mapviz_plugins::PlanRoutePlugin::ui_ [private] |
Definition at line 107 of file plan_route_plugin.h.
std::vector<geometry_msgs::Pose> mapviz_plugins::PlanRoutePlugin::waypoints_ [private] |
Definition at line 119 of file plan_route_plugin.h.