Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
VisionGui Class Reference

Class having one attribute per OpenCV 2D Viewer. More...

#include <vision_gui.h>

List of all members.

Public Member Functions

void guiDrawKeypoints ()
 VisionGui ()
 Constructor.
 ~VisionGui ()
 Destructor.

Public Attributes

bool new_processed_img_available

Private Member Functions

void convertMsgToAttributes (ucl_drone::ProcessedImageMsg::ConstPtr msg)
 Translation to OpenCV format.
void processedImageCb (const ucl_drone::ProcessedImageMsg::ConstPtr processed_image)
 Callbacks.

Private Attributes

cv_bridge::CvImagePtr cv_ptr
 Measure after translation to OpenCV format.
bool draw_keypoints
 Launch parameters.
bool draw_target
std::vector< cv::Point2f > keypoints
ucl_drone::ProcessedImageMsg::ConstPtr lastProcessedImgReceived
 Measure.
ros::NodeHandle nh_
 ros node
std::string processed_img_channel
ros::Subscriber processed_img_sub
 Subscribers.
std::vector< cv::Point2f > target_cornersAndCenter
bool target_detected

Detailed Description

Class having one attribute per OpenCV 2D Viewer.

Definition at line 40 of file vision_gui.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 13 of file vision_gui.cpp.

Destructor.

Definition at line 30 of file vision_gui.cpp.


Member Function Documentation

void VisionGui::convertMsgToAttributes ( ucl_drone::ProcessedImageMsg::ConstPtr  msg) [private]

Translation to OpenCV format.

Definition at line 77 of file vision_gui.cpp.

Definition at line 44 of file vision_gui.cpp.

void VisionGui::processedImageCb ( const ucl_drone::ProcessedImageMsg::ConstPtr  processed_image) [private]

Callbacks.

Definition at line 36 of file vision_gui.cpp.


Member Data Documentation

Measure after translation to OpenCV format.

Definition at line 64 of file vision_gui.h.

bool VisionGui::draw_keypoints [private]

Launch parameters.

Definition at line 47 of file vision_gui.h.

bool VisionGui::draw_target [private]

Definition at line 48 of file vision_gui.h.

std::vector< cv::Point2f > VisionGui::keypoints [private]

Definition at line 66 of file vision_gui.h.

ucl_drone::ProcessedImageMsg::ConstPtr VisionGui::lastProcessedImgReceived [private]

Measure.

Definition at line 61 of file vision_gui.h.

Definition at line 81 of file vision_gui.h.

ros node

Definition at line 44 of file vision_gui.h.

std::string VisionGui::processed_img_channel [private]

Definition at line 52 of file vision_gui.h.

Subscribers.

Definition at line 51 of file vision_gui.h.

std::vector< cv::Point2f > VisionGui::target_cornersAndCenter [private]

Definition at line 67 of file vision_gui.h.

Definition at line 69 of file vision_gui.h.


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


ucl_drone
Author(s): dronesinma
autogenerated on Sat Jun 8 2019 20:51:53