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

#include <image_plugin.h>

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

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 Slots inherited from mapviz::MapvizPlugin
virtual void DrawIcon ()
 
virtual bool SupportsPainting ()
 

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 ()
 
- 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 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)
 
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)
 
void SetTargetFrame (std::string frame_id)
 
void SetType (const std::string &type)
 
void SetVisible (bool visible)
 
std::string Type () const
 
bool Visible () const
 
virtual ~MapvizPlugin ()
 

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)
 
- Protected Member Functions inherited from mapviz::MapvizPlugin
 MapvizPlugin ()
 

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_
 
std::string transport_
 
Ui::image_config ui_
 
Units units_
 
double width_
 

Additional Inherited Members

- 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::TransformManagerPtr tf_manager_
 
std::string type_
 
bool visible_
 

Detailed Description

Definition at line 60 of file image_plugin.h.

Member Enumeration Documentation

◆ Anchor

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.

◆ Units

Enumerator
PIXELS 
PERCENT 

Definition at line 77 of file image_plugin.h.

Constructor & Destructor Documentation

◆ ImagePlugin()

mapviz_plugins::ImagePlugin::ImagePlugin ( )

Definition at line 53 of file image_plugin.cpp.

◆ ~ImagePlugin()

mapviz_plugins::ImagePlugin::~ImagePlugin ( )
virtual

Definition at line 96 of file image_plugin.cpp.

Member Function Documentation

◆ AnchorToString()

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

Definition at line 602 of file image_plugin.cpp.

◆ CreateLocalNode()

void mapviz_plugins::ImagePlugin::CreateLocalNode ( )

Definition at line 662 of file image_plugin.cpp.

◆ Draw()

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

Implements mapviz::MapvizPlugin.

Definition at line 422 of file image_plugin.cpp.

◆ DrawIplImage()

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

Definition at line 388 of file image_plugin.cpp.

◆ GetConfigWidget()

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

Reimplemented from mapviz::MapvizPlugin.

Definition at line 364 of file image_plugin.cpp.

◆ imageCallback()

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

Definition at line 312 of file image_plugin.cpp.

◆ Initialize()

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

Implements mapviz::MapvizPlugin.

Definition at line 371 of file image_plugin.cpp.

◆ KeepRatioChanged

void mapviz_plugins::ImagePlugin::KeepRatioChanged ( bool  checked)
protectedslot

Definition at line 220 of file image_plugin.cpp.

◆ LoadConfig()

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

Implements mapviz::MapvizPlugin.

Definition at line 513 of file image_plugin.cpp.

◆ PrintError()

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

Implements mapviz::MapvizPlugin.

Definition at line 349 of file image_plugin.cpp.

◆ PrintInfo()

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

Implements mapviz::MapvizPlugin.

Definition at line 354 of file image_plugin.cpp.

◆ PrintWarning()

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

Implements mapviz::MapvizPlugin.

Definition at line 359 of file image_plugin.cpp.

◆ Resubscribe

void mapviz_plugins::ImagePlugin::Resubscribe ( )
slot

Definition at line 229 of file image_plugin.cpp.

◆ SaveConfig()

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

Implements mapviz::MapvizPlugin.

Definition at line 589 of file image_plugin.cpp.

◆ ScaleImage()

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

Definition at line 378 of file image_plugin.cpp.

◆ SelectTopic

void mapviz_plugins::ImagePlugin::SelectTopic ( )
protectedslot

Definition at line 238 of file image_plugin.cpp.

◆ SetAnchor

void mapviz_plugins::ImagePlugin::SetAnchor ( QString  anchor)
protectedslot

Definition at line 120 of file image_plugin.cpp.

◆ SetHeight

void mapviz_plugins::ImagePlugin::SetHeight ( double  height)
protectedslot

Definition at line 115 of file image_plugin.cpp.

◆ SetNode()

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

Reimplemented from mapviz::MapvizPlugin.

Definition at line 673 of file image_plugin.cpp.

◆ SetOffsetX

void mapviz_plugins::ImagePlugin::SetOffsetX ( int  offset)
protectedslot

Definition at line 100 of file image_plugin.cpp.

◆ SetOffsetY

void mapviz_plugins::ImagePlugin::SetOffsetY ( int  offset)
protectedslot

Definition at line 105 of file image_plugin.cpp.

