Public Slots | Signals | Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes
mapviz::MapvizPlugin Class Reference

#include <mapviz_plugin.h>

List of all members.

Public Slots

virtual void DrawIcon ()
virtual bool SupportsPainting ()

Signals

void DrawOrderChanged (int draw_order)
void SizeChanged ()
void TargetFrameChanged (const std::string &target_frame)
void UseLatestTransformsChanged (bool use_latest_transforms)
void VisibleChanged (bool visible)

Public Member Functions

virtual void ClearHistory ()
virtual void Draw (double x, double y, double scale)=0
int DrawOrder () const
void DrawPlugin (double x, double y, double scale)
virtual QWidget * GetConfigWidget (QWidget *parent)
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)
virtual void LoadConfig (const YAML::Node &load, const std::string &path)=0
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)
virtual void PrintError (const std::string &message)=0
virtual void PrintInfo (const std::string &message)=0
void PrintMeasurements ()
virtual void PrintWarning (const std::string &message)=0
virtual void SaveConfig (YAML::Emitter &emitter, const std::string &path)=0
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)
virtual void Shutdown ()=0
virtual void Transform ()=0
std::string Type () const
bool Visible () const
virtual ~MapvizPlugin ()

Static Public Member Functions

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 Member Functions

virtual bool Initialize (QGLWidget *canvas)=0
 MapvizPlugin ()

Protected Attributes

QGLWidget * canvas_
int draw_order_
IconWidgeticon_
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_

Private Attributes

Stopwatch meas_draw_
Stopwatch meas_paint_
Stopwatch meas_transform_

Detailed Description

Definition at line 57 of file mapviz_plugin.h.


Constructor & Destructor Documentation

virtual mapviz::MapvizPlugin::~MapvizPlugin ( ) [inline, virtual]

Definition at line 62 of file mapviz_plugin.h.

mapviz::MapvizPlugin::MapvizPlugin ( ) [inline, protected]

Definition at line 315 of file mapviz_plugin.h.


Member Function Documentation

virtual void mapviz::MapvizPlugin::ClearHistory ( ) [inline, virtual]

Definition at line 75 of file mapviz_plugin.h.

virtual void mapviz::MapvizPlugin::Draw ( double  x,
double  y,
double  scale 
) [pure virtual]

Draws on the Mapviz canvas using OpenGL commands; this will be called before Paint();

virtual void mapviz::MapvizPlugin::DrawIcon ( ) [inline, virtual, slot]

Definition at line 273 of file mapviz_plugin.h.

int mapviz::MapvizPlugin::DrawOrder ( ) const [inline]

Definition at line 106 of file mapviz_plugin.h.

void mapviz::MapvizPlugin::DrawOrderChanged ( int  draw_order) [signal]
void mapviz::MapvizPlugin::DrawPlugin ( double  x,
double  y,
double  scale 
) [inline]

Definition at line 122 of file mapviz_plugin.h.

virtual QWidget* mapviz::MapvizPlugin::GetConfigWidget ( QWidget *  parent) [inline, virtual]

Definition at line 252 of file mapviz_plugin.h.

bool mapviz::MapvizPlugin::GetTransform ( const ros::Time stamp,
swri_transform_util::Transform transform,
bool  use_latest_transforms = true 
) [inline]

Definition at line 175 of file mapviz_plugin.h.

bool mapviz::MapvizPlugin::GetTransform ( const std::string &  source,
const ros::Time stamp,
swri_transform_util::Transform transform 
) [inline]

Definition at line 211 of file mapviz_plugin.h.

virtual bool mapviz::MapvizPlugin::Initialize ( boost::shared_ptr< tf::TransformListener tf_listener,
QGLWidget *  canvas 
) [inline, virtual]

Definition at line 64 of file mapviz_plugin.h.

virtual bool mapviz::MapvizPlugin::Initialize ( QGLWidget *  canvas) [protected, pure virtual]
virtual void mapviz::MapvizPlugin::LoadConfig ( const YAML::Node &  load,
const std::string &  path 
) [pure virtual]
std::string mapviz::MapvizPlugin::Name ( ) const [inline]

Definition at line 100 of file mapviz_plugin.h.

virtual void mapviz::MapvizPlugin::Paint ( QPainter *  painter,
double  x,
double  y,
double  scale 
) [inline, virtual]

Draws on the Mapviz canvas using a QPainter; this is called after Draw(). You only need to implement this if you're actually using a QPainter.

Definition at line 87 of file mapviz_plugin.h.

void mapviz::MapvizPlugin::PaintPlugin ( QPainter *  painter,
double  x,
double  y,
double  scale 
) [inline]

Definition at line 136 of file mapviz_plugin.h.

virtual void mapviz::MapvizPlugin::PrintError ( const std::string &  message) [pure virtual]
void mapviz::MapvizPlugin::PrintErrorHelper ( QLabel *  status_label,
const std::string &  message,
double  throttle = 0.0 
) [inline, static]

Definition at line 337 of file mapviz_plugin.h.

virtual void mapviz::MapvizPlugin::PrintInfo ( const std::string &  message) [pure virtual]
void mapviz::MapvizPlugin::PrintInfoHelper ( QLabel *  status_label,
const std::string &  message,
double  throttle = 0.0 
) [inline, static]

Definition at line 357 of file mapviz_plugin.h.

Definition at line 260 of file mapviz_plugin.h.

virtual void mapviz::MapvizPlugin::PrintWarning ( const std::string &  message) [pure virtual]
void mapviz::MapvizPlugin::PrintWarningHelper ( QLabel *  status_label,
const std::string &  message,
double  throttle = 0.0 
) [inline, static]

Definition at line 377 of file mapviz_plugin.h.

virtual void mapviz::MapvizPlugin::SaveConfig ( YAML::Emitter &  emitter,
const std::string &  path 
) [pure virtual]
void mapviz::MapvizPlugin::SetDrawOrder ( int  order) [inline]

Definition at line 108 of file mapviz_plugin.h.

void mapviz::MapvizPlugin::SetIcon ( IconWidget icon) [inline]

Definition at line 258 of file mapviz_plugin.h.

void mapviz::MapvizPlugin::SetName ( const std::string &  name) [inline]

Definition at line 98 of file mapviz_plugin.h.

virtual void mapviz::MapvizPlugin::SetNode ( const ros::NodeHandle node) [inline, virtual]

Definition at line 117 of file mapviz_plugin.h.

void mapviz::MapvizPlugin::SetTargetFrame ( std::string  frame_id) [inline]

Definition at line 150 of file mapviz_plugin.h.

void mapviz::MapvizPlugin::SetType ( const std::string &  type) [inline]

Definition at line 102 of file mapviz_plugin.h.

void mapviz::MapvizPlugin::SetUseLatestTransforms ( bool  value) [inline]

Definition at line 89 of file mapviz_plugin.h.

void mapviz::MapvizPlugin::SetVisible ( bool  visible) [inline]

Definition at line 166 of file mapviz_plugin.h.

virtual void mapviz::MapvizPlugin::Shutdown ( ) [pure virtual]
virtual bool mapviz::MapvizPlugin::SupportsPainting ( ) [inline, virtual, slot]

Override this to return "true" if you want QPainter support for your plugin.

Definition at line 279 of file mapviz_plugin.h.

void mapviz::MapvizPlugin::TargetFrameChanged ( const std::string &  target_frame) [signal]
virtual void mapviz::MapvizPlugin::Transform ( ) [pure virtual]
std::string mapviz::MapvizPlugin::Type ( ) const [inline]

Definition at line 104 of file mapviz_plugin.h.

void mapviz::MapvizPlugin::UseLatestTransformsChanged ( bool  use_latest_transforms) [signal]
bool mapviz::MapvizPlugin::Visible ( ) const [inline]

Definition at line 164 of file mapviz_plugin.h.

void mapviz::MapvizPlugin::VisibleChanged ( bool  visible) [signal]

Member Data Documentation

QGLWidget* mapviz::MapvizPlugin::canvas_ [protected]

Definition at line 296 of file mapviz_plugin.h.

Definition at line 311 of file mapviz_plugin.h.

Definition at line 297 of file mapviz_plugin.h.

Definition at line 293 of file mapviz_plugin.h.

Definition at line 331 of file mapviz_plugin.h.

Definition at line 330 of file mapviz_plugin.h.

Definition at line 329 of file mapviz_plugin.h.

std::string mapviz::MapvizPlugin::name_ [protected]

Definition at line 307 of file mapviz_plugin.h.

Definition at line 299 of file mapviz_plugin.h.

std::string mapviz::MapvizPlugin::source_frame_ [protected]

Definition at line 305 of file mapviz_plugin.h.

std::string mapviz::MapvizPlugin::target_frame_ [protected]

Definition at line 304 of file mapviz_plugin.h.

boost::shared_ptr<tf::TransformListener> mapviz::MapvizPlugin::tf_ [protected]

Definition at line 301 of file mapviz_plugin.h.

Definition at line 302 of file mapviz_plugin.h.

std::string mapviz::MapvizPlugin::type_ [protected]

Definition at line 306 of file mapviz_plugin.h.

Definition at line 309 of file mapviz_plugin.h.

Definition at line 294 of file mapviz_plugin.h.


The documentation for this class was generated from the following file:


mapviz
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 18:50:58