30 #ifndef LASER_SCAN_UTILS_LASERSCAN_H 
   31 #define LASER_SCAN_UTILS_LASERSCAN_H 
   37 #include "boost/numeric/ublas/matrix.hpp" 
   38 #include "boost/thread/mutex.hpp" 
   43 #include "sensor_msgs/LaserScan.h" 
   44 #include "sensor_msgs/PointCloud.h" 
   45 #include "sensor_msgs/PointCloud.h" 
   48 #include <sensor_msgs/PointCloud2.h> 
   54 #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries 
   55   #ifdef laser_geometry_EXPORTS // we are building a shared lib/dll 
   56     #define LASER_GEOMETRY_DECL ROS_HELPER_EXPORT 
   57   #else // we are using shared lib/dll 
   58     #define LASER_GEOMETRY_DECL ROS_HELPER_IMPORT 
   60 #else // ros is being built around static libraries 
   61   #define LASER_GEOMETRY_DECL 
   71   namespace channel_option
 
  140                          sensor_msgs::PointCloud& cloud_out,
 
  141                          double range_cutoff = -1.0,
 
  144         return projectLaser_ (scan_in, cloud_out, range_cutoff, 
false, channel_options);
 
  164                          sensor_msgs::PointCloud2 &cloud_out,
 
  165                          double range_cutoff = -1.0,
 
  168         projectLaser_(scan_in, cloud_out, range_cutoff, channel_options);
 
  194                                            const sensor_msgs::LaserScan& scan_in,
 
  195                                            sensor_msgs::PointCloud& cloud_out,
 
  200         return transformLaserScanToPointCloud_ (target_frame, cloud_out, scan_in, 
tf, range_cutoff, channel_options);
 
  223                                            const sensor_msgs::LaserScan& scan_in,
 
  224                                            sensor_msgs::PointCloud& cloud_out,
 
  228         return transformLaserScanToPointCloud_ (target_frame, cloud_out, scan_in, 
tf, -1.0, channel_options);
 
  254                                            const sensor_msgs::LaserScan &scan_in,
 
  255                                            sensor_msgs::PointCloud2 &cloud_out,
 
  257                                            double range_cutoff = -1.0,
 
  260         transformLaserScanToPointCloud_(target_frame, scan_in, cloud_out, 
tf, range_cutoff, channel_options);
 
  286                                           const sensor_msgs::LaserScan &scan_in,
 
  287                                           sensor_msgs::PointCloud2 &cloud_out,
 
  289                                           double range_cutoff = -1.0,
 
  292         transformLaserScanToPointCloud_(target_frame, scan_in, cloud_out, 
tf, range_cutoff, channel_options);
 
  319                                           const sensor_msgs::LaserScan &scan_in,
 
  320                                           sensor_msgs::PointCloud2 &cloud_out,
 
  321                                           const std::string &fixed_frame,
 
  323                                           double range_cutoff = -1.0,
 
  326         transformLaserScanToPointCloud_(target_frame, scan_in, cloud_out, fixed_frame, 
tf, range_cutoff, channel_options);
 
  337       const boost::numeric::ublas::matrix<double>& getUnitVectors_(
double angle_min,
 
  339                                                                    double angle_increment,
 
  340                                                                    unsigned int length);
 
  345       void projectLaser_ (
const sensor_msgs::LaserScan& scan_in,
 
  346                           sensor_msgs::PointCloud& cloud_out,
 
  349                           int channel_options);
 
  352       void projectLaser_ (
const sensor_msgs::LaserScan& scan_in,
 
  353                           sensor_msgs::PointCloud2 &cloud_out,
 
  355                           int channel_options);
 
  358       void transformLaserScanToPointCloud_ (
const std::string& target_frame,
 
  359                                             sensor_msgs::PointCloud& cloud_out,
 
  360                                             const sensor_msgs::LaserScan& scan_in,
 
  363                                             int channel_options);
 
  366       void transformLaserScanToPointCloud_ (
const std::string &target_frame,
 
  367                                             const sensor_msgs::LaserScan &scan_in,
 
  368                                             sensor_msgs::PointCloud2 &cloud_out,
 
  371                                             int channel_options);
 
  374       void transformLaserScanToPointCloud_ (
const std::string &target_frame,
 
  375                                             const sensor_msgs::LaserScan &scan_in,
 
  376                                             sensor_msgs::PointCloud2 &cloud_out,
 
  379                                             int channel_options);
 
  382       void transformLaserScanToPointCloud_ (
const std::string &target_frame,
 
  383                                             const sensor_msgs::LaserScan &scan_in,
 
  384                                             sensor_msgs::PointCloud2 &cloud_out,
 
  385                                             const std::string &fixed_frame,
 
  388                                             int channel_options);
 
  391       void transformLaserScanToPointCloud_ (
const std::string &target_frame,
 
  392                                             const sensor_msgs::LaserScan &scan_in,
 
  393                                             sensor_msgs::PointCloud2 &cloud_out,
 
  395                                             tf2::Vector3 origin_start,
 
  397                                             tf2::Vector3 origin_end,
 
  399                                             int channel_options);
 
  411 #endif //LASER_SCAN_UTILS_LASERSCAN_H