pc_accumulation.h
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 <ros/ros.h>
29 #include <pcl_ros/transforms.h>
30 #include <pcl/conversions.h>
31 #include <pcl/point_cloud.h>
32 #include <pcl/point_types.h>
33 #include <laser_geometry/laser_geometry.h>
34 #include <sensor_msgs/PointCloud2.h>
35 #include <sensor_msgs/LaserScan.h>
36 #include <tf/transform_listener.h>
37 #include <nav_msgs/Odometry.h>
38 #include <pcl_conversions/pcl_conversions.h>
39 
54 using namespace std;
56 {
57  public:
58 
59  tf::TransformListener *p_listener;
60  ros::NodeHandle* p_n;
61  double voxel_size;
62  std::string _acc_frame_id;
63 
64  nav_msgs::Odometry odometry_;
65  ros::Time time_msg;
66 
67  sensor_msgs::PointCloud2 msg_cloud;
68 
69  pcl::PointCloud<pcl::PointXYZRGB> pcl_pc_acc; //accumulation pc
70 
77  int pointcloud_accumulated(sensor_msgs::LaserScan& scan_in,std::string acc_frame_id)
78  {
79 
80  laser_geometry::LaserProjection projector_;
81  pcl::PointCloud<pcl::PointXYZ> pc_tmp;
82  pcl::PointCloud<pcl::PointXYZRGB> pc_laser;
83  sensor_msgs::PointCloud2 poincloud_in;
84  //Transformacao de LaserScan para PointCloud
85  projector_.transformLaserScanToPointCloud(scan_in.header.frame_id,scan_in,poincloud_in,*p_listener);
86 
87 
88  pcl::PCLPointCloud2 pcl_pc;
89  pcl_conversions::toPCL(poincloud_in, pcl_pc);
90  pcl::fromPCLPointCloud2(pcl_pc, pc_tmp);
91 
92  pcl::fromROSMsg(poincloud_in,pc_tmp);
93 // pc_tmp.header.frame_id=scan_in.header.frame_id;
94 
95  pc_laser.points.resize(pc_tmp.size());
96 
97  for (size_t i = 0; i < pc_laser.points.size(); i++)
98  {
99 
100  pc_laser.points[i].x = pc_tmp.points[i].x;
101  pc_laser.points[i].y = pc_tmp.points[i].y;
102  pc_laser.points[i].z = pc_tmp.points[i].z;
103  pc_laser.points[i].r = 0.0;
104  pc_laser.points[i].g = 0.0;
105  pc_laser.points[i].b = 0.0;
106  }
107  pc_laser.header.frame_id = scan_in.header.frame_id;
108 
109  std::cout<<"Message stamp not set!! please correct"<<std::endl;
110 // pc_laser.header.stamp = scan_in.header.stamp;
111 
112  return pointcloud_accumulated(pc_laser,acc_frame_id);
113  };
114 
121  int pointcloud_accumulated(sensor_msgs::PointCloud2& pc_in,std::string acc_frame_id)
122  {
123  pcl::PointCloud<pcl::PointXYZRGB> pcl_pc; //temporary pcl
124  for (size_t i=0; i <pc_in.fields.size();i++)
125  {
126  if (pc_in.fields[i].name=="rgb")
127  {
128  ROS_ERROR("TEM RGB");
129 
130  pcl::fromROSMsg(pc_in,pcl_pc);
131  }
132  else
133  {
134 
135  pcl::PointCloud<pcl::PointXYZ> pcl_tmp; //temporary pcl
136  pcl::fromROSMsg(pc_in,pcl_tmp);
137  pcl_pc.points.resize(pcl_tmp.size());
138  for (size_t i = 0; i < pcl_pc.points.size(); i++)
139  {
140  pcl_pc.points[i].x = pcl_tmp.points[i].x;
141  pcl_pc.points[i].y = pcl_tmp.points[i].y;
142  pcl_pc.points[i].z = pcl_tmp.points[i].z;
143  pcl_pc.points[i].r = 0.0;
144  pcl_pc.points[i].g = 0.0;
145  pcl_pc.points[i].b = 0.0;
146  }
147 
148  }
149  }
150  pcl_pc.header.frame_id=pc_in.header.frame_id;
151  return pointcloud_accumulated(pcl_pc,acc_frame_id);
152 
153  };
154  int pointcloud_accumulated(pcl::PointCloud<pcl::PointXYZRGB> pcl_pc,std::string acc_frame_id);
155 
156 
164  int remove_points_from_pointcloud(pcl::PointCloud<pcl::PointXYZRGB> pcl_pc,float dist,std::string frame_id)
165  {
166  tf::StampedTransform transform;
167 
168  try
169  {
170  std::cout<<"Message stamp not set!! please correct"<<std::endl;
171  p_listener->lookupTransform(frame_id,_acc_frame_id , ros::Time::now(), transform);
172 // p_listener->lookupTransform(frame_id,_acc_frame_id , pcl_pc.header.stamp, transform);
173  }
174  catch (tf::TransformException ex)
175  {
176  ROS_ERROR("%s",ex.what());
177  return 0;
178  }
179 // ROS_INFO("get origin");
180  double X0 = transform.getOrigin().x();
181  double Y0 = transform.getOrigin().y();
182  double Z0 = transform.getOrigin().z();
183 
184  return remove_points_from_pointcloud(pcl_pc,dist, X0, Y0, Z0);
185  }
186 
187  int remove_points_from_pointcloud(pcl::PointCloud<pcl::PointXYZRGB> pcl_pc,float dist, float X0, float Y0, float Z0);
188 
189 private:
190 
191 };
std::string _acc_frame_id
nav_msgs::Odometry odometry_
sensor_msgs::PointCloud2 msg_cloud
ros::NodeHandle * p_n
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::Time time_msg
int pointcloud_accumulated(sensor_msgs::PointCloud2 &pc_in, std::string acc_frame_id)
Function that receive a PointCloud2 and Accumulation Frame If PointCloud2 has no field "rgb" then it ...


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