$search
00001 00005 #ifndef _THERMALVIS_FLOW_H_ 00006 #define _THERMALVIS_FLOW_H_ 00007 00008 #include "general_resources.hpp" 00009 #include "ros_resources.hpp" 00010 #include "opencv_resources.hpp" 00011 00012 #include "improc.hpp" 00013 #include "video.hpp" 00014 #include "features.hpp" 00015 #include "tracks.hpp" 00016 #include "initialization.hpp" 00017 00018 #include "feature_tracks.h" 00019 00020 #include "flowConfig.h" 00021 00022 const char __PROGRAM__[] = "THERMALVIS_FLOW"; 00023 00024 typedef dynamic_reconfigure::Server < thermalvis::flowConfig > Server; 00025 00026 #define DEFAULT_ALPHA 0.00 00027 #define MS_PER_SEC 1000.0 00028 00029 bool wantsToShutdown = false; 00030 void mySigintHandler(int sig); 00031 00032 void imageCallback(const sensor_msgs::ImageConstPtr& msg); 00033 void parameterCallback(const sensor_msgs::CameraInfo& msg); 00034 00036 struct trackerData { 00037 00038 string video_stream, video_sequence; 00039 string camera_parameters; 00040 string read_addr; 00041 00042 bool softSync; 00043 double syncDiff; 00044 unsigned long soft_diff_limit; 00045 00046 cameraParameters cameraData; 00047 00048 //double alpha; 00049 double delayTimeout; 00050 double flowThreshold; 00051 double maxFrac; 00052 00053 int minTrackedFeaturesPerDetector, maxTrackedFeaturesPerDetector; 00054 int maxFeatures; 00055 int maximumDetectionFeatures; 00056 int maxProjectionsPerFeature; 00057 00058 bool debugMode; 00059 bool outputTrackCount; 00060 00061 string detector[MAX_DETECTORS], descriptor[MAX_DETECTORS]; 00062 double sensitivity[MAX_DETECTORS]; 00063 string method[MAX_DETECTORS]; 00064 bool method_match[MAX_DETECTORS]; 00065 00066 int newDetectionFramecountTrigger; 00067 00068 //string normalizationMode; 00069 //int minLimit, maxLimit; 00070 00071 int nearSearchHistory; 00072 int farSearchHistory; 00073 00074 int minPointsForWarning; 00075 00076 int drawingHistory; 00077 00078 int lossGaps[2]; 00079 00080 double minDistance; 00081 00082 unsigned int numDetectors; 00083 00084 bool obtainStartingData(ros::NodeHandle& nh); 00085 void initializeDetectors(Ptr<FeatureDetector> *det, Ptr<FeatureDetector> *hom); 00086 void initializeDescriptors(Ptr<DescriptorExtractor> *desc, Ptr<DescriptorExtractor> *hom); 00087 00088 }; 00089 00090 // example: http://ua-ros-pkg.googlecode.com/svn/trunk/arrg/ua_vision/object_tracking/src/object_tracker_node.cpp 00092 class featureTrackerNode { 00093 private: 00094 00095 Scalar trackDrawingColors[MAX_DETECTORS], keyDrawingColors[MAX_DETECTORS]; 00096 00097 ofstream trackCountStream; 00098 00099 Size ksize; 00100 double blurSigma; 00101 00102 vector<unsigned int> lostTrackIndices; 00103 int referenceFrame; 00104 00105 bool undergoingDelay; 00106 00107 Mat dispMat; 00108 00109 bool infoProcessed, infoSent; 00110 00111 Mat H12; 00112 00113 double factor, minResponse; // minVal, maxVal, 00114 00115 ros::Timer timer, features_timer; 00116 00117 trackerData configData; 00118 00119 sensor_msgs::CameraInfo debug_camera_info; 00120 00121 unsigned int lastPeak[MAX_DETECTORS]; 00122 00123 ros::Publisher tracks_pub; 00124 image_transport::CameraPublisher debug_pub; 00125 00126 image_transport::CameraSubscriber camera_sub; 00127 ros::Subscriber info_sub; 00128 image_transport::Subscriber image_sub; 00129 00130 int previouslyTrackedPoints; 00131 00132 cv_bridge::CvImagePtr cv_ptr; 00133 00134 Mat normalizedMat, blownImage, displayImage2, subscribedImage, drawImage2; 00135 Mat newImage, grayImage, realImage, mappedImage, lastImage, olderImage; 00136 00137 //gpu::GpuMat gmap1, gmap2; 00138 00139 // http://docs.opencv.org/doc/tutorials/gpu/gpu-basics-similarity/gpu-basics-similarity.html#how-to-do-it-the-gpu 00140 //Mat I1; // Main memory item - read image into with imread for example 00141 //gpu::GpuMat gI; // GPU matrix - for now empty 00142 //gI1.upload(I1); // Upload a data from the system memory to the GPU memory 00143 //I1 = gI1; // Download, gI1.download(I1) will work too 00144 00145 //Mat map1, map2; 00146 00147 struct timeval cycle_timer, test_timer; 00148 double elapsedTime, testTime; 00149 00150 unsigned int frameCount; 00151 unsigned int readyFrame; 00152 00153 00154 00155 image_transport::CameraPublisher pub_debug; 00156 sensor_msgs::Image msg_debug; 00157 00158 char debug_pub_name[256]; 00159 char tracks_pub_name[256]; 00160 ros::NodeHandle private_node_handle; 00161 00162 char nodeName[256]; 00163 00164 Mat displayImage, drawImage, drawImage_resized; 00165 00166 Mat grayImageBuffer[MAXIMUM_FRAMES_TO_STORE], mappedImageBuffer[MAXIMUM_FRAMES_TO_STORE]; 00167 00168 Mat blurredImage; 00169 00170 vector<KeyPoint> currPoints[MAX_DETECTORS]; 00171 vector<Point2f> startingPoints[MAX_DETECTORS], finishingPoints[MAX_DETECTORS], guidingPoints[MAX_DETECTORS]; 00172 vector<Point2f> historicalPoints[MAX_DETECTORS], recoveredPoints[MAX_DETECTORS]; 00173 vector<featureTrack> displayTracks[MAX_DETECTORS]; 00174 00175 Ptr<FeatureDetector> keypointDetector[MAX_DETECTORS]; 00176 Ptr<FeatureDetector> homographyDetector; 00177 00178 vector<KeyPoint> homogPoints[2]; 00179 Ptr<DescriptorExtractor> descriptorExtractor[MAX_DETECTORS]; 00180 Ptr<DescriptorExtractor> homographyExtractor; 00181 Mat homogDescriptors[2]; 00182 00183 ros::Time info_time, image_time, original_time, dodgeTime; 00184 00185 int distanceConstraint; 00186 00187 int peakTracks; 00188 00189 vector<featureTrack> featureTrackVector; 00190 00191 Mat olderImages[MAXIMUM_FRAMES_TO_STORE][2]; 00192 Mat workingImOld[MAXIMUM_FRAMES_TO_STORE], workingImNew[MAXIMUM_FRAMES_TO_STORE]; 00193 00194 dynamic_reconfigure::Server<thermalvis::flowConfig> server; 00195 dynamic_reconfigure::Server<thermalvis::flowConfig>::CallbackType f; 00196 00197 double averageTrackLength; 00198 00199 public: 00200 featureTrackerNode(ros::NodeHandle& nh, trackerData startupData); 00201 00202 void timed_loop(const ros::TimerEvent& event); 00203 00204 void features_loop(const ros::TimerEvent& event); 00205 00206 void handle_delay(); 00207 00208 void handle_very_new(); 00209 00210 void act_on_image(); 00211 void process_info(const sensor_msgs::CameraInfoConstPtr& info_msg); 00212 00213 void handle_camera(const sensor_msgs::ImageConstPtr& msg_ptr, const sensor_msgs::CameraInfoConstPtr& info_msg); 00214 void handle_image(const sensor_msgs::ImageConstPtr& msg_ptr); 00215 void handle_info(const sensor_msgs::CameraInfoConstPtr& info_msg); 00216 00217 void serverCallback(thermalvis::flowConfig &config, uint32_t level); 00218 00219 void prepareForTermination(); 00220 00221 int publish_tracks(ros::Publisher *pub_message); 00222 }; 00223 00224 boost::shared_ptr < featureTrackerNode > *globalNodePtr; 00225 00226 #endif