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 #ifndef JSK_PCL_ROS_MULTI_PLANE_SEGMENTATION_H_
00038 #define JSK_PCL_ROS_MULTI_PLANE_SEGMENTATION_H_
00039
00040 #include <pcl_ros/pcl_nodelet.h>
00041 #include "jsk_recognition_utils/pcl_util.h"
00042 #include "jsk_recognition_utils/geo_util.h"
00043 #include "jsk_recognition_utils/pcl_conversion_util.h"
00044 #include <dynamic_reconfigure/server.h>
00045 #include <message_filters/subscriber.h>
00046 #include <message_filters/time_synchronizer.h>
00047 #include <message_filters/sync_policies/approximate_time.h>
00048 #include <message_filters/synchronizer.h>
00049
00050 #include <jsk_pcl_ros/MultiPlaneSACSegmentationConfig.h>
00051 #include <jsk_topic_tools/connection_based_nodelet.h>
00052 #include "jsk_pcl_ros/tf_listener_singleton.h"
00053
00054
00056
00058 #include <sensor_msgs/PointCloud2.h>
00059 #include <jsk_recognition_msgs/PolygonArray.h>
00060 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
00061 #include <jsk_recognition_msgs/ClusterPointIndices.h>
00062 #include <sensor_msgs/Imu.h>
00063
00064 namespace jsk_pcl_ros
00065 {
00066 class MultiPlaneSACSegmentation: public jsk_topic_tools::ConnectionBasedNodelet
00067 {
00068 public:
00069 typedef pcl::PointXYZRGB PointT;
00070 typedef jsk_pcl_ros::MultiPlaneSACSegmentationConfig Config;
00071 typedef message_filters::sync_policies::ExactTime<
00072 sensor_msgs::PointCloud2,
00073 sensor_msgs::PointCloud2 > SyncPolicy;
00074 typedef message_filters::sync_policies::ExactTime<
00075 sensor_msgs::PointCloud2,
00076 jsk_recognition_msgs::ClusterPointIndices > SyncClusterPolicy;
00077 typedef message_filters::sync_policies::ApproximateTime<
00078 sensor_msgs::PointCloud2,
00079 sensor_msgs::Imu
00080 > SyncImuPolicy;
00081 typedef message_filters::sync_policies::ApproximateTime<
00082 sensor_msgs::PointCloud2,
00083 sensor_msgs::PointCloud2,
00084 sensor_msgs::Imu
00085 > SyncNormalImuPolicy;
00086 typedef message_filters::Synchronizer<SyncNormalImuPolicy>
00087 NormalImuSynchronizer;
00088 protected:
00090
00092 virtual void onInit();
00093
00094 virtual void segment(const sensor_msgs::PointCloud2::ConstPtr& msg);
00095 virtual void segment(const sensor_msgs::PointCloud2::ConstPtr& msg,
00096 const sensor_msgs::PointCloud2::ConstPtr& msg_nromal);
00097 virtual void segmentWithImu(const sensor_msgs::PointCloud2::ConstPtr& msg,
00098 const sensor_msgs::Imu::ConstPtr& imu);
00099 virtual void segmentWithImu(const sensor_msgs::PointCloud2::ConstPtr& msg,
00100 const sensor_msgs::PointCloud2::ConstPtr& msg_nromal,
00101 const sensor_msgs::Imu::ConstPtr& imu);
00102 virtual void segmentWithClusters(
00103 const sensor_msgs::PointCloud2::ConstPtr& msg,
00104 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& clusters);
00105 virtual void applyRecursiveRANSAC(
00106 const pcl::PointCloud<PointT>::Ptr& input,
00107 const pcl::PointCloud<pcl::Normal>::Ptr& normal,
00108 const Eigen::Vector3f& imu_vector,
00109 std::vector<pcl::PointIndices::Ptr>& output_inliers,
00110 std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients,
00111 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& output_polygons);
00112 virtual void publishResult(
00113 const std_msgs::Header& header,
00114 const std::vector<pcl::PointIndices::Ptr>& inliers,
00115 const std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
00116 const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes);
00117 virtual void configCallback (Config &config, uint32_t level);
00118
00119 virtual void subscribe();
00120 virtual void unsubscribe();
00121
00123
00125 ros::Subscriber sub_;
00126 ros::Publisher pub_inliers_, pub_coefficients_, pub_polygons_;
00127 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00128 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > sync_;
00129 boost::shared_ptr<message_filters::Synchronizer<SyncClusterPolicy> > sync_cluster_;
00130 boost::shared_ptr<message_filters::Synchronizer<SyncImuPolicy> > sync_imu_;
00131 boost::shared_ptr<message_filters::Synchronizer<SyncNormalImuPolicy> > sync_normal_imu_;
00132 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00133 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_normal_;
00134 message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_clusters_;
00135 message_filters::Subscriber<sensor_msgs::Imu> sub_imu_;
00136 boost::mutex mutex_;
00137 tf::TransformListener* tf_listener_;
00138
00140
00142 double outlier_threshold_;
00143 int min_inliers_;
00144 int min_points_;
00145 int max_iterations_;
00146 bool use_normal_;
00147 bool use_clusters_;
00148 bool use_imu_parallel_;
00149 bool use_imu_perpendicular_;
00150 double eps_angle_;
00151 double normal_distance_weight_;
00152 int min_trial_;
00153 private:
00154
00155 };
00156 }
00157
00158 #endif