#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 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, 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 | 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 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.
| virtual mapviz::MapvizPlugin::~MapvizPlugin |
( |
| ) |
|
|
inlinevirtual |
| mapviz::MapvizPlugin::MapvizPlugin |
( |
| ) |
|
|
inlineprotected |
| virtual void mapviz::MapvizPlugin::ClearHistory |
( |
| ) |
|
|
inlinevirtual |
| 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 |
( |
| ) |
|
|
inlinevirtualslot |
| int mapviz::MapvizPlugin::DrawOrder |
( |
| ) |
const |
|
inline |
| void mapviz::MapvizPlugin::DrawOrderChanged |
( |
int |
draw_order | ) |
|
|
signal |
| void mapviz::MapvizPlugin::DrawPlugin |
( |
double |
x, |
|
|
double |
y, |
|
|
double |
scale |
|
) |
| |
|
inline |
| virtual QWidget* mapviz::MapvizPlugin::GetConfigWidget |
( |
QWidget * |
parent | ) |
|
|
inlinevirtual |
| virtual bool mapviz::MapvizPlugin::Initialize |
( |
QGLWidget * |
canvas | ) |
|
|
protectedpure virtual |
| virtual void mapviz::MapvizPlugin::LoadConfig |
( |
const YAML::Node & |
load, |
|
|
const std::string & |
path |
|
) |
| |
|
pure virtual |
| std::string mapviz::MapvizPlugin::Name |
( |
| ) |
const |
|
inline |
| 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.
| void mapviz::MapvizPlugin::PaintPlugin |
( |
QPainter * |
painter, |
|
|
double |
x, |
|
|
double |
y, |
|
|
double |
scale |
|
) |
| |
|
inline |
| 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 |
|
) |
| |
|
inlinestatic |
| 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 |
|
) |
| |
|
inlinestatic |
| void mapviz::MapvizPlugin::PrintMeasurements |
( |
| ) |
|
|
inline |
| 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 |
|
) |
| |
|
inlinestatic |
| virtual void mapviz::MapvizPlugin::SaveConfig |
( |
YAML::Emitter & |
emitter, |
|
|
const std::string & |
path |
|
) |
| |
|
pure virtual |
| void mapviz::MapvizPlugin::SetDrawOrder |
( |
int |
order | ) |
|
|
inline |
| void mapviz::MapvizPlugin::SetIcon |
( |
IconWidget * |
icon | ) |
|
|
inline |
| void mapviz::MapvizPlugin::SetName |
( |
const std::string & |
name | ) |
|
|
inline |
| void mapviz::MapvizPlugin::SetTargetFrame |
( |
std::string |
frame_id | ) |
|
|
inline |
| void mapviz::MapvizPlugin::SetType |
( |
const std::string & |
type | ) |
|
|
inline |
| void mapviz::MapvizPlugin::SetUseLatestTransforms |
( |
bool |
value | ) |
|
|
inline |
| void mapviz::MapvizPlugin::SetVisible |
( |
bool |
visible | ) |
|
|
inline |
| virtual void mapviz::MapvizPlugin::Shutdown |
( |
| ) |
|
|
pure virtual |
| void mapviz::MapvizPlugin::SizeChanged |
( |
| ) |
|
|
signal |
| virtual bool mapviz::MapvizPlugin::SupportsPainting |
( |
| ) |
|
|
inlinevirtualslot |
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 |
| void mapviz::MapvizPlugin::UseLatestTransformsChanged |
( |
bool |
use_latest_transforms | ) |
|
|
signal |
| bool mapviz::MapvizPlugin::Visible |
( |
| ) |
const |
|
inline |
| void mapviz::MapvizPlugin::VisibleChanged |
( |
bool |
visible | ) |
|
|
signal |
| QGLWidget* mapviz::MapvizPlugin::canvas_ |
|
protected |
| int mapviz::MapvizPlugin::draw_order_ |
|
protected |
| bool mapviz::MapvizPlugin::initialized_ |
|
protected |
| Stopwatch mapviz::MapvizPlugin::meas_transform_ |
|
private |
| std::string mapviz::MapvizPlugin::name_ |
|
protected |
| std::string mapviz::MapvizPlugin::source_frame_ |
|
protected |
| std::string mapviz::MapvizPlugin::target_frame_ |
|
protected |
| std::string mapviz::MapvizPlugin::type_ |
|
protected |
| bool mapviz::MapvizPlugin::use_latest_transforms_ |
|
protected |
| bool mapviz::MapvizPlugin::visible_ |
|
protected |
The documentation for this class was generated from the following file: