Public Types | Public Slots | Public Member Functions | Protected Slots | Protected Member Functions | Private Member Functions | Private Attributes
mapviz_plugins::ImagePlugin Class Reference

#include <image_plugin.h>

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

List of all members.

Public Types

enum  Anchor {
  TOP_LEFT, TOP_CENTER, TOP_RIGHT, CENTER_LEFT,
  CENTER, CENTER_RIGHT, BOTTOM_LEFT, BOTTOM_CENTER,
  BOTTOM_RIGHT
}
enum  Units { PIXELS, PERCENT }

Public Slots

void Resubscribe ()

Public Member Functions

void CreateLocalNode ()
void Draw (double x, double y, double scale)
QWidget * GetConfigWidget (QWidget *parent)
 ImagePlugin ()
bool Initialize (QGLWidget *canvas)
void LoadConfig (const YAML::Node &node, const std::string &path)
void SaveConfig (YAML::Emitter &emitter, const std::string &path)
virtual void SetNode (const ros::NodeHandle &node)
void Shutdown ()
void Transform ()
virtual ~ImagePlugin ()

Protected Slots

void KeepRatioChanged (bool checked)
void SelectTopic ()
void SetAnchor (QString anchor)
void SetHeight (double height)
void SetOffsetX (int offset)
void SetOffsetY (int offset)
void SetSubscription (bool visible)
void SetTransport (const QString &transport)
void SetUnits (QString units)
void SetWidth (double width)
void TopicEdited ()

Protected Member Functions

void PrintError (const std::string &message)
void PrintInfo (const std::string &message)
void PrintWarning (const std::string &message)

Private Member Functions

std::string AnchorToString (Anchor anchor)
void DrawIplImage (cv::Mat *image)
void imageCallback (const sensor_msgs::ImageConstPtr &image)
void ScaleImage (double width, double height)
std::string UnitsToString (Units units)

Private Attributes

Anchor anchor_
QWidget * config_widget_
cv_bridge::CvImagePtr cv_image_
bool force_resubscribe_
bool has_image_
bool has_message_
double height_
sensor_msgs::Image image_
image_transport::Subscriber image_sub_
double last_height_
double last_width_
ros::NodeHandle local_node_
int offset_x_
int offset_y_
double original_aspect_ratio_
cv::Mat scaled_image_
std::string topic_
QString transport_
Ui::image_config ui_
Units units_
double width_

Detailed Description

Definition at line 60 of file image_plugin.h.


Member Enumeration Documentation

Enumerator:
TOP_LEFT 
TOP_CENTER 
TOP_RIGHT 
CENTER_LEFT 
CENTER 
CENTER_RIGHT 
BOTTOM_LEFT 
BOTTOM_CENTER 
BOTTOM_RIGHT 

Definition at line 65 of file image_plugin.h.

Enumerator:
PIXELS 
PERCENT 

Definition at line 77 of file image_plugin.h.


Constructor & Destructor Documentation

Definition at line 53 of file image_plugin.cpp.

Definition at line 96 of file image_plugin.cpp.


Member Function Documentation

std::string mapviz_plugins::ImagePlugin::AnchorToString ( Anchor  anchor) [private]

Definition at line 605 of file image_plugin.cpp.

Definition at line 665 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::Draw ( double  x,
double  y,
double  scale 
) [virtual]

Implements mapviz::MapvizPlugin.

Definition at line 423 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::DrawIplImage ( cv::Mat *  image) [private]

Definition at line 391 of file image_plugin.cpp.

QWidget * mapviz_plugins::ImagePlugin::GetConfigWidget ( QWidget *  parent) [virtual]

Reimplemented from mapviz::MapvizPlugin.

Definition at line 367 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::imageCallback ( const sensor_msgs::ImageConstPtr &  image) [private]

Definition at line 315 of file image_plugin.cpp.

bool mapviz_plugins::ImagePlugin::Initialize ( QGLWidget *  canvas) [virtual]

Implements mapviz::MapvizPlugin.

Definition at line 374 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::KeepRatioChanged ( bool  checked) [protected, slot]

Definition at line 223 of file image_plugin.cpp.

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

Implements mapviz::MapvizPlugin.

Definition at line 514 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::PrintError ( const std::string &  message) [protected, virtual]

Implements mapviz::MapvizPlugin.

Definition at line 352 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::PrintInfo ( const std::string &  message) [protected, virtual]

Implements mapviz::MapvizPlugin.

Definition at line 357 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::PrintWarning ( const std::string &  message) [protected, virtual]

Implements mapviz::MapvizPlugin.

Definition at line 362 of file image_plugin.cpp.

Definition at line 232 of file image_plugin.cpp.

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

Implements mapviz::MapvizPlugin.

Definition at line 592 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::ScaleImage ( double  width,
double  height 
) [private]

Definition at line 381 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::SelectTopic ( ) [protected, slot]

Definition at line 241 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::SetAnchor ( QString  anchor) [protected, slot]

Definition at line 120 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::SetHeight ( double  height) [protected, slot]

Definition at line 115 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::SetNode ( const ros::NodeHandle node) [virtual]

Reimplemented from mapviz::MapvizPlugin.

Definition at line 676 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::SetOffsetX ( int  offset) [protected, slot]

Definition at line 100 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::SetOffsetY ( int  offset) [protected, slot]

Definition at line 105 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::SetSubscription ( bool  visible) [protected, slot]

Definition at line 196 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::SetTransport ( const QString &  transport) [protected, slot]

Definition at line 216 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::SetUnits ( QString  units) [protected, slot]

Definition at line 160 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::SetWidth ( double  width) [protected, slot]

Definition at line 110 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::Shutdown ( ) [inline, virtual]

Implements mapviz::MapvizPlugin.

Definition at line 83 of file image_plugin.h.

void mapviz_plugins::ImagePlugin::TopicEdited ( ) [protected, slot]

Definition at line 259 of file image_plugin.cpp.

void mapviz_plugins::ImagePlugin::Transform ( ) [inline, virtual]

Implements mapviz::MapvizPlugin.

Definition at line 90 of file image_plugin.h.

std::string mapviz_plugins::ImagePlugin::UnitsToString ( Units  units) [private]

Definition at line 649 of file image_plugin.cpp.


Member Data Documentation

Definition at line 123 of file image_plugin.h.

Definition at line 120 of file image_plugin.h.

Definition at line 144 of file image_plugin.h.

Definition at line 131 of file image_plugin.h.

Definition at line 132 of file image_plugin.h.

Definition at line 140 of file image_plugin.h.

Definition at line 128 of file image_plugin.h.

sensor_msgs::Image mapviz_plugins::ImagePlugin::image_ [private]

Definition at line 142 of file image_plugin.h.

Definition at line 139 of file image_plugin.h.

Definition at line 135 of file image_plugin.h.

Definition at line 134 of file image_plugin.h.

Definition at line 138 of file image_plugin.h.

Definition at line 125 of file image_plugin.h.

Definition at line 126 of file image_plugin.h.

Definition at line 136 of file image_plugin.h.

Definition at line 145 of file image_plugin.h.

std::string mapviz_plugins::ImagePlugin::topic_ [private]

Definition at line 122 of file image_plugin.h.

Definition at line 129 of file image_plugin.h.

Ui::image_config mapviz_plugins::ImagePlugin::ui_ [private]

Definition at line 119 of file image_plugin.h.

Definition at line 124 of file image_plugin.h.

Definition at line 127 of file 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 18:51:07