pointcloud_to_laserscan_nodelet.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010-2012, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *
00035  */
00036 
00037 /*
00038  * Author: Paul Bovbel
00039  */
00040 
00041 #ifndef POINTCLOUD_TO_LASERSCAN_POINTCLOUD_TO_LASERSCAN_NODELET
00042 #define POINTCLOUD_TO_LASERSCAN_POINTCLOUD_TO_LASERSCAN_NODELET
00043 
00044 #include <ros/ros.h>
00045 #include <boost/thread/mutex.hpp>
00046 
00047 #include <pcl/point_cloud.h>
00048 #include <pcl_ros/point_cloud.h>
00049 #include <pcl/point_types.h>
00050 #include <pcl/ros/conversions.h>
00051 
00052 #include <tf/transform_listener.h>
00053 #include <nodelet/nodelet.h>
00054 
00055 namespace pointcloud_to_laserscan
00056 {
00057   typedef pcl::PointXYZ Point;
00058   typedef pcl::PointCloud<Point> PointCloud;
00059 
00064   class PointCloudToLaserScanNodelet : public nodelet::Nodelet
00065   {
00066 
00067   public:
00068     PointCloudToLaserScanNodelet() { };
00069 
00070   private:
00071     virtual void onInit();
00072 
00073     void cloudCb(const PointCloud::ConstPtr &cloud_msg);
00074 
00075     void connectCb();
00076 
00077     void disconnectCb();
00078 
00079     ros::NodeHandle nh_, private_nh_;
00080     ros::Publisher pub_;
00081     ros::Subscriber sub_;
00082     tf::TransformListener tf_;
00083     boost::mutex connect_mutex_;
00084 
00085     // ROS Parameters
00086     unsigned int input_queue_size_;
00087     std::string target_frame_;
00088     double min_height_, max_height_, angle_min_, angle_max_, angle_increment_, scan_time_, range_min_, range_max_;
00089     bool use_inf_;
00090   };
00091 
00092 }  // pointcloud_to_laserscan
00093 
00094 #endif  // POINTCLOUD_TO_LASERSCAN_POINTCLOUD_TO_LASERSCAN_NODELET


pointcloud_to_laserscan
Author(s): Tully Foote
autogenerated on Wed Aug 26 2015 15:25:52