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 #include "jsk_pcl_ros/multi_plane_sac_segmentation.h"
00037 #include <pcl/sample_consensus/method_types.h>
00038 #include <pcl/sample_consensus/model_types.h>
00039 #include <pcl/segmentation/sac_segmentation.h>
00040 #include <pcl/filters/extract_indices.h>
00041 #include "jsk_pcl_ros/pcl_util.h"
00042 #include <eigen_conversions/eigen_msg.h>
00043
00044 namespace jsk_pcl_ros
00045 {
00046 void MultiPlaneSACSegmentation::onInit()
00047 {
00048 ConnectionBasedNodelet::onInit();
00049 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00050 dynamic_reconfigure::Server<Config>::CallbackType f =
00051 boost::bind (&MultiPlaneSACSegmentation::configCallback, this, _1, _2);
00052 srv_->setCallback (f);
00053 pnh_->param("use_normal", use_normal_, false);
00054 pnh_->param("use_clusters", use_clusters_, false);
00055 pnh_->param("use_imu_parallel", use_imu_parallel_, false);
00056 pnh_->param("use_imu_perpendicular", use_imu_perpendicular_, false);
00057
00058 if (use_imu_perpendicular_ && use_imu_parallel_) {
00059 JSK_NODELET_ERROR("Cannot use ~use_imu_perpendicular and ~use_imu_parallel at the same time");
00060 return;
00061 }
00062 if (use_imu_perpendicular_ || use_imu_parallel_) {
00063 tf_listener_ = TfListenerSingleton::getInstance();
00064 }
00066
00068 pub_inliers_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output_indices", 1);
00069 pub_coefficients_
00070 = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_, "output_coefficients", 1);
00071 pub_polygons_ = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output_polygons", 1);
00072 }
00073
00074 void MultiPlaneSACSegmentation::subscribe()
00075 {
00077
00079 if (use_imu_perpendicular_ || use_imu_parallel_) {
00080 sub_input_.subscribe(*pnh_, "input", 1);
00081 sub_imu_.subscribe(*pnh_, "input_imu", 1);
00082 if (use_normal_) {
00083 sub_normal_.subscribe(*pnh_, "input_normal", 1);
00084 sync_normal_imu_ = boost::make_shared<NormalImuSynchronizer>(100);
00085 sync_normal_imu_->connectInput(sub_input_, sub_normal_, sub_imu_);
00086 sync_normal_imu_->registerCallback(
00087 boost::bind(
00088 &MultiPlaneSACSegmentation::segmentWithImu,
00089 this, _1, _2, _3));
00090 }
00091 else {
00092 sync_imu_ = boost::make_shared<message_filters::Synchronizer<SyncImuPolicy> >(100);
00093 sync_imu_->connectInput(sub_input_, sub_imu_);
00094 sync_imu_->registerCallback(boost::bind(
00095 &MultiPlaneSACSegmentation::segmentWithImu,
00096 this, _1, _2));
00097 }
00098 }
00099 else if (use_normal_) {
00100 sub_input_.subscribe(*pnh_, "input", 1);
00101 sub_normal_.subscribe(*pnh_, "input_normal", 1);
00102 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00103 sync_->connectInput(sub_input_, sub_normal_);
00104 sync_->registerCallback(boost::bind(&MultiPlaneSACSegmentation::segment,
00105 this, _1, _2));
00106 }
00107 else if (use_clusters_) {
00108 JSK_NODELET_INFO("use clusters");
00109 sub_input_.subscribe(*pnh_, "input", 1);
00110 sub_clusters_.subscribe(*pnh_, "input_clusters", 1);
00111 sync_cluster_
00112 = boost::make_shared<message_filters::Synchronizer<SyncClusterPolicy> >(100);
00113 sync_cluster_->connectInput(sub_input_, sub_clusters_);
00114 sync_cluster_->registerCallback(
00115 boost::bind(&MultiPlaneSACSegmentation::segmentWithClusters,
00116 this, _1, _2));
00117 }
00118 else {
00119 sub_ = pnh_->subscribe("input", 1, &MultiPlaneSACSegmentation::segment, this);
00120 }
00121 }
00122
00123 void MultiPlaneSACSegmentation::unsubscribe()
00124 {
00126
00128 if (use_normal_) {
00129 sub_input_.unsubscribe();
00130 sub_normal_.unsubscribe();
00131 }
00132 else if (use_clusters_) {
00133 sub_input_.unsubscribe();
00134 sub_clusters_.unsubscribe();
00135 }
00136 else {
00137 sub_.shutdown();
00138 }
00139 }
00140
00141 void MultiPlaneSACSegmentation::configCallback (Config &config, uint32_t level)
00142 {
00143 boost::mutex::scoped_lock lock(mutex_);
00144 outlier_threshold_ = config.outlier_threshold;
00145 min_inliers_ = config.min_inliers;
00146 min_points_ = config.min_points;
00147 max_iterations_ = config.max_iterations;
00148 eps_angle_ = config.eps_angle;
00149 normal_distance_weight_ = config.normal_distance_weight;
00150 min_trial_ = config.min_trial;
00151 }
00152
00153 void MultiPlaneSACSegmentation::applyRecursiveRANSAC(
00154 const pcl::PointCloud<PointT>::Ptr& input,
00155 const pcl::PointCloud<pcl::Normal>::Ptr& normal,
00156 const Eigen::Vector3f& imu_vector,
00157 std::vector<pcl::PointIndices::Ptr>& output_inliers,
00158 std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients,
00159 std::vector<ConvexPolygon::Ptr>& output_polygons)
00160 {
00161 pcl::PointCloud<PointT>::Ptr rest_cloud (new pcl::PointCloud<PointT>);
00162 pcl::PointCloud<pcl::Normal>::Ptr rest_normal (new pcl::PointCloud<pcl::Normal>);
00163 *rest_cloud = *input;
00164 *rest_normal = *normal;
00165 int counter = 0;
00166 while (true) {
00167 JSK_NODELET_INFO("apply RANSAC: %d", counter);
00168 ++counter;
00169 pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
00170 pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
00171 if (!use_normal_) {
00172 pcl::SACSegmentation<PointT> seg;
00173 seg.setOptimizeCoefficients (true);
00174 seg.setRadiusLimits(0.3, std::numeric_limits<double>::max ());
00175 seg.setMethodType (pcl::SAC_RANSAC);
00176 seg.setDistanceThreshold (outlier_threshold_);
00177 seg.setInputCloud(rest_cloud);
00178 seg.setMaxIterations (max_iterations_);
00179 if (use_imu_parallel_) {
00180 seg.setModelType(pcl::SACMODEL_PARALLEL_PLANE);
00181 seg.setAxis(imu_vector);
00182 seg.setEpsAngle(eps_angle_);
00183 }
00184 else if (use_imu_perpendicular_) {
00185 seg.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE);
00186 seg.setAxis(imu_vector);
00187 seg.setEpsAngle(eps_angle_);
00188 }
00189 else {
00190 seg.setModelType (pcl::SACMODEL_PLANE);
00191 }
00192 seg.segment (*inliers, *coefficients);
00193 }
00194 else {
00195 pcl::SACSegmentationFromNormals<PointT, pcl::Normal> seg;
00196 seg.setOptimizeCoefficients (true);
00197
00198 seg.setMethodType (pcl::SAC_RANSAC);
00199 seg.setDistanceThreshold (outlier_threshold_);
00200 seg.setNormalDistanceWeight(normal_distance_weight_);
00201 seg.setInputCloud(rest_cloud);
00202 seg.setInputNormals(rest_normal);
00203 seg.setMaxIterations (max_iterations_);
00204 if (use_imu_parallel_) {
00205 seg.setModelType (pcl::SACMODEL_NORMAL_PARALLEL_PLANE);
00206 seg.setAxis(imu_vector);
00207 seg.setEpsAngle(eps_angle_);
00208 }
00209 else if (use_imu_perpendicular_) {
00210 seg.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00211 seg.setAxis(imu_vector);
00212 seg.setEpsAngle(eps_angle_);
00213 }
00214 else {
00215 seg.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00216 }
00217 seg.segment (*inliers, *coefficients);
00218 }
00219 JSK_NODELET_INFO("inliers: %lu", inliers->indices.size());
00220 if (inliers->indices.size() >= min_inliers_) {
00221 output_inliers.push_back(inliers);
00222 output_coefficients.push_back(coefficients);
00223 ConvexPolygon::Ptr convex = convexFromCoefficientsAndInliers<PointT>(
00224 input, inliers, coefficients);
00225 output_polygons.push_back(convex);
00226 }
00227 else {
00228 if (min_trial_ <= counter) {
00229 return;
00230 }
00231 }
00232
00233
00234 pcl::PointCloud<PointT>::Ptr next_rest_cloud
00235 (new pcl::PointCloud<PointT>);
00236 pcl::PointCloud<pcl::Normal>::Ptr next_rest_normal
00237 (new pcl::PointCloud<pcl::Normal>);
00238 pcl::ExtractIndices<PointT> ex;
00239 ex.setInputCloud(rest_cloud);
00240 ex.setIndices(inliers);
00241 ex.setNegative(true);
00242 ex.setKeepOrganized(true);
00243 ex.filter(*next_rest_cloud);
00244 if (use_normal_) {
00245 pcl::ExtractIndices<pcl::Normal> ex_normal;
00246 ex_normal.setInputCloud(rest_normal);
00247 ex_normal.setIndices(inliers);
00248 ex_normal.setNegative(true);
00249 ex_normal.setKeepOrganized(true);
00250 ex_normal.filter(*next_rest_normal);
00251 }
00252 if (next_rest_cloud->points.size() < min_points_) {
00253 JSK_NODELET_INFO("no more enough points are left");
00254 return;
00255 }
00256 rest_cloud = next_rest_cloud;
00257 rest_normal = next_rest_normal;
00258 }
00259 }
00260
00261 void MultiPlaneSACSegmentation::segmentWithClusters(
00262 const sensor_msgs::PointCloud2::ConstPtr& msg,
00263 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& clusters)
00264 {
00265 boost::mutex::scoped_lock lock(mutex_);
00266 pcl::PointCloud<PointT>::Ptr input (new pcl::PointCloud<PointT>);
00267 pcl::fromROSMsg(*msg, *input);
00268 std::vector<pcl::PointIndices::Ptr> cluster_indices
00269 = pcl_conversions::convertToPCLPointIndices(clusters->cluster_indices);
00270 pcl::ExtractIndices<PointT> ex;
00271 ex.setInputCloud(input);
00272 ex.setKeepOrganized(true);
00273 std::vector<pcl::PointIndices::Ptr> all_inliers;
00274 std::vector<pcl::ModelCoefficients::Ptr> all_coefficients;
00275 std::vector<ConvexPolygon::Ptr> all_convexes;
00276 for (size_t i = 0; i < cluster_indices.size(); i++) {
00277 pcl::PointIndices::Ptr indices = cluster_indices[i];
00278 pcl::PointCloud<PointT>::Ptr cluster_cloud (new pcl::PointCloud<PointT>);
00279 pcl::PointCloud<pcl::Normal>::Ptr normal (new pcl::PointCloud<pcl::Normal>);
00280 ex.setIndices(indices);
00281
00282 ex.filter(*cluster_cloud);
00283 std::vector<pcl::PointIndices::Ptr> inliers;
00284 std::vector<pcl::ModelCoefficients::Ptr> coefficients;
00285 std::vector<ConvexPolygon::Ptr> convexes;
00286 Eigen::Vector3f dummy_imu_vector;
00287 applyRecursiveRANSAC(cluster_cloud, normal, dummy_imu_vector, inliers, coefficients, convexes);
00288 appendVector(all_inliers, inliers);
00289 appendVector(all_coefficients, coefficients);
00290 appendVector(all_convexes, convexes);
00291 }
00292 publishResult(msg->header, all_inliers, all_coefficients, all_convexes);
00293 }
00294
00295 void MultiPlaneSACSegmentation::publishResult(
00296 const std_msgs::Header& header,
00297 const std::vector<pcl::PointIndices::Ptr>& inliers,
00298 const std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
00299 const std::vector<ConvexPolygon::Ptr>& convexes)
00300 {
00301 jsk_recognition_msgs::ClusterPointIndices ros_indices_output;
00302 jsk_recognition_msgs::ModelCoefficientsArray ros_coefficients_output;
00303 jsk_recognition_msgs::PolygonArray ros_polygon_output;
00304 ros_indices_output.header = header;
00305 ros_coefficients_output.header = header;
00306 ros_polygon_output.header = header;
00307 ros_indices_output.cluster_indices
00308 = pcl_conversions::convertToROSPointIndices(inliers, header);
00309 ros_coefficients_output.coefficients
00310 = pcl_conversions::convertToROSModelCoefficients(coefficients, header);
00311 pub_inliers_.publish(ros_indices_output);
00312 pub_coefficients_.publish(ros_coefficients_output);
00313 for (size_t i = 0; i < convexes.size(); i++) {
00314 geometry_msgs::PolygonStamped polygon;
00315 polygon.header = header;
00316 polygon.polygon = convexes[i]->toROSMsg();
00317 ros_polygon_output.polygons.push_back(polygon);
00318 }
00319 pub_polygons_.publish(ros_polygon_output);
00320 }
00321
00322 void MultiPlaneSACSegmentation::segmentWithImu(
00323 const sensor_msgs::PointCloud2::ConstPtr& msg,
00324 const sensor_msgs::Imu::ConstPtr& imu_msg)
00325 {
00326 segmentWithImu(msg, sensor_msgs::PointCloud2::ConstPtr(), imu_msg);
00327 }
00328
00329 void MultiPlaneSACSegmentation::segmentWithImu(
00330 const sensor_msgs::PointCloud2::ConstPtr& msg,
00331 const sensor_msgs::PointCloud2::ConstPtr& normal_msg,
00332 const sensor_msgs::Imu::ConstPtr& imu_msg)
00333 {
00334 boost::mutex::scoped_lock lock(mutex_);
00335 pcl::PointCloud<PointT>::Ptr input (new pcl::PointCloud<PointT>);
00336 pcl::PointCloud<pcl::Normal>::Ptr
00337 normal (new pcl::PointCloud<pcl::Normal>);
00338 pcl::fromROSMsg(*msg, *input);
00339 if (normal_msg) {
00340 pcl::fromROSMsg(*normal_msg, *normal);
00341 }
00342 geometry_msgs::Vector3Stamped stamped_imu, transformed_stamped_imu;
00343 stamped_imu.header = imu_msg->header;
00344 stamped_imu.vector = imu_msg->linear_acceleration;
00345 try {
00346 tf_listener_->waitForTransform(
00347 msg->header.frame_id, imu_msg->header.frame_id, imu_msg->header.stamp,
00348 ros::Duration(0.1));
00349 tf_listener_->transformVector(
00350 msg->header.frame_id, stamped_imu, transformed_stamped_imu);
00351 Eigen::Vector3d imu_vectord;
00352 Eigen::Vector3f imu_vector;
00353 tf::vectorMsgToEigen(transformed_stamped_imu.vector, imu_vectord);
00354 pointFromVectorToVector<Eigen::Vector3d, Eigen::Vector3f>(
00355 imu_vectord, imu_vector);
00356 imu_vector = - imu_vector;
00357
00358 std::vector<pcl::PointIndices::Ptr> inliers;
00359 std::vector<pcl::ModelCoefficients::Ptr> coefficients;
00360 std::vector<ConvexPolygon::Ptr> convexes;
00361 applyRecursiveRANSAC(input, normal, imu_vector,
00362 inliers, coefficients, convexes);
00363 publishResult(msg->header, inliers, coefficients, convexes);
00364 }
00365 catch (tf2::ConnectivityException &e) {
00366 JSK_NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00367 }
00368 catch (tf2::InvalidArgumentException &e) {
00369 JSK_NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00370 }
00371 catch (tf2::ExtrapolationException& e) {
00372 JSK_NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
00373 }
00374
00375 }
00376
00377 void MultiPlaneSACSegmentation::segment(
00378 const sensor_msgs::PointCloud2::ConstPtr& msg,
00379 const sensor_msgs::PointCloud2::ConstPtr& msg_normal)
00380 {
00381 boost::mutex::scoped_lock lock(mutex_);
00382 pcl::PointCloud<PointT>::Ptr input (new pcl::PointCloud<PointT>);
00383 pcl::PointCloud<pcl::Normal>::Ptr normal (new pcl::PointCloud<pcl::Normal>);
00384 pcl::fromROSMsg(*msg, *input);
00385 pcl::fromROSMsg(*msg_normal, *normal);
00386 std::vector<pcl::PointIndices::Ptr> inliers;
00387 std::vector<pcl::ModelCoefficients::Ptr> coefficients;
00388 std::vector<ConvexPolygon::Ptr> convexes;
00389 Eigen::Vector3f dummy_imu_vector;
00390 applyRecursiveRANSAC(input, normal, dummy_imu_vector,
00391 inliers, coefficients, convexes);
00392 publishResult(msg->header, inliers, coefficients, convexes);
00393 }
00394
00395 void MultiPlaneSACSegmentation::segment(
00396 const sensor_msgs::PointCloud2::ConstPtr& msg)
00397 {
00398 segment(msg, sensor_msgs::PointCloud2::ConstPtr());
00399 }
00400 }
00401
00402 #include <pluginlib/class_list_macros.h>
00403 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::MultiPlaneSACSegmentation, nodelet::Nodelet);