#include <image_cropper.h>

Public Member Functions | |
| virtual bool | eventFilter (QObject *watched, QEvent *event) |
| ImageCropper () | |
| 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 | onInTopicChanged (int index) |
| virtual void | onOutTopicChanged () |
| virtual void | onRemoveSelection () |
| virtual void | onSelectionFinished (QPoint p1, QPoint p2) |
| virtual void | onSelectionInProgress (QPoint p1, QPoint p2) |
| virtual void | updateTopicList () |
Protected Member Functions | |
| virtual void | callbackImage (const sensor_msgs::Image::ConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &ci) |
| virtual void | enforceSelectionConstraints (QPoint &p) |
| virtual QList< QString > | getTopicList (const QSet< QString > &message_types, const QList< QString > &transports) |
| virtual void | publishCrop () |
| virtual void | selectTopic (const QString &topic) |
Protected Member Functions inherited from nodelet::Nodelet | |
| ros::CallbackQueueInterface & | getMTCallbackQueue () const |
| ros::NodeHandle & | getMTNodeHandle () const |
| ros::NodeHandle & | getMTPrivateNodeHandle () const |
| const V_string & | getMyArgv () const |
| const std::string & | getName () const |
| ros::NodeHandle & | getNodeHandle () const |
| ros::NodeHandle & | getPrivateNodeHandle () const |
| const M_string & | getRemappingArgs () const |
| ros::CallbackQueueInterface & | getSTCallbackQueue () const |
| std::string | getSuffixedName (const std::string &suffix) const |
Protected Attributes | |
| sensor_msgs::CameraInfoConstPtr | camera_info_ |
| cv::Mat | conversion_mat_ |
| double | image_max_value_ |
| double | image_min_value_ |
| image_transport::CameraPublisher | publisher_ |
| QImage | qimage_ |
| QMutex | qimage_mutex_ |
| bool | selected_ |
| QImage | selected_region_ |
| QRectF | selection_ |
| QSizeF | selection_size_ |
| QSizeF | selection_size_rect_ |
| QPointF | selection_top_left_ |
| QPointF | selection_top_left_rect_ |
| sensor_msgs::Image::ConstPtr | sens_msg_image_ |
| image_transport::CameraSubscriber | subscriber_ |
| Ui::ImageCropperWidget | ui_ |
| QWidget * | widget_ |
Definition at line 56 of file image_cropper.h.
| rqt_image_cropping::ImageCropper::ImageCropper | ( | ) |
Definition at line 50 of file image_cropper.cpp.
|
protectedvirtual |
Definition at line 378 of file image_cropper.cpp.
|
protectedvirtual |
Definition at line 361 of file image_cropper.cpp.
|
virtual |
Definition at line 90 of file image_cropper.cpp.
|
protectedvirtual |
Definition at line 198 of file image_cropper.cpp.
|
virtual |
Reimplemented from qt_gui_cpp::Plugin.
Definition at line 58 of file image_cropper.cpp.
|
protectedvirtualslot |
Definition at line 373 of file image_cropper.cpp.
|
protectedvirtualslot |
Definition at line 245 of file image_cropper.cpp.
|
protectedvirtualslot |
Definition at line 272 of file image_cropper.cpp.
|
protectedvirtualslot |
Definition at line 355 of file image_cropper.cpp.
|
protectedvirtualslot |
Definition at line 308 of file image_cropper.cpp.
|
protectedvirtualslot |
Definition at line 292 of file image_cropper.cpp.
|
protectedvirtual |
Definition at line 444 of file image_cropper.cpp.
|
virtual |
Reimplemented from qt_gui_cpp::Plugin.
Definition at line 144 of file image_cropper.cpp.
|
virtual |
Reimplemented from qt_gui_cpp::Plugin.
Definition at line 135 of file image_cropper.cpp.
|
protectedvirtual |
Definition at line 235 of file image_cropper.cpp.
|
virtual |
Reimplemented from rqt_gui_cpp::Plugin.
Definition at line 129 of file image_cropper.cpp.
|
protectedvirtualslot |
Definition at line 157 of file image_cropper.cpp.
|
protected |
Definition at line 118 of file image_cropper.h.
|
protected |
Definition at line 127 of file image_cropper.h.
|
protected |
Definition at line 121 of file image_cropper.h.
|
protected |
Definition at line 120 of file image_cropper.h.
|
protected |
Definition at line 115 of file image_cropper.h.
|
protected |
Definition at line 123 of file image_cropper.h.
|
protected |
Definition at line 125 of file image_cropper.h.
|
protected |
Definition at line 136 of file image_cropper.h.
|
protected |
Definition at line 124 of file image_cropper.h.
|
protected |
Definition at line 129 of file image_cropper.h.
|
protected |
Definition at line 133 of file image_cropper.h.
|
protected |
Definition at line 134 of file image_cropper.h.
|
protected |
Definition at line 131 of file image_cropper.h.
|
protected |
Definition at line 132 of file image_cropper.h.
|
protected |
Definition at line 117 of file image_cropper.h.
|
protected |
Definition at line 114 of file image_cropper.h.
|
protected |
Definition at line 110 of file image_cropper.h.
|
protected |
Definition at line 112 of file image_cropper.h.