featureTracking.cpp
Go to the documentation of this file.
00001 #include <math.h>
00002 #include <stdio.h>
00003 #include <stdlib.h>
00004 #include <ros/ros.h>
00005 
00006 #include "cameraParameters.h"
00007 #include "pointDefinition.h"
00008 
00009 using namespace std;
00010 using namespace cv;
00011 
00012 bool systemInited = false;
00013 double timeCur, timeLast;
00014 
00015 const int imagePixelNum = imageHeight * imageWidth;
00016 CvSize imgSize = cvSize(imageWidth, imageHeight);
00017 
00018 IplImage *imageCur = cvCreateImage(imgSize, IPL_DEPTH_8U, 1);
00019 IplImage *imageLast = cvCreateImage(imgSize, IPL_DEPTH_8U, 1);
00020 
00021 int showCount = 0;
00022 const int showSkipNum = 2;
00023 const int showDSRate = 2;
00024 CvSize showSize = cvSize(imageWidth / showDSRate, imageHeight / showDSRate);
00025 
00026 IplImage *imageShowMono = cvCreateImage(showSize, IPL_DEPTH_8U, 1);
00027 IplImage *imageShowRGB = cvCreateImage(showSize, IPL_DEPTH_8U, 3);
00028 
00029 CvMat kMat = cvMat(3, 3, CV_64FC1, kArray);
00030 CvMat dMat = cvMat(4, 1, CV_64FC1, dArray);
00031 
00032 IplImage *mapx, *mapy;
00033 
00034 const int maxFeatureNumPerSubregion = 20;
00035 const int xSubregionNum = 6;
00036 const int ySubregionNum = 4;
00037 const int totalSubregionNum = xSubregionNum * ySubregionNum;
00038 const int MAXFEATURENUM = maxFeatureNumPerSubregion * totalSubregionNum;
00039 
00040 const int xBoundary = 30;
00041 const int yBoundary = 30;
00042 const double subregionWidth = (double)(imageWidth - 2 * xBoundary) / (double)xSubregionNum;
00043 const double subregionHeight = (double)(imageHeight - 2 * yBoundary) / (double)ySubregionNum;
00044 
00045 const double maxTrackDis = 100;
00046 const int winSize = 21;
00047 
00048 IplImage *imageEig, *imageTmp, *pyrCur, *pyrLast;
00049 
00050 CvPoint2D32f *featuresCur = new CvPoint2D32f[2 * MAXFEATURENUM];
00051 CvPoint2D32f *featuresLast = new CvPoint2D32f[2 * MAXFEATURENUM];
00052 char featuresFound[2 * MAXFEATURENUM];
00053 float featuresError[2 * MAXFEATURENUM];
00054 
00055 int featuresIndFromStart = 0;
00056 int featuresInd[2 * MAXFEATURENUM] = {0};
00057 
00058 int totalFeatureNum = 0;
00059 int subregionFeatureNum[2 * totalSubregionNum] = {0};
00060 
00061 pcl::PointCloud<ImagePoint>::Ptr imagePointsCur(new pcl::PointCloud<ImagePoint>());
00062 pcl::PointCloud<ImagePoint>::Ptr imagePointsLast(new pcl::PointCloud<ImagePoint>());
00063 
00064 ros::Publisher *imagePointsLastPubPointer;
00065 ros::Publisher *imageShowPubPointer;
00066 sensor_msgs::CvBridge bridge;
00067 
00068 void imageDataHandler(const sensor_msgs::Image::ConstPtr& imageData) 
00069 {
00070   timeLast = timeCur;
00071   timeCur = imageData->header.stamp.toSec();
00072 
00073   IplImage *imageTemp = imageLast;
00074   imageLast = imageCur;
00075   imageCur = imageTemp;
00076 
00077   for (int i = 0; i < imagePixelNum; i++) {
00078     imageCur->imageData[i] = (char)imageData->data[i];
00079   }
00080 
00081   IplImage *t = cvCloneImage(imageCur);
00082   cvRemap(t, imageCur, mapx, mapy);
00083   //cvEqualizeHist(imageCur, imageCur);
00084   cvReleaseImage(&t);
00085 
00086   CvPoint2D32f *featuresTemp = featuresLast;
00087   featuresLast = featuresCur;
00088   featuresCur = featuresTemp;
00089 
00090   pcl::PointCloud<ImagePoint>::Ptr imagePointsTemp = imagePointsLast;
00091   imagePointsLast = imagePointsCur;
00092   imagePointsCur = imagePointsTemp;
00093   imagePointsCur->clear();
00094 
00095   if (!systemInited) {
00096     systemInited = true;
00097     return;
00098   }
00099 
00100   int recordFeatureNum = totalFeatureNum;
00101   for (int i = 0; i < ySubregionNum; i++) {
00102     for (int j = 0; j < xSubregionNum; j++) {
00103       int ind = xSubregionNum * i + j;
00104       int numToFind = maxFeatureNumPerSubregion - subregionFeatureNum[ind];
00105 
00106       if (numToFind > 0) {
00107         int subregionLeft = xBoundary + (int)(subregionWidth * j);
00108         int subregionTop = yBoundary + (int)(subregionHeight * i);
00109         CvRect subregion = cvRect(subregionLeft, subregionTop, (int)subregionWidth, (int)subregionHeight);
00110         cvSetImageROI(imageLast, subregion);
00111 
00112         cvGoodFeaturesToTrack(imageLast, imageEig, imageTmp, featuresLast + totalFeatureNum,
00113                               &numToFind, 0.1, 5.0, NULL, 3, 1, 0.04);
00114 
00115         for(int k = 0; k < numToFind; k++) {
00116           featuresLast[totalFeatureNum + k].x += subregionLeft;
00117           featuresLast[totalFeatureNum + k].y += subregionTop;
00118           featuresInd[totalFeatureNum + k] = featuresIndFromStart;
00119           featuresIndFromStart++;
00120         }
00121         totalFeatureNum += numToFind;
00122         subregionFeatureNum[ind] += numToFind;
00123 
00124         cvResetImageROI(imageLast);
00125       }
00126     }
00127   }
00128 
00129   cvCalcOpticalFlowPyrLK(imageLast, imageCur, pyrLast, pyrCur,
00130                          featuresLast, featuresCur, totalFeatureNum, cvSize(winSize, winSize), 
00131                          3, featuresFound, featuresError, 
00132                          cvTermCriteria(CV_TERMCRIT_ITER | CV_TERMCRIT_EPS, 30, 0.01), 0);
00133 
00134   for (int i = 0; i < totalSubregionNum; i++) {
00135     subregionFeatureNum[i] = 0;
00136   }
00137 
00138   ImagePoint point;
00139   int featureCount = 0;
00140   double meanShiftX = 0, meanShiftY = 0;
00141   for (int i = 0; i < totalFeatureNum; i++) {
00142     double trackDis = sqrt((featuresLast[i].x - featuresCur[i].x) 
00143                     * (featuresLast[i].x - featuresCur[i].x)
00144                     + (featuresLast[i].y - featuresCur[i].y) 
00145                     * (featuresLast[i].y - featuresCur[i].y));
00146 
00147     if (!(trackDis > maxTrackDis || featuresCur[i].x < xBoundary || 
00148       featuresCur[i].x > imageWidth - xBoundary || featuresCur[i].y < yBoundary || 
00149       featuresCur[i].y > imageHeight - yBoundary)) {
00150 
00151       int xInd = (int)((featuresLast[i].x - xBoundary) / subregionWidth);
00152       int yInd = (int)((featuresLast[i].y - yBoundary) / subregionHeight);
00153       int ind = xSubregionNum * yInd + xInd;
00154 
00155       if (subregionFeatureNum[ind] < maxFeatureNumPerSubregion) {
00156         featuresCur[featureCount].x = featuresCur[i].x;
00157         featuresCur[featureCount].y = featuresCur[i].y;
00158         featuresLast[featureCount].x = featuresLast[i].x;
00159         featuresLast[featureCount].y = featuresLast[i].y;
00160         featuresInd[featureCount] = featuresInd[i];
00161 
00162         point.u = -(featuresCur[featureCount].x - kArray[2]) / kArray[0];
00163         point.v = -(featuresCur[featureCount].y - kArray[5]) / kArray[4];
00164         point.ind = featuresInd[featureCount];
00165         imagePointsCur->push_back(point);
00166 
00167         if (i >= recordFeatureNum) {
00168           point.u = -(featuresLast[featureCount].x - kArray[2]) / kArray[0];
00169           point.v = -(featuresLast[featureCount].y - kArray[5]) / kArray[4];
00170           imagePointsLast->push_back(point);
00171         }
00172 
00173         meanShiftX += fabs((featuresCur[featureCount].x - featuresLast[featureCount].x) / kArray[0]);
00174         meanShiftY += fabs((featuresCur[featureCount].y - featuresLast[featureCount].y) / kArray[4]);
00175 
00176         featureCount++;
00177         subregionFeatureNum[ind]++;
00178       }
00179     }
00180   }
00181   totalFeatureNum = featureCount;
00182   meanShiftX /= totalFeatureNum;
00183   meanShiftY /= totalFeatureNum;
00184 
00185   imagePointsLast->header.stamp = ros::Time().fromSec(timeLast);
00186   sensor_msgs::PointCloud2 imagePointsLast2;
00187   pcl::toROSMsg(*imagePointsLast, imagePointsLast2);
00188   imagePointsLastPubPointer->publish(imagePointsLast2);
00189 
00190   showCount = (showCount + 1) % (showSkipNum + 1);
00191   if (showCount == showSkipNum) {
00192     cvResize(imageLast, imageShowMono);
00193     cvCvtColor(imageShowMono, imageShowRGB, CV_GRAY2RGB);
00194 
00195     /*for(int i = 0; i < totalFeatureNum; i++) {
00196       cvCircle(imageShowRGB, cvPoint(featuresCur[i].x / showDSRate, featuresCur[i].y / showDSRate), 
00197                1, CV_RGB(0, 0, 255), 2);
00198     }*/
00199 
00200     sensor_msgs::Image::Ptr imageShowPointer = bridge.cvToImgMsg(imageShowRGB, "bgr8");
00201     imageShowPubPointer->publish(imageShowPointer);
00202   }
00203 }
00204 
00205 int main(int argc, char** argv)
00206 {
00207   ros::init(argc, argv, "featureTracking");
00208   ros::NodeHandle nh;
00209 
00210   mapx = cvCreateImage(imgSize, IPL_DEPTH_32F, 1);
00211   mapy = cvCreateImage(imgSize, IPL_DEPTH_32F, 1);
00212   cvInitUndistortMap(&kMat, &dMat, mapx, mapy);
00213 
00214   CvSize subregionSize = cvSize((int)subregionWidth, (int)subregionHeight);
00215   imageEig = cvCreateImage(subregionSize, IPL_DEPTH_32F, 1);
00216   imageTmp = cvCreateImage(subregionSize, IPL_DEPTH_32F, 1);
00217 
00218   CvSize pyrSize = cvSize(imageWidth + 8, imageHeight / 3);
00219   pyrCur = cvCreateImage(pyrSize, IPL_DEPTH_32F, 1);
00220   pyrLast = cvCreateImage(pyrSize, IPL_DEPTH_32F, 1);
00221 
00222   ros::Subscriber imageDataSub = nh.subscribe<sensor_msgs::Image>("/image/raw", 1, imageDataHandler);
00223 
00224   ros::Publisher imagePointsLastPub = nh.advertise<sensor_msgs::PointCloud2> ("/image_points_last", 5);
00225   imagePointsLastPubPointer = &imagePointsLastPub;
00226 
00227   ros::Publisher imageShowPub = nh.advertise<sensor_msgs::Image>("/image/show", 1);
00228   imageShowPubPointer = &imageShowPub;
00229 
00230   ros::spin();
00231 
00232   return 0;
00233 }
00234 


demo_lidar
Author(s): Ji Zhang
autogenerated on Fri Jan 3 2014 11:17:39