processDepthmap.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::PointXYZI>::Ptr depthCloud(new pcl::PointCloud<pcl::PointXYZI>());
00023 pcl::PointCloud<pcl::PointXYZI>::Ptr tempCloud(new pcl::PointCloud<pcl::PointXYZI>());
00024 pcl::PointCloud<pcl::PointXYZI>::Ptr tempCloud2(new pcl::PointCloud<pcl::PointXYZI>());
00025 
00026 double timeRec = 0;
00027 double rxRec = 0, ryRec = 0, rzRec = 0;
00028 double txRec = 0, tyRec = 0, tzRec = 0;
00029 
00030 ros::Publisher *depthCloudPubPointer = NULL;
00031 
00032 void voDataHandler(const nav_msgs::Odometry::ConstPtr& voData)
00033 {
00034   double time = voData->header.stamp.toSec();
00035 
00036   double roll, pitch, yaw;
00037   geometry_msgs::Quaternion geoQuat = voData->pose.pose.orientation;
00038   tf::Matrix3x3(tf::Quaternion(geoQuat.z, -geoQuat.x, -geoQuat.y, geoQuat.w)).getRPY(roll, pitch, yaw);
00039 
00040   double rx = voData->twist.twist.angular.x - rxRec;
00041   double ry = voData->twist.twist.angular.y - ryRec;
00042   double rz = voData->twist.twist.angular.z - rzRec;
00043 
00044   if (ry < -PI) {
00045     ry += 2 * PI;
00046   } else if (ry > PI) {
00047     ry -= 2 * PI;
00048   }
00049 
00050   double tx = voData->pose.pose.position.x - txRec;
00051   double ty = voData->pose.pose.position.y - tyRec;
00052   double tz = voData->pose.pose.position.z - tzRec;
00053 
00054   rxRec = voData->twist.twist.angular.x;
00055   ryRec = voData->twist.twist.angular.y;
00056   rzRec = voData->twist.twist.angular.z;
00057 
00058   txRec = voData->pose.pose.position.x;
00059   tyRec = voData->pose.pose.position.y;
00060   tzRec = voData->pose.pose.position.z;
00061 
00062   float x1 = cos(yaw) * tx + sin(yaw) * tz;
00063   float y1 = ty;
00064   float z1 = -sin(yaw) * tx + cos(yaw) * tz;
00065 
00066   float x2 = x1;
00067   float y2 = cos(pitch) * y1 - sin(pitch) * z1;
00068   float z2 = sin(pitch) * y1 + cos(pitch) * z1;
00069 
00070   tx = cos(roll) * x2 + sin(roll) * y2;
00071   ty = -sin(roll) * x2 + cos(roll) * y2;
00072   tz = z2;
00073 
00074   double cosrx = cos(rx);
00075   double sinrx = sin(rx);
00076   double cosry = cos(ry);
00077   double sinry = sin(ry);
00078   double cosrz = cos(rz);
00079   double sinrz = sin(rz);
00080 
00081   if (time - timeRec < 0.5 && syncCloudInd >= 0) {
00082     pcl::PointXYZI point;
00083     tempCloud->clear();
00084     double x1, y1, z1, x2, y2, z2;
00085     int depthCloudNum = depthCloud->points.size();
00086     for (int i = 0; i < depthCloudNum; i++) {
00087       point = depthCloud->points[i];
00088 
00089       x1 = cosry * point.x - sinry * point.z;
00090       y1 = point.y;
00091       z1 = sinry * point.x + cosry * point.z;
00092 
00093       x2 = x1;
00094       y2 = cosrx * y1 + sinrx * z1;
00095       z2 = -sinrx * y1 + cosrx * z1;
00096 
00097       point.x = cosrz * x2 + sinrz * y2 - tx;
00098       point.y = -sinrz * x2 + cosrz * y2 - ty;
00099       point.z = z2 - tz;
00100 
00101       double pointDis = sqrt(point.x * point.x + point.y * point.y + point.z * point.z);
00102       if (fabs(point.x / point.z) < 2 && fabs(point.y / point.z) < 1 && point.z > 0.5 && pointDis < 15) {
00103         tempCloud->push_back(point);
00104       }
00105     }
00106 
00107     while (syncCloudTime[cloudRegInd] <= time && cloudRegInd != (syncCloudInd + 1) % keepSyncCloudNum) {
00108       double scale = (time - syncCloudTime[cloudRegInd]) / (time - timeRec);
00109       if (scale > 1) {
00110         scale = 1;
00111       } else if (scale < 0) {
00112         scale = 0;
00113       }
00114 
00115       double rx2 = rx * scale;
00116       double ry2 = ry * scale;
00117       double rz2 = rz * scale;
00118 
00119       double tx2 = tx * scale;
00120       double ty2 = ty * scale;
00121       double tz2 = tz * scale;
00122 
00123       double cosrx2 = cos(rx2);
00124       double sinrx2 = sin(rx2);
00125       double cosry2 = cos(ry2);
00126       double sinry2 = sin(ry2);
00127       double cosrz2 = cos(rz2);
00128       double sinrz2 = sin(rz2);
00129 
00130       pcl::PointCloud<pcl::PointXYZ>::Ptr syncCloudPointer = syncCloudArray[cloudRegInd];
00131       int syncCloudNum = syncCloudPointer->points.size();
00132       for (int i = 0; i < syncCloudNum; i++) {
00133         point.x = syncCloudPointer->points[i].x;
00134         point.y = syncCloudPointer->points[i].y;
00135         point.z = syncCloudPointer->points[i].z;
00136 
00137         x1 = cosry2 * point.x - sinry2 * point.z;
00138         y1 = point.y;
00139         z1 = sinry2 * point.x + cosry2 * point.z;
00140 
00141         x2 = x1;
00142         y2 = cosrx2 * y1 + sinrx2 * z1;
00143         z2 = -sinrx2 * y1 + cosrx2 * z1;
00144 
00145         point.x = cosrz2 * x2 + sinrz2 * y2 - tx2;
00146         point.y = -sinrz2 * x2 + cosrz2 * y2 - ty2;
00147         point.z = z2 - tz2;
00148 
00149         double pointDis = sqrt(point.x * point.x + point.y * point.y + point.z * point.z);
00150         if (fabs(point.x / point.z) < 2 && fabs(point.y / point.z) < 1.5 && point.z > 0.5 && 
00151             pointDis < 15) {
00152           tempCloud->push_back(point);
00153         }
00154       }
00155       cloudRegInd = (cloudRegInd + 1) % keepSyncCloudNum;
00156     }
00157 
00158     depthCloud->clear();
00159     pcl::VoxelGrid<pcl::PointXYZI> downSizeFilter;
00160     downSizeFilter.setInputCloud(tempCloud);
00161     downSizeFilter.setLeafSize(0.05, 0.05, 0.05);
00162     downSizeFilter.filter(*depthCloud);
00163     depthCloudNum = depthCloud->points.size();
00164 
00165     tempCloud->clear();
00166     for (int i = 0; i < depthCloudNum; i++) {
00167       point = depthCloud->points[i];
00168 
00169       if (fabs(point.x / point.z) < 1 && fabs(point.y / point.z) < 0.6) {
00170         point.intensity = depthCloud->points[i].z;
00171         point.x *= 10 / depthCloud->points[i].z;
00172         point.y *= 10 / depthCloud->points[i].z;
00173         point.z = 10;
00174 
00175         tempCloud->push_back(point);
00176       }
00177     }
00178 
00179     tempCloud2->clear();
00180     downSizeFilter.setInputCloud(tempCloud);
00181     downSizeFilter.setLeafSize(0.1, 0.1, 0.1);
00182     downSizeFilter.filter(*tempCloud2);
00183     int tempCloud2Num = tempCloud2->points.size();
00184 
00185     for (int i = 0; i < tempCloud2Num; i++) {
00186       tempCloud2->points[i].z = tempCloud2->points[i].intensity;
00187       tempCloud2->points[i].x *= tempCloud2->points[i].z / 10;
00188       tempCloud2->points[i].y *= tempCloud2->points[i].z / 10;
00189       tempCloud2->points[i].intensity = 10;
00190     }
00191 
00192     tempCloud2->header.frame_id = "camera2";
00193     tempCloud2->header.stamp = voData->header.stamp;
00194     sensor_msgs::PointCloud2 depthCloud2;
00195     pcl::toROSMsg(*tempCloud2, depthCloud2);
00196     depthCloudPubPointer->publish(depthCloud2);
00197   }
00198 
00199   timeRec = time;
00200 }
00201 
00202 void syncCloudHandler(const sensor_msgs::PointCloud2ConstPtr& syncCloud2)
00203 {
00204   double time = syncCloud2->header.stamp.toSec();
00205 
00206   syncCloudInd = (syncCloudInd + 1) % keepSyncCloudNum;
00207   syncCloudTime[syncCloudInd] = time;
00208   pcl::PointCloud<pcl::PointXYZ>::Ptr syncCloudPointer = syncCloudArray[syncCloudInd];
00209   syncCloudPointer->clear();
00210   pcl::fromROSMsg(*syncCloud2, *syncCloudPointer);
00211 }
00212 
00213 int main(int argc, char** argv)
00214 {
00215   ros::init(argc, argv, "processDepthmap");
00216   ros::NodeHandle nh;
00217 
00218   for (int i = 0; i < keepSyncCloudNum; i++) {
00219     pcl::PointCloud<pcl::PointXYZ>::Ptr syncCloudTemp(new pcl::PointCloud<pcl::PointXYZ>());
00220     syncCloudArray[i] = syncCloudTemp;
00221   }
00222 
00223   ros::Subscriber voDataSub = nh.subscribe<nav_msgs::Odometry> ("/cam_to_init", 5, voDataHandler);
00224 
00225   ros::Subscriber syncCloudSub = nh.subscribe<sensor_msgs::PointCloud2>
00226                                  ("/sync_scan_cloud_filtered", 5, syncCloudHandler);
00227 
00228   ros::Publisher depthCloudPub = nh.advertise<sensor_msgs::PointCloud2> ("/depth_cloud", 5);
00229   depthCloudPubPointer = &depthCloudPub;
00230 
00231   ros::spin();
00232 
00233   return 0;
00234 }


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