laser_3d_pointcloud.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 ***************************************************************************************************/
27 #ifndef _LASER3D_POINTCLOUD_H_
28 #define _LASER3D_POINTCLOUD_H_
29 
37 #include <stdio.h>
38 #include <ros/ros.h>
39 #include <laser_geometry/laser_geometry.h>
40 #include <sensor_msgs/LaserScan.h>
41 #include <sensor_msgs/JointState.h>
42 #include <sensor_msgs/PointCloud2.h>
43 #include <tf/transform_listener.h>
44 #include <pcl_ros/transforms.h>
45 #include <pcl/conversions.h>
46 #include <pcl_conversions/pcl_conversions.h>
47 #include <pcl/point_cloud.h>
48 #include <pcl/point_types.h>
49 #include <Eigen/Core>
50 #include <map>
51 #include <tf/tf.h>
52 
53 #include <boost/numeric/ublas/matrix.hpp>
54 #include <boost/thread/mutex.hpp>
55 
56 
57 
58  // NOTE: invalid scan errors (will be present in LaserScan.msg in D-Turtle)
59  const float LASER_SCAN_INVALID = -1.0;
60  const float LASER_SCAN_MIN_RANGE = -2.0;
61  const float LASER_SCAN_MAX_RANGE = -3.0;
62 
63  namespace channel_option
64  {
66 
72  {
73  None = 0x00,
74  Intensity = 0x01,
75  Index = 0x02,
76  Distance = 0x04,
77  Timestamp = 0x08,
78  Viewpoint = 0x10,
80  };
81  }
82 
92 {
93  public:
94 
96  tf::TransformListener *p_listener;
97 
99  pcl::PointCloud<pcl::PointXYZ> pc_accumulated;
100 
102  size_t cloud_size;
103 
105  std::vector<sensor_msgs::JointStatePtr> joints;
106 
109 
112 
114  std::vector<sensor_msgs::LaserScanPtr> scans;
115 
118 
121 
124 
126  {
127  accumulation_mode=1;
128  max_scans_accumulated=450;
129  pointcloud_stamp=1;
130 
131  angle_min_=0;
132  angle_max_=0;
133  laser_count=0;
134  laserscan_arrived=false;
135  }
136 
137  ~las3D_PointCloud();
138 
146  void accumulate_cloud(pcl::PointCloud<pcl::PointXYZ>* pc_in);
147 
148 
172  int las3D_transformLaserScanToPointCloud(const std::string &target_frame,
173  const sensor_msgs::LaserScan &scan_in,
174  sensor_msgs::PointCloud2 &cloud_out,
175  const sensor_msgs::JointState &state_start,
176  const sensor_msgs::JointState &state_end,
177  tf::Transformer &tf,
178  double range_cutoff = -1.0,
179  int channel_options = channel_option::Default)
180  {
181  int error=0;
182  error=las3D_transformLaserScanToPointCloud_(target_frame, scan_in, cloud_out, state_start,state_end, tf, range_cutoff, channel_options);
183  return error;
184  }
185 
207  int las3D_transformLaserScanToPointCloud(const std::string &target_frame,
208  const sensor_msgs::LaserScan &scan_in,
209  sensor_msgs::PointCloud2 &cloud_out,
210  tf::Transformer &tf,
211  double range_cutoff = -1.0,
212  int channel_options = channel_option::Default)
213  {
214  int error=0;
215  error=las3D_transformLaserScanToPointCloud_(target_frame, scan_in, cloud_out, tf, range_cutoff, channel_options);
216  return error;
217  }
218 
219  protected:
220 
222 
227  const boost::numeric::ublas::matrix<double>& getUnitVectors_(double angle_min,
228  double angle_max,
229  double angle_increment,
230  unsigned int length);
231 
232  private:
233 
234 
236  void las3D_projectLaser_ (const sensor_msgs::LaserScan& scan_in,
237  sensor_msgs::PointCloud2 &cloud_out,
238  double range_cutoff,
239  int channel_options);
240 
241 
243  int las3D_transformLaserScanToPointCloud_ (const std::string &target_frame,
244  const sensor_msgs::LaserScan &scan_in,
245  sensor_msgs::PointCloud2 &cloud_out,
246  const sensor_msgs::JointState &state_start,
247  const sensor_msgs::JointState &state_end,
248  tf::Transformer &tf,
249  double range_cutoff,
250  int channel_options);
251 
252  int las3D_transformLaserScanToPointCloud_ (const std::string &target_frame,
253  const sensor_msgs::LaserScan &scan_in,
254  sensor_msgs::PointCloud2 &cloud_out,
255  tf::Transformer &tf,
256  double range_cutoff,
257  int channel_options);
258 
259 
261  std::map<std::string,boost::numeric::ublas::matrix<double>* > unit_vector_map_;
262  float angle_min_;
263  float angle_max_;
264  Eigen::ArrayXXd co_sine_map_;
265  boost::mutex guv_mutex_;
266 
267 }; //end class
268 
269 #endif
int accumulation_mode
Type of accumulation wanted to be used.
const float LASER_SCAN_MAX_RANGE
pcl::PointCloud< pcl::PointXYZ > pc_accumulated
PointCloud<pcl::PointXYZ> to accumulate the laser scans.
int laser_count
Number of laser scans received.
const float LASER_SCAN_MIN_RANGE
Eigen::ArrayXXd co_sine_map_
std::map< std::string, boost::numeric::ublas::matrix< double > * > unit_vector_map_
Internal map of pointers to stored values.
int pointcloud_stamp
Time stamp to the output cloud, when using rosbag or in real time accumulation.
int las3D_transformLaserScanToPointCloud(const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud2 &cloud_out, 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 scan tim...
std::vector< sensor_msgs::JointStatePtr > joints
Vector with the external shaft angle mensage.
ChannelOption
Enumerated output channels options.
const float LASER_SCAN_INVALID
Enable "intensities" and "index" channels.
Enable "intensities" channel.
Enable "distances" channel.
Enable "viewpoint" channel.
tf::TransformListener * p_listener
ROS tf listener.
std::vector< sensor_msgs::LaserScanPtr > scans
Vector with the laser scans received.
Class to accumulate point clouds laser3D.
bool laserscan_arrived
bool laser scan received
Enable no channels.
size_t cloud_size
PointCloud size.
int max_scans_accumulated
Max of scans to be accumulated.
Enable "index" channel.
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...
Enable "stamps" channel.


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