00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #ifndef _LASER3D_POINTCLOUD_H_
00028 #define _LASER3D_POINTCLOUD_H_
00029
00037 #include <stdio.h>
00038 #include <ros/ros.h>
00039 #include <laser_geometry/laser_geometry.h>
00040 #include <sensor_msgs/LaserScan.h>
00041 #include <sensor_msgs/JointState.h>
00042 #include <sensor_msgs/PointCloud2.h>
00043 #include <tf/transform_listener.h>
00044 #include <pcl_ros/transforms.h>
00045 #include <pcl/ros/conversions.h>
00046 #include <pcl/point_cloud.h>
00047 #include <pcl/point_types.h>
00048 #include <Eigen/Core>
00049 #include <map>
00050 #include <tf/tf.h>
00051
00052 #include <boost/numeric/ublas/matrix.hpp>
00053 #include <boost/thread/mutex.hpp>
00054
00055
00056
00057
00058 const float LASER_SCAN_INVALID = -1.0;
00059 const float LASER_SCAN_MIN_RANGE = -2.0;
00060 const float LASER_SCAN_MAX_RANGE = -3.0;
00061
00062 namespace channel_option
00063 {
00065
00070 enum ChannelOption
00071 {
00072 None = 0x00,
00073 Intensity = 0x01,
00074 Index = 0x02,
00075 Distance = 0x04,
00076 Timestamp = 0x08,
00077 Viewpoint = 0x10,
00078 Default = (Intensity | Index)
00079 };
00080 }
00081
00090 class las3D_PointCloud
00091 {
00092 public:
00093
00095 tf::TransformListener *p_listener;
00096
00098 pcl::PointCloud<pcl::PointXYZ> pc_accumulated;
00099
00101 size_t cloud_size;
00102
00104 std::vector<sensor_msgs::JointStatePtr> joints;
00105
00107 int laser_count;
00108
00110 bool laserscan_arrived;
00111
00113 std::vector<sensor_msgs::LaserScanPtr> scans;
00114
00116 int accumulation_mode;
00117
00119 int max_scans_accumulated;
00120
00122 int pointcloud_stamp;
00123
00124 las3D_PointCloud()
00125 {
00126 accumulation_mode=1;
00127 max_scans_accumulated=450;
00128 pointcloud_stamp=1;
00129
00130 angle_min_=0;
00131 angle_max_=0;
00132 laser_count=0;
00133 laserscan_arrived=false;
00134 }
00135
00136 ~las3D_PointCloud();
00137
00145 void accumulate_cloud(pcl::PointCloud<pcl::PointXYZ>* pc_in);
00146
00147
00171 int las3D_transformLaserScanToPointCloud(const std::string &target_frame,
00172 const sensor_msgs::LaserScan &scan_in,
00173 sensor_msgs::PointCloud2 &cloud_out,
00174 const sensor_msgs::JointState &state_start,
00175 const sensor_msgs::JointState &state_end,
00176 tf::Transformer &tf,
00177 double range_cutoff = -1.0,
00178 int channel_options = channel_option::Default)
00179 {
00180 int error=0;
00181 error=las3D_transformLaserScanToPointCloud_(target_frame, scan_in, cloud_out, state_start,state_end, tf, range_cutoff, channel_options);
00182 return error;
00183 }
00184
00206 int las3D_transformLaserScanToPointCloud(const std::string &target_frame,
00207 const sensor_msgs::LaserScan &scan_in,
00208 sensor_msgs::PointCloud2 &cloud_out,
00209 tf::Transformer &tf,
00210 double range_cutoff = -1.0,
00211 int channel_options = channel_option::Default)
00212 {
00213 int error=0;
00214 error=las3D_transformLaserScanToPointCloud_(target_frame, scan_in, cloud_out, tf, range_cutoff, channel_options);
00215 return error;
00216 }
00217
00218 protected:
00219
00221
00226 const boost::numeric::ublas::matrix<double>& getUnitVectors_(double angle_min,
00227 double angle_max,
00228 double angle_increment,
00229 unsigned int length);
00230
00231 private:
00232
00233
00235 void las3D_projectLaser_ (const sensor_msgs::LaserScan& scan_in,
00236 sensor_msgs::PointCloud2 &cloud_out,
00237 double range_cutoff,
00238 int channel_options);
00239
00240
00242 int las3D_transformLaserScanToPointCloud_ (const std::string &target_frame,
00243 const sensor_msgs::LaserScan &scan_in,
00244 sensor_msgs::PointCloud2 &cloud_out,
00245 const sensor_msgs::JointState &state_start,
00246 const sensor_msgs::JointState &state_end,
00247 tf::Transformer &tf,
00248 double range_cutoff,
00249 int channel_options);
00250
00251 int las3D_transformLaserScanToPointCloud_ (const std::string &target_frame,
00252 const sensor_msgs::LaserScan &scan_in,
00253 sensor_msgs::PointCloud2 &cloud_out,
00254 tf::Transformer &tf,
00255 double range_cutoff,
00256 int channel_options);
00257
00258
00260 std::map<std::string,boost::numeric::ublas::matrix<double>* > unit_vector_map_;
00261 float angle_min_;
00262 float angle_max_;
00263 Eigen::ArrayXXd co_sine_map_;
00264 boost::mutex guv_mutex_;
00265
00266 };
00267
00268 #endif