◆ SetSubscription

void mapviz_plugins::ImagePlugin::SetSubscription ( bool  visible)
protectedslot

Definition at line 196 of file image_plugin.cpp.

◆ SetTransport

void mapviz_plugins::ImagePlugin::SetTransport ( const QString &  transport)
protectedslot

Definition at line 213 of file image_plugin.cpp.

◆ SetUnits

void mapviz_plugins::ImagePlugin::SetUnits ( QString  units)
protectedslot

Definition at line 160 of file image_plugin.cpp.

◆ SetWidth

void mapviz_plugins::ImagePlugin::SetWidth ( double  width)
protectedslot

Definition at line 110 of file image_plugin.cpp.

◆ Shutdown()

void mapviz_plugins::ImagePlugin::Shutdown ( )
inlinevirtual

Implements mapviz::MapvizPlugin.

Definition at line 83 of file image_plugin.h.

◆ TopicEdited

void mapviz_plugins::ImagePlugin::TopicEdited ( )
protectedslot

Definition at line 256 of file image_plugin.cpp.

◆ Transform()

void mapviz_plugins::ImagePlugin::Transform ( )
inlinevirtual

Implements mapviz::MapvizPlugin.

Definition at line 90 of file image_plugin.h.

◆ UnitsToString()

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

Definition at line 646 of file image_plugin.cpp.

Member Data Documentation

◆ anchor_

Anchor mapviz_plugins::ImagePlugin::anchor_
private

Definition at line 123 of file image_plugin.h.

◆ config_widget_

QWidget* mapviz_plugins::ImagePlugin::config_widget_
private

Definition at line 120 of file image_plugin.h.

◆ cv_image_

cv_bridge::CvImagePtr mapviz_plugins::ImagePlugin::cv_image_
private

Definition at line 144 of file image_plugin.h.

◆ force_resubscribe_

bool mapviz_plugins::ImagePlugin::force_resubscribe_
private

Definition at line 131 of file image_plugin.h.

◆ has_image_

bool mapviz_plugins::ImagePlugin::has_image_
private

Definition at line 132 of file image_plugin.h.

◆ has_message_

bool mapviz_plugins::ImagePlugin::has_message_
private

Definition at line 140 of file image_plugin.h.

◆ height_

double mapviz_plugins::ImagePlugin::height_
private

Definition at line 128 of file image_plugin.h.

◆ image_

sensor_msgs::Image mapviz_plugins::ImagePlugin::image_
private

Definition at line 142 of file image_plugin.h.

◆ image_sub_

image_transport::Subscriber mapviz_plugins::ImagePlugin::image_sub_
private

Definition at line 139 of file image_plugin.h.

◆ last_height_

double mapviz_plugins::ImagePlugin::last_height_
private

Definition at line 135 of file image_plugin.h.

◆ last_width_

double mapviz_plugins::ImagePlugin::last_width_
private

Definition at line 134 of file image_plugin.h.

◆ local_node_

ros::NodeHandle mapviz_plugins::ImagePlugin::local_node_
private

Definition at line 138 of file image_plugin.h.

◆ offset_x_

int mapviz_plugins::ImagePlugin::offset_x_
private

Definition at line 125 of file image_plugin.h.

◆ offset_y_

int mapviz_plugins::ImagePlugin::offset_y_
private

Definition at line 126 of file image_plugin.h.

◆ original_aspect_ratio_

double mapviz_plugins::ImagePlugin::original_aspect_ratio_
private

Definition at line 136 of file image_plugin.h.

◆ scaled_image_

cv::Mat mapviz_plugins::ImagePlugin::scaled_image_
private

Definition at line 145 of file image_plugin.h.

◆ topic_

std::string mapviz_plugins::ImagePlugin::topic_
private

Definition at line 122 of file image_plugin.h.

◆ transport_

std::string mapviz_plugins::ImagePlugin::transport_
private

Definition at line 129 of file image_plugin.h.

◆ ui_

Ui::image_config mapviz_plugins::ImagePlugin::ui_
private

Definition at line 119 of file image_plugin.h.

◆ units_

Units mapviz_plugins::ImagePlugin::units_
private

Definition at line 124 of file image_plugin.h.

◆ width_

double mapviz_plugins::ImagePlugin::width_
private

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 Wed Jan 17 2024 03:27:49