tracks.hpp
Go to the documentation of this file.
00001 
00005 #ifndef _THERMALVIS_TRACKS_H_
00006 #define _THERMALVIS_TRACKS_H_
00007 
00008 #include "general_resources.hpp"
00009 #include "opencv_resources.hpp"
00010 #include "camera.hpp"
00011 #include "tools.hpp"
00012 
00013 #define DEFAULT_MAX_VELOCITY                    10000.0
00014 #define MAX_TIME_DIFF_FOR_PREDICTION    99.0
00015 
00017 struct indexedFeature {
00018         unsigned int imageIndex;
00019         cv::Point2f featureCoord;
00020         
00021         indexedFeature(const int& i, const cv::Point2f& f) {
00022                 imageIndex = i;
00023                 featureCoord = f;
00024         }
00025         
00026         
00027 };
00028 
00030 struct featureTrack {
00031         
00032         long int trackIndex;
00033         vector<indexedFeature> locations;
00034         bool isTriangulated;
00035         unsigned int firstOccurence;
00036         double velocityWeighting;
00037         double velocity_x, velocity_y;
00038         
00039         featureTrack();
00040         
00042         void set3dLoc(const cv::Point3d& loc);
00043         
00045         void reset3dLoc(const cv::Point3d& loc);
00046         cv::Point3d get3dLoc();
00047         
00048         void addFeature(indexedFeature& feat) {
00049                 
00050                 if (locations.size() == 0) { 
00051                         locations.push_back(feat);
00052                         return;
00053                 }
00054                 
00055                 unsigned int pos = 0;
00056                                 
00057                 while (locations.at(pos).imageIndex < feat.imageIndex) {
00058                         pos++;
00059                         if (pos >= locations.size()) {
00060                                 break;
00061                         }
00062                 }
00063                 
00064                 locations.insert(locations.begin()+pos, feat);
00065         }
00066         
00067         cv::Point2f getCoord(unsigned int cam_idx);
00068         bool occursInSequence(const vector<unsigned int>& indices);
00069         
00070         protected:
00071                 cv::Point3d xyzEstimate;
00072                 
00073         
00074 };
00075 
00077 void clearDangerFeatures(vector<featureTrack>& featureTrackVector, long int index);
00078 
00080 int findTrackPosition(const vector<featureTrack>& featureTrackVector, long int index);
00081 
00082 unsigned int getActiveTrackCount(const vector<featureTrack>& featureTrackVector, unsigned int previousIndex, unsigned int latestIndex);
00083 
00084 void removeObsoleteElements(vector<featureTrack>& featureTrackVector, const vector<unsigned int>& activeFrameIndices);
00085 
00087 void assignEstimatesBasedOnVelocities(const vector<featureTrack>& featureTrackVector, const vector<cv::Point2f>& startingPoints, vector<cv::Point2f>& finishingPoints, unsigned int idx, double time1, double time2);
00088 
00090 double updateFeatureSpeeds(vector<featureTrack>& featureTrackVector, unsigned int idx1, double time1, unsigned int idx2, double time2, double maxVelocity = DEFAULT_MAX_VELOCITY);
00091 
00093 double obtainFeatureSpeeds(const vector<featureTrack>& featureTrackVector, unsigned int idx1, double time1, unsigned int idx2, double time2);
00094 
00096 void addMatchesToVector(vector<featureTrack>& featureTrackVector, unsigned int index1, vector<cv::Point2f>& points1, unsigned int index2, vector<cv::Point2f>& points2, long int &starting_track_index, double minSeparation, bool debug = false);
00097 
00099 int addMatchToVector(vector<featureTrack>& featureTrackVector, unsigned int index1, const cv::Point2f& point1, unsigned int index2, const cv::Point2f& point2, long int &starting_track_index, const cv::Point2f& velocity = cv::Point2f(0.0,0.0), bool debug = false);
00100 
00101 
00103 void addProjectionsToVector(vector<featureTrack>& featureTrackVector, unsigned int index, vector<cv::Point2f>& points, long int &starting_track_index, double minSeparation = 0.0);
00104 
00106 void addProjectionToVector(vector<featureTrack>& featureTrackVector, unsigned int index, const cv::Point2f& point, long int &starting_track_index);
00107 
00108 
00109 void drawFeatureTracks(cv::Mat& src, cv::Mat& dst, vector<featureTrack>& tracks, const cv::Scalar& tColor, const cv::Scalar& kColor, unsigned int index, unsigned int history = 10);
00110 
00111 void redistortTracks(const vector<featureTrack>& src, vector<featureTrack>& dst, const cv::Mat& cameraMatrix, const cv::Mat& distCoeffs, unsigned int latest, const cv::Mat& newCamMat=cv::Mat::eye(3,3,CV_64FC1), unsigned int history = 5);
00112 
00113 bool createTrackMatrix(const vector<featureTrack>& src, cv::Mat& dst, int latest = -1);
00114 
00116 void assignHistoricalPoints(const vector<featureTrack>& src, unsigned int idx_1, unsigned int idx_2, vector<cv::Point2f>& dst);
00117 
00118 #endif


thermalvis
Author(s): Stephen Vidas
autogenerated on Sun Jan 5 2014 11:38:45