plane_supported_cuboid_estimator_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 
00038 #include "jsk_pcl_ros/plane_supported_cuboid_estimator.h"
00039 #include "jsk_recognition_utils/pcl_conversion_util.h"
00040 #include "jsk_recognition_utils/geo_util.h"
00041 #include "jsk_recognition_utils/pcl_util.h"
00042 #include <ctime>
00043 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00044 #include <pcl/filters/extract_indices.h>
00045 #include <pcl/filters/crop_box.h>
00046 #include <algorithm>
00047 #include <pcl/common/centroid.h>
00048 
00049 namespace jsk_pcl_ros
00050 {
00051   void PlaneSupportedCuboidEstimator::onInit()
00052   {
00053     DiagnosticNodelet::onInit();
00054     tf_ = TfListenerSingleton::getInstance();
00055     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00056     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00057       boost::bind (&PlaneSupportedCuboidEstimator::configCallback, this, _1, _2);
00058     srv_->setCallback (f);
00059     pnh_->param("sensor_frame", sensor_frame_, std::string("odom"));
00060     pub_result_ = pnh_->advertise<jsk_recognition_msgs::BoundingBoxArray>("output/result", 1);
00061     pub_result_pose_ = pnh_->advertise<geometry_msgs::PoseStamped>("output/result_pose", 1);
00062     pub_particles_ = pnh_->advertise<sensor_msgs::PointCloud2>("output/particles", 1);
00063     pub_candidate_cloud_ = pnh_->advertise<sensor_msgs::PointCloud2>("output/candidate_cloud", 1);
00064     pub_histogram_global_x_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/global/x", 1);
00065     pub_histogram_global_y_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/global/y", 1);
00066     pub_histogram_global_z_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/global/z", 1);
00067     pub_histogram_global_roll_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/global/roll", 1);
00068     pub_histogram_global_pitch_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/global/pitch", 1);
00069     pub_histogram_global_yaw_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/global/yaw", 1);
00070     pub_histogram_dx_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/dx", 1);
00071     pub_histogram_dy_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/dy", 1);
00072     pub_histogram_dz_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/dz", 1);
00073     random_generator_ = boost::mt19937(static_cast<unsigned long>(time(0)));
00074     // Subscribe
00075     sub_polygon_.subscribe(*pnh_, "input/polygon", 10);
00076     sub_coefficients_.subscribe(*pnh_, "input/coefficients", 10);
00077     sync_polygon_ = boost::make_shared<message_filters::Synchronizer<PolygonSyncPolicy> >(100);
00078     sync_polygon_->connectInput(sub_polygon_, sub_coefficients_);
00079     sync_polygon_->registerCallback(boost::bind(&PlaneSupportedCuboidEstimator::polygonCallback, this, _1, _2));
00080     sub_cloud_ = pnh_->subscribe("input", 1, &PlaneSupportedCuboidEstimator::cloudCallback, this);
00081     sub_fast_cloud_ = pnh_->subscribe("fast_input", 1, &PlaneSupportedCuboidEstimator::fastCloudCallback,
00082                                       this);
00083     srv_reset_ = pnh_->advertiseService("reset", &PlaneSupportedCuboidEstimator::resetCallback, this);
00084 
00085     onInitPostProcess();
00086   }
00087 
00088   void PlaneSupportedCuboidEstimator::subscribe()
00089   {
00090 
00091   }
00092   
00093   void PlaneSupportedCuboidEstimator::unsubscribe()
00094   {
00095 
00096   }
00097 
00098   size_t PlaneSupportedCuboidEstimator::getNearestPolygon(
00099     const Particle& p,
00100     const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& polygons)
00101   {
00102     size_t min_index = 0;
00103     double min_distance = DBL_MAX;
00104     Eigen::Vector3f inp = p.getVector3fMap();
00105     for (size_t i = 0; i < polygons.size(); i++) {
00106       jsk_recognition_utils::ConvexPolygon::Ptr polygon = polygons[i];
00107       Eigen::Vector3f p;
00108       polygon->project(inp, p);
00109       double d = (p - inp).norm();
00110       if (d < min_distance) {
00111         min_distance = d;
00112         min_index = i;
00113       }
00114     }
00115     return min_index;
00116   }
00117   
00118   void PlaneSupportedCuboidEstimator::updateParticlePolygonRelationship(
00119     ParticleCloud::Ptr particles)
00120   {
00121     if (latest_polygon_msg_->polygons.size() == 0) {
00122       NODELET_ERROR("no valid polygons, skip update relationship");
00123       return;
00124     }
00125 
00126     // The order of convexes and polygons_ should be same
00127     // because it is inside of critical section.
00128     std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes(latest_polygon_msg_->polygons.size());
00129     for (size_t i = 0; i < latest_polygon_msg_->polygons.size(); i++) {
00130       jsk_recognition_utils::ConvexPolygon::Ptr polygon = jsk_recognition_utils::ConvexPolygon::fromROSMsgPtr(latest_polygon_msg_->polygons[i].polygon);
00131       polygon->decomposeToTriangles();
00132       convexes[i] = polygon;
00133     }
00134 
00135 #ifdef _OPENMP
00136 #pragma omp parallel for
00137 #endif
00138     // Second, compute distances and assing polygons.
00139     for (size_t i = 0; i < particles->points.size(); i++) {
00140       size_t nearest_index = getNearestPolygon(particles->points[i], convexes);
00141       //particles->points[i].plane = polygons[nearest_index];
00142       particles->points[i].plane_index = (int)nearest_index;
00143     }
00144   }
00145 
00146   void PlaneSupportedCuboidEstimator::fastCloudCallback(
00147     const sensor_msgs::PointCloud2::ConstPtr& msg)
00148   {
00149     boost::mutex::scoped_lock lock(mutex_);
00150     if (!tracker_) {
00151       return;
00152     }
00153     ParticleCloud::Ptr particles = tracker_->getParticles();
00154     Eigen::Vector4f center;
00155     pcl::compute3DCentroid(*particles, center);
00156     if (center.norm() < fast_cloud_threshold_) {
00157       estimate(msg);
00158     }
00159   }
00160 
00161   void PlaneSupportedCuboidEstimator::estimate(
00162     const sensor_msgs::PointCloud2::ConstPtr& msg)
00163   {
00164     // Update polygons_ vector
00165     polygons_.clear();
00166     for (size_t i = 0; i < latest_polygon_msg_->polygons.size(); i++) {
00167       Polygon::Ptr polygon = Polygon::fromROSMsgPtr(latest_polygon_msg_->polygons[i].polygon);
00168       polygon->decomposeToTriangles();
00169       polygons_.push_back(polygon);
00170     }
00171     
00172     try {
00173     // viewpoint
00174     tf::StampedTransform transform
00175       = lookupTransformWithDuration(tf_, sensor_frame_, msg->header.frame_id,
00176                                     ros::Time(0.0),
00177                                     ros::Duration(0.0));
00178     tf::vectorTFToEigen(transform.getOrigin(), viewpoint_);
00179 
00180     if (!tracker_) {
00181       NODELET_INFO("initTracker");
00182       pcl::PointCloud<pcl::tracking::ParticleCuboid>::Ptr particles = initParticles();
00183       tracker_.reset(new pcl::tracking::ROSCollaborativeParticleFilterTracker<pcl::PointXYZ, pcl::tracking::ParticleCuboid>);
00184       tracker_->setCustomSampleFunc(boost::bind(&PlaneSupportedCuboidEstimator::sample, this, _1));
00185       tracker_->setLikelihoodFunc(boost::bind(&PlaneSupportedCuboidEstimator::likelihood, this, _1, _2));
00186       tracker_->setParticles(particles);
00187       tracker_->setParticleNum(particle_num_);
00188     }
00189     else {
00190       pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
00191       pcl::fromROSMsg(*msg, *cloud);
00192       tracker_->setInputCloud(cloud);
00193       // Before call compute() method, we prepare candidate_cloud_ for
00194       // weight phase.
00195       candidate_cloud_.reset(new pcl::PointCloud<pcl::PointXYZ>);
00196       std::set<int> all_indices;
00197       for (size_t i = 0; i < latest_polygon_msg_->polygons.size(); i++) {
00198         Polygon::Ptr polygon = Polygon::fromROSMsgPtr(latest_polygon_msg_->polygons[i].polygon);
00199         pcl::ExtractPolygonalPrismData<pcl::PointXYZ> prism_extract;
00200         pcl::PointCloud<pcl::PointXYZ>::Ptr
00201           boundaries (new pcl::PointCloud<pcl::PointXYZ>);
00202         polygon->boundariesToPointCloud<pcl::PointXYZ>(*boundaries);
00203         boundaries->points.push_back(boundaries->points[0]);
00204         prism_extract.setInputCloud(cloud);
00205         prism_extract.setViewPoint(viewpoint_[0], viewpoint_[1], viewpoint_[2]);
00206         prism_extract.setHeightLimits(init_local_position_z_min_, init_local_position_z_max_);
00207         prism_extract.setInputPlanarHull(boundaries);
00208         pcl::PointIndices output_indices;
00209         prism_extract.segment(output_indices);
00210         for (size_t i = 0; i < output_indices.indices.size(); i++) {
00211           all_indices.insert(output_indices.indices[i]);
00212         }
00213       }
00214       pcl::ExtractIndices<pcl::PointXYZ> ex;
00215       ex.setInputCloud(cloud);
00216       pcl::PointIndices::Ptr indices (new pcl::PointIndices);
00217       indices->indices = std::vector<int>(all_indices.begin(), all_indices.end());
00218       ex.setIndices(indices);
00219       ex.filter(*candidate_cloud_);
00220       sensor_msgs::PointCloud2 ros_candidate_cloud;
00221       pcl::toROSMsg(*candidate_cloud_, ros_candidate_cloud);
00222       ros_candidate_cloud.header = msg->header;
00223       pub_candidate_cloud_.publish(ros_candidate_cloud);
00224       // check the number of candidate points
00225       if (candidate_cloud_->points.size() == 0) {
00226         NODELET_ERROR("No candidate cloud");
00227         return;
00228       }
00229       tree_.setInputCloud(candidate_cloud_);
00230       if (support_plane_updated_) {
00231         // Compute assignment between particles and polygons
00232         NODELET_INFO("polygon updated");
00233         updateParticlePolygonRelationship(tracker_->getParticles());
00234       }
00235       ROS_INFO("start tracker_->compute()");
00236       tracker_->compute();
00237       ROS_INFO("done tracker_->compute()");
00238       Particle result = tracker_->getResult();
00239       jsk_recognition_msgs::BoundingBoxArray box_array;
00240       box_array.header = msg->header;
00241       box_array.boxes.push_back(result.toBoundingBox());
00242       box_array.boxes[0].header = msg->header;
00243       pub_result_.publish(box_array);
00244       geometry_msgs::PoseStamped pose;
00245       pose.pose = box_array.boxes[0].pose;
00246       pose.header = box_array.header;
00247       pub_result_pose_.publish(pose);
00248     }
00249     support_plane_updated_ = false;
00250     ParticleCloud::Ptr particles = tracker_->getParticles();
00251     // Publish histograms
00252     publishHistogram(particles, 0, pub_histogram_global_x_, msg->header);
00253     publishHistogram(particles, 1, pub_histogram_global_y_, msg->header);
00254     publishHistogram(particles, 2, pub_histogram_global_z_, msg->header);
00255     publishHistogram(particles, 3, pub_histogram_global_roll_, msg->header);
00256     publishHistogram(particles, 4, pub_histogram_global_pitch_, msg->header);
00257     publishHistogram(particles, 5, pub_histogram_global_yaw_, msg->header);
00258     publishHistogram(particles, 6, pub_histogram_dx_, msg->header);
00259     publishHistogram(particles, 7, pub_histogram_dy_, msg->header);
00260     publishHistogram(particles, 8, pub_histogram_dz_, msg->header);
00261     // Publish particles
00262     sensor_msgs::PointCloud2 ros_particles;
00263     pcl::toROSMsg(*particles, ros_particles);
00264     ros_particles.header = msg->header;
00265     pub_particles_.publish(ros_particles);
00266     }
00267     catch (tf2::TransformException& e) {
00268       ROS_ERROR("tf exception");
00269     }
00270   }
00271   
00272   void PlaneSupportedCuboidEstimator::cloudCallback(
00273     const sensor_msgs::PointCloud2::ConstPtr& msg)
00274   {
00275     boost::mutex::scoped_lock lock(mutex_);
00276     NODELET_INFO("cloudCallback");
00277     if (!latest_polygon_msg_ || !latest_coefficients_msg_) {
00278       NODELET_WARN("Not yet polygon is available");
00279       return;
00280     }
00281 
00282     if (!tracker_) {
00283       NODELET_INFO("initTracker");
00284       // Update polygons_ vector
00285       polygons_.clear();
00286       for (size_t i = 0; i < latest_polygon_msg_->polygons.size(); i++) {
00287         Polygon::Ptr polygon = Polygon::fromROSMsgPtr(latest_polygon_msg_->polygons[i].polygon);
00288         polygons_.push_back(polygon);
00289       }
00290       // viewpoint
00291       tf::StampedTransform transform
00292         = lookupTransformWithDuration(tf_, sensor_frame_, msg->header.frame_id,
00293                                       ros::Time(0.0),
00294                                       ros::Duration(0.0));
00295       tf::vectorTFToEigen(transform.getOrigin(), viewpoint_);
00296       
00297       ParticleCloud::Ptr particles = initParticles();
00298       tracker_.reset(new pcl::tracking::ROSCollaborativeParticleFilterTracker<pcl::PointXYZ, pcl::tracking::ParticleCuboid>);
00299       tracker_->setCustomSampleFunc(boost::bind(&PlaneSupportedCuboidEstimator::sample, this, _1));
00300       tracker_->setLikelihoodFunc(boost::bind(&PlaneSupportedCuboidEstimator::likelihood, this, _1, _2));
00301       tracker_->setParticles(particles);
00302       tracker_->setParticleNum(particle_num_);
00303       support_plane_updated_ = false;
00304       // Publish histograms
00305       publishHistogram(particles, 0, pub_histogram_global_x_, msg->header);
00306       publishHistogram(particles, 1, pub_histogram_global_y_, msg->header);
00307       publishHistogram(particles, 2, pub_histogram_global_z_, msg->header);
00308       publishHistogram(particles, 3, pub_histogram_global_roll_, msg->header);
00309       publishHistogram(particles, 4, pub_histogram_global_pitch_, msg->header);
00310       publishHistogram(particles, 5, pub_histogram_global_yaw_, msg->header);
00311       publishHistogram(particles, 6, pub_histogram_dx_, msg->header);
00312       publishHistogram(particles, 7, pub_histogram_dy_, msg->header);
00313       publishHistogram(particles, 8, pub_histogram_dz_, msg->header);
00314       // Publish particles
00315       sensor_msgs::PointCloud2 ros_particles;
00316       pcl::toROSMsg(*particles, ros_particles);
00317       ros_particles.header = msg->header;
00318       pub_particles_.publish(ros_particles);
00319       
00320     }
00321     else {
00322       ParticleCloud::Ptr particles = tracker_->getParticles();
00323       Eigen::Vector4f center;
00324       pcl::compute3DCentroid(*particles, center);
00325       if (center.norm() > fast_cloud_threshold_) {
00326         estimate(msg);
00327       }
00328     }
00329   }
00330 
00331   void PlaneSupportedCuboidEstimator::publishHistogram(
00332     ParticleCloud::Ptr particles, int index, ros::Publisher& pub, const std_msgs::Header& header)
00333   {
00334     const double step = 0.001;
00335     // Lookup min/max
00336     float max_value = -FLT_MAX;
00337     float min_value = FLT_MAX;
00338     for (size_t i = 0; i < particles->points.size(); i++) {
00339       max_value = std::max(max_value, particles->points[i][index]);
00340       min_value = std::min(min_value, particles->points[i][index]);
00341     }
00342     int num = (max_value - min_value) / step + 1;
00343     std::vector<unsigned int> bins(num, 0);
00344     for (size_t i = 0; i < particles->points.size(); i++) {
00345       float value =  particles->points[i][index];
00346       const int bin_index = (value - min_value) / step;
00347       const int min_confirmed_bin_index = std::min(bin_index, num - 1);
00348       bins[min_confirmed_bin_index] = bins[min_confirmed_bin_index] + 1;
00349     }
00350     
00351     jsk_recognition_msgs::HistogramWithRange histogram;
00352     histogram.header = header;
00353     for (size_t i = 0; i < bins.size(); i++) {
00354       jsk_recognition_msgs::HistogramWithRangeBin bin;
00355       bin.min_value = i * step + min_value;
00356       bin.max_value = (i + 1) * step + min_value;
00357       bin.count = bins[i];
00358       histogram.bins.push_back(bin);
00359     }
00360     pub.publish(histogram);
00361   }
00362   
00363   pcl::tracking::ParticleCuboid PlaneSupportedCuboidEstimator::sample(const pcl::tracking::ParticleCuboid& p)
00364   {
00365     pcl::tracking::ParticleCuboid sampled_particle;
00366     // Motion model is tricky.
00367     // It's not a tracking problem, so we need to limit noise of motion model
00368     // The new particle should satisfy:
00369     //   1. within a polygon
00370     //   2. within local z range
00371     //   3. within local pitch/roll range
00372     //   4. within world yaw range
00373     //   5. within dx/dy/dz range
00374     //sampled_particle = p;
00375     sampled_particle.x = randomGaussian(p.x, step_x_variance_, random_generator_);
00376     sampled_particle.y = randomGaussian(p.y, step_y_variance_, random_generator_);
00377     sampled_particle.z = randomGaussian(p.z, step_z_variance_, random_generator_);
00378     sampled_particle.roll = randomGaussian(p.roll, step_roll_variance_, random_generator_);
00379     sampled_particle.pitch = randomGaussian(p.pitch, step_pitch_variance_, random_generator_);
00380     sampled_particle.yaw = randomGaussian(p.yaw, step_yaw_variance_, random_generator_);
00381     sampled_particle.dx = std::max(randomGaussian(p.dx, step_dx_variance_, random_generator_),
00382                                    min_dx_);
00383     sampled_particle.dy = std::max(randomGaussian(p.dy, step_dy_variance_, random_generator_),
00384                                    min_dy_);
00385     sampled_particle.dz = std::max(randomGaussian(p.dz, step_dz_variance_, random_generator_),
00386                                    min_dz_);
00387     sampled_particle.plane_index = p.plane_index;
00388     sampled_particle.weight = p.weight;
00389     return sampled_particle;
00390   }
00391   
00392   void PlaneSupportedCuboidEstimator::likelihood(pcl::PointCloud<pcl::PointXYZ>::ConstPtr input,
00393                                                  pcl::tracking::ParticleCuboid& p)
00394   {
00395     p.weight = computeLikelihood(p, candidate_cloud_, tree_, viewpoint_,
00396                                  polygons_, latest_polygon_msg_->likelihood,
00397                                  config_);
00398   }
00399   
00400   void PlaneSupportedCuboidEstimator::polygonCallback(
00401       const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
00402       const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coef_msg)
00403   {
00404     boost::mutex::scoped_lock lock(mutex_);
00405     latest_polygon_msg_ = polygon_msg;
00406     latest_coefficients_msg_ = coef_msg;
00407     support_plane_updated_ = true;
00408   }
00409 
00410   size_t PlaneSupportedCuboidEstimator::chooseUniformRandomPlaneIndex(const std::vector<Polygon::Ptr>& polygons)
00411   {
00412     // randomly select plane according to their area
00413     std::vector<double> area_table(polygons.size());
00414     double sum = 0;
00415     for (size_t i = 0; i < latest_polygon_msg_->polygons.size(); i++) {
00416       area_table[i] = polygons[i]->area();
00417       if (use_init_polygon_likelihood_) {
00418         area_table[i] = area_table[i] * latest_polygon_msg_->likelihood[i];
00419       }
00420       sum += area_table[i];
00421     }
00422     double val = randomUniform(0, sum, random_generator_);
00423     double bin_start = 0.0;
00424     for (size_t i = 0; i < latest_polygon_msg_->polygons.size(); i++) {
00425       if (val >= bin_start && val < bin_start + area_table[i]) {
00426         return i;
00427       }
00428       bin_start += area_table[i];
00429     }
00430     // Unexpected region here
00431     NODELET_ERROR("should not reach here, failed to select plane randomly");
00432     return 0;
00433   }
00434   
00435   pcl::PointCloud<pcl::tracking::ParticleCuboid>::Ptr PlaneSupportedCuboidEstimator::initParticles()
00436   {
00437     pcl::PointCloud<pcl::tracking::ParticleCuboid>::Ptr particles (new pcl::PointCloud<pcl::tracking::ParticleCuboid>);
00438     particles->points.resize(particle_num_);
00439     std::vector<Polygon::Ptr> polygons(latest_polygon_msg_->polygons.size());
00440     for (size_t i = 0; i < latest_polygon_msg_->polygons.size(); i++) {
00441       Polygon::Ptr polygon = Polygon::fromROSMsgPtr(latest_polygon_msg_->polygons[i].polygon);
00442       polygons[i] = polygon;
00443     }
00444     for (size_t i = 0; i < particle_num_; i++) {
00445       while (true) {
00446         pcl::tracking::ParticleCuboid p_local;
00447         size_t plane_i = chooseUniformRandomPlaneIndex(polygons);
00448         Polygon::Ptr polygon = polygons[plane_i];
00449         Eigen::Vector3f v = polygon->randomSampleLocalPoint(random_generator_);
00450         v[2] = randomUniform(init_local_position_z_min_, init_local_position_z_max_,
00451                              random_generator_);
00452         p_local.getVector3fMap() = v;
00453         p_local.roll = randomGaussian(init_local_orientation_roll_mean_, init_local_orientation_roll_variance_, random_generator_);
00454         p_local.pitch = randomGaussian(init_local_orientation_pitch_mean_, init_local_orientation_pitch_variance_, random_generator_);
00455         p_local.yaw = randomGaussian(init_local_orientation_yaw_mean_,
00456                                      init_local_orientation_yaw_variance_,
00457                                      random_generator_);
00458         p_local.dx = randomGaussian(init_dx_mean_, init_dx_variance_, random_generator_);
00459         p_local.dy = randomGaussian(init_dy_mean_, init_dy_variance_, random_generator_);
00460         p_local.dz = randomGaussian(init_dz_mean_, init_dz_variance_, random_generator_);
00461         pcl::tracking::ParticleCuboid p_global =  p_local * polygon->coordinates();
00462         if (use_init_world_position_z_model_) {
00463           if (p_global.z < init_world_position_z_min_ ||
00464               p_global.z > init_world_position_z_max_) {
00465             continue;
00466           }
00467         }
00468         p_global.plane_index = plane_i;
00469         if (disable_init_pitch_) {
00470           p_global.pitch = 0;
00471         }
00472         if (disable_init_roll_) {
00473           p_global.roll = 0;
00474         }
00475         if (use_global_init_yaw_) {
00476           p_global.yaw = randomGaussian(init_global_orientation_yaw_mean_,
00477                                         init_global_orientation_yaw_variance_,
00478                                         random_generator_);
00479         }
00480         
00481         particles->points[i] = p_global;
00482         break;
00483       }
00484     }
00485     return particles;
00486   }
00487 
00488   void PlaneSupportedCuboidEstimator::configCallback(Config& config, uint32_t level)
00489   {
00490     boost::mutex::scoped_lock lock(mutex_);
00491     config_ = config;
00492     init_local_position_z_min_ = config.init_local_position_z_min;
00493     init_local_position_z_max_ = config.init_local_position_z_max;
00494     use_init_world_position_z_model_ = config.use_init_world_position_z_model;
00495     init_world_position_z_min_ = config.init_world_position_z_min;
00496     init_world_position_z_max_ = config.init_world_position_z_max;
00497     init_local_orientation_roll_mean_ = config.init_local_orientation_roll_mean;
00498     init_local_orientation_roll_variance_ = config.init_local_orientation_roll_variance;
00499     init_local_orientation_pitch_mean_ = config.init_local_orientation_pitch_mean;
00500     init_local_orientation_pitch_variance_ = config.init_local_orientation_pitch_variance;
00501     init_local_orientation_yaw_mean_ = config.init_local_orientation_yaw_mean;
00502     init_local_orientation_yaw_variance_ = config.init_local_orientation_yaw_variance;
00503     use_global_init_yaw_ = config.use_global_init_yaw;
00504     init_global_orientation_yaw_mean_ = config.init_global_orientation_yaw_mean;
00505     init_global_orientation_yaw_variance_ = config.init_global_orientation_yaw_variance;
00506     init_dx_mean_ = config.init_dx_mean;
00507     init_dx_variance_ = config.init_dx_variance;
00508     init_dy_mean_ = config.init_dy_mean;
00509     init_dy_variance_ = config.init_dy_variance;
00510     init_dz_mean_ = config.init_dz_mean;
00511     init_dz_variance_ = config.init_dz_variance;
00512     particle_num_ = config.particle_num;
00513     step_x_variance_ = config.step_x_variance;
00514     step_y_variance_ = config.step_y_variance;
00515     step_z_variance_ = config.step_z_variance;
00516     step_roll_variance_ = config.step_roll_variance;
00517     step_pitch_variance_ = config.step_pitch_variance;
00518     step_yaw_variance_ = config.step_yaw_variance;
00519     step_dx_variance_ = config.step_dx_variance;
00520     step_dy_variance_ = config.step_dy_variance;
00521     step_dz_variance_ = config.step_dz_variance;
00522     min_dx_ = config.min_dx;
00523     min_dy_ = config.min_dy;
00524     min_dz_ = config.min_dz;
00525     use_init_polygon_likelihood_ = config.use_init_polygon_likelihood;
00526     fast_cloud_threshold_ = config.fast_cloud_threshold;
00527     disable_init_roll_ = config.disable_init_roll;
00528     disable_init_pitch_ = config.disable_init_pitch;
00529   }
00530 
00531   bool PlaneSupportedCuboidEstimator::resetCallback(std_srvs::EmptyRequest& req,
00532                                                     std_srvs::EmptyResponse& res)
00533   {
00534     boost::mutex::scoped_lock lock(mutex_);
00535     latest_polygon_msg_ = jsk_recognition_msgs::PolygonArray::ConstPtr();
00536     latest_coefficients_msg_ = jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr();
00537     tracker_.reset();
00538     return true;
00539   }
00540 }
00541 
00542 #include <pluginlib/class_list_macros.h>
00543 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::PlaneSupportedCuboidEstimator, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:50