Public Member Functions | Public Attributes | Private Attributes | Static Private Attributes
ProcessedImage Class Reference

Provide tools to process keypoint extraction. More...

#include <processed_image.h>

List of all members.

Public Member Functions

void convertToMsg (ucl_drone::ProcessedImageMsg::Ptr &msg, Target target)
 Destructor.
 ProcessedImage ()
 estimated pose of the drone before the visual estimation
 ProcessedImage (const sensor_msgs::Image image, const ucl_drone::Pose3D pose, ProcessedImage &prev, bool use_OpticalFlowPyrLK)
 Constructor.
 ~ProcessedImage ()
 Constructor.

Public Attributes

cv_bridge::CvImagePtr cv_ptr
 the message to be sent
cv::Mat descriptors
 vector of keypoints detected
sensor_msgs::Image image
 the keypoints descripors in opencv format
std::vector< cv::KeyPoint > keypoints
 conversion from ROS to OpenCV Image format
ucl_drone::Pose3D pose
 video image in the ROS format after rescaling

Private Attributes

ucl_drone::ProcessedImageMsg::Ptr msg
 the number of keypoints detected in the last image

Static Private Attributes

static int last_number_of_keypoints = 0

Detailed Description

Provide tools to process keypoint extraction.

Definition at line 21 of file processed_image.h.


Constructor & Destructor Documentation

estimated pose of the drone before the visual estimation

Definition at line 18 of file processed_image.cpp.

ProcessedImage::ProcessedImage ( const sensor_msgs::Image  image,
const ucl_drone::Pose3D  pose,
ProcessedImage prev,
bool  use_OpticalFlowPyrLK 
)

Constructor.

Definition at line 28 of file processed_image.cpp.

Constructor.

Definition at line 148 of file processed_image.cpp.


Member Function Documentation

void ProcessedImage::convertToMsg ( ucl_drone::ProcessedImageMsg::Ptr &  msg,
Target  target 
)

Destructor.

build a message that can be sent to other nodes

Definition at line 155 of file processed_image.cpp.


Member Data Documentation

the message to be sent

Definition at line 28 of file processed_image.h.

vector of keypoints detected

Definition at line 30 of file processed_image.h.

sensor_msgs::Image ProcessedImage::image

the keypoints descripors in opencv format

Definition at line 31 of file processed_image.h.

std::vector< cv::KeyPoint > ProcessedImage::keypoints

conversion from ROS to OpenCV Image format

Definition at line 29 of file processed_image.h.

int ProcessedImage::last_number_of_keypoints = 0 [static, private]

Definition at line 24 of file processed_image.h.

ucl_drone::ProcessedImageMsg::Ptr ProcessedImage::msg [private]

the number of keypoints detected in the last image

Definition at line 25 of file processed_image.h.

ucl_drone::Pose3D ProcessedImage::pose

video image in the ROS format after rescaling

Definition at line 32 of file processed_image.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