plane_supported_cuboid_estimator_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #define BOOST_PARAMETER_MAX_ARITY 7
37 
42 #include <ctime>
43 #include <pcl/segmentation/extract_polygonal_prism_data.h>
44 #include <pcl/filters/extract_indices.h>
45 #include <pcl/filters/crop_box.h>
46 #include <algorithm>
47 #include <pcl/common/centroid.h>
48 
49 namespace jsk_pcl_ros
50 {
52  {
53  DiagnosticNodelet::onInit();
55  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
56  typename dynamic_reconfigure::Server<Config>::CallbackType f =
57  boost::bind (&PlaneSupportedCuboidEstimator::configCallback, this, _1, _2);
58  srv_->setCallback (f);
59  pnh_->param("sensor_frame", sensor_frame_, std::string("odom"));
60  pub_result_ = pnh_->advertise<jsk_recognition_msgs::BoundingBoxArray>("output/result", 1);
61  pub_result_pose_ = pnh_->advertise<geometry_msgs::PoseStamped>("output/result_pose", 1);
62  pub_particles_ = pnh_->advertise<sensor_msgs::PointCloud2>("output/particles", 1);
63  pub_candidate_cloud_ = pnh_->advertise<sensor_msgs::PointCloud2>("output/candidate_cloud", 1);
64  pub_histogram_global_x_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/global/x", 1);
65  pub_histogram_global_y_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/global/y", 1);
66  pub_histogram_global_z_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/global/z", 1);
67  pub_histogram_global_roll_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/global/roll", 1);
68  pub_histogram_global_pitch_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/global/pitch", 1);
69  pub_histogram_global_yaw_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/global/yaw", 1);
70  pub_histogram_dx_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/dx", 1);
71  pub_histogram_dy_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/dy", 1);
72  pub_histogram_dz_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>("output/histogram/dz", 1);
73  random_generator_ = boost::mt19937(static_cast<unsigned long>(time(0)));
74  // Subscribe
75  sub_polygon_.subscribe(*pnh_, "input/polygon", 10);
76  sub_coefficients_.subscribe(*pnh_, "input/coefficients", 10);
77  sync_polygon_ = boost::make_shared<message_filters::Synchronizer<PolygonSyncPolicy> >(100);
79  sync_polygon_->registerCallback(boost::bind(&PlaneSupportedCuboidEstimator::polygonCallback, this, _1, _2));
80  sub_cloud_ = pnh_->subscribe("input", 1, &PlaneSupportedCuboidEstimator::cloudCallback, this);
81  sub_fast_cloud_ = pnh_->subscribe("fast_input", 1, &PlaneSupportedCuboidEstimator::fastCloudCallback,
82  this);
83  srv_reset_ = pnh_->advertiseService("reset", &PlaneSupportedCuboidEstimator::resetCallback, this);
84 
86  }
87 
89  {
90 
91  }
92 
94  {
95 
96  }
97 
99  const Particle& p,
100  const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& polygons)
101  {
102  size_t min_index = 0;
103  double min_distance = DBL_MAX;
104  Eigen::Vector3f inp = p.getVector3fMap();
105  for (size_t i = 0; i < polygons.size(); i++) {
107  Eigen::Vector3f p;
108  polygon->project(inp, p);
109  double d = (p - inp).norm();
110  if (d < min_distance) {
111  min_distance = d;
112  min_index = i;
113  }
114  }
115  return min_index;
116  }
117 
119  ParticleCloud::Ptr particles)
120  {
121  if (latest_polygon_msg_->polygons.size() == 0) {
122  NODELET_ERROR("no valid polygons, skip update relationship");
123  return;
124  }
125 
126  // The order of convexes and polygons_ should be same
127  // because it is inside of critical section.
128  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes(latest_polygon_msg_->polygons.size());
129  for (size_t i = 0; i < latest_polygon_msg_->polygons.size(); i++) {
131  polygon->decomposeToTriangles();
132  convexes[i] = polygon;
133  }
134 
135 #ifdef _OPENMP
136 #pragma omp parallel for
137 #endif
138  // Second, compute distances and assing polygons.
139  for (size_t i = 0; i < particles->points.size(); i++) {
140  size_t nearest_index = getNearestPolygon(particles->points[i], convexes);
141  //particles->points[i].plane = polygons[nearest_index];
142  particles->points[i].plane_index = (int)nearest_index;
143  }
144  }
145 
147  const sensor_msgs::PointCloud2::ConstPtr& msg)
148  {
149  boost::mutex::scoped_lock lock(mutex_);
150  if (!tracker_) {
151  return;
152  }
153  ParticleCloud::Ptr particles = tracker_->getParticles();
154  Eigen::Vector4f center;
155  pcl::compute3DCentroid(*particles, center);
156  if (center.norm() < fast_cloud_threshold_) {
157  estimate(msg);
158  }
159  }
160 
162  const sensor_msgs::PointCloud2::ConstPtr& msg)
163  {
164  // Update polygons_ vector
165  polygons_.clear();
166  for (size_t i = 0; i < latest_polygon_msg_->polygons.size(); i++) {
168  polygon->decomposeToTriangles();
169  polygons_.push_back(polygon);
170  }
171 
172  try {
173  // viewpoint
174  tf::StampedTransform transform
175  = lookupTransformWithDuration(tf_, sensor_frame_, msg->header.frame_id,
176  ros::Time(0.0),
177  ros::Duration(1.0));
179 
180  if (!tracker_) {
181  NODELET_INFO("initTracker");
182  pcl::PointCloud<pcl::tracking::ParticleCuboid>::Ptr particles = initParticles();
186  tracker_->setParticles(particles);
187  tracker_->setParticleNum(particle_num_);
188  }
189  else {
190  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
191  pcl::fromROSMsg(*msg, *cloud);
192  tracker_->setInputCloud(cloud);
193  // Before call compute() method, we prepare candidate_cloud_ for
194  // weight phase.
195  candidate_cloud_.reset(new pcl::PointCloud<pcl::PointXYZ>);
196  std::set<int> all_indices;
197  for (size_t i = 0; i < latest_polygon_msg_->polygons.size(); i++) {
199  pcl::ExtractPolygonalPrismData<pcl::PointXYZ> prism_extract;
200  pcl::PointCloud<pcl::PointXYZ>::Ptr
201  boundaries (new pcl::PointCloud<pcl::PointXYZ>);
202  polygon->boundariesToPointCloud<pcl::PointXYZ>(*boundaries);
203  boundaries->points.push_back(boundaries->points[0]);
204  prism_extract.setInputCloud(cloud);
205  prism_extract.setViewPoint(viewpoint_[0], viewpoint_[1], viewpoint_[2]);
206  prism_extract.setHeightLimits(init_local_position_z_min_, init_local_position_z_max_);
207  prism_extract.setInputPlanarHull(boundaries);
208  pcl::PointIndices output_indices;
209  prism_extract.segment(output_indices);
210  for (size_t i = 0; i < output_indices.indices.size(); i++) {
211  all_indices.insert(output_indices.indices[i]);
212  }
213  }
214  pcl::ExtractIndices<pcl::PointXYZ> ex;
215  ex.setInputCloud(cloud);
216  pcl::PointIndices::Ptr indices (new pcl::PointIndices);
217  indices->indices = std::vector<int>(all_indices.begin(), all_indices.end());
218  ex.setIndices(indices);
219  ex.filter(*candidate_cloud_);
220  sensor_msgs::PointCloud2 ros_candidate_cloud;
221  pcl::toROSMsg(*candidate_cloud_, ros_candidate_cloud);
222  ros_candidate_cloud.header = msg->header;
223  pub_candidate_cloud_.publish(ros_candidate_cloud);
224  // check the number of candidate points
225  if (candidate_cloud_->points.size() == 0) {
226  NODELET_ERROR("No candidate cloud");
227  return;
228  }
229  tree_.setInputCloud(candidate_cloud_);
231  // Compute assignment between particles and polygons
232  NODELET_INFO("polygon updated");
234  }
235  ROS_INFO("start tracker_->compute()");
236  tracker_->compute();
237  ROS_INFO("done tracker_->compute()");
238  Particle result = tracker_->getResult();
239  jsk_recognition_msgs::BoundingBoxArray box_array;
240  box_array.header = msg->header;
241  box_array.boxes.push_back(result.toBoundingBox());
242  box_array.boxes[0].header = msg->header;
243  pub_result_.publish(box_array);
244  geometry_msgs::PoseStamped pose;
245  pose.pose = box_array.boxes[0].pose;
246  pose.header = box_array.header;
248  }
249  support_plane_updated_ = false;
250  ParticleCloud::Ptr particles = tracker_->getParticles();
251  // Publish histograms
252  publishHistogram(particles, 0, pub_histogram_global_x_, msg->header);
253  publishHistogram(particles, 1, pub_histogram_global_y_, msg->header);
254  publishHistogram(particles, 2, pub_histogram_global_z_, msg->header);
255  publishHistogram(particles, 3, pub_histogram_global_roll_, msg->header);
256  publishHistogram(particles, 4, pub_histogram_global_pitch_, msg->header);
257  publishHistogram(particles, 5, pub_histogram_global_yaw_, msg->header);
258  publishHistogram(particles, 6, pub_histogram_dx_, msg->header);
259  publishHistogram(particles, 7, pub_histogram_dy_, msg->header);
260  publishHistogram(particles, 8, pub_histogram_dz_, msg->header);
261  // Publish particles
262  sensor_msgs::PointCloud2 ros_particles;
263  pcl::toROSMsg(*particles, ros_particles);
264  ros_particles.header = msg->header;
265  pub_particles_.publish(ros_particles);
266  }
267  catch (tf2::TransformException& e) {
268  ROS_ERROR("tf exception");
269  }
270  }
271 
273  const sensor_msgs::PointCloud2::ConstPtr& msg)
274  {
275  boost::mutex::scoped_lock lock(mutex_);
276  NODELET_INFO("cloudCallback");
278  NODELET_WARN("Not yet polygon is available");
279  return;
280  }
281 
282  if (!tracker_) {
283  NODELET_INFO("initTracker");
284  // Update polygons_ vector
285  polygons_.clear();
286  for (size_t i = 0; i < latest_polygon_msg_->polygons.size(); i++) {
288  polygons_.push_back(polygon);
289  }
290  try {
291  // viewpoint
292  tf::StampedTransform transform
293  = lookupTransformWithDuration(tf_, sensor_frame_, msg->header.frame_id,
294  ros::Time(0.0),
295  ros::Duration(1.0));
297  }
298  catch (tf2::TransformException& e) {
299  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
300  return;
301  }
302 
303  ParticleCloud::Ptr particles = initParticles();
307  tracker_->setParticles(particles);
308  tracker_->setParticleNum(particle_num_);
309  support_plane_updated_ = false;
310  // Publish histograms
311  publishHistogram(particles, 0, pub_histogram_global_x_, msg->header);
312  publishHistogram(particles, 1, pub_histogram_global_y_, msg->header);
313  publishHistogram(particles, 2, pub_histogram_global_z_, msg->header);
314  publishHistogram(particles, 3, pub_histogram_global_roll_, msg->header);
315  publishHistogram(particles, 4, pub_histogram_global_pitch_, msg->header);
316  publishHistogram(particles, 5, pub_histogram_global_yaw_, msg->header);
317  publishHistogram(particles, 6, pub_histogram_dx_, msg->header);
318  publishHistogram(particles, 7, pub_histogram_dy_, msg->header);
319  publishHistogram(particles, 8, pub_histogram_dz_, msg->header);
320  // Publish particles
321  sensor_msgs::PointCloud2 ros_particles;
322  pcl::toROSMsg(*particles, ros_particles);
323  ros_particles.header = msg->header;
324  pub_particles_.publish(ros_particles);
325 
326  }
327  else {
328  ParticleCloud::Ptr particles = tracker_->getParticles();
329  Eigen::Vector4f center;
330  pcl::compute3DCentroid(*particles, center);
331  if (center.norm() > fast_cloud_threshold_) {
332  estimate(msg);
333  }
334  }
335  }
336 
338  ParticleCloud::Ptr particles, int index, ros::Publisher& pub, const std_msgs::Header& header)
339  {
340  const double step = 0.001;
341  // Lookup min/max
342  float max_value = -FLT_MAX;
343  float min_value = FLT_MAX;
344  for (size_t i = 0; i < particles->points.size(); i++) {
345  max_value = std::max(max_value, particles->points[i][index]);
346  min_value = std::min(min_value, particles->points[i][index]);
347  }
348  int num = (max_value - min_value) / step + 1;
349  std::vector<unsigned int> bins(num, 0);
350  for (size_t i = 0; i < particles->points.size(); i++) {
351  float value = particles->points[i][index];
352  const int bin_index = (value - min_value) / step;
353  const int min_confirmed_bin_index = std::min(bin_index, num - 1);
354  bins[min_confirmed_bin_index] = bins[min_confirmed_bin_index] + 1;
355  }
356 
357  jsk_recognition_msgs::HistogramWithRange histogram;
358  histogram.header = header;
359  for (size_t i = 0; i < bins.size(); i++) {
360  jsk_recognition_msgs::HistogramWithRangeBin bin;
361  bin.min_value = i * step + min_value;
362  bin.max_value = (i + 1) * step + min_value;
363  bin.count = bins[i];
364  histogram.bins.push_back(bin);
365  }
366  pub.publish(histogram);
367  }
368 
370  {
371  pcl::tracking::ParticleCuboid sampled_particle;
372  // Motion model is tricky.
373  // It's not a tracking problem, so we need to limit noise of motion model
374  // The new particle should satisfy:
375  // 1. within a polygon
376  // 2. within local z range
377  // 3. within local pitch/roll range
378  // 4. within world yaw range
379  // 5. within dx/dy/dz range
380  //sampled_particle = p;
381  sampled_particle.x = randomGaussian(p.x, step_x_variance_, random_generator_);
382  sampled_particle.y = randomGaussian(p.y, step_y_variance_, random_generator_);
383  sampled_particle.z = randomGaussian(p.z, step_z_variance_, random_generator_);
388  min_dx_);
390  min_dy_);
392  min_dz_);
393  sampled_particle.plane_index = p.plane_index;
394  sampled_particle.weight = p.weight;
395  return sampled_particle;
396  }
397 
398  void PlaneSupportedCuboidEstimator::likelihood(pcl::PointCloud<pcl::PointXYZ>::ConstPtr input,
400  {
402  polygons_, latest_polygon_msg_->likelihood,
403  config_);
404  }
405 
407  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
408  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coef_msg)
409  {
410  boost::mutex::scoped_lock lock(mutex_);
411  latest_polygon_msg_ = polygon_msg;
412  latest_coefficients_msg_ = coef_msg;
413  support_plane_updated_ = true;
414  }
415 
416  size_t PlaneSupportedCuboidEstimator::chooseUniformRandomPlaneIndex(const std::vector<Polygon::Ptr>& polygons)
417  {
418  // randomly select plane according to their area
419  std::vector<double> area_table(polygons.size());
420  double sum = 0;
421  for (size_t i = 0; i < latest_polygon_msg_->polygons.size(); i++) {
422  area_table[i] = polygons[i]->area();
424  area_table[i] = area_table[i] * latest_polygon_msg_->likelihood[i];
425  }
426  sum += area_table[i];
427  }
428  double val = randomUniform(0, sum, random_generator_);
429  double bin_start = 0.0;
430  for (size_t i = 0; i < latest_polygon_msg_->polygons.size(); i++) {
431  if (val >= bin_start && val < bin_start + area_table[i]) {
432  return i;
433  }
434  bin_start += area_table[i];
435  }
436  // Unexpected region here
437  NODELET_ERROR("should not reach here, failed to select plane randomly");
438  return 0;
439  }
440 
441  pcl::PointCloud<pcl::tracking::ParticleCuboid>::Ptr PlaneSupportedCuboidEstimator::initParticles()
442  {
443  pcl::PointCloud<pcl::tracking::ParticleCuboid>::Ptr particles (new pcl::PointCloud<pcl::tracking::ParticleCuboid>);
444  particles->points.resize(particle_num_);
445  std::vector<Polygon::Ptr> polygons(latest_polygon_msg_->polygons.size());
446  for (size_t i = 0; i < latest_polygon_msg_->polygons.size(); i++) {
448  polygons[i] = polygon;
449  }
450  for (size_t i = 0; i < particle_num_; i++) {
451  while (true) {
453  size_t plane_i = chooseUniformRandomPlaneIndex(polygons);
454  Polygon::Ptr polygon = polygons[plane_i];
455  Eigen::Vector3f v = polygon->randomSampleLocalPoint(random_generator_);
458  p_local.getVector3fMap() = v;
467  pcl::tracking::ParticleCuboid p_global = p_local * polygon->coordinates();
469  if (p_global.z < init_world_position_z_min_ ||
470  p_global.z > init_world_position_z_max_) {
471  continue;
472  }
473  }
474  p_global.plane_index = plane_i;
475  if (disable_init_pitch_) {
476  p_global.pitch = 0;
477  }
478  if (disable_init_roll_) {
479  p_global.roll = 0;
480  }
481  if (use_global_init_yaw_) {
485  }
486 
487  particles->points[i] = p_global;
488  break;
489  }
490  }
491  return particles;
492  }
493 
495  {
496  boost::mutex::scoped_lock lock(mutex_);
497  config_ = config;
498  init_local_position_z_min_ = config.init_local_position_z_min;
499  init_local_position_z_max_ = config.init_local_position_z_max;
500  use_init_world_position_z_model_ = config.use_init_world_position_z_model;
501  init_world_position_z_min_ = config.init_world_position_z_min;
502  init_world_position_z_max_ = config.init_world_position_z_max;
503  init_local_orientation_roll_mean_ = config.init_local_orientation_roll_mean;
504  init_local_orientation_roll_variance_ = config.init_local_orientation_roll_variance;
505  init_local_orientation_pitch_mean_ = config.init_local_orientation_pitch_mean;
506  init_local_orientation_pitch_variance_ = config.init_local_orientation_pitch_variance;
507  init_local_orientation_yaw_mean_ = config.init_local_orientation_yaw_mean;
508  init_local_orientation_yaw_variance_ = config.init_local_orientation_yaw_variance;
509  use_global_init_yaw_ = config.use_global_init_yaw;
510  init_global_orientation_yaw_mean_ = config.init_global_orientation_yaw_mean;
511  init_global_orientation_yaw_variance_ = config.init_global_orientation_yaw_variance;
512  init_dx_mean_ = config.init_dx_mean;
513  init_dx_variance_ = config.init_dx_variance;
514  init_dy_mean_ = config.init_dy_mean;
515  init_dy_variance_ = config.init_dy_variance;
516  init_dz_mean_ = config.init_dz_mean;
517  init_dz_variance_ = config.init_dz_variance;
518  particle_num_ = config.particle_num;
519  step_x_variance_ = config.step_x_variance;
520  step_y_variance_ = config.step_y_variance;
521  step_z_variance_ = config.step_z_variance;
522  step_roll_variance_ = config.step_roll_variance;
523  step_pitch_variance_ = config.step_pitch_variance;
524  step_yaw_variance_ = config.step_yaw_variance;
525  step_dx_variance_ = config.step_dx_variance;
526  step_dy_variance_ = config.step_dy_variance;
527  step_dz_variance_ = config.step_dz_variance;
528  min_dx_ = config.min_dx;
529  min_dy_ = config.min_dy;
530  min_dz_ = config.min_dz;
531  use_init_polygon_likelihood_ = config.use_init_polygon_likelihood;
532  fast_cloud_threshold_ = config.fast_cloud_threshold;
533  disable_init_roll_ = config.disable_init_roll;
534  disable_init_pitch_ = config.disable_init_pitch;
535  }
536 
537  bool PlaneSupportedCuboidEstimator::resetCallback(std_srvs::EmptyRequest& req,
538  std_srvs::EmptyResponse& res)
539  {
540  boost::mutex::scoped_lock lock(mutex_);
541  latest_polygon_msg_ = jsk_recognition_msgs::PolygonArray::ConstPtr();
542  latest_coefficients_msg_ = jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr();
543  tracker_.reset();
544  return true;
545  }
546 }
547 
d
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
double min(const OneDataStat &d)
wrapper function for min method for boost::function
Definition: one_data_stat.h:94
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &msg)
num
boost::shared_ptr< message_filters::Synchronizer< PolygonSyncPolicy > > sync_polygon_
virtual size_t getNearestPolygon(const Particle &p, const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &polygons)
Compute the nearest polygon to the particle `p&#39;.
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
double max(const OneDataStat &d)
wrapper function for max method for boost::function
virtual void configCallback(Config &config, uint32_t level)
virtual void updateParticlePolygonRelationship(ParticleCloud::Ptr particles)
Compute distances between particles and polygons and assing each particle to the nearest polygon...
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr latest_coefficients_msg_
value
static ConvexPolygon::Ptr fromROSMsgPtr(const geometry_msgs::Polygon &polygon)
pose
int min_index
virtual void publishHistogram(ParticleCloud::Ptr particles, int index, ros::Publisher &pub, const std_msgs::Header &header)
virtual size_t chooseUniformRandomPlaneIndex(const std::vector< Polygon::Ptr > &polygons)
virtual void fastCloudCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
pcl::PointCloud< pcl::PointXYZ >::Ptr candidate_cloud_
static Polygon::Ptr fromROSMsgPtr(const geometry_msgs::Polygon &polygon)
result
jsk_recognition_msgs::BoundingBox toBoundingBox()
#define ROS_INFO(...)
virtual void polygonCallback(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coef_msg)
virtual void likelihood(pcl::PointCloud< pcl::PointXYZ >::ConstPtr input, pcl::tracking::ParticleCuboid &p)
double randomGaussian(double mean, double var, boost::mt19937 &gen)
virtual pcl::PointCloud< pcl::tracking::ParticleCuboid >::Ptr initParticles()
pcl::tracking::ROSCollaborativeParticleFilterTracker< pcl::PointXYZ, pcl::tracking::ParticleCuboid >::Ptr tracker_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
virtual pcl::tracking::ParticleCuboid sample(const pcl::tracking::ParticleCuboid &p)
jsk_recognition_msgs::PolygonArray::ConstPtr latest_polygon_msg_
void vectorTFToEigen(const tf::Vector3 &t, Eigen::Vector3d &e)
#define NODELET_INFO(...)
double computeLikelihood(const pcl::tracking::ParticleCuboid &p, pcl::PointCloud< pcl::PointXYZ >::ConstPtr cloud, pcl::KdTreeFLANN< pcl::PointXYZ > &tree, const Eigen::Vector3f &viewpoint, const std::vector< Polygon::Ptr > &polygons, const std::vector< float > &polygon_likelihood, const Config &config)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
virtual bool resetCallback(std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res)
T sum(T *pf, int length)
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
step
GLfloat v[8][3]
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
static tf::TransformListener * getInstance()
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::PlaneSupportedCuboidEstimator, nodelet::Nodelet)
cloud
#define ROS_ERROR(...)
double randomUniform(double min, double max, boost::mt19937 &gen)
polygons


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47