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 maginify_ = config.maginify;
00167 keep_organized_ = config.keep_organized;
00168 }
00169
00170 void MultiPlaneExtraction::updateDiagnostic(
00171 diagnostic_updater::DiagnosticStatusWrapper &stat)
00172 {
00173 if (vital_checker_->isAlive()) {
00174 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00175 "MultiPlaneExtraction running");
00176 stat.add("Minimum Height", min_height_);
00177 stat.add("Maximum Height", max_height_);
00178 stat.add("Number of Planes", plane_counter_.mean());
00179 }
00180 else {
00181 jsk_topic_tools::addDiagnosticErrorSummary(
00182 "MultiPlaneExtraction", vital_checker_, stat);
00183 }
00184 }
00185
00186 void MultiPlaneExtraction::fillEmptyIndices(
00187 const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
00188 {
00189 jsk_recognition_msgs::ClusterPointIndices indices;
00190 indices.header = polygons->header;
00191 indices.cluster_indices.resize(polygons->polygons.size());
00192 null_indices_.add(
00193 boost::make_shared<jsk_recognition_msgs::ClusterPointIndices>(indices));
00194 }
00195
00196 void MultiPlaneExtraction::fillEmptyCoefficients(
00197 const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
00198 {
00199 jsk_recognition_msgs::ModelCoefficientsArray coeffs;
00200 coeffs.header = polygons->header;
00201 coeffs.coefficients.resize(polygons->polygons.size());
00202 null_coefficients_.add(
00203 boost::make_shared<jsk_recognition_msgs::ModelCoefficientsArray>(coeffs));
00204 }
00205
00206 void MultiPlaneExtraction::extract(const sensor_msgs::PointCloud2::ConstPtr& input,
00207 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices,
00208 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
00209 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons)
00210 {
00211 boost::mutex::scoped_lock lock(mutex_);
00212 vital_checker_->poke();
00213
00214 if(!jsk_recognition_utils::isSameFrameId(input->header.frame_id,
00215 indices->header.frame_id) ||
00216 !jsk_recognition_utils::isSameFrameId(input->header.frame_id,
00217 coefficients->header.frame_id) ||
00218 !jsk_recognition_utils::isSameFrameId(input->header.frame_id,
00219 polygons->header.frame_id)) {
00220 std::ostringstream oss;
00221 oss << "frame id does not match. cloud: " << input->header.frame_id
00222 << ", polygons: " << polygons->header.frame_id;
00223 if (use_indices_) {
00224 oss << ", indices: " << indices->header.frame_id;
00225 }
00226 if (use_coefficients_) {
00227 oss << ", coefficients: " << coefficients->header.frame_id;
00228 }
00229 NODELET_ERROR_STREAM(oss.str());
00230 return;
00231 }
00232
00233
00234 Eigen::Vector3f viewpoint;
00235 if (use_sensor_frame_) {
00236 try {
00237 tf::StampedTransform transform
00238 = lookupTransformWithDuration(tf_listener_,
00239 input->header.frame_id,
00240 sensor_frame_,
00241 input->header.stamp,
00242 ros::Duration(5.0));
00243 Eigen::Affine3f sensor_pose;
00244 tf::transformTFToEigen(transform, sensor_pose);
00245 viewpoint = Eigen::Vector3f(sensor_pose.translation());
00246 }
00247 catch (tf2::ConnectivityException &e)
00248 {
00249 NODELET_ERROR("Transform error: %s", e.what());
00250 }
00251 catch (tf2::InvalidArgumentException &e)
00252 {
00253 NODELET_ERROR("Transform error: %s", e.what());
00254 }
00255 catch (...)
00256 {
00257 NODELET_ERROR("Unknown transform error");
00258 }
00259 }
00260
00261
00262 pcl::PointCloud<pcl::PointXYZRGB>::Ptr input_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
00263 pcl::PointCloud<pcl::PointXYZRGB>::Ptr nonplane_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
00264 pcl::fromROSMsg(*input, *input_cloud);
00265 if (indices) {
00266
00267 pcl::PointIndices::Ptr all_indices (new pcl::PointIndices);
00268 for (size_t i = 0; i < indices->cluster_indices.size(); i++) {
00269 std::vector<int> one_indices = indices->cluster_indices[i].indices;
00270 for (size_t j = 0; j < one_indices.size(); j++) {
00271 all_indices->indices.push_back(one_indices[j]);
00272 }
00273 }
00274
00275
00276 pcl::ExtractIndices<pcl::PointXYZRGB> extract_nonplane;
00277 extract_nonplane.setNegative(true);
00278 extract_nonplane.setKeepOrganized(keep_organized_);
00279 extract_nonplane.setInputCloud(input_cloud);
00280 extract_nonplane.setIndices(all_indices);
00281 extract_nonplane.filter(*nonplane_cloud);
00282 sensor_msgs::PointCloud2 ros_result;
00283 pcl::toROSMsg(*nonplane_cloud, ros_result);
00284 ros_result.header = input->header;
00285 nonplane_pub_.publish(ros_result);
00286 }
00287 else {
00288 nonplane_cloud = input_cloud;
00289 }
00290
00291
00292
00293 std::set<int> result_set;
00294 plane_counter_.add(polygons->polygons.size());
00295 for (size_t plane_i = 0; plane_i < polygons->polygons.size(); plane_i++) {
00296 if (use_coefficients_) {
00297
00298 for (size_t vec_i = 0; vec_i < 3; ++vec_i)
00299 viewpoint[vec_i] = coefficients->coefficients[plane_i].values[vec_i];
00300 }
00301 pcl::ExtractPolygonalPrismData<pcl::PointXYZRGB> prism_extract;
00302 prism_extract.setViewPoint(viewpoint[0], viewpoint[1], viewpoint[2]);
00303 pcl::PointCloud<pcl::PointXYZRGB>::Ptr hull_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
00304 geometry_msgs::Polygon the_polygon = polygons->polygons[plane_i].polygon;
00305 if (the_polygon.points.size() <= 2) {
00306 NODELET_WARN("too small polygon");
00307 continue;
00308 }
00309
00310 Eigen::Vector3f centroid(0, 0, 0);
00311 for (size_t i = 0; i < the_polygon.points.size(); i++) {
00312 pcl::PointXYZRGB p;
00313 jsk_recognition_utils::pointFromXYZToXYZ<geometry_msgs::Point32, pcl::PointXYZRGB>(
00314 the_polygon.points[i], p);
00315 centroid = centroid + p.getVector3fMap();
00316 }
00317 centroid = centroid / the_polygon.points.size();
00318
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 Eigen::Vector3f dir = (p.getVector3fMap() - centroid).normalized();
00324 p.getVector3fMap() = dir * maginify_ + p.getVector3fMap();
00325 hull_cloud->points.push_back(p);
00326 }
00327
00328 pcl::PointXYZRGB p_last;
00329 jsk_recognition_utils::pointFromXYZToXYZ<geometry_msgs::Point32, pcl::PointXYZRGB>(
00330 the_polygon.points[0], p_last);
00331 hull_cloud->points.push_back(p_last);
00332
00333 prism_extract.setInputCloud(nonplane_cloud);
00334 prism_extract.setHeightLimits(min_height_, max_height_);
00335 prism_extract.setInputPlanarHull(hull_cloud);
00336 pcl::PointIndices output_indices;
00337 prism_extract.segment(output_indices);
00338
00339 for (size_t i = 0; i < output_indices.indices.size(); i++) {
00340 result_set.insert(output_indices.indices[i]);
00341 }
00342 }
00343
00344
00345
00346 pcl::PointCloud<pcl::PointXYZRGB> result_cloud;
00347 pcl::PointIndices::Ptr all_result_indices (new pcl::PointIndices());
00348 for (std::set<int>::iterator it = result_set.begin();
00349 it != result_set.end();
00350 it++) {
00351 all_result_indices->indices.push_back(*it);
00352 }
00353
00354 pcl::ExtractIndices<pcl::PointXYZRGB> extract_all_indices;
00355 extract_all_indices.setKeepOrganized(keep_organized_);
00356 extract_all_indices.setInputCloud(nonplane_cloud);
00357 extract_all_indices.setIndices(all_result_indices);
00358 extract_all_indices.filter(result_cloud);
00359
00360 sensor_msgs::PointCloud2 ros_result;
00361 pcl::toROSMsg(result_cloud, ros_result);
00362 ros_result.header = input->header;
00363 pub_.publish(ros_result);
00364 PCLIndicesMsg ros_indices;
00365 pcl_conversions::fromPCL(*all_result_indices, ros_indices);
00366 ros_indices.header = input->header;
00367 pub_indices_.publish(ros_indices);
00368 diagnostic_updater_->update();
00369 }
00370 }
00371
00372 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::MultiPlaneExtraction, nodelet::Nodelet);