00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #include <pc_accumulation/pc_accumulation.h>
00028 #include <pcl/filters/voxel_grid.h>
00029
00030
00031
00041
00042 sensor_msgs::PointCloud2 voxel_filter(sensor_msgs::PointCloud2 msg_in, float voxel_size)
00043 {
00044 sensor_msgs::PointCloud2 msg_out;
00045 sensor_msgs::PointCloud2ConstPtr msg_ptr (new sensor_msgs::PointCloud2 (msg_in));
00046 pcl::VoxelGrid<sensor_msgs::PointCloud2> sor;
00047 sor.setInputCloud(msg_ptr);
00048 sor.setLeafSize (voxel_size, voxel_size, voxel_size);
00049 sor.filter (msg_out);
00050 return msg_out;
00051 }
00052
00053
00064 int pc_accumulation::pointcloud_accumulated(pcl::PointCloud<pcl::PointXYZRGB> pcl_pc,std::string acc_frame_id)
00065 {
00066 tf::StampedTransform transform;
00067
00068 pcl_pc.header.stamp=ros::Time();
00069 pcl::PointCloud<pcl::PointXYZRGB> pcl_transformed;
00070
00071 bool have_transform=false;
00072 try
00073 {
00074 p_listener->lookupTransform(acc_frame_id,pcl_pc.header.frame_id , pcl_pc.header.stamp, transform);
00075 have_transform=true;
00076 }
00077 catch (tf::TransformException ex)
00078 {
00079 if(p_listener->waitForTransform(acc_frame_id,pcl_pc.header.frame_id,pcl_pc.header.stamp, ros::Duration(3.0)))
00080 {
00081 try
00082 {
00083 p_listener->lookupTransform(acc_frame_id,pcl_pc.header.frame_id , pcl_pc.header.stamp, transform);
00084 have_transform=true;
00085 }
00086 catch (tf::TransformException ex)
00087 {
00088 ROS_ERROR("Could not lookup transform after waiting 3 secs\n.%s",ex.what());
00089 }
00090 }
00091 else
00092 {
00093 ROS_ERROR("Could find valid transform after waiting 3 secs\n.%s",ex.what());
00094 }
00095 }
00096
00097 if (have_transform==false)
00098 {
00099 return 0;
00100 }
00101
00102
00103 pcl_ros::transformPointCloud(pcl_pc,pcl_transformed,transform);
00104 pcl_transformed.header.frame_id=acc_frame_id;
00105
00106 pcl_pc_acc+=pcl_transformed;
00107
00108 sensor_msgs::PointCloud2 pc_trans;
00109 sensor_msgs::PointCloud2 pc_voxel;
00110
00111 pcl::toROSMsg(pcl_pc_acc,pc_trans);
00112
00113 pc_voxel=voxel_filter(pc_trans,voxel_size);
00114 pcl::fromROSMsg(pc_voxel,pcl_pc_acc);
00115
00116 pcl_pc_acc.header.frame_id=acc_frame_id;
00117 return 1;
00118 }
00119
00131
00132 int pc_accumulation::remove_points_from_pointcloud(pcl::PointCloud<pcl::PointXYZRGB> pcl_pc,float dist, float X0, float Y0, float Z0)
00133 {
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143
00144
00145 for(long int i=pcl_pc.points.size()-1; i>0; --i)
00146 {
00147 float dist_x, dist_y, dist_z, dist_norm;
00148
00149 dist_x=pcl_pc.points[i].x-X0;
00150 dist_y=pcl_pc.points[i].y-Y0;
00151 dist_z=pcl_pc.points[i].z-Z0;
00152
00153 dist_norm=sqrt(dist_x*dist_x + dist_y*dist_y + dist_z*dist_z);
00154
00155
00156
00157
00158
00159
00160
00161
00162
00163
00164
00165
00166
00167 if(dist_norm>dist)
00168 {
00169 pcl_pc.erase(pcl_pc.points.begin()+i);
00170 }
00171 }
00172 pcl_pc_acc=pcl_pc;
00173
00174 return 1;
00175 }
00176
00177
00178