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 "nodelet/nodelet.h" 00048 #include "tf2_ros/buffer.h" 00049 #include "tf2_ros/transform_listener.h" 00050 #include "tf2_ros/message_filter.h" 00051 #include "message_filters/subscriber.h" 00052 #include "sensor_msgs/PointCloud2.h" 00053 00054 00055 namespace pointcloud_to_laserscan 00056 { 00057 typedef tf2_ros::MessageFilter<sensor_msgs::PointCloud2> MessageFilter; 00062 class PointCloudToLaserScanNodelet : public nodelet::Nodelet 00063 { 00064 00065 public: 00066 PointCloudToLaserScanNodelet(); 00067 00068 private: 00069 virtual void onInit(); 00070 00071 void cloudCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg); 00072 void failureCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg, 00073 tf2_ros::filter_failure_reasons::FilterFailureReason reason); 00074 00075 void connectCb(); 00076 00077 void disconnectCb(); 00078 00079 ros::NodeHandle nh_, private_nh_; 00080 ros::Publisher pub_; 00081 boost::mutex connect_mutex_; 00082 00083 boost::shared_ptr<tf2_ros::Buffer> tf2_; 00084 boost::shared_ptr<tf2_ros::TransformListener> tf2_listener_; 00085 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_; 00086 boost::shared_ptr<MessageFilter> message_filter_; 00087 00088 // ROS Parameters 00089 unsigned int input_queue_size_; 00090 std::string target_frame_; 00091 double tolerance_; 00092 double min_height_, max_height_, angle_min_, angle_max_, angle_increment_, scan_time_, range_min_, range_max_; 00093 bool use_inf_; 00094 }; 00095 00096 } // pointcloud_to_laserscan 00097 00098 #endif // POINTCLOUD_TO_LASERSCAN_POINTCLOUD_TO_LASERSCAN_NODELET