$search

featureTrackerNode Class Reference

Manages the optical flow procedure. More...

#include <flow.hpp>

List of all members.

Public Member Functions

void act_on_image ()
void features_loop (const ros::TimerEvent &event)
 featureTrackerNode (ros::NodeHandle &nh, trackerData startupData)
void handle_camera (const sensor_msgs::ImageConstPtr &msg_ptr, const sensor_msgs::CameraInfoConstPtr &info_msg)
void handle_delay ()
void handle_image (const sensor_msgs::ImageConstPtr &msg_ptr)
void handle_info (const sensor_msgs::CameraInfoConstPtr &info_msg)
void handle_very_new ()
void prepareForTermination ()
void process_info (const sensor_msgs::CameraInfoConstPtr &info_msg)
int publish_tracks (ros::Publisher *pub_message)
void serverCallback (thermalvis::flowConfig &config, uint32_t level)
void timed_loop (const ros::TimerEvent &event)

Private Attributes

double averageTrackLength
Mat blownImage
Mat blurredImage
double blurSigma
image_transport::CameraSubscriber camera_sub
trackerData configData
vector< KeyPoint > currPoints [MAX_DETECTORS]
cv_bridge::CvImagePtr cv_ptr
sensor_msgs::CameraInfo debug_camera_info
image_transport::CameraPublisher debug_pub
char debug_pub_name [256]
Ptr< DescriptorExtractor > descriptorExtractor [MAX_DETECTORS]
Mat displayImage
Mat displayImage2
vector< featureTrackdisplayTracks [MAX_DETECTORS]
Mat dispMat
int distanceConstraint
ros::Time dodgeTime
Mat drawImage
Mat drawImage2
Mat drawImage_resized
double elapsedTime
dynamic_reconfigure::Server
< thermalvis::flowConfig >
::CallbackType 
f
double factor
ros::Timer features_timer
vector< featureTrackfeatureTrackVector
vector< Point2f > finishingPoints [MAX_DETECTORS]
unsigned int frameCount
Mat grayImage
Mat grayImageBuffer [MAXIMUM_FRAMES_TO_STORE]
vector< Point2f > guidingPoints [MAX_DETECTORS]
Mat H12
vector< Point2f > historicalPoints [MAX_DETECTORS]
Mat homogDescriptors [2]
vector< KeyPoint > homogPoints [2]
Ptr< FeatureDetector > homographyDetector
Ptr< DescriptorExtractor > homographyExtractor
image_transport::Subscriber image_sub
ros::Time image_time
ros::Subscriber info_sub
ros::Time info_time
bool infoProcessed
bool infoSent
Scalar keyDrawingColors [MAX_DETECTORS]
Ptr< FeatureDetector > keypointDetector [MAX_DETECTORS]
Size ksize
Mat lastImage
unsigned int lastPeak [MAX_DETECTORS]
vector< unsigned int > lostTrackIndices
Mat mappedImage
Mat mappedImageBuffer [MAXIMUM_FRAMES_TO_STORE]
double minResponse
sensor_msgs::Image msg_debug
Mat newImage
char nodeName [256]
Mat normalizedMat
Mat olderImage
Mat olderImages [MAXIMUM_FRAMES_TO_STORE][2]
ros::Time original_time
int peakTracks
int previouslyTrackedPoints
ros::NodeHandle private_node_handle
image_transport::CameraPublisher pub_debug
unsigned int readyFrame
Mat realImage
vector< Point2f > recoveredPoints [MAX_DETECTORS]
int referenceFrame
dynamic_reconfigure::Server
< thermalvis::flowConfig > 
server
vector< Point2f > startingPoints [MAX_DETECTORS]
Mat subscribedImage
struct timeval cycle_timer test_timer
double testTime
ros::Timer timer
ofstream trackCountStream
Scalar trackDrawingColors [MAX_DETECTORS]
ros::Publisher tracks_pub
char tracks_pub_name [256]
bool undergoingDelay
Mat workingImNew [MAXIMUM_FRAMES_TO_STORE]
Mat workingImOld [MAXIMUM_FRAMES_TO_STORE]

Detailed Description

Manages the optical flow procedure.

Definition at line 92 of file flow.hpp.


