registerPointCloud.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 <nav_msgs/Odometry.h>
00007 
00008 #include <tf/transform_datatypes.h>
00009 #include <tf/transform_listener.h>
00010 #include <tf/transform_broadcaster.h>
00011 
00012 #include "pointDefinition.h"
00013 
00014 const double PI = 3.1415926;
00015 
00016 const int keepSyncCloudNum = 20;
00017 double syncCloudTime[keepSyncCloudNum] = {0};
00018 pcl::PointCloud<pcl::PointXYZ>::Ptr syncCloudArray[keepSyncCloudNum];
00019 int syncCloudInd = -1;
00020 int cloudRegInd = 0;
00021 
00022 pcl::PointCloud<pcl::PointXYZ>::Ptr surroundCloud(new pcl::PointCloud<pcl::PointXYZ>());
00023 pcl::PointCloud<pcl::PointXYZ>::Ptr tempCloud(new pcl::PointCloud<pcl::PointXYZ>());
00024 
00025 double timeRec = 0;
00026 double rxRec = 0, ryRec = 0, rzRec = 0;
00027 double txRec = 0, tyRec = 0, tzRec = 0;
00028 
00029 int showCount = 0;
00030 const int showSkipNum = 8;
00031 
00032 ros::Publisher *surroundCloudPubPointer = NULL;
00033 
00034 void voDataHandler(const nav_msgs::Odometry::ConstPtr& voData)
00035 {
00036   showCount = (showCount + 1) % (showSkipNum + 1);
00037   if (showCount != showSkipNum) {
00038     return;
00039   }
00040 
00041   double time = voData->header.stamp.toSec();
00042 
00043   double rx, ry, rz;
00044   geometry_msgs::Quaternion geoQuat = voData->pose.pose.orientation;
00045   tf::Matrix3x3(tf::Quaternion(geoQuat.z, -geoQuat.x, -geoQuat.y, geoQuat.w)).getRPY(rz, rx, ry);
00046 
00047   double tx = voData->pose.pose.position.x;
00048   double ty = voData->pose.pose.position.y;
00049   double tz = voData->pose.pose.position.z;
00050 
00051   if (time - timeRec < 0.5 && syncCloudInd >= 0) {
00052     pcl::PointXYZ point;
00053     tempCloud->clear();
00054     int surroundCloudNum = surroundCloud->points.size();
00055     for (int i = 0; i < surroundCloudNum; i++) {
00056       point = surroundCloud->points[i];
00057 
00058       double xDiff = point.x - tx;
00059       double yDiff = point.y - ty;
00060       double zDiff = point.z - tz;
00061 
00062       double pointDis = sqrt(xDiff * xDiff + yDiff * yDiff + zDiff * zDiff);
00063       if (pointDis < 50) {
00064         tempCloud->push_back(point);
00065       }
00066     }
00067 
00068     while (syncCloudTime[cloudRegInd] <= time && cloudRegInd != (syncCloudInd + 1) % keepSyncCloudNum) {
00069       double scaleLast =  (time - syncCloudTime[cloudRegInd]) / (time - timeRec);
00070       double scaleCur =  (syncCloudTime[cloudRegInd] - timeRec) / (time - timeRec);
00071       if (scaleLast > 1) {
00072         scaleLast = 1;
00073       } else if (scaleLast < 0) {
00074         scaleLast = 0;
00075       }
00076       if (scaleCur > 1) {
00077         scaleCur = 1;
00078       } else if (scaleCur < 0) {
00079         scaleCur = 0;
00080       }
00081 
00082       double rx2 = rx * scaleCur + rxRec * scaleLast;
00083       double ry2;
00084       if (ry - ryRec > PI) {
00085         ry2 = ry * scaleCur + (ryRec + 2 * PI) * scaleLast;
00086       } else if (ry - ryRec < -PI) {
00087         ry2 = ry * scaleCur + (ryRec - 2 * PI) * scaleLast;
00088       } else {
00089         ry2 = ry * scaleCur + ryRec * scaleLast;
00090       }
00091       double rz2 = rz * scaleCur + rzRec * scaleLast;
00092 
00093       double tx2 = tx * scaleCur + txRec * scaleLast;
00094       double ty2 = ty * scaleCur + tyRec * scaleLast;
00095       double tz2 = tz * scaleCur + tzRec * scaleLast;
00096 
00097       double cosrx2 = cos(rx2);
00098       double sinrx2 = sin(rx2);
00099       double cosry2 = cos(ry2);
00100       double sinry2 = sin(ry2);
00101       double cosrz2 = cos(rz2);
00102       double sinrz2 = sin(rz2);
00103 
00104       pcl::PointCloud<pcl::PointXYZ>::Ptr syncCloudPointer = syncCloudArray[cloudRegInd];
00105       int syncCloudNum = syncCloudPointer->points.size();
00106       for (int i = 0; i < syncCloudNum; i++) {
00107         point = syncCloudPointer->points[i];
00108         double pointDis = sqrt(point.x * point.x + point.y * point.y + point.z * point.z);
00109         if (pointDis > 0.3 && pointDis < 5) {
00110           double x1 = cosrz2 * point.x - sinrz2 * point.y;
00111           double y1 = sinrz2 * point.x + cosrz2 * point.y;
00112           double z1 = point.z;
00113 
00114           double x2 = x1;
00115           double y2 = cosrx2 * y1 + sinrx2 * z1;
00116           double z2 = -sinrx2 * y1 + cosrx2 * z1;
00117 
00118           point.x = cosry2 * x2 - sinry2 * z2 + tx2;
00119           point.y = y2 + ty2;
00120           point.z = sinry2 * x2 + cosry2 * z2 + tz2;
00121 
00122           tempCloud->push_back(point);
00123         }
00124       }
00125 
00126       cloudRegInd = (cloudRegInd + 1) % keepSyncCloudNum;
00127     }
00128 
00129     surroundCloud->clear();
00130     pcl::VoxelGrid<pcl::PointXYZ> downSizeFilter;
00131     downSizeFilter.setInputCloud(tempCloud);
00132     downSizeFilter.setLeafSize(0.2, 0.2, 0.2);
00133     downSizeFilter.filter(*surroundCloud);
00134     surroundCloudNum = surroundCloud->points.size();
00135 
00136     surroundCloud->header.frame_id = "/camera_init";
00137     surroundCloud->header.stamp = voData->header.stamp;
00138     sensor_msgs::PointCloud2 surroundCloud2;
00139     pcl::toROSMsg(*surroundCloud, surroundCloud2);
00140     surroundCloudPubPointer->publish(surroundCloud2);
00141   }
00142 
00143   rxRec = rx; ryRec = ry; rzRec = rz;
00144   txRec = tx; tyRec = ty; tzRec = tz;
00145 
00146   timeRec = time;
00147 }
00148 
00149 void syncCloudHandler(const sensor_msgs::PointCloud2ConstPtr& syncCloud2)
00150 {
00151   double time = syncCloud2->header.stamp.toSec();
00152 
00153   syncCloudInd = (syncCloudInd + 1) % keepSyncCloudNum;
00154   syncCloudTime[syncCloudInd] = time;
00155   pcl::PointCloud<pcl::PointXYZ>::Ptr syncCloudPointer = syncCloudArray[syncCloudInd];
00156   syncCloudPointer->clear();
00157   pcl::fromROSMsg(*syncCloud2, *syncCloudPointer);
00158 }
00159 
00160 int main(int argc, char** argv)
00161 {
00162   ros::init(argc, argv, "registerPointCloud");
00163   ros::NodeHandle nh;
00164 
00165   for (int i = 0; i < keepSyncCloudNum; i++) {
00166     pcl::PointCloud<pcl::PointXYZ>::Ptr syncCloudTemp(new pcl::PointCloud<pcl::PointXYZ>());
00167     syncCloudArray[i] = syncCloudTemp;
00168   }
00169 
00170   ros::Subscriber voDataSub = nh.subscribe<nav_msgs::Odometry> ("/cam2_to_init", 5, voDataHandler);
00171 
00172   ros::Subscriber syncCloudSub = nh.subscribe<sensor_msgs::PointCloud2>
00173                                  ("/sync_scan_cloud_filtered", 5, syncCloudHandler);
00174 
00175   ros::Publisher surroundCloudPub = nh.advertise<sensor_msgs::PointCloud2> ("/surround_cloud", 1);
00176   surroundCloudPubPointer = &surroundCloudPub;
00177 
00178   ros::spin();
00179 
00180   return 0;
00181 }


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