main.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 ***************************************************************************************************/
38 
39 //GLOBAL VARIABLES
41 int phis_count=0;
42 int firstscan=1;
43 ros::Time firstscan_stamp;
44 ros::Time phi1_stamp;
45 ros::Time phi2_stamp;
46 sensor_msgs::JointStatePtr first_state1(new sensor_msgs::JointState);
47 sensor_msgs::JointStatePtr first_state2(new sensor_msgs::JointState);
48 
54 void state_cb (const sensor_msgs::JointState::ConstPtr& state_in)
55 {
56  //only access corret joint state
57  std::string joint_name = "/connect_laser_roof_rotating";
58  if (joint_name.compare(state_in->name[0]) != 0)
59  return;
60 
61  if (firstscan)
62  {
64  *first_state2=*state_in;
65 
67  phi2_stamp = state_in->header.stamp;
68 
69  phis_count++;
70  }
71 
72  sensor_msgs::JointStatePtr new_state(new sensor_msgs::JointState);
73  *new_state=*state_in;
74 
75  if (!firstscan)//store the state joints in to vector
76  g_las3D->joints.push_back(new_state);
77 
78 }
79 
85 void scan_cb(const sensor_msgs::LaserScan::ConstPtr& scan_in)
86 {
87 
88  if (g_las3D->accumulation_mode==2 || g_las3D->accumulation_mode==3)
89  {
90  sensor_msgs::LaserScanPtr new_scan(new sensor_msgs::LaserScan);
91  *new_scan=*scan_in;
92  int error=0;
93  sensor_msgs::PointCloud2 pcmsg_in;
94 
95  //transform the laser scan using the scan time stamps
96  error=g_las3D->las3D_transformLaserScanToPointCloud(ros::names::remap("/ac_frame"), *new_scan,pcmsg_in,*g_las3D->p_listener);
97 
98  if (error)
99  return;
100 
101  pcl::PointCloud<pcl::PointXYZ> pc_in;
102  pcl::PCLPointCloud2 pcl_pc;
103  pcl_conversions::toPCL(pcmsg_in, pcl_pc);
104  pcl::fromPCLPointCloud2(pcl_pc, pc_in);
105 
106  pcl::fromROSMsg(pcmsg_in,pc_in);
107 
108  //accumulate the laser scans
109  g_las3D->accumulate_cloud(&pc_in);
110 
111  g_las3D->laser_count++;
112  g_las3D->laserscan_arrived=true;
113 
114  }
115  else if (g_las3D->accumulation_mode==1)
116  {
117  if (phis_count<2)
118  return;
119 
120  if (firstscan)
121  {
122  firstscan_stamp = scan_in->header.stamp;
123 
125  {
126  firstscan=0;
127  g_las3D->joints.push_back(first_state1);
128  g_las3D->joints.push_back(first_state2);
129  }
130  else
131  return;
132  }
133 
134  int error=0;
135 
136  sensor_msgs::LaserScanPtr new_scan(new sensor_msgs::LaserScan);
137  *new_scan=*scan_in;
138 
139  g_las3D->scans.push_back(new_scan); //store the scans to a vector
140 
141  if(g_las3D->joints.size()<2) //not enough phis to process a scan
142  return;
143 
144  while(g_las3D->joints.size()>=2 && g_las3D->scans.size()>0)
145  {
146  int need_state=0;
147  sensor_msgs::LaserScanPtr working_scan(new sensor_msgs::LaserScan);
148  *working_scan=*g_las3D->scans[0]; //get the oldest scan
149  g_las3D->scans.erase(g_las3D->scans.begin());
150 
151  //state start
152  sensor_msgs::JointStatePtr state_start(new sensor_msgs::JointState);
153  *state_start=*g_las3D->joints[0];
154 
155  g_las3D->joints.erase(g_las3D->joints.begin());
156 
157  //state end
158  sensor_msgs::JointStatePtr state_end(new sensor_msgs::JointState);
159  *state_end=*g_las3D->joints[0];
160 
161  //if phi start is lost, get new scan
162  while (working_scan->header.stamp<state_start->header.stamp)
163  {
164  if (g_las3D->scans.size()>0)
165  *working_scan=*g_las3D->scans[0];
166  else
167  {
168  need_state=1;
169  break;
170  }
171 
172  g_las3D->scans.erase(g_las3D->scans.begin());
173 
174  }
175  //if scan is lost and has no relation with the latest phi, get the phi with relation with the scan
176  while (working_scan->header.stamp>state_end->header.stamp)
177  {
178  g_las3D->joints.erase(g_las3D->joints.begin());
179 
180  if (g_las3D->joints.size()>0)
181  *state_end=*g_las3D->joints[0];
182  else
183  {
184  need_state=1;
185  break;
186  }
187  }
188 
189  if (need_state)
190  return;
191 
192  sensor_msgs::PointCloud2 pcmsg_in;
193 
194  //transform the laser scan in to a point cloud using the external shaft information
195  if (g_las3D->accumulation_mode==1)
196  error=g_las3D->las3D_transformLaserScanToPointCloud(ros::names::remap("/ac_frame"), *working_scan,pcmsg_in,*state_start,*state_end,*g_las3D->p_listener);
197 
198  if (error)
199  return;
200 
201  pcl::PointCloud<pcl::PointXYZ> pc_in;
202  pcl::fromROSMsg(pcmsg_in,pc_in);
203 
204  g_las3D->accumulate_cloud(&pc_in);
205 
206  g_las3D->laser_count++;
207  g_las3D->laserscan_arrived=true;
208 
209 // erase some old data
210  if (g_las3D->laser_count>g_las3D->max_scans_accumulated)
211  g_las3D->pc_accumulated.erase(g_las3D->pc_accumulated.begin(),g_las3D->pc_accumulated.begin()+g_las3D->cloud_size);
212  }
213  }
214 
215 }
216 
217 
218 int main(int argc, char **argv)
219 {
220  ros::init(argc, argv, "laser3D_pointcloud");
221  ros::NodeHandle n("~");
222  tf::TransformListener listener(n,ros::Duration(100));
223  //Declaration of class
224  las3D_PointCloud las3D;
225  g_las3D=&las3D;
226 
227  g_las3D->p_listener=&listener;
228 
229  double output_freq;
230  n.param("output_frequency", output_freq, 200.0);
231  n.param("accumulation_mode", g_las3D->accumulation_mode, 1);
232  n.param("max_scans_accumulated", g_las3D->max_scans_accumulated, 450);
233  n.param("pointcloud_stamp", g_las3D->pointcloud_stamp,1);
234 
235  //Test the remapping of /ac_frame
236  if (ros::names::remap("/ac_frame")=="/ac_frame")
237  {
238  ROS_ERROR("/ac_frame was not remapped. Aborting program.");
239  ros::shutdown();
240  }
241 
242  //declare the subsriber
243  ros::Subscriber sub_phiversion = n.subscribe ("/laserscan0", 100, scan_cb);
244  ros::Subscriber sub_state = n.subscribe ("/joint_state", 100, state_cb);
245 
246  //declare the publisher
247  ros::Publisher pub = n.advertise<sensor_msgs::PointCloud2>("/pc_out", 1);
248 
249  ros::Rate loop_rate(output_freq);
250 
251  while (n.ok())
252  {
253  ros::spinOnce();
254 
255  if (g_las3D->laserscan_arrived)
256  {
257  g_las3D->laserscan_arrived=false;
258  sensor_msgs::PointCloud2 pcmsg_out;
259  pcl::toROSMsg(g_las3D->pc_accumulated, pcmsg_out);
260  // set the time stamp of output pointcloud
261  if (g_las3D->pointcloud_stamp)
262  pcmsg_out.header.stamp = ros::Time::now();
263  else
264  {
265  std::cout<<"The message stamp is missing!!, please solve!!"<<std::endl;
266 // pcmsg_out.header.stamp = g_las3D->pc_accumulated.header.stamp;
267  }
268 #if _USE_DEBUG_
269  ROS_INFO("Publishing pc_accumulated with %d points", (int)g_las3D->pc_accumulated.size());
270 #endif
271  //publish the pointcloud
272  pub.publish(pcmsg_out);
273 
274  }
275 
276  loop_rate.sleep();
277  }
278 
279 }
void scan_cb(const sensor_msgs::LaserScan::ConstPtr &scan_in)
Callback from the LaserScan subscribed topic.
Definition: main.cpp:85
int accumulation_mode
Type of accumulation wanted to be used.
pcl::PointCloud< pcl::PointXYZ > pc_accumulated
PointCloud<pcl::PointXYZ> to accumulate the laser scans.
int laser_count
Number of laser scans received.
int main(int argc, char **argv)
Definition: main.cpp:218
void state_cb(const sensor_msgs::JointState::ConstPtr &state_in)
Callback from the JointState subscribed topic.
Definition: main.cpp:54
int pointcloud_stamp
Time stamp to the output cloud, when using rosbag or in real time accumulation.
int phis_count
Definition: main.cpp:41
ros::Time firstscan_stamp
Definition: main.cpp:43
std::vector< sensor_msgs::JointStatePtr > joints
Vector with the external shaft angle mensage.
void accumulate_cloud(pcl::PointCloud< pcl::PointXYZ > *pc_in)
Function to accumulate PointCloud. Receives the pointcloud with the transformed laser scan and accumu...
sensor_msgs::JointStatePtr first_state1(new sensor_msgs::JointState)
las3D_PointCloud * g_las3D
Definition: main.cpp:40
sensor_msgs::JointStatePtr first_state2(new sensor_msgs::JointState)
ros::Time phi1_stamp
Definition: main.cpp:44
tf::TransformListener * p_listener
ROS tf listener.
std::vector< sensor_msgs::LaserScanPtr > scans
Vector with the laser scans received.
int firstscan
Definition: main.cpp:42
Class to accumulate point clouds laser3D.
bool laserscan_arrived
bool laser scan received
size_t cloud_size
PointCloud size.
int max_scans_accumulated
Max of scans to be accumulated.
int las3D_transformLaserScanToPointCloud(const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud2 &cloud_out, const sensor_msgs::JointState &state_start, const sensor_msgs::JointState &state_end, tf::Transformer &tf, double range_cutoff=-1.0, int channel_options=channel_option::Default)
Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2 in target frame using the external...
ros::Time phi2_stamp
Definition: main.cpp:45


laser_3d_pointcloud
Author(s): Diogo Matos
autogenerated on Mon Mar 2 2015 01:32:06