Constructor & Destructor Documentation

featureTrackerNode::featureTrackerNode ( ros::NodeHandle nh,
trackerData  startupData 
)

Definition at line 1225 of file flow.cpp.


Member Function Documentation

void featureTrackerNode::act_on_image (  ) 

Definition at line 405 of file flow.cpp.

void featureTrackerNode::features_loop ( const ros::TimerEvent event  ) 

Definition at line 527 of file flow.cpp.

void featureTrackerNode::handle_camera ( const sensor_msgs::ImageConstPtr msg_ptr,
const sensor_msgs::CameraInfoConstPtr info_msg 
)

Definition at line 259 of file flow.cpp.

void featureTrackerNode::handle_delay (  ) 

Definition at line 1178 of file flow.cpp.

void featureTrackerNode::handle_image ( const sensor_msgs::ImageConstPtr msg_ptr  ) 

Definition at line 383 of file flow.cpp.

void featureTrackerNode::handle_info ( const sensor_msgs::CameraInfoConstPtr info_msg  ) 

Definition at line 358 of file flow.cpp.

void featureTrackerNode::handle_very_new (  ) 

Definition at line 1064 of file flow.cpp.

void featureTrackerNode::prepareForTermination (  ) 

Definition at line 1060 of file flow.cpp.

void featureTrackerNode::process_info ( const sensor_msgs::CameraInfoConstPtr info_msg  ) 

Definition at line 276 of file flow.cpp.

int featureTrackerNode::publish_tracks ( ros::Publisher pub_message  ) 

Definition at line 188 of file flow.cpp.

void featureTrackerNode::serverCallback ( thermalvis::flowConfig &  config,
uint32_t  level 
)

Definition at line 1340 of file flow.cpp.

void featureTrackerNode::timed_loop ( const ros::TimerEvent event  ) 

Definition at line 1334 of file flow.cpp.


Member Data Documentation

Definition at line 197 of file flow.hpp.

Definition at line 134 of file flow.hpp.

Definition at line 168 of file flow.hpp.

Definition at line 100 of file flow.hpp.

Definition at line 126 of file flow.hpp.

Definition at line 117 of file flow.hpp.

vector<KeyPoint> featureTrackerNode::currPoints[MAX_DETECTORS] [private]

Definition at line 170 of file flow.hpp.

Definition at line 132 of file flow.hpp.

Definition at line 119 of file flow.hpp.

Definition at line 124 of file flow.hpp.

Definition at line 158 of file flow.hpp.

Ptr<DescriptorExtractor> featureTrackerNode::descriptorExtractor[MAX_DETECTORS] [private]

Definition at line 179 of file flow.hpp.

Definition at line 164 of file flow.hpp.

Definition at line 134 of file flow.hpp.

vector<featureTrack> featureTrackerNode::displayTracks[MAX_DETECTORS] [private]

Definition at line 173 of file flow.hpp.

Definition at line 107 of file flow.hpp.

Definition at line 185 of file flow.hpp.

Definition at line 183 of file flow.hpp.

Definition at line 164 of file flow.hpp.

Definition at line 134 of file flow.hpp.

Definition at line 164 of file flow.hpp.

Definition at line 148 of file flow.hpp.

dynamic_reconfigure::Server<thermalvis::flowConfig>::CallbackType featureTrackerNode::f [private]

Definition at line 195 of file flow.hpp.

double featureTrackerNode::factor [private]

Definition at line 113 of file flow.hpp.

Definition at line 115 of file flow.hpp.

Definition at line 189 of file flow.hpp.

vector<Point2f> featureTrackerNode::finishingPoints[MAX_DETECTORS] [private]

Definition at line 171 of file flow.hpp.

unsigned int featureTrackerNode::frameCount [private]

Definition at line 150 of file flow.hpp.

Definition at line 135 of file flow.hpp.

Mat featureTrackerNode::grayImageBuffer[MAXIMUM_FRAMES_TO_STORE] [private]

Definition at line 166 of file flow.hpp.

vector<Point2f> featureTrackerNode::guidingPoints[MAX_DETECTORS] [private]

Definition at line 171 of file flow.hpp.

