Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043 #ifndef SEGBOT_SENSORS_VELODYNE_FILTER_H_
00044 #define SEGBOT_SENSORS_VELODYNE_FILTER_H_
00045
00046
00047 #include <pcl/filters/filter.h>
00048 #include "pcl_ros/pcl_nodelet.h"
00049
00050
00051 #include <dynamic_reconfigure/server.h>
00052 #include "pcl_ros/FilterConfig.h"
00053
00054 #include <geometry_msgs/Point.h>
00055
00056
00057 #include <pcl_ros/filters/filter.h>
00058
00059
00060 #include <segbot_sensors/SegbotVelodyneOutlierRemovalConfig.h>
00061
00062 namespace segbot_sensors
00063 {
00064 namespace sync_policies = message_filters::sync_policies;
00065
00066 using namespace pcl_ros;
00067
00072 class Filter : public PCLNodelet
00073 {
00074 public:
00075 typedef sensor_msgs::PointCloud2 PointCloud2;
00076
00077 typedef boost::shared_ptr <std::vector<int> > IndicesPtr;
00078 typedef boost::shared_ptr <const std::vector<int> > IndicesConstPtr;
00079
00080 Filter () {}
00081
00082 protected:
00084 ros::Subscriber sub_input_;
00085
00086 message_filters::Subscriber<PointCloud2> sub_input_filter_;
00087
00089 std::string filter_field_name_;
00090
00092 double filter_limit_min_;
00093
00095 double filter_limit_max_;
00096
00098 bool filter_limit_negative_;
00099
00101 std::string tf_input_frame_;
00102
00104 std::string tf_input_orig_frame_;
00105
00107 std::string tf_output_frame_;
00108
00110 boost::mutex mutex_;
00111
00116 virtual bool
00117 child_init (ros::NodeHandle &nh, bool &has_service)
00118 {
00119 has_service = false;
00120 return (true);
00121 }
00122
00128 virtual void
00129 filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices,
00130 PointCloud2 &output) = 0;
00131
00133 virtual void
00134 onInit ();
00135
00140 void
00141 computePublish (const PointCloud2::ConstPtr &input, const IndicesPtr &indices);
00142
00143 private:
00145 boost::shared_ptr<dynamic_reconfigure::Server<pcl_ros::FilterConfig> > srv_;
00146
00148 boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud2, PointIndices> > > sync_input_indices_e_;
00149 boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2, PointIndices> > > sync_input_indices_a_;
00150
00152 virtual void
00153 config_callback (pcl_ros::FilterConfig &config, uint32_t level);
00154
00156 void
00157 input_indices_callback (const PointCloud2::ConstPtr &cloud,
00158 const PointIndicesConstPtr &indices);
00159 public:
00160 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00161 };
00162
00163 class SegbotVelodyneOutlierRemoval : public Filter
00164 {
00165 protected:
00167 boost::shared_ptr <dynamic_reconfigure::Server<SegbotVelodyneOutlierRemovalConfig> > srv_;
00168
00174 inline void
00175 filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices,
00176 PointCloud2 &output)
00177 {
00178 boost::mutex::scoped_lock lock (mutex_);
00179 pcl::PCLPointCloud2::Ptr pcl_cloud(new pcl::PCLPointCloud2);
00180 pcl_conversions::toPCL(*input, *pcl_cloud);
00181 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00182 pcl::fromPCLPointCloud2(*pcl_cloud, *cloud);
00183
00184 for (pcl::PointCloud<pcl::PointXYZ>::iterator it = cloud->begin(); it != cloud->end();) {
00185
00186 float &x = it->x;
00187 float &y = it->y;
00188 bool point_not_in_polygon = false;
00189 for (int i = 0, j = footprint_.size() - 1; i < footprint_.size(); j = i++) {
00190 if (((footprint_[i].y > y) != (footprint_[j].y > y)) &&
00191 (x < (footprint_[j].x - footprint_[i].x) * (y - footprint_[i].y) / (footprint_[j].y - footprint_[i].y) + footprint_[i].x)) {
00192 point_not_in_polygon = !point_not_in_polygon;
00193 }
00194 }
00195 if (point_not_in_polygon) {
00196 it = cloud->erase(it);
00197 } else {
00198
00199 ++it;
00200 }
00201 }
00202
00203 pcl::toPCLPointCloud2(*cloud, *pcl_cloud);
00204 pcl_conversions::moveFromPCL(*pcl_cloud, output);
00205 }
00206
00211 bool child_init (ros::NodeHandle &nh, bool &has_service);
00212
00217 void config_callback (segbot_sensors::SegbotVelodyneOutlierRemovalConfig &config, uint32_t level);
00218
00219 public:
00220 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00221
00222 private:
00223 std::vector<geometry_msgs::Point> footprint_;
00224 boost::shared_ptr<ros::Publisher> footprint_publisher_;
00225 std::string frame_;
00226 };
00227 }
00228
00229 #endif