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


demo_rgbd
Author(s): Ji Zhang
autogenerated on Mon Jan 6 2014 11:16:08