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

#include <image_view.h>

Inheritance diagram for rqt_image_view::ImageView:
Inheritance graph
[legend]

Public Member Functions

 ImageView ()
 
virtual void initPlugin (qt_gui_cpp::PluginContext &context)
 
virtual void restoreSettings (const qt_gui_cpp::Settings &plugin_settings, const qt_gui_cpp::Settings &instance_settings)
 
virtual void saveSettings (qt_gui_cpp::Settings &plugin_settings, qt_gui_cpp::Settings &instance_settings) const
 
virtual void shutdownPlugin ()
 
- Public Member Functions inherited from rqt_gui_cpp::Plugin
 Plugin ()
 
- Public Member Functions inherited from qt_gui_cpp::Plugin
virtual bool hasConfiguration () const
 
 Plugin ()
 
virtual void triggerConfiguration ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Protected Slots

virtual void onDynamicRange (bool checked)
 
virtual void onHideToolbarChanged (bool hide)
 
virtual void onMouseLeft (int x, int y)
 
virtual void onMousePublish (bool checked)
 
virtual void onPubTopicChanged ()
 
virtual void onRotateLeft ()
 
virtual void onRotateRight ()
 
virtual void onTopicChanged (int index)
 
virtual void onZoom1 (bool checked)
 
virtual void saveImage ()
 
virtual void setColorSchemeList ()
 
virtual void updateNumGridlines ()
 
virtual void updateTopicList ()
 

Protected Member Functions

virtual void callbackImage (const sensor_msgs::Image::ConstPtr &msg)
 
QList< int > getGridIndices (int size) const
 
virtual ROS_DEPRECATED QList< QString > getTopicList (const QSet< QString > &message_types, const QList< QString > &transports)
 
virtual QSet< QString > getTopics (const QSet< QString > &message_types, const QSet< QString > &message_sub_types, const QList< QString > &transports)
 
virtual void invertPixels (int x, int y)
 
virtual void overlayGrid ()
 
virtual void selectTopic (const QString &topic)
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Protected Attributes

cv::Mat conversion_mat_
 
image_transport::Subscriber subscriber_
 
Ui::ImageViewWidget ui_
 
QWidget * widget_
 

Private Types

enum  RotateState {
  ROTATE_0 = 0, ROTATE_90 = 1, ROTATE_180 = 2, ROTATE_270 = 3,
  ROTATE_STATE_COUNT
}
 

Private Member Functions

void syncRotateLabel ()
 

Private Attributes

QString arg_topic_name
 
QAction * hide_toolbar_action_
 
int num_gridlines_
 
ros::Publisher pub_mouse_left_
 
bool pub_topic_custom_
 
RotateState rotate_state_
 

Detailed Description

Definition at line 60 of file image_view.h.

Member Enumeration Documentation

◆ RotateState

Enumerator
ROTATE_0 
ROTATE_90 
ROTATE_180 
ROTATE_270 
ROTATE_STATE_COUNT 

Definition at line 136 of file image_view.h.

Constructor & Destructor Documentation

◆ ImageView()

rqt_image_view::ImageView::ImageView ( )

Definition at line 48 of file image_view.cpp.

Member Function Documentation

◆ callbackImage()

void rqt_image_view::ImageView::callbackImage ( const sensor_msgs::Image::ConstPtr &  msg)
protectedvirtual

Definition at line 564 of file image_view.cpp.

◆ getGridIndices()

QList< int > rqt_image_view::ImageView::getGridIndices ( int  size) const
protected

Definition at line 502 of file image_view.cpp.

◆ getTopicList()

QList< QString > rqt_image_view::ImageView::getTopicList ( const QSet< QString > &  message_types,
const QList< QString > &  transports 
)
protectedvirtual

Definition at line 258 of file image_view.cpp.

◆ getTopics()

QSet< QString > rqt_image_view::ImageView::getTopics ( const QSet< QString > &  message_types,
const QSet< QString > &  message_sub_types,
const QList< QString > &  transports 
)
protectedvirtual

Definition at line 264 of file image_view.cpp.

◆ initPlugin()

void rqt_image_view::ImageView::initPlugin ( qt_gui_cpp::PluginContext context)
virtual

Reimplemented from qt_gui_cpp::Plugin.

Definition at line 57 of file image_view.cpp.

◆ invertPixels()

void rqt_image_view::ImageView::invertPixels ( int  x,
int  y 
)
protectedvirtual

Definition at line 492 of file image_view.cpp.

◆ onDynamicRange

void rqt_image_view::ImageView::onDynamicRange ( bool  checked)
protectedvirtualslot

Definition at line 371 of file image_view.cpp.

◆ onHideToolbarChanged

void rqt_image_view::ImageView::onHideToolbarChanged ( bool  hide)
protectedvirtualslot

