pc_accumulation_nodelet.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 ***************************************************************************************************/
34 #define PFLN {printf("%s %d\n",__FILE__, __LINE__);}
35 
37 //GLOBAL VARIABLES
38 ros::Publisher cloud_pc_laserScan;
39 ros::Publisher cloud_pc_pointcloud;
43 
44 
45 bool process_laser_scan[5]={false,false,false,false,false};
46 bool process_point_cloud[5]={false,false,false,false,false};
47 
48 
53 void OdometryCallBack (const nav_msgs::OdometryConstPtr & odom_in)
54 {
55  p_lib->odometry_=*odom_in;
56 }
57 
62 void pointcloud_Callback(const sensor_msgs::PointCloud2Ptr& image)
63 {
64  p_lib->pointcloud_accumulated(*image,acc_frame);
65 }
66 
71 void laserscan_Callback(const sensor_msgs::LaserScanPtr& scan_in)
72 {
73  p_lib->pointcloud_accumulated(*scan_in,acc_frame);
74 }
75 
76 
81 void Remove_Publish(const ros::TimerEvent&)
82 {
83  sensor_msgs::PointCloud2 msg;
85  pcl::toROSMsg(p_lib->pcl_pc_acc,msg);
86  cloud_pc_pointcloud.publish(msg);
87 }
88 
89 
90 int main(int argc, char **argv)
91 {
92  ros::init(argc, argv, "nodelet"); // Initialize ROS coms
93  ros::NodeHandle n("~"); //The node handle
94 // T=ros::Time::now();
95  //Check topic remapping
96  //Test the remapping of the /laserscan s
97  for (int i=0; i<5; i++)
98  {
99  char str[1024];
100  sprintf(str,"/laserscan%d", i);
101  if (ros::names::remap(str)!=str)
102  {
103  process_laser_scan[i] = true;
104  }
105  }
106 
107  //Test the remapping of the /pointcloud s
108  for (int i=0; i<5; i++)
109  {
110  char str[1024];
111  sprintf(str,"/pointcloud%d", i);
112  if (ros::names::remap(str)!=str)
113  {
114  process_point_cloud[i] = true;
115  }
116  }
117  std::vector<ros::Subscriber> sub;
118  //Creates ROS subscribers if the laserscan topics where remapped
119  for (int i=0; i<5; i++)
120  {
121  if (process_laser_scan[i]==true)
122  {
123  char str[1024];
124  sprintf(str,"/laserscan%d", i);
125  ros::Subscriber sub_ = n.subscribe (str, 1, laserscan_Callback);
126  ROS_INFO("Subscribing to %s", (ros::names::remap(str)).c_str());
127  sub.push_back(sub_);
128  }
129  }
130 
131  //Creates ROS subscribers if the pointcloud topics where remapped
132  for (int i=0; i<5; i++)
133  {
134  if (process_point_cloud[i]==true)
135  {
136  char str[1024];
137  sprintf(str,"/pointcloud%d", i);
138  ros::Subscriber sub_ = n.subscribe (str, 1, pointcloud_Callback);
139  ROS_INFO("Subscribing to %s", (ros::names::remap(str)).c_str());
140  ROS_INFO("REcebeu pointcloud");
141  sub.push_back(sub_);
142  }
143  }
144 
145 
146  if (sub.size()==0)
147  {
148  ROS_ERROR("No /laserscan[0 4] or /pointcloud[0 4] where remapped. Aborting...");
149  ros::shutdown();
150  }
151 
152 
153  //Check param remapping
154  if (!n.hasParam("acc_frame")) //
155  {
156  ROS_ERROR("Didn't introduce a accumulation frame");
157  return -1;
158  }
159  else
160  {
161  n.getParam("acc_frame",acc_frame);
162  }
163 
164 
165  //verify accumulation parameters
166  if (!n.hasParam("distance_from"))
167  ROS_WARN("distance for accumulation 15 meters");
168  else
169  n.param("distance_from",distance_from, 15.0);
170 
171  if (!n.hasParam("timer_value"))
172  ROS_WARN("Frequency of publication 2.0 sec");
173  else
174  n.param("timer_value",timer_value, 2.0);
175 
176 
177 
178  // Declaration class
179  pc_accumulation lib;
180 
181 
182  if (!n.hasParam("voxel_size"))
183  ROS_WARN("Voxel_size Default 0.4 meter");
184  else
185  n.param("voxel_size",lib.voxel_size, 0.4);
186  //remap string
187  string removed_from;
188  if (!n.hasParam("removed_from"))
189  {
190  ROS_ERROR("Remove from frame not Defined");
191  return -1;
192  }
193  else
194  n.getParam("removed_from",removed_from);
195 
196  lib._acc_frame_id=removed_from;
197 
198  //Pointer to lib
199  p_lib=&lib;
200 
201  //Remove&Publish accumulated pointcloud
202  ros::Timer timer = n.createTimer(ros::Duration(timer_value), Remove_Publish);
203 
204  tf::TransformListener listener(n,ros::Duration(10));
205  // Transform Listener
206  lib.p_listener=&listener;
207  // Node Handle
208  lib.p_n=&n;
209 
210  cloud_pc_pointcloud = n.advertise<sensor_msgs::PointCloud2>("/pc_out_pointcloud", 1);
211  ros::Subscriber odom = n.subscribe ("odometry_topic", 1, OdometryCallBack);
212 
213 
214  ros::Rate loop_rate(50);
215  ros::spin();
216 
217 
218  return 0;
219 }
std::string _acc_frame_id
nav_msgs::Odometry odometry_
bool process_point_cloud[5]
void pointcloud_Callback(const sensor_msgs::PointCloud2Ptr &image)
Callback from the PointCloud subscribed topic.
ros::NodeHandle * p_n
std::string acc_frame
double distance_from
pcl::PointCloud< pcl::PointXYZRGB > pcl_pc_acc
void OdometryCallBack(const nav_msgs::OdometryConstPtr &odom_in)
Callback from the Odometry subscribed topic.
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...
void laserscan_Callback(const sensor_msgs::LaserScanPtr &scan_in)
Callback from the LaserScan subscribed topic.
std::string laser_topic
std::string pc_topic
Ros includes.
pc_accumulation * p_lib
ros::Publisher cloud_pc_pointcloud
double timer_value
bool process_laser_scan[5]
int main(int argc, char **argv)
void Remove_Publish(const ros::TimerEvent &)
Function responsible for Remove and Publish PointCloud ()
ros::Publisher cloud_pc_laserScan


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