$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 * 00029 */ 00030 00039 #ifndef CART_STATE_ESTIMATOR_POLYGON_POINT_CLOUD_FILTER_H 00040 #define CART_STATE_ESTIMATOR_POLYGON_POINT_CLOUD_FILTER_H 00041 00042 #include <filters/filter_base.h> 00043 #include <tf/transform_listener.h> 00044 #include <sensor_msgs/PointCloud.h> 00045 #include <ros/ros.h> 00046 #include <dynamic_reconfigure/server.h> 00047 #include <cart_state_estimator/PolygonPointCloudFilterConfig.h> 00048 00049 namespace cart_state_estimator 00050 { 00051 00058 class PolygonPointCloudFilter : public filters::FilterBase<sensor_msgs::PointCloud> 00059 { 00060 public: 00061 00062 PolygonPointCloudFilter() : dyn_srv_(NULL) {} 00063 ~PolygonPointCloudFilter() { delete dyn_srv_; } 00064 bool configure(); 00065 bool update (const sensor_msgs::PointCloud& input_scan, sensor_msgs::PointCloud& filtered_scan); 00066 bool inPolygon (const geometry_msgs::Point32& p) const; 00067 00068 private: 00069 00070 dynamic_reconfigure::Server<cart_state_estimator::PolygonPointCloudFilterConfig>* dyn_srv_; 00071 00072 void configCB(cart_state_estimator::PolygonPointCloudFilterConfig &config, uint32_t level); 00073 00074 bool passthrough_; 00075 tf::TransformListener tf_; 00076 ros::NodeHandle nh_; 00077 ros::Publisher filter_polygon_pub_; 00078 std::vector<geometry_msgs::Point32> poly_; 00079 std::string frame_; 00080 }; 00081 00082 00083 } // namespace 00084 00085 #endif // include guard