Definition at line 459 of file image_view.cpp.

◆ onMouseLeft

void rqt_image_view::ImageView::onMouseLeft ( int  x,
int  y 
)
protectedvirtualslot

Definition at line 419 of file image_view.cpp.

◆ onMousePublish

void rqt_image_view::ImageView::onMousePublish ( bool  checked)
protectedvirtualslot

Definition at line 395 of file image_view.cpp.

◆ onPubTopicChanged

void rqt_image_view::ImageView::onPubTopicChanged ( )
protectedvirtualslot

Definition at line 453 of file image_view.cpp.

◆ onRotateLeft

void rqt_image_view::ImageView::onRotateLeft ( )
protectedvirtualslot

Definition at line 464 of file image_view.cpp.

◆ onRotateRight

void rqt_image_view::ImageView::onRotateRight ( )
protectedvirtualslot

Definition at line 474 of file image_view.cpp.

◆ onTopicChanged

void rqt_image_view::ImageView::onTopicChanged ( int  index)
protectedvirtualslot

Definition at line 326 of file image_view.cpp.

◆ onZoom1

void rqt_image_view::ImageView::onZoom1 ( bool  checked)
protectedvirtualslot

Definition at line 354 of file image_view.cpp.

◆ overlayGrid()

void rqt_image_view::ImageView::overlayGrid ( )
protectedvirtual

Definition at line 541 of file image_view.cpp.

◆ restoreSettings()

void rqt_image_view::ImageView::restoreSettings ( const qt_gui_cpp::Settings plugin_settings,
const qt_gui_cpp::Settings instance_settings 
)
virtual

Reimplemented from qt_gui_cpp::Plugin.

Definition at line 143 of file image_view.cpp.

◆ saveImage

void rqt_image_view::ImageView::saveImage ( )
protectedvirtualslot

Definition at line 381 of file image_view.cpp.

◆ saveSettings()

void rqt_image_view::ImageView::saveSettings ( qt_gui_cpp::Settings plugin_settings,
qt_gui_cpp::Settings instance_settings 
) const
virtual

Reimplemented from qt_gui_cpp::Plugin.

Definition at line 126 of file image_view.cpp.

◆ selectTopic()

void rqt_image_view::ImageView::selectTopic ( const QString &  topic)
protectedvirtual

Definition at line 312 of file image_view.cpp.

◆ setColorSchemeList

void rqt_image_view::ImageView::setColorSchemeList ( )
protectedvirtualslot

Definition at line 190 of file image_view.cpp.

◆ shutdownPlugin()

void rqt_image_view::ImageView::shutdownPlugin ( )
virtual

Reimplemented from rqt_gui_cpp::Plugin.

Definition at line 120 of file image_view.cpp.

◆ syncRotateLabel()

void rqt_image_view::ImageView::syncRotateLabel ( )
private

Definition at line 480 of file image_view.cpp.

◆ updateNumGridlines

void rqt_image_view::ImageView::updateNumGridlines ( )
protectedvirtualslot

Definition at line 376 of file image_view.cpp.

◆ updateTopicList

void rqt_image_view::ImageView::updateTopicList ( )
protectedvirtualslot

Definition at line 215 of file image_view.cpp.

Member Data Documentation

◆ arg_topic_name

QString rqt_image_view::ImageView::arg_topic_name
private

Definition at line 147 of file image_view.h.

◆ conversion_mat_

cv::Mat rqt_image_view::ImageView::conversion_mat_
protected

Definition at line 132 of file image_view.h.

◆ hide_toolbar_action_

QAction* rqt_image_view::ImageView::hide_toolbar_action_
private

Definition at line 152 of file image_view.h.

◆ num_gridlines_

int rqt_image_view::ImageView::num_gridlines_
private

Definition at line 154 of file image_view.h.

◆ pub_mouse_left_

ros::Publisher rqt_image_view::ImageView::pub_mouse_left_
private

Definition at line 148 of file image_view.h.

◆ pub_topic_custom_

bool rqt_image_view::ImageView::pub_topic_custom_
private

Definition at line 150 of file image_view.h.

◆ rotate_state_

RotateState rqt_image_view::ImageView::rotate_state_
private

Definition at line 156 of file image_view.h.

◆ subscriber_

image_transport::Subscriber rqt_image_view::ImageView::subscriber_
protected

Definition at line 130 of file image_view.h.

◆ ui_

Ui::ImageViewWidget rqt_image_view::ImageView::ui_
protected

Definition at line 126 of file image_view.h.

◆ widget_

QWidget* rqt_image_view::ImageView::widget_
protected

Definition at line 128 of file image_view.h.


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


rqt_image_view
Author(s): Dirk Thomas , Mabel Zhang
autogenerated on Fri May 26 2023 02:31:55