Mat featureTrackerNode::H12 [private]

Definition at line 111 of file flow.hpp.

vector<Point2f> featureTrackerNode::historicalPoints[MAX_DETECTORS] [private]

Definition at line 172 of file flow.hpp.

Definition at line 181 of file flow.hpp.

vector<KeyPoint> featureTrackerNode::homogPoints[2] [private]

Definition at line 178 of file flow.hpp.

Ptr<FeatureDetector> featureTrackerNode::homographyDetector [private]

Definition at line 176 of file flow.hpp.

Ptr<DescriptorExtractor> featureTrackerNode::homographyExtractor [private]

Definition at line 180 of file flow.hpp.

Definition at line 128 of file flow.hpp.

Definition at line 183 of file flow.hpp.

Definition at line 127 of file flow.hpp.

Definition at line 183 of file flow.hpp.

Definition at line 109 of file flow.hpp.

Definition at line 109 of file flow.hpp.

Scalar featureTrackerNode::keyDrawingColors[MAX_DETECTORS] [private]

Definition at line 95 of file flow.hpp.

Ptr<FeatureDetector> featureTrackerNode::keypointDetector[MAX_DETECTORS] [private]

Definition at line 175 of file flow.hpp.

Size featureTrackerNode::ksize [private]

Definition at line 99 of file flow.hpp.

Definition at line 135 of file flow.hpp.

unsigned int featureTrackerNode::lastPeak[MAX_DETECTORS] [private]

Definition at line 121 of file flow.hpp.

vector<unsigned int> featureTrackerNode::lostTrackIndices [private]

Definition at line 102 of file flow.hpp.

Definition at line 135 of file flow.hpp.

Mat featureTrackerNode::mappedImageBuffer[MAXIMUM_FRAMES_TO_STORE] [private]

Definition at line 166 of file flow.hpp.

Definition at line 113 of file flow.hpp.

Definition at line 156 of file flow.hpp.

Definition at line 135 of file flow.hpp.

char featureTrackerNode::nodeName[256] [private]

Definition at line 162 of file flow.hpp.

Definition at line 134 of file flow.hpp.

Definition at line 135 of file flow.hpp.

Mat featureTrackerNode::olderImages[MAXIMUM_FRAMES_TO_STORE][2] [private]

Definition at line 191 of file flow.hpp.

Definition at line 183 of file flow.hpp.

Definition at line 187 of file flow.hpp.

Definition at line 130 of file flow.hpp.

Definition at line 160 of file flow.hpp.

Definition at line 155 of file flow.hpp.

unsigned int featureTrackerNode::readyFrame [private]

Definition at line 151 of file flow.hpp.

Definition at line 135 of file flow.hpp.

vector<Point2f> featureTrackerNode::recoveredPoints[MAX_DETECTORS] [private]

Definition at line 172 of file flow.hpp.

Definition at line 103 of file flow.hpp.

dynamic_reconfigure::Server<thermalvis::flowConfig> featureTrackerNode::server [private]

Definition at line 194 of file flow.hpp.

vector<Point2f> featureTrackerNode::startingPoints[MAX_DETECTORS] [private]

Definition at line 171 of file flow.hpp.

Definition at line 134 of file flow.hpp.

struct timeval cycle_timer featureTrackerNode::test_timer [private]

Definition at line 147 of file flow.hpp.

double featureTrackerNode::testTime [private]

Definition at line 148 of file flow.hpp.

Definition at line 115 of file flow.hpp.

Definition at line 97 of file flow.hpp.

Scalar featureTrackerNode::trackDrawingColors[MAX_DETECTORS] [private]

Definition at line 95 of file flow.hpp.

Definition at line 123 of file flow.hpp.

Definition at line 159 of file flow.hpp.

Definition at line 105 of file flow.hpp.

Mat featureTrackerNode::workingImNew[MAXIMUM_FRAMES_TO_STORE] [private]

Definition at line 192 of file flow.hpp.

Mat featureTrackerNode::workingImOld[MAXIMUM_FRAMES_TO_STORE] [private]

Definition at line 192 of file flow.hpp.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


thermalvis
Author(s): Stephen Vidas
autogenerated on Tue Mar 5 12:25:47 2013