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_extraction.h"
00037 #include <pluginlib/class_list_macros.h>
00038 #include <pcl/filters/extract_indices.h>
00039 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00040 #include <jsk_recognition_utils/pcl_ros_util.h>
00041 #include <jsk_topic_tools/log_utils.h>
00042 #include <pcl/filters/project_inliers.h>
00043 #include <set>
00044 #include <sstream>
00045
00046 namespace jsk_pcl_ros
00047 {
00048
00049 void MultiPlaneExtraction::onInit()
00050 {
00051 pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
00052 DiagnosticNodelet::onInit();
00053 pnh_->param("use_indices", use_indices_, true);
00054 pnh_->param("use_async", use_async_, false);
00056
00058 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00059 nonplane_pub_ = advertise<pcl::PointCloud<pcl::PointXYZRGB> >(*pnh_, "output_nonplane_cloud", 1);
00060 pub_indices_ = advertise<PCLIndicesMsg>(*pnh_, "output/indices", 1);
00061 if (!pnh_->getParam("max_queue_size", maximum_queue_size_)) {
00062 maximum_queue_size_ = 100;
00063 }
00064
00065 pnh_->param("use_coefficients", use_coefficients_, false);
00066 pnh_->param("use_sensor_frame", use_sensor_frame_, false);
00067 if (use_sensor_frame_) {
00068 pnh_->param("sensor_frame", sensor_frame_, std::string("head_root"));
00069 tf_listener_ = TfListenerSingleton::getInstance();
00070 if (use_coefficients_) {
00071 NODELET_WARN("'~use_sensor_frame' and '~use_coefficients' cannot be enabled at the same time."
00072 " disabled '~use_coefficients'");
00073 use_coefficients_ = false;
00074 }
00075 } else if (!use_coefficients_) {
00076 NODELET_WARN("'~use_coefficients' and '~use_sensor_frame' are both disabled."
00077 " Normal axes of planes are estimated with PCA"
00078 " and they may be flipped unintentionally.");
00079 }
00080
00082
00084 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00085 dynamic_reconfigure::Server<Config>::CallbackType f =
00086 boost::bind (&MultiPlaneExtraction::configCallback, this, _1, _2);
00087 srv_->setCallback (f);
00088 onInitPostProcess();
00089 }
00090
00091 void MultiPlaneExtraction::subscribe()
00092 {
00094
00096
00097 sub_input_.subscribe(*pnh_, "input", 1);
00098 sub_polygons_.subscribe(*pnh_, "input_polygons", 1);
00099
00100 if (use_coefficients_) {
00101 sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
00102 } else {
00103 sub_polygons_.registerCallback(
00104 boost::bind(&MultiPlaneExtraction::fillEmptyCoefficients, this, _1));
00105 }
00106
00107 if (use_indices_) {
00108 sub_indices_.subscribe(*pnh_, "indices", 1);
00109 } else {
00110 sub_polygons_.registerCallback(
00111 boost::bind(&MultiPlaneExtraction::fillEmptyIndices, this, _1));
00112 }
00113
00114 if (use_async_) {
00115 async_ = boost::make_shared<message_filters::Synchronizer<ASyncPolicy> >(maximum_queue_size_);
00116 if (use_indices_) {
00117 if (use_coefficients_) {
00118 async_->connectInput(sub_input_, sub_indices_, sub_coefficients_, sub_polygons_);
00119 } else {
00120 async_->connectInput(sub_input_, sub_indices_, null_coefficients_, sub_polygons_);
00121 }
00122 } else {
00123 if (use_coefficients_) {
00124 async_->connectInput(sub_input_, null_indices_, sub_coefficients_, sub_polygons_);
00125 } else {
00126 async_->connectInput(sub_input_, null_indices_, null_coefficients_, sub_polygons_);
00127 }
00128 }
00129 async_->registerCallback(boost::bind(&MultiPlaneExtraction::extract, this, _1, _2, _3, _4));
00130 } else {
00131 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(maximum_queue_size_);
00132 if (use_indices_) {
00133 if (use_coefficients_) {
00134 sync_->connectInput(sub_input_, sub_indices_, sub_coefficients_, sub_polygons_);
00135 } else {
00136 sync_->connectInput(sub_input_, sub_indices_, null_coefficients_, sub_polygons_);
00137 }
00138 } else {
00139 if (use_coefficients_) {
00140 sync_->connectInput(sub_input_, null_indices_, sub_coefficients_, sub_polygons_);
00141 } else {
00142 sync_->connectInput(sub_input_, null_indices_, null_coefficients_, sub_polygons_);
00143 }
00144 }
00145 sync_->registerCallback(boost::bind(&MultiPlaneExtraction::extract, this, _1, _2, _3, _4));
00146 }
00147 }
00148
00149 void MultiPlaneExtraction::unsubscribe()
00150 {
00151 sub_input_.unsubscribe();
00152 if (use_indices_) {
00153 sub_indices_.unsubscribe();
00154 }
00155 sub_polygons_.unsubscribe();
00156 if (use_coefficients_) {
00157 sub_coefficients_.unsubscribe();
00158 }
00159 }
00160
00161 void MultiPlaneExtraction::configCallback(Config& config, uint32_t level)
00162 {
00163 boost::mutex::scoped_lock lock(mutex_);
00164 min_height_ = config.min_height;
00165 max_height_ = config.max_height;
00166 keep_organized_ = config.keep_organized;
00167
00168 if (magnify_ != config.magnify)
00169 {
00170 magnify_ = config.magnify;
00171 config.maginify = magnify_;
00172 }
00173 else if (magnify_ != config.maginify)
00174 {
00175 ROS_WARN_STREAM_ONCE("parameter 'maginify' is deprecated! Use 'magnify' instead!");
00176 magnify_ = config.maginify;
00177 config.magnify = magnify_;
00178 }
00179 }
00180
00181 void MultiPlaneExtraction::updateDiagnostic(
00182 diagnostic_updater::DiagnosticStatusWrapper &stat)
00183 {
00184 if (vital_checker_->isAlive()) {
00185 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00186 "MultiPlaneExtraction running");
00187 stat.add("Minimum Height", min_height_);
00188 stat.add("Maximum Height", max_height_);
00189 stat.add("Number of Planes", plane_counter_.mean());
00190 }
00191 DiagnosticNodelet::updateDiagnostic(stat);
00192 }
00193
00194 void MultiPlaneExtraction::fillEmptyIndices(
00195 const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
00196 {
00197 jsk_recognition_msgs::ClusterPointIndices indices;
00198 indices.header = polygons->header;
00199 indices.cluster_indices.resize(polygons->polygons.size());
00200 null_indices_.add(
00201 boost::make_shared<jsk_recognition_msgs::ClusterPointIndices>(indices));
00202 }
00203
00204 void MultiPlaneExtraction::fillEmptyCoefficients(
00205 const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
00206 {
00207 jsk_recognition_msgs::ModelCoefficientsArray coeffs;
00208 coeffs.header = polygons->header;
00209 coeffs.coefficients.resize(polygons->polygons.size());
00210 null_coefficients_.add(
00211 boost::make_shared<jsk_recognition_msgs::ModelCoefficientsArray>(coeffs));
00212 }
00213
00214 void MultiPlaneExtraction::extract(const sensor_msgs::PointCloud2::ConstPtr& input,
00215 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices,
00216 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
00217 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons)
00218 {
00219 boost::mutex::scoped_lock lock(mutex_);
00220 vital_checker_->poke();
00221
00222 if(!jsk_recognition_utils::isSameFrameId(input->header.frame_id,
00223 indices->header.frame_id) ||
00224 !jsk_recognition_utils::isSameFrameId(input->header.frame_id,
00225 coefficients->header.frame_id) ||
00226 !jsk_recognition_utils::isSameFrameId(input->header.frame_id,
00227 polygons->header.frame_id)) {
00228 std::ostringstream oss;
00229 oss << "frame id does not match. cloud: " << input->header.frame_id
00230 << ", polygons: " << polygons->header.frame_id;
00231 if (use_indices_) {
00232 oss << ", indices: " << indices->header.frame_id;
00233 }
00234 if (use_coefficients_) {
00235 oss << ", coefficients: " << coefficients->header.frame_id;
00236 }
00237 NODELET_ERROR_STREAM(oss.str());
00238 return;
00239 }
00240
00241
00242 Eigen::Vector3f viewpoint = Eigen::Vector3f::Zero();
00243 if (use_sensor_frame_) {
00244 try {
00245 tf::StampedTransform transform
00246 = lookupTransformWithDuration(tf_listener_,
00247 input->header.frame_id,
00248 sensor_frame_,
00249 input->header.stamp,
00250 ros::Duration(5.0));
00251 Eigen::Affine3f sensor_pose;
00252 tf::transformTFToEigen(transform, sensor_pose);
00253 viewpoint = Eigen::Vector3f(sensor_pose.translation());
00254 }
00255 catch (tf2::ConnectivityException &e)
00256 {
00257 NODELET_ERROR("Transform error: %s", e.what());
00258 }
00259 catch (tf2::InvalidArgumentException &e)
00260 {
00261 NODELET_ERROR("Transform error: %s", e.what());
00262 }
00263 catch (...)
00264 {
00265 NODELET_ERROR("Unknown transform error");
00266 }
00267 }
00268
00269
00270 pcl::PointCloud<pcl::PointXYZRGB>::Ptr input_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
00271 pcl::PointCloud<pcl::PointXYZRGB>::Ptr nonplane_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
00272 pcl::fromROSMsg(*input, *input_cloud);
00273 if (indices) {
00274
00275 pcl::PointIndices::Ptr all_indices (new pcl::PointIndices);
00276 for (size_t i = 0; i < indices->cluster_indices.size(); i++) {
00277 std::vector<int> one_indices = indices->cluster_indices[i].indices;
00278 for (size_t j = 0; j < one_indices.size(); j++) {
00279 all_indices->indices.push_back(one_indices[j]);
00280 }
00281 }
00282
00283
00284 pcl::ExtractIndices<pcl::PointXYZRGB> extract_nonplane;
00285 extract_nonplane.setNegative(true);
00286 extract_nonplane.setKeepOrganized(keep_organized_);
00287 extract_nonplane.setInputCloud(input_cloud);
00288 extract_nonplane.setIndices(all_indices);
00289 extract_nonplane.filter(*nonplane_cloud);
00290 sensor_msgs::PointCloud2 ros_result;
00291 pcl::toROSMsg(*nonplane_cloud, ros_result);
00292 ros_result.header = input->header;
00293 nonplane_pub_.publish(ros_result);
00294 }
00295 else {
00296 nonplane_cloud = input_cloud;
00297 }
00298
00299
00300
00301 std::set<int> result_set;
00302 plane_counter_.add(polygons->polygons.size());
00303 for (size_t plane_i = 0; plane_i < polygons->polygons.size(); plane_i++) {
00304 if (use_coefficients_) {
00305
00306 for (size_t vec_i = 0; vec_i < 3; ++vec_i)
00307 viewpoint[vec_i] = coefficients->coefficients[plane_i].values[vec_i];
00308 }
00309 pcl::ExtractPolygonalPrismData<pcl::PointXYZRGB> prism_extract;
00310 prism_extract.setViewPoint(viewpoint[0], viewpoint[1], viewpoint[2]);
00311 pcl::PointCloud<pcl::PointXYZRGB>::Ptr hull_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
00312 geometry_msgs::Polygon the_polygon = polygons->polygons[plane_i].polygon;
00313 if (the_polygon.points.size() <= 2) {
00314 NODELET_WARN("too small polygon");
00315 continue;
00316 }
00317
00318 Eigen::Vector3f centroid(0, 0, 0);
00319 for (size_t i = 0; i < the_polygon.points.size(); i++) {
00320 pcl::PointXYZRGB p;
00321 jsk_recognition_utils::pointFromXYZToXYZ<geometry_msgs::Point32, pcl::PointXYZRGB>(
00322 the_polygon.points[i], p);
00323 centroid = centroid + p.getVector3fMap();
00324 }
00325 centroid = centroid / the_polygon.points.size();
00326
00327 for (size_t i = 0; i < the_polygon.points.size(); i++) {
00328 pcl::PointXYZRGB p;
00329 jsk_recognition_utils::pointFromXYZToXYZ<geometry_msgs::Point32, pcl::PointXYZRGB>(
00330 the_polygon.points[i], p);
00331 Eigen::Vector3f dir = (p.getVector3fMap() - centroid).normalized();
00332 p.getVector3fMap() = dir * magnify_ + p.getVector3fMap();
00333 hull_cloud->points.push_back(p);
00334 }
00335
00336 pcl::PointXYZRGB p_last;
00337 jsk_recognition_utils::pointFromXYZToXYZ<geometry_msgs::Point32, pcl::PointXYZRGB>(
00338 the_polygon.points[0], p_last);
00339 hull_cloud->points.push_back(p_last);
00340
00341 prism_extract.setInputCloud(nonplane_cloud);
00342 prism_extract.setHeightLimits(min_height_, max_height_);
00343 prism_extract.setInputPlanarHull(hull_cloud);
00344 pcl::PointIndices output_indices;
00345 prism_extract.segment(output_indices);
00346
00347 for (size_t i = 0; i < output_indices.indices.size(); i++) {
00348 result_set.insert(output_indices.indices[i]);
00349 }
00350 }
00351
00352
00353
00354 pcl::PointCloud<pcl::PointXYZRGB> result_cloud;
00355 pcl::PointIndices::Ptr all_result_indices (new pcl::PointIndices());
00356 for (std::set<int>::iterator it = result_set.begin();
00357 it != result_set.end();
00358 it++) {
00359 all_result_indices->indices.push_back(*it);
00360 }
00361
00362 pcl::ExtractIndices<pcl::PointXYZRGB> extract_all_indices;
00363 extract_all_indices.setKeepOrganized(keep_organized_);
00364 extract_all_indices.setInputCloud(nonplane_cloud);
00365 extract_all_indices.setIndices(all_result_indices);
00366 extract_all_indices.filter(result_cloud);
00367
00368 sensor_msgs::PointCloud2 ros_result;
00369 pcl::toROSMsg(result_cloud, ros_result);
00370 ros_result.header = input->header;
00371 pub_.publish(ros_result);
00372 PCLIndicesMsg ros_indices;
00373 pcl_conversions::fromPCL(*all_result_indices, ros_indices);
00374 ros_indices.header = input->header;
00375 pub_indices_.publish(ros_indices);
00376 diagnostic_updater_->update();
00377 }
00378 }
00379
00380 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::MultiPlaneExtraction, nodelet::Nodelet);