Public Member Functions | Protected Slots | Protected Member Functions | Protected Attributes
jsk_rviz_plugins::OverlayImageDisplay Class Reference

#include <overlay_image_display.h>

Inheritance diagram for jsk_rviz_plugins::OverlayImageDisplay:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual int getX ()
virtual int getY ()
virtual bool isInRegion (int x, int y)
virtual void movePosition (int x, int y)
 OverlayImageDisplay ()
virtual void setPosition (int x, int y)
virtual ~OverlayImageDisplay ()

Protected Slots

void updateAlpha ()
void updateHeight ()
void updateKeepAspectRatio ()
void updateLeft ()
void updateTop ()
void updateTopic ()
void updateWidth ()

Protected Member Functions

virtual void onDisable ()
virtual void onEnable ()
virtual void onInitialize ()
virtual void processMessage (const sensor_msgs::Image::ConstPtr &msg)
virtual void redraw ()
virtual void setImageSize ()
virtual void subscribe ()
virtual void unsubscribe ()
virtual void update (float wall_dt, float ros_dt)

Protected Attributes

double alpha_
rviz::FloatPropertyalpha_property_
int height_
rviz::IntPropertyheight_property_
bool is_msg_available_
std::shared_ptr
< image_transport::ImageTransport
it_
bool keep_aspect_ratio_
rviz::BoolPropertykeep_aspect_ratio_property_
int left_
rviz::IntPropertyleft_property_
sensor_msgs::Image::ConstPtr msg_
boost::mutex mutex_
OverlayObject::Ptr overlay_
bool require_update_
image_transport::Subscriber sub_
int top_
rviz::IntPropertytop_property_
ImageTransportHintsPropertytransport_hint_property_
rviz::RosTopicPropertyupdate_topic_property_
int width_
rviz::IntPropertywidth_property_

Detailed Description

Definition at line 61 of file overlay_image_display.h.


Constructor & Destructor Documentation

Definition at line 51 of file overlay_image_display.cpp.

Definition at line 84 of file overlay_image_display.cpp.


Member Function Documentation

virtual int jsk_rviz_plugins::OverlayImageDisplay::getX ( ) [inline, virtual]

Definition at line 72 of file overlay_image_display.h.

virtual int jsk_rviz_plugins::OverlayImageDisplay::getY ( ) [inline, virtual]

Definition at line 73 of file overlay_image_display.h.

bool jsk_rviz_plugins::OverlayImageDisplay::isInRegion ( int  x,
int  y 
) [virtual]

Definition at line 308 of file overlay_image_display.cpp.

void jsk_rviz_plugins::OverlayImageDisplay::movePosition ( int  x,
int  y 
) [virtual]

Definition at line 314 of file overlay_image_display.cpp.

void jsk_rviz_plugins::OverlayImageDisplay::onDisable ( ) [protected, virtual]

Reimplemented from rviz::Display.

Definition at line 117 of file overlay_image_display.cpp.

void jsk_rviz_plugins::OverlayImageDisplay::onEnable ( ) [protected, virtual]

Reimplemented from rviz::Display.

Definition at line 110 of file overlay_image_display.cpp.

Reimplemented from rviz::Display.

Definition at line 96 of file overlay_image_display.cpp.

void jsk_rviz_plugins::OverlayImageDisplay::processMessage ( const sensor_msgs::Image::ConstPtr &  msg) [protected, virtual]

Definition at line 145 of file overlay_image_display.cpp.

void jsk_rviz_plugins::OverlayImageDisplay::redraw ( ) [protected, virtual]

Definition at line 189 of file overlay_image_display.cpp.

Definition at line 240 of file overlay_image_display.cpp.

void jsk_rviz_plugins::OverlayImageDisplay::setPosition ( int  x,
int  y 
) [virtual]

Definition at line 320 of file overlay_image_display.cpp.

void jsk_rviz_plugins::OverlayImageDisplay::subscribe ( ) [protected, virtual]

Definition at line 131 of file overlay_image_display.cpp.

Definition at line 125 of file overlay_image_display.cpp.

void jsk_rviz_plugins::OverlayImageDisplay::update ( float  wall_dt,
float  ros_dt 
) [protected, virtual]

Reimplemented from rviz::Display.

Definition at line 160 of file overlay_image_display.cpp.

Definition at line 295 of file overlay_image_display.cpp.

Definition at line 276 of file overlay_image_display.cpp.

Definition at line 301 of file overlay_image_display.cpp.

Definition at line 289 of file overlay_image_display.cpp.

Definition at line 283 of file overlay_image_display.cpp.

Definition at line 234 of file overlay_image_display.cpp.

Definition at line 269 of file overlay_image_display.cpp.


Member Data Documentation

Definition at line 87 of file overlay_image_display.h.

Definition at line 85 of file overlay_image_display.h.

Definition at line 86 of file overlay_image_display.h.

Definition at line 82 of file overlay_image_display.h.

Definition at line 91 of file overlay_image_display.h.

Definition at line 88 of file overlay_image_display.h.

Definition at line 93 of file overlay_image_display.h.

Definition at line 80 of file overlay_image_display.h.

Definition at line 86 of file overlay_image_display.h.

Definition at line 83 of file overlay_image_display.h.

sensor_msgs::Image::ConstPtr jsk_rviz_plugins::OverlayImageDisplay::msg_ [protected]

Definition at line 90 of file overlay_image_display.h.

Definition at line 73 of file overlay_image_display.h.

Definition at line 77 of file overlay_image_display.h.

Definition at line 92 of file overlay_image_display.h.

Definition at line 89 of file overlay_image_display.h.

Definition at line 86 of file overlay_image_display.h.

Definition at line 84 of file overlay_image_display.h.

Definition at line 79 of file overlay_image_display.h.

Definition at line 78 of file overlay_image_display.h.

Definition at line 86 of file overlay_image_display.h.

Definition at line 81 of file overlay_image_display.h.


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


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Wed May 1 2019 02:40:22