pc_accumulation.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
28 #include <pcl/filters/voxel_grid.h>
29 //#include <fstream>
30 //#include <iostream>
31 
41 //voxel_filter
42 sensor_msgs::PointCloud2 voxel_filter(sensor_msgs::PointCloud2 msg_in, float voxel_size)
43 {
44  ROS_ERROR("Voxel grid does not work with sensor_msgs::PointCloud2, convertion is needed\n");
45 // sensor_msgs::PointCloud2 msg_out;
46 // sensor_msgs::PointCloud2ConstPtr msg_ptr (new sensor_msgs::PointCloud2 (msg_in));
47 // pcl::VoxelGrid<sensor_msgs::PointCloud2> sor;
48 // sor.setInputCloud(msg_ptr);
49 // sor.setLeafSize (voxel_size, voxel_size, voxel_size);
50 // sor.filter (msg_out);
51 // return msg_out;
52 }
53 
54 
65 int pc_accumulation::pointcloud_accumulated(pcl::PointCloud<pcl::PointXYZRGB> pcl_pc,std::string acc_frame_id)
66 {
67  tf::StampedTransform transform;
68 
69 // pcl_pc.header.stamp = ros::Time();
70  ROS_ERROR("Point cloud stamp not set\n");
71 
72  pcl::PointCloud<pcl::PointXYZRGB> pcl_transformed;
73 
74  bool have_transform=false;
75  try
76  {
77 // p_listener->lookupTransform(acc_frame_id,pcl_pc.header.frame_id , pcl_pc.header.stamp, transform);
78  p_listener->lookupTransform(acc_frame_id,pcl_pc.header.frame_id , ros::Time::now(), transform);
79  ROS_ERROR("Point cloud stamp not set\n");
80 
81  have_transform=true;
82  }
83  catch (tf::TransformException ex)
84  {
85 // if(p_listener->waitForTransform(acc_frame_id,pcl_pc.header.frame_id,pcl_pc.header.stamp, ros::Duration(3.0)))
86 // {
87 
88  ROS_ERROR("Point cloud stamp not set\n");
89 
90  if(p_listener->waitForTransform(acc_frame_id,pcl_pc.header.frame_id,ros::Time::now(), ros::Duration(3.0)))
91  {
92  try
93  {
94  p_listener->lookupTransform(acc_frame_id,pcl_pc.header.frame_id , ros::Time::now(), transform);
95 
96  ROS_ERROR("Point cloud stamp not set\n");
97 
98 // p_listener->lookupTransform(acc_frame_id,pcl_pc.header.frame_id , pcl_pc.header.stamp, transform);
99  have_transform=true;
100  }
101  catch (tf::TransformException ex)
102  {
103  ROS_ERROR("Could not lookup transform after waiting 3 secs\n.%s",ex.what());
104  }
105  }
106  else
107  {
108  ROS_ERROR("Could find valid transform after waiting 3 secs\n.%s",ex.what());
109  }
110  }
111 
112  if (have_transform==false)
113  {
114  return 0;
115  }
116 
117  // Transform pc1 to pc2 ->transform
118  pcl_ros::transformPointCloud(pcl_pc,pcl_transformed,transform);
119  pcl_transformed.header.frame_id=acc_frame_id;
120 
121  pcl_pc_acc+=pcl_transformed;
122 
123  sensor_msgs::PointCloud2 pc_trans;
124  sensor_msgs::PointCloud2 pc_voxel;
125 
126  pcl::toROSMsg(pcl_pc_acc,pc_trans);
127 
128  pc_voxel=voxel_filter(pc_trans,voxel_size);
129  pcl::fromROSMsg(pc_voxel,pcl_pc_acc);
130 
131  pcl_pc_acc.header.frame_id=acc_frame_id;
132  return 1;
133 }
134 
146 //ofstream myfile;
147 int pc_accumulation::remove_points_from_pointcloud(pcl::PointCloud<pcl::PointXYZRGB> pcl_pc,float dist, float X0, float Y0, float Z0)
148 {
149 /* int counttt=0,counttttt=0;
150 
151  static int init=0;
152  if (init==0)
153  {
154  init=1;
155  myfile.open ("../percentagem.txt");
156  }
157 */
158 
159 // ROS_INFO("before cleanup %ld points", pcl_pc.points.size());
160  for(long int i=pcl_pc.points.size()-1; i>0; --i)
161  {
162  float dist_x, dist_y, dist_z, dist_norm;
163 
164  dist_x=pcl_pc.points[i].x-X0;
165  dist_y=pcl_pc.points[i].y-Y0;
166  dist_z=pcl_pc.points[i].z-Z0;
167 
168  dist_norm=sqrt(dist_x*dist_x + dist_y*dist_y + dist_z*dist_z);
169  //verificar qto pontos se encontram
170  /* if (sqrt(dist_x*dist_x)> 8 || (sqrt(dist_y*dist_y)> 2 || sqrt(dist_z*dist_z)> 0.2))
171  {
172  pcl_pc.erase(pcl_pc.points.begin()+i);
173  ROS_INFO("after cleanup %ld points", pcl_pc.points.size());
174  }
175  if(( (dist_x>0 &&dist_x<5) || sqrt(dist_y*dist_y)< 0.5) && sqrt(dist_z*dist_z)< 0.2)
176  {
177  counttttt++;
178  if ( dist_z< 0.10 && dist_z>-0.10)
179  counttt++;
180  }*/
181 
182  if(dist_norm>dist) //verify distance
183  {
184  pcl_pc.erase(pcl_pc.points.begin()+i);
185  }
186  }
187  pcl_pc_acc=pcl_pc;
188 
189  return 1;
190 }
191 
192 
193 
pcl::PointCloud< pcl::PointXYZRGB > pcl_pc_acc
int remove_points_from_pointcloud(pcl::PointCloud< pcl::PointXYZRGB > pcl_pc, float dist, std::string frame_id)
Function the removes points from cloud This function calculated the origin of the given accumulation ...
tf::TransformListener * p_listener
int pointcloud_accumulated(sensor_msgs::LaserScan &scan_in, std::string acc_frame_id)
Function that receive a LaserScan and Accumulation Frame It converts the laserScan to a pcl::PointXYZ...
Ros includes.
sensor_msgs::PointCloud2 voxel_filter(sensor_msgs::PointCloud2 msg_in, float voxel_size)


pc_accumulation
Author(s): Pedro Salvado
autogenerated on Mon Mar 2 2015 01:32:32