00001 // -*- mode: c++ -*- 00002 /********************************************************************* 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2014, JSK Lab 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/o2r other materials provided 00017 * with the distribution. 00018 * * Neither the name of the JSK Lab nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 *********************************************************************/ 00035 00036 00037 #ifndef JSK_PCL_ROS_NORMAL_DIRECTION_FILTER_H_ 00038 #define JSK_PCL_ROS_NORMAL_DIRECTION_FILTER_H_ 00039 00040 #include <pcl_ros/point_cloud.h> 00041 #include <sensor_msgs/PointCloud2.h> 00042 #include <jsk_topic_tools/diagnostic_nodelet.h> 00043 #include "jsk_pcl_ros/NormalDirectionFilterConfig.h" 00044 #include <dynamic_reconfigure/server.h> 00045 #include <message_filters/subscriber.h> 00046 #include <message_filters/time_synchronizer.h> 00047 #include <message_filters/synchronizer.h> 00048 #include <message_filters/sync_policies/approximate_time.h> 00049 #include <sensor_msgs/Imu.h> 00050 #include "jsk_pcl_ros/tf_listener_singleton.h" 00051 00052 00053 namespace jsk_pcl_ros 00054 { 00055 class NormalDirectionFilter: public jsk_topic_tools::DiagnosticNodelet 00056 { 00057 public: 00058 typedef NormalDirectionFilterConfig Config; 00059 typedef message_filters::sync_policies::ApproximateTime< 00060 sensor_msgs::PointCloud2, 00061 sensor_msgs::Imu> SyncPolicy; 00062 NormalDirectionFilter(): DiagnosticNodelet("NormalDirectionFilter") {} 00063 protected: 00065 // methods 00067 virtual void onInit(); 00068 virtual void filter(const sensor_msgs::PointCloud2::ConstPtr& msg); 00069 virtual void filter(const sensor_msgs::PointCloud2::ConstPtr& msg, 00070 const sensor_msgs::Imu::ConstPtr& imu_msg); 00071 virtual void filterIndices( 00072 const pcl::PointCloud<pcl::Normal>::Ptr& normal, 00073 const Eigen::Vector3f& direction, 00074 pcl::PointIndices& indices); 00075 virtual void subscribe(); 00076 virtual void unsubscribe(); 00077 virtual void configCallback (Config &config, uint32_t level); 00079 // ROS variables 00081 ros::Subscriber sub_; 00082 ros::Publisher pub_; 00083 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_; 00084 message_filters::Subscriber<sensor_msgs::Imu> sub_imu_; 00085 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_; 00086 boost::mutex mutex_; 00087 boost::shared_ptr<dynamic_reconfigure::Server<Config> > srv_; 00088 00090 // parameters 00092 Eigen::Vector3f static_direction_; 00093 double eps_angle_; 00094 double angle_offset_; 00095 tf::TransformListener* tf_listener_; 00096 bool use_imu_; 00097 int queue_size_; 00098 private: 00099 00100 }; 00101 } 00102 00103 #endif