#include <mapviz_plugin.h>
|
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 | GetTransform (const std::string &source, const ros::Time &stamp, swri_transform_util::Transform &transform) |
|
virtual bool | Initialize (boost::shared_ptr< tf::TransformListener > tf_listener, swri_transform_util::TransformManagerPtr tf_manager, 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 | SetVisible (bool visible) |
|
virtual void | Shutdown ()=0 |
|
virtual void | Transform ()=0 |
|
std::string | Type () const |
|
bool | Visible () const |
|
virtual | ~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) |
|
Definition at line 57 of file mapviz_plugin.h.
◆ ~MapvizPlugin()
virtual mapviz::MapvizPlugin::~MapvizPlugin |
( |
| ) |
|
|
inlinevirtual |
◆ MapvizPlugin()
mapviz::MapvizPlugin::MapvizPlugin |
( |
| ) |
|
|
inlineprotected |
◆ ClearHistory()
virtual void mapviz::MapvizPlugin::ClearHistory |
( |
| ) |
|
|
inlinevirtual |
◆ Draw()
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();
◆ DrawIcon
virtual void mapviz::MapvizPlugin::DrawIcon |
( |
| ) |
|
|
inlinevirtualslot |
◆ DrawOrder()
int mapviz::MapvizPlugin::DrawOrder |
( |
| ) |
const |
|
inline |
◆ DrawOrderChanged
void mapviz::MapvizPlugin::DrawOrderChanged |
( |
int |
draw_order | ) |
|
|
signal |
◆ DrawPlugin()
void mapviz::MapvizPlugin::DrawPlugin |
( |
double |
x, |
|
|
double |
y, |
|
|
double |
scale |
|
) |
| |
|
inline |
◆ GetConfigWidget()
virtual QWidget* mapviz::MapvizPlugin::GetConfigWidget |
( |
QWidget * |
parent | ) |
|
|
inlinevirtual |
◆ GetTransform() [1/2]
◆ GetTransform() [2/2]
◆ Initialize() [1/2]
◆ Initialize() [2/2]
virtual bool mapviz::MapvizPlugin::Initialize |
( |
QGLWidget * |
canvas | ) |
|
|
protectedpure virtual |
◆ LoadConfig()
virtual void mapviz::MapvizPlugin::LoadConfig |
( |
const YAML::Node & |
load, |
|
|
const std::string & |
path |
|
) |
| |
|
pure virtual |
◆ Name()
std::string mapviz::MapvizPlugin::Name |
( |
| ) |
const |
|
inline |
◆ Paint()
virtual void mapviz::MapvizPlugin::Paint |
( |
QPainter * |
painter, |
|
|
double |
x, |
|
|
double |
y, |
|
|
double |
scale |
|
) |
| |
|
inlinevirtual |
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.
◆ PaintPlugin()
void mapviz::MapvizPlugin::PaintPlugin |
( |
QPainter * |
painter, |
|
|
double |
x, |
|
|
double |
y, |
|
|
double |
scale |
|
) |
| |
|
inline |
◆ PrintError()
virtual void mapviz::MapvizPlugin::PrintError |
( |
const std::string & |
message | ) |
|
|
pure virtual |
◆ PrintErrorHelper()
void mapviz::MapvizPlugin::PrintErrorHelper |
( |
QLabel * |
status_label, |
|
|
const std::string & |
message, |
|
|
double |
throttle = 0.0 |
|
) |
| |
|
inlinestatic |
◆ PrintInfo()
virtual void mapviz::MapvizPlugin::PrintInfo |
( |
const std::string & |
message | ) |
|
|
pure virtual |
◆ PrintInfoHelper()
void mapviz::MapvizPlugin::PrintInfoHelper |
( |
QLabel * |
status_label, |
|
|
const std::string & |
message, |
|
|
double |
throttle = 0.0 |
|
) |
| |
|
inlinestatic |
◆ PrintMeasurements()
void mapviz::MapvizPlugin::PrintMeasurements |
( |
| ) |
|
|
inline |
◆ PrintWarning()
virtual void mapviz::MapvizPlugin::PrintWarning |
( |
const std::string & |
message | ) |
|
|
pure virtual |
◆ PrintWarningHelper()
void mapviz::MapvizPlugin::PrintWarningHelper |
( |
QLabel * |
status_label, |
|
|
const std::string & |
message, |
|
|
double |
throttle = 0.0 |
|
) |
| |
|
inlinestatic |
◆ SaveConfig()
virtual void mapviz::MapvizPlugin::SaveConfig |
( |
YAML::Emitter & |
emitter, |
|
|
const std::string & |
path |
|
) |
| |
|
pure virtual |
◆ SetDrawOrder()
void mapviz::MapvizPlugin::SetDrawOrder |
( |
int |
order | ) |
|
|
inline |
◆ SetIcon()
void mapviz::MapvizPlugin::SetIcon |
( |
IconWidget * |
icon | ) |
|
|
inline |
◆ SetName()
void mapviz::MapvizPlugin::SetName |
( |
const std::string & |
name | ) |
|
|
inline |
◆ SetNode()
◆ SetTargetFrame()
void mapviz::MapvizPlugin::SetTargetFrame |
( |
std::string |
frame_id | ) |
|
|
inline |
◆ SetType()
void mapviz::MapvizPlugin::SetType |
( |
const std::string & |
type | ) |
|
|
inline |
◆ SetVisible()
void mapviz::MapvizPlugin::SetVisible |
( |
bool |
visible | ) |
|
|
inline |
◆ Shutdown()
virtual void mapviz::MapvizPlugin::Shutdown |
( |
| ) |
|
|
pure virtual |
◆ SizeChanged
void mapviz::MapvizPlugin::SizeChanged |
( |
| ) |
|
|
signal |
◆ SupportsPainting
virtual bool mapviz::MapvizPlugin::SupportsPainting |
( |
| ) |
|
|
inlinevirtualslot |
Override this to return "true" if you want QPainter support for your plugin.
Definition at line 232 of file mapviz_plugin.h.
◆ TargetFrameChanged
void mapviz::MapvizPlugin::TargetFrameChanged |
( |
const std::string & |
target_frame | ) |
|
|
signal |
◆ Transform()
virtual void mapviz::MapvizPlugin::Transform |
( |
| ) |
|
|
pure virtual |
◆ Type()
std::string mapviz::MapvizPlugin::Type |
( |
| ) |
const |
|
inline |
◆ UseLatestTransformsChanged
void mapviz::MapvizPlugin::UseLatestTransformsChanged |
( |
bool |
use_latest_transforms | ) |
|
|
signal |
◆ Visible()
bool mapviz::MapvizPlugin::Visible |
( |
| ) |
const |
|
inline |
◆ VisibleChanged
void mapviz::MapvizPlugin::VisibleChanged |
( |
bool |
visible | ) |
|
|
signal |
◆ canvas_
QGLWidget* mapviz::MapvizPlugin::canvas_ |
|
protected |
◆ draw_order_
int mapviz::MapvizPlugin::draw_order_ |
|
protected |
◆ icon_
◆ initialized_
bool mapviz::MapvizPlugin::initialized_ |
|
protected |
◆ meas_draw_
◆ meas_paint_
◆ meas_transform_
Stopwatch mapviz::MapvizPlugin::meas_transform_ |
|
private |
◆ name_
std::string mapviz::MapvizPlugin::name_ |
|
protected |
◆ node_
◆ source_frame_
std::string mapviz::MapvizPlugin::source_frame_ |
|
protected |
◆ target_frame_
std::string mapviz::MapvizPlugin::target_frame_ |
|
protected |
◆ tf_
◆ tf_manager_
◆ type_
std::string mapviz::MapvizPlugin::type_ |
|
protected |
◆ visible_
bool mapviz::MapvizPlugin::visible_ |
|
protected |
The documentation for this class was generated from the following file: