Public Member Functions | Protected Slots | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
mapviz_plugins::RobotImagePlugin Class Reference

#include <robot_image_plugin.h>

Inheritance diagram for mapviz_plugins::RobotImagePlugin:
Inheritance graph
[legend]

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)
 
 RobotImagePlugin ()
 
void SaveConfig (YAML::Emitter &emitter, const std::string &path)
 
void Shutdown ()
 
void Transform ()
 
virtual ~RobotImagePlugin ()
 
- Public Member Functions inherited from mapviz::MapvizPlugin
virtual void ClearHistory ()
 
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 FrameEdited ()
 
void HeightChanged (double value)
 
void RatioCustomToggled (bool toggled)
 
void RatioEqualToggled (bool toggled)
 
void RatioOriginalToggled (bool toggled)
 
void SelectFile ()
 
void SelectFrame ()
 
void WidthChanged (double value)
 

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 LoadImage ()
 
void UpdateShape ()
 

Private Attributes

tf::Point bottom_left_
 
tf::Point bottom_left_transformed_
 
tf::Point bottom_right_
 
tf::Point bottom_right_transformed_
 
QWidget * config_widget_
 
int dimension_
 
std::string filename_
 
double height_
 
QImage image_
 
double image_ratio_
 
int texture_id_
 
bool texture_loaded_
 
tf::Point top_left_
 
tf::Point top_left_transformed_
 
tf::Point top_right_
 
tf::Point top_right_transformed_
 
bool transformed_
 
Ui::robot_image_config ui_
 
double width_
 

Additional Inherited Members

- 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::MapvizPlugin
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::TransformListenertf_
 
swri_transform_util::TransformManager tf_manager_
 
std::string type_
 
bool use_latest_transforms_
 
bool visible_
 

Detailed Description

Definition at line 55 of file robot_image_plugin.h.

Constructor & Destructor Documentation

mapviz_plugins::RobotImagePlugin::RobotImagePlugin ( )

Definition at line 54 of file robot_image_plugin.cpp.

mapviz_plugins::RobotImagePlugin::~RobotImagePlugin ( )
virtual

Definition at line 86 of file robot_image_plugin.cpp.

Member Function Documentation

void mapviz_plugins::RobotImagePlugin::Draw ( double  x,
double  y,
double  scale 
)
virtual

Implements mapviz::MapvizPlugin.

Definition at line 211 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::FrameEdited ( )
protectedslot

Definition at line 116 of file robot_image_plugin.cpp.

QWidget * mapviz_plugins::RobotImagePlugin::GetConfigWidget ( QWidget *  parent)
virtual

Reimplemented from mapviz::MapvizPlugin.

Definition at line 197 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::HeightChanged ( double  value)
protectedslot

Definition at line 140 of file robot_image_plugin.cpp.

bool mapviz_plugins::RobotImagePlugin::Initialize ( QGLWidget *  canvas)
virtual

Implements mapviz::MapvizPlugin.

Definition at line 204 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::LoadConfig ( const YAML::Node &  node,
const std::string &  path 
)
virtual

Implements mapviz::MapvizPlugin.

Definition at line 315 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::LoadImage ( )
private

Definition at line 253 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::PrintError ( const std::string &  message)
protectedvirtual

Implements mapviz::MapvizPlugin.

Definition at line 182 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::PrintInfo ( const std::string &  message)
protectedvirtual

Implements mapviz::MapvizPlugin.

Definition at line 187 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::PrintWarning ( const std::string &  message)
protectedvirtual

Implements mapviz::MapvizPlugin.

Definition at line 192 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::RatioCustomToggled ( bool  toggled)
protectedslot

Definition at line 156 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::RatioEqualToggled ( bool  toggled)
protectedslot

Definition at line 146 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::RatioOriginalToggled ( bool  toggled)
protectedslot

Definition at line 164 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::SaveConfig ( YAML::Emitter &  emitter,
const std::string &  path 
)
virtual

Implements mapviz::MapvizPlugin.

Definition at line 364 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::SelectFile ( )
protectedslot

Definition at line 90 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::SelectFrame ( )
protectedslot

Definition at line 106 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::Shutdown ( )
inlinevirtual

Implements mapviz::MapvizPlugin.

Definition at line 64 of file robot_image_plugin.h.

void mapviz_plugins::RobotImagePlugin::Transform ( )
virtual

Implements mapviz::MapvizPlugin.

Definition at line 234 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::UpdateShape ( )
private

Definition at line 174 of file robot_image_plugin.cpp.

void mapviz_plugins::RobotImagePlugin::WidthChanged ( double  value)
protectedslot

Definition at line 128 of file robot_image_plugin.cpp.

Member Data Documentation

tf::Point mapviz_plugins::RobotImagePlugin::bottom_left_
private

Definition at line 108 of file robot_image_plugin.h.

tf::Point mapviz_plugins::RobotImagePlugin::bottom_left_transformed_
private

Definition at line 113 of file robot_image_plugin.h.

tf::Point mapviz_plugins::RobotImagePlugin::bottom_right_
private

Definition at line 109 of file robot_image_plugin.h.

tf::Point mapviz_plugins::RobotImagePlugin::bottom_right_transformed_
private

Definition at line 114 of file robot_image_plugin.h.

QWidget* mapviz_plugins::RobotImagePlugin::config_widget_
private

Definition at line 92 of file robot_image_plugin.h.

int mapviz_plugins::RobotImagePlugin::dimension_
private

Definition at line 100 of file robot_image_plugin.h.

std::string mapviz_plugins::RobotImagePlugin::filename_
private

Definition at line 98 of file robot_image_plugin.h.

double mapviz_plugins::RobotImagePlugin::height_
private

Definition at line 95 of file robot_image_plugin.h.

QImage mapviz_plugins::RobotImagePlugin::image_
private

Definition at line 99 of file robot_image_plugin.h.

double mapviz_plugins::RobotImagePlugin::image_ratio_
private

Definition at line 96 of file robot_image_plugin.h.

int mapviz_plugins::RobotImagePlugin::texture_id_
private

Definition at line 101 of file robot_image_plugin.h.

bool mapviz_plugins::RobotImagePlugin::texture_loaded_
private

Definition at line 102 of file robot_image_plugin.h.

tf::Point mapviz_plugins::RobotImagePlugin::top_left_
private

Definition at line 106 of file robot_image_plugin.h.

tf::Point mapviz_plugins::RobotImagePlugin::top_left_transformed_
private

Definition at line 111 of file robot_image_plugin.h.

tf::Point mapviz_plugins::RobotImagePlugin::top_right_
private

Definition at line 107 of file robot_image_plugin.h.

tf::Point mapviz_plugins::RobotImagePlugin::top_right_transformed_
private

Definition at line 112 of file robot_image_plugin.h.

bool mapviz_plugins::RobotImagePlugin::transformed_
private

Definition at line 104 of file robot_image_plugin.h.

Ui::robot_image_config mapviz_plugins::RobotImagePlugin::ui_
private

Definition at line 91 of file robot_image_plugin.h.

double mapviz_plugins::RobotImagePlugin::width_
private

Definition at line 94 of file robot_image_plugin.h.


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


mapviz_plugins
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 19:25:17