#include <gps_plugin.h>

Public Member Functions | |
| void | Draw (double x, double y, double scale) |
| QWidget * | GetConfigWidget (QWidget *parent) |
| GpsPlugin () | |
| bool | Initialize (QGLWidget *canvas) |
| void | LoadConfig (const YAML::Node &node, const std::string &path) |
| void | SaveConfig (YAML::Emitter &emitter, const std::string &path) |
| void | Shutdown () |
| virtual | ~GpsPlugin () |
Public Member Functions inherited from mapviz_plugins::PointDrawingPlugin | |
| void | ClearHistory () |
| virtual void | CollectLaps () |
| virtual bool | DrawArrow (const StampedPoint &point) |
| virtual bool | DrawArrows () |
| virtual bool | DrawLaps () |
| virtual bool | DrawLapsArrows () |
| virtual bool | DrawLines () |
| virtual bool | DrawPoints (double scale) |
| PointDrawingPlugin () | |
| virtual void | Transform () |
| virtual bool | TransformPoint (StampedPoint &point) |
| virtual void | UpdateColor (QColor base_color, int i) |
| virtual | ~PointDrawingPlugin () |
Public Member Functions inherited from mapviz::MapvizPlugin | |
| int | DrawOrder () const |
| void | DrawPlugin (double x, double y, double scale) |
| bool | GetTransform (const ros::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms=true) |
| bool | GetTransform (const std::string &source, const ros::Time &stamp, swri_transform_util::Transform &transform) |
| virtual bool | Initialize (boost::shared_ptr< tf::TransformListener > tf_listener, QGLWidget *canvas) |
| std::string | Name () const |
| virtual void | Paint (QPainter *painter, double x, double y, double scale) |
| void | PaintPlugin (QPainter *painter, double x, double y, double scale) |
| void | PrintMeasurements () |
| void | SetDrawOrder (int order) |
| void | SetIcon (IconWidget *icon) |
| void | SetName (const std::string &name) |
| virtual void | SetNode (const ros::NodeHandle &node) |
| void | SetTargetFrame (std::string frame_id) |
| void | SetType (const std::string &type) |
| void | SetUseLatestTransforms (bool value) |
| void | SetVisible (bool visible) |
| std::string | Type () const |
| bool | Visible () const |
| virtual | ~MapvizPlugin () |
Protected Slots | |
| void | SelectTopic () |
| void | TopicEdited () |
Protected Slots inherited from mapviz_plugins::PointDrawingPlugin | |
| virtual void | BufferSizeChanged (int value) |
| virtual void | DrawIcon () |
| virtual void | PositionToleranceChanged (double value) |
| virtual void | SetArrowSize (int arrowSize) |
| virtual void | SetColor (const QColor &color) |
| virtual void | SetDrawStyle (QString style) |
| virtual void | SetStaticArrowSizes (bool isChecked) |
Protected Member Functions | |
| void | PrintError (const std::string &message) |
| void | PrintInfo (const std::string &message) |
| void | PrintWarning (const std::string &message) |
Protected Member Functions inherited from mapviz::MapvizPlugin | |
| MapvizPlugin () | |
Private Member Functions | |
| void | GPSFixCallback (const gps_common::GPSFixConstPtr &gps) |
Private Attributes | |
| QWidget * | config_widget_ |
| ros::Subscriber | gps_sub_ |
| bool | has_message_ |
| swri_transform_util::LocalXyWgs84Util | local_xy_util_ |
| std::string | topic_ |
| Ui::gps_config | ui_ |
Additional Inherited Members | |
Public Types inherited from mapviz_plugins::PointDrawingPlugin | |
| enum | DrawStyle { LINES = 0, POINTS, ARROWS } |
Public Slots inherited from mapviz::MapvizPlugin | |
| virtual void | DrawIcon () |
| virtual bool | SupportsPainting () |
Signals inherited from mapviz::MapvizPlugin | |
| void | DrawOrderChanged (int draw_order) |
| void | SizeChanged () |
| void | TargetFrameChanged (const std::string &target_frame) |
| void | UseLatestTransformsChanged (bool use_latest_transforms) |
| void | VisibleChanged (bool visible) |
Static Public Member Functions inherited from mapviz::MapvizPlugin | |
| static void | PrintErrorHelper (QLabel *status_label, const std::string &message, double throttle=0.0) |
| static void | PrintInfoHelper (QLabel *status_label, const std::string &message, double throttle=0.0) |
| static void | PrintWarningHelper (QLabel *status_label, const std::string &message, double throttle=0.0) |
Protected Attributes inherited from mapviz_plugins::PointDrawingPlugin | |
| int | arrow_size_ |
| int | buffer_holder_ |
| int | buffer_size_ |
| QColor | color_ |
| bool | covariance_checked_ |
| StampedPoint | cur_point_ |
| DrawStyle | draw_style_ |
| bool | lap_checked_ |
| bool | new_lap_ |
| std::list< StampedPoint > | points_ |
| double | position_tolerance_ |
| double | scale_ |
| bool | static_arrow_sizes_ |
Protected Attributes inherited from mapviz::MapvizPlugin | |
| QGLWidget * | canvas_ |
| int | draw_order_ |
| IconWidget * | icon_ |
| bool | initialized_ |
| std::string | name_ |
| ros::NodeHandle | node_ |
| std::string | source_frame_ |
| std::string | target_frame_ |
| boost::shared_ptr< tf::TransformListener > | tf_ |
| swri_transform_util::TransformManager | tf_manager_ |
| std::string | type_ |
| bool | use_latest_transforms_ |
| bool | visible_ |
Definition at line 50 of file gps_plugin.h.
| mapviz_plugins::GpsPlugin::GpsPlugin | ( | ) |
Definition at line 46 of file gps_plugin.cpp.
|
virtual |
Definition at line 80 of file gps_plugin.cpp.
|
virtual |
Implements mapviz::MapvizPlugin.
Definition at line 194 of file gps_plugin.cpp.
|
virtual |
Reimplemented from mapviz::MapvizPlugin.
Definition at line 179 of file gps_plugin.cpp.
|
private |
Definition at line 118 of file gps_plugin.cpp.
|
virtual |
Implements mapviz::MapvizPlugin.
Definition at line 186 of file gps_plugin.cpp.
|
virtual |
Implements mapviz::MapvizPlugin.
Definition at line 202 of file gps_plugin.cpp.
|
protectedvirtual |
Implements mapviz::MapvizPlugin.
Definition at line 164 of file gps_plugin.cpp.
|
protectedvirtual |
Implements mapviz::MapvizPlugin.
Definition at line 169 of file gps_plugin.cpp.
|
protectedvirtual |
Implements mapviz::MapvizPlugin.
Definition at line 174 of file gps_plugin.cpp.
|
virtual |
Implements mapviz::MapvizPlugin.
Definition at line 275 of file gps_plugin.cpp.
|
protectedslot |
Definition at line 84 of file gps_plugin.cpp.
|
inlinevirtual |
Implements mapviz::MapvizPlugin.
Definition at line 59 of file gps_plugin.h.
|
protectedslot |
Definition at line 96 of file gps_plugin.cpp.
|
private |
Definition at line 81 of file gps_plugin.h.
|
private |
Definition at line 85 of file gps_plugin.h.
|
private |
Definition at line 86 of file gps_plugin.h.
|
private |
Definition at line 88 of file gps_plugin.h.
|
private |
Definition at line 83 of file gps_plugin.h.
|
private |
Definition at line 80 of file gps_plugin.h.