plane_supported_cuboid_estimator.h
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/or 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 
37 #ifndef JSK_PCL_ROS_PLANE_SUPPORTED_CUBOID_ESTIMATOR_H_
38 #define JSK_PCL_ROS_PLANE_SUPPORTED_CUBOID_ESTIMATOR_H_
39 
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
44 #include <boost/random.hpp>
45 #include <dynamic_reconfigure/server.h>
49 #include <algorithm>
50 
51 
52 // ROS messages
53 #include <jsk_recognition_msgs/PolygonArray.h>
54 #include <jsk_recognition_msgs/BoundingBoxArray.h>
55 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
56 #include <jsk_recognition_msgs/HistogramWithRange.h>
57 #include <jsk_pcl_ros/PlaneSupportedCuboidEstimatorConfig.h>
58 #include <sensor_msgs/PointCloud2.h>
59 #include <std_srvs/Empty.h>
60 
61 // pcl
62 #include <pcl/tracking/tracking.h>
65 #include <pcl/kdtree/kdtree_flann.h>
66 
67 namespace jsk_pcl_ros
68 {
69 
70  // Utility function to compute likelihood
75  inline double binaryLikelihood(double v, double min, double max)
76  {
77  if (v < min) {
78  return 0;
79  }
80  else if (v > max) {
81  return 0;
82  }
83  else {
84  return 1;
85  }
86  }
87 
88  template <class Config>
90  pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloud,
91  const std::vector<Polygon::Ptr>& planes,
92  const Config& config)
93  {
94  double likelihood = 1.0;
95  Polygon::Ptr plane = planes[p.plane_index];
96  if (p.plane_index == -1) {
97  // Do nothing
98  }
99  else {
100  Eigen::Vector3f projected_point;
101  plane->project(Eigen::Vector3f(p.getVector3fMap()), projected_point);
102  if (plane->isInside(projected_point)) {
103  likelihood *= 1.0;
104  }
105  else {
106  likelihood = 0.0;
107  }
108  }
109  float local_z = plane->distanceToPoint(Eigen::Vector3f(p.getVector3fMap()));
110  likelihood *= binaryLikelihood(local_z, config.range_likelihood_local_min_z, config.range_likelihood_local_max_z);
111  return likelihood;
112  }
113 
114  template <class Config>
117  const std::vector<Polygon::Ptr>& planes,
118  const Config& config)
119  {
120  Polygon::Ptr plane = planes[p.plane_index];
121  if (config.use_support_plane_angular_likelihood) {
122  // double cos_likelihood = (p.toEigenMatrix().rotation() * Eigen::Vector3f::UnitZ()).dot(plane->getNormal());
123  double cos_likelihood = (p.toEigenMatrix().rotation() * Eigen::Vector3f::UnitX()).dot(plane->getNormal());
124  // ROS_INFO("cos_likelihood: %f", cos_likelihood);
125  return pow(std::abs(cos_likelihood),
126  config.support_plane_angular_likelihood_weight_power);
127  }
128  else {
129  return 1.0;
130  }
131  }
132 
133 
134  template <class Config>
135  double surfaceAreaLikelihood(
137  const Config& config)
138  {
139  if (config.use_surface_area_likelihood) {
140  double v = p.area();
141  return 1.0 / (1.0 + pow(v, config.surface_area_error_power));
142  }
143  else {
144  return 1.0;
145  }
146  }
147 
148  template <class Config>
151  pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloud,
152  pcl::KdTreeFLANN<pcl::PointXYZ>& tree,
153  const Eigen::Vector3f& viewpoint,
154  const Config& config)
155  {
156  Eigen::Affine3f pose = p.toEigenMatrix();
157  Eigen::Affine3f pose_inv = pose.inverse();
158  const Eigen::Vector3f local_vp = pose_inv * viewpoint;
159  std::vector<int> visible_faces = p.visibleFaceIndices(local_vp);
160  double r = sqrt(p.dx /2 * p.dx/2 + p.dy/2 * p.dy/2 + p.dz/2 * p.dz/2);
161  std::vector<int> candidate_point_indices;
162  std::vector<float> candidate_point_distances;
163  pcl::PointXYZ xyz_point;
164  xyz_point.getVector3fMap() = p.getVector3fMap();
165  size_t inliers = 0;
166  // roughly search near points by kdtree radius search
167  tree.radiusSearch(xyz_point, r + config.outlier_distance, candidate_point_indices, candidate_point_distances);
168  if (candidate_point_indices.size() < config.min_inliers) {
169  return 0;
170  }
171  else {
172  //ROS_INFO("indices: %lu", candidate_point_indices.size());
173  double error = 0.0;
174 
176  std::vector<Polygon::Ptr> faces = cube->faces();
177  for (size_t i = 0; i < candidate_point_indices.size(); i++) {
178  int index = candidate_point_indices[i];
179  Eigen::Vector3f v = cloud->points[index].getVector3fMap();
180  if (config.use_occlusion_likelihood) {
181  double d = p.distanceNearestToPlaneWithOcclusion(v, visible_faces, faces);
182  if (d <= config.outlier_distance) {
183  //error *= 1 / (1 + pow(d, config.plane_distance_error_power));
184  error += pow(d, config.plane_distance_error_power);
185  ++inliers;
186  }
187  }
188  else {
189  Eigen::Vector3f local_v = pose_inv * v;
190  double d = p.signedDistanceToPlane(local_v, p.nearestPlaneIndex(local_v));
191  if (config.use_inside_points_distance_zero) {
192  if (d < 0) {
193  d = 0;
194  }
195  }
196  else {
197  d = std::abs(d);
198  }
199  if (d <= config.outlier_distance) {
200  //error *= 1 / (1 + pow(d, config.plane_distance_error_power));
201  error += pow(d, config.plane_distance_error_power);
202  ++inliers;
203  }
204  }
205  }
206  // ROS_INFO("inliers: %lu", inliers);
207  // ROS_INFO("error: %f", error);
208  size_t expected_num = p.volume() / config.expected_density / config.expected_density / config.expected_density;
209  // ROS_INFO("expected: %lu", expected_num);
210  if (inliers < config.min_inliers) {
211  return 0;
212  }
213  else {
214  double non_inlier_value = 1 / (1 + error / inliers);
215  if (config.use_inliers) {
216  // how to compute expected inliers...?
217  // double inliers_err = std::abs(p.volume() / config.expected_density - inliers);
218  // return non_inlier_value * (1 / (1 + pow(inliers_err, config.inliers_power)));
219  double inlier_likelihood = 1 / (1 + pow(expected_num - inliers, config.inliers_power));
220  // ROS_INFO("inlier likelihood: %f", inlier_likelihood);
221  return non_inlier_value * inlier_likelihood;
222  }
223  else {
224  return non_inlier_value;
225  }
226  }
227  }
228  }
229 
230  template <class Config>
232  const std::vector<float>& polygon_likelihood,
233  const Config& config)
234  {
235  if (config.use_polygon_likelihood) {
236  return polygon_likelihood[p.plane_index];
237  }
238  else {
239  return 1.0;
240  }
241  }
242 
243  template <class Config>
245  pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloud,
246  pcl::KdTreeFLANN<pcl::PointXYZ>& tree,
247  const Eigen::Vector3f& viewpoint,
248  const std::vector<Polygon::Ptr>& polygons,
249  const std::vector<float>& polygon_likelihood,
250  const Config& config)
251  {
252  double range_likelihood = 1.0;
253  if (config.use_range_likelihood) {
254  range_likelihood = rangeLikelihood(p, cloud, polygons, config);
255  }
256  //p.weight = std::abs(p.z);
257  if (range_likelihood == 0.0) {
258  return range_likelihood;
259  }
260  else {
261  return (range_likelihood * distanceFromPlaneBasedError(p, cloud, tree, viewpoint, config)
262  * supportPlaneAngularLikelihood(p, polygons, config)
264  * planeLikelihood(p, polygon_likelihood, config));
265  }
266  }
267 
268  class PlaneSupportedCuboidEstimator: public jsk_topic_tools::DiagnosticNodelet
269  {
270  public:
272  typedef pcl::PointCloud<Particle> ParticleCloud;
274  typedef PlaneSupportedCuboidEstimatorConfig Config;
276  jsk_recognition_msgs::PolygonArray,
277  jsk_recognition_msgs::ModelCoefficientsArray> PolygonSyncPolicy;
278 
279  PlaneSupportedCuboidEstimator(): DiagnosticNodelet("PlaneSupportedCuboidEstimator") {}
281  protected:
282  virtual void onInit();
283  virtual void subscribe();
284  virtual void unsubscribe();
285  virtual void polygonCallback(
286  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
287  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coef_msg);
288  virtual void cloudCallback(
289  const sensor_msgs::PointCloud2::ConstPtr& msg);
290  virtual void estimate(
291  const sensor_msgs::PointCloud2::ConstPtr& msg);
292  virtual void fastCloudCallback(
293  const sensor_msgs::PointCloud2::ConstPtr& msg);
294  virtual pcl::PointCloud<pcl::tracking::ParticleCuboid>::Ptr initParticles();
295  virtual size_t chooseUniformRandomPlaneIndex(const std::vector<Polygon::Ptr>& polygons);
296  virtual void configCallback(Config& config, uint32_t level);
297 
298  // For particle filtering
300  // Likelihood
301  virtual void likelihood(pcl::PointCloud<pcl::PointXYZ>::ConstPtr input,
303  virtual void publishHistogram(ParticleCloud::Ptr particles, int index,
305  const std_msgs::Header& header);
306  virtual bool resetCallback(std_srvs::EmptyRequest& req,
307  std_srvs::EmptyResponse& res);
308 
313  virtual size_t getNearestPolygon(
314  const Particle& p,
315  const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& polygons);
323  virtual void updateParticlePolygonRelationship(ParticleCloud::Ptr particles);
344  jsk_recognition_msgs::PolygonArray::ConstPtr latest_polygon_msg_;
345  jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr latest_coefficients_msg_;
346  pcl::PointCloud<pcl::PointXYZ>::Ptr candidate_cloud_;
348  // Parameters for initialization of particles
349  // local position z is sampled by uniform distribution
350  Config config_;
365 
368 
375 
380  double step_pitch_variance_;
381  double step_yaw_variance_;
385 
386  double min_dx_;
387  double min_dy_;
388  double min_dz_;
392  std::string sensor_frame_;
393  boost::mt19937 random_generator_;
395  Eigen::Vector3f viewpoint_;
398  std::vector<Polygon::Ptr> polygons_;
399  pcl::KdTreeFLANN<pcl::PointXYZ> tree_;
400  private:
401  };
402 }
403 
404 #endif
jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_roll_
ros::Publisher pub_histogram_global_roll_
Definition: plane_supported_cuboid_estimator.h:365
jsk_pcl_ros::PlaneSupportedCuboidEstimator::particle_num_
int particle_num_
Definition: plane_supported_cuboid_estimator.h:423
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_global_orientation_yaw_variance_
double init_global_orientation_yaw_variance_
Definition: plane_supported_cuboid_estimator.h:396
jsk_pcl_ros::PlaneSupportedCuboidEstimator::estimate
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: plane_supported_cuboid_estimator_nodelet.cpp:172
jsk_pcl_ros::PlaneSupportedCuboidEstimator::sync_polygon_
boost::shared_ptr< message_filters::Synchronizer< PolygonSyncPolicy > > sync_polygon_
Definition: plane_supported_cuboid_estimator.h:375
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dy_variance_
double init_dy_variance_
Definition: plane_supported_cuboid_estimator.h:404
jsk_pcl_ros::PlaneSupportedCuboidEstimator::tf_
tf::TransformListener * tf_
Definition: plane_supported_cuboid_estimator.h:426
jsk_pcl_ros::PlaneSupportedCuboidEstimator::latest_polygon_msg_
jsk_recognition_msgs::PolygonArray::ConstPtr latest_polygon_msg_
Definition: plane_supported_cuboid_estimator.h:376
ros::Publisher
jsk_pcl_ros::PlaneSupportedCuboidEstimator::sub_polygon_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
Definition: plane_supported_cuboid_estimator.h:373
boost::shared_ptr< Cube >
i
int i
jsk_pcl_ros::PlaneSupportedCuboidEstimator::chooseUniformRandomPlaneIndex
virtual size_t chooseUniformRandomPlaneIndex(const std::vector< Polygon::Ptr > &polygons)
Definition: plane_supported_cuboid_estimator_nodelet.cpp:427
sample_simulate_tabletop_cloud.header
header
Definition: sample_simulate_tabletop_cloud.py:162
jsk_pcl_ros::planeLikelihood
double planeLikelihood(const pcl::tracking::ParticleCuboid &p, const std::vector< float > &polygon_likelihood, const Config &config)
Definition: plane_supported_cuboid_estimator.h:263
jsk_pcl_ros::PlaneSupportedCuboidEstimator::onInit
virtual void onInit()
Definition: plane_supported_cuboid_estimator_nodelet.cpp:51
jsk_pcl_ros::PlaneSupportedCuboidEstimator::likelihood
virtual void likelihood(pcl::PointCloud< pcl::PointXYZ >::ConstPtr input, pcl::tracking::ParticleCuboid &p)
Definition: plane_supported_cuboid_estimator_nodelet.cpp:409
jsk_pcl_ros::PlaneSupportedCuboidEstimator::Particle
pcl::tracking::ParticleCuboid Particle
Definition: plane_supported_cuboid_estimator.h:303
p
p
jsk_pcl_ros::PlaneSupportedCuboidEstimator::min_dz_
double min_dz_
Definition: plane_supported_cuboid_estimator.h:420
jsk_pcl_ros::PlaneSupportedCuboidEstimator::latest_coefficients_msg_
jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr latest_coefficients_msg_
Definition: plane_supported_cuboid_estimator.h:377
jsk_pcl_ros::PlaneSupportedCuboidEstimator::sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
Definition: plane_supported_cuboid_estimator.h:374
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_global_orientation_yaw_mean_
double init_global_orientation_yaw_mean_
Definition: plane_supported_cuboid_estimator.h:395
jsk_pcl_ros::PlaneSupportedCuboidEstimator::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: plane_supported_cuboid_estimator_nodelet.cpp:505
jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_candidate_cloud_
ros::Publisher pub_candidate_cloud_
Definition: plane_supported_cuboid_estimator.h:361
jsk_pcl_ros::PlaneSupportedCuboidEstimator::tree_
pcl::KdTreeFLANN< pcl::PointXYZ > tree_
Definition: plane_supported_cuboid_estimator.h:431
jsk_pcl_ros::min
double min(const OneDataStat &d)
wrapper function for min method for boost::function
Definition: one_data_stat.h:126
cube
Cube cube(Eigen::Vector3f(1, 0, 0), Eigen::Quaternionf(0.108755, 0.088921, 0.108755, 0.984092), Eigen::Vector3f(0.3, 0.3, 0.3))
jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_y_variance_
double step_y_variance_
Definition: plane_supported_cuboid_estimator.h:409
geo_util.h
jsk_pcl_ros::PlaneSupportedCuboidEstimator::min_dy_
double min_dy_
Definition: plane_supported_cuboid_estimator.h:419
likelihood
likelihood
jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_y_
ros::Publisher pub_histogram_global_y_
Definition: plane_supported_cuboid_estimator.h:363
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dy_mean_
double init_dy_mean_
Definition: plane_supported_cuboid_estimator.h:403
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dz_mean_
double init_dz_mean_
Definition: plane_supported_cuboid_estimator.h:405
attention_pose_set.pub
pub
Definition: attention_pose_set.py:8
jsk_pcl_ros::PlaneSupportedCuboidEstimator::disable_init_roll_
bool disable_init_roll_
Definition: plane_supported_cuboid_estimator.h:398
time_synchronizer.h
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_yaw_variance_
double init_local_orientation_yaw_variance_
Definition: plane_supported_cuboid_estimator.h:393
faces
GLint faces[6][4]
simple_particle_filter.h
jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_dx_
ros::Publisher pub_histogram_dx_
Definition: plane_supported_cuboid_estimator.h:368
tf_listener_singleton.h
jsk_pcl_ros::binaryLikelihood
double binaryLikelihood(double v, double min, double max)
return 1.0 if v satisfies min < v < max, return 0 otherwise.
Definition: plane_supported_cuboid_estimator.h:107
jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_dx_variance_
double step_dx_variance_
Definition: plane_supported_cuboid_estimator.h:414
jsk_pcl_ros::distanceFromPlaneBasedError
double distanceFromPlaneBasedError(const pcl::tracking::ParticleCuboid &p, pcl::PointCloud< pcl::PointXYZ >::ConstPtr cloud, pcl::KdTreeFLANN< pcl::PointXYZ > &tree, const Eigen::Vector3f &viewpoint, const Config &config)
Definition: plane_supported_cuboid_estimator.h:181
jsk_pcl_ros::rangeLikelihood
double rangeLikelihood(const pcl::tracking::ParticleCuboid &p, pcl::PointCloud< pcl::PointXYZ >::ConstPtr cloud, const std::vector< Polygon::Ptr > &planes, const Config &config)
Definition: plane_supported_cuboid_estimator.h:121
cloud
cloud
jsk_pcl_ros::PlaneSupportedCuboidEstimator::srv_reset_
ros::ServiceServer srv_reset_
Definition: plane_supported_cuboid_estimator.h:372
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray >
ros::ServiceServer
particle_cuboid.h
jsk_pcl_ros::PlaneSupportedCuboidEstimator::polygonCallback
virtual void polygonCallback(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coef_msg)
Definition: plane_supported_cuboid_estimator_nodelet.cpp:417
jsk_pcl_ros::PlaneSupportedCuboidEstimator::use_global_init_yaw_
bool use_global_init_yaw_
Definition: plane_supported_cuboid_estimator.h:394
pose
pose
jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_z_variance_
double step_z_variance_
Definition: plane_supported_cuboid_estimator.h:410
jsk_pcl_ros::PlaneSupportedCuboidEstimator::viewpoint_
Eigen::Vector3f viewpoint_
Definition: plane_supported_cuboid_estimator.h:427
jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_yaw_
ros::Publisher pub_histogram_global_yaw_
Definition: plane_supported_cuboid_estimator.h:367
jsk_pcl_ros::PlaneSupportedCuboidEstimator::PlaneSupportedCuboidEstimator
PlaneSupportedCuboidEstimator()
Definition: plane_supported_cuboid_estimator.h:311
jsk_pcl_ros::PlaneSupportedCuboidEstimator::getNearestPolygon
virtual size_t getNearestPolygon(const Particle &p, const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &polygons)
Compute the nearest polygon to the particle ā€˜p’.
Definition: plane_supported_cuboid_estimator_nodelet.cpp:109
jsk_pcl_ros::PlaneSupportedCuboidEstimator::Config
PlaneSupportedCuboidEstimatorConfig Config
Definition: plane_supported_cuboid_estimator.h:306
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_roll_variance_
double init_local_orientation_roll_variance_
Definition: plane_supported_cuboid_estimator.h:389
tree
tree
jsk_pcl_ros::PlaneSupportedCuboidEstimator::tracker_
pcl::tracking::ROSCollaborativeParticleFilterTracker< pcl::PointXYZ, pcl::tracking::ParticleCuboid >::Ptr tracker_
Definition: plane_supported_cuboid_estimator.h:429
jsk_pcl_ros::PlaneSupportedCuboidEstimator::fastCloudCallback
virtual void fastCloudCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: plane_supported_cuboid_estimator_nodelet.cpp:157
pcl::tracking::ParticleCuboid
Definition: particle_cuboid.h:134
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::PlaneSupportedCuboidEstimator::updateParticlePolygonRelationship
virtual void updateParticlePolygonRelationship(ParticleCloud::Ptr particles)
Compute distances between particles and polygons and assing each particle to the nearest polygon....
Definition: plane_supported_cuboid_estimator_nodelet.cpp:129
jsk_pcl_ros::PlaneSupportedCuboidEstimator::use_init_world_position_z_model_
bool use_init_world_position_z_model_
Definition: plane_supported_cuboid_estimator.h:385
jsk_pcl_ros::PlaneSupportedCuboidEstimator::unsubscribe
virtual void unsubscribe()
Definition: plane_supported_cuboid_estimator_nodelet.cpp:104
jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_dz_variance_
double step_dz_variance_
Definition: plane_supported_cuboid_estimator.h:416
subscriber.h
jsk_pcl_ros::PlaneSupportedCuboidEstimator::sub_cloud_
ros::Subscriber sub_cloud_
Definition: plane_supported_cuboid_estimator.h:357
jsk_pcl_ros::PlaneSupportedCuboidEstimator::sensor_frame_
std::string sensor_frame_
Definition: plane_supported_cuboid_estimator.h:424
jsk_pcl_ros::PlaneSupportedCuboidEstimator::mutex_
boost::mutex mutex_
Definition: plane_supported_cuboid_estimator.h:356
jsk_pcl_ros::PlaneSupportedCuboidEstimator::fast_cloud_threshold_
double fast_cloud_threshold_
Definition: plane_supported_cuboid_estimator.h:421
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_position_z_min_
double init_local_position_z_min_
Definition: plane_supported_cuboid_estimator.h:383
jsk_pcl_ros::PlaneSupportedCuboidEstimator::~PlaneSupportedCuboidEstimator
virtual ~PlaneSupportedCuboidEstimator()
Definition: plane_supported_cuboid_estimator_nodelet.cpp:88
jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_z_
ros::Publisher pub_histogram_global_z_
Definition: plane_supported_cuboid_estimator.h:364
jsk_pcl_ros::PlaneSupportedCuboidEstimator::publishHistogram
virtual void publishHistogram(ParticleCloud::Ptr particles, int index, ros::Publisher &pub, const std_msgs::Header &header)
Definition: plane_supported_cuboid_estimator_nodelet.cpp:348
attention_pose_set.r
r
Definition: attention_pose_set.py:9
jsk_pcl_ros::PlaneSupportedCuboidEstimator::subscribe
virtual void subscribe()
Definition: plane_supported_cuboid_estimator_nodelet.cpp:99
jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_dz_
ros::Publisher pub_histogram_dz_
Definition: plane_supported_cuboid_estimator.h:370
d
d
jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_result_
ros::Publisher pub_result_
Definition: plane_supported_cuboid_estimator.h:359
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_world_position_z_max_
double init_world_position_z_max_
Definition: plane_supported_cuboid_estimator.h:387
jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_result_pose_
ros::Publisher pub_result_pose_
Definition: plane_supported_cuboid_estimator.h:371
jsk_pcl_ros::computeLikelihood
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)
Definition: plane_supported_cuboid_estimator.h:276
jsk_pcl_ros::supportPlaneAngularLikelihood
double supportPlaneAngularLikelihood(const pcl::tracking::ParticleCuboid &p, const std::vector< Polygon::Ptr > &planes, const Config &config)
Definition: plane_supported_cuboid_estimator.h:147
jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_particles_
ros::Publisher pub_particles_
Definition: plane_supported_cuboid_estimator.h:360
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_yaw_mean_
double init_local_orientation_yaw_mean_
Definition: plane_supported_cuboid_estimator.h:392
jsk_pcl_ros::PlaneSupportedCuboidEstimator::config_
Config config_
Definition: plane_supported_cuboid_estimator.h:382
pcl_conversion_util.h
jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_roll_variance_
double step_roll_variance_
Definition: plane_supported_cuboid_estimator.h:411
jsk_pcl_ros::PlaneSupportedCuboidEstimator::resetCallback
virtual bool resetCallback(std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res)
Definition: plane_supported_cuboid_estimator_nodelet.cpp:548
jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_dy_
ros::Publisher pub_histogram_dy_
Definition: plane_supported_cuboid_estimator.h:369
jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_pitch_
ros::Publisher pub_histogram_global_pitch_
Definition: plane_supported_cuboid_estimator.h:366
error
pointer error(enum errorcode ec,...) pointer error(va_alist) va_dcl
jsk_pcl_ros::PlaneSupportedCuboidEstimator::min_dx_
double min_dx_
Definition: plane_supported_cuboid_estimator.h:418
dot
T dot(T *pf1, T *pf2, int length)
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_pitch_mean_
double init_local_orientation_pitch_mean_
Definition: plane_supported_cuboid_estimator.h:390
jsk_pcl_ros::PlaneSupportedCuboidEstimator::candidate_cloud_
pcl::PointCloud< pcl::PointXYZ >::Ptr candidate_cloud_
Definition: plane_supported_cuboid_estimator.h:378
jsk_pcl_ros::PlaneSupportedCuboidEstimator::support_plane_updated_
bool support_plane_updated_
Definition: plane_supported_cuboid_estimator.h:428
sqrt
double sqrt()
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dx_mean_
double init_dx_mean_
Definition: plane_supported_cuboid_estimator.h:401
jsk_pcl_ros::PlaneSupportedCuboidEstimator::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: plane_supported_cuboid_estimator.h:379
jsk_pcl_ros::PlaneSupportedCuboidEstimator::random_generator_
boost::mt19937 random_generator_
Definition: plane_supported_cuboid_estimator.h:425
jsk_pcl_ros::PlaneSupportedCuboidEstimator::Ptr
boost::shared_ptr< PlaneSupportedCuboidEstimator > Ptr
Definition: plane_supported_cuboid_estimator.h:305
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_position_z_max_
double init_local_position_z_max_
Definition: plane_supported_cuboid_estimator.h:384
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_pitch_variance_
double init_local_orientation_pitch_variance_
Definition: plane_supported_cuboid_estimator.h:391
jsk_pcl_ros::PlaneSupportedCuboidEstimator::disable_init_pitch_
bool disable_init_pitch_
Definition: plane_supported_cuboid_estimator.h:399
tf::TransformListener
index
unsigned int index
synchronizer.h
jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_x_
ros::Publisher pub_histogram_global_x_
Definition: plane_supported_cuboid_estimator.h:362
jsk_recognition_utils::Cube::faces
std::vector< Polygon::Ptr > faces()
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::PlaneSupportedCuboidEstimator::sample
virtual pcl::tracking::ParticleCuboid sample(const pcl::tracking::ParticleCuboid &p)
Definition: plane_supported_cuboid_estimator_nodelet.cpp:380
jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_x_variance_
double step_x_variance_
Definition: plane_supported_cuboid_estimator.h:408
jsk_pcl_ros::PlaneSupportedCuboidEstimator::polygons_
std::vector< Polygon::Ptr > polygons_
Definition: plane_supported_cuboid_estimator.h:430
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dx_variance_
double init_dx_variance_
Definition: plane_supported_cuboid_estimator.h:402
jsk_pcl_ros::PlaneSupportedCuboidEstimator::sub_fast_cloud_
ros::Subscriber sub_fast_cloud_
Definition: plane_supported_cuboid_estimator.h:358
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
message_filters::sync_policies::ExactTime
jsk_pcl_ros::PlaneSupportedCuboidEstimator::initParticles
virtual pcl::PointCloud< pcl::tracking::ParticleCuboid >::Ptr initParticles()
Definition: plane_supported_cuboid_estimator_nodelet.cpp:452
jsk_pcl_ros::surfaceAreaLikelihood
double surfaceAreaLikelihood(const pcl::tracking::ParticleCuboid &p, const Config &config)
Definition: plane_supported_cuboid_estimator.h:167
jsk_recognition_utils::Polygon::Ptr
boost::shared_ptr< Polygon > Ptr
jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_pitch_variance_
double step_pitch_variance_
Definition: plane_supported_cuboid_estimator.h:412
config
config
jsk_pcl_ros::PlaneSupportedCuboidEstimator::cloudCallback
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: plane_supported_cuboid_estimator_nodelet.cpp:283
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_world_position_z_min_
double init_world_position_z_min_
Definition: plane_supported_cuboid_estimator.h:386
jsk_pcl_ros::PlaneSupportedCuboidEstimator::ParticleCloud
pcl::PointCloud< Particle > ParticleCloud
Definition: plane_supported_cuboid_estimator.h:304
sample_pointcloud_localization_client.req
req
Definition: sample_pointcloud_localization_client.py:15
jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_yaw_variance_
double step_yaw_variance_
Definition: plane_supported_cuboid_estimator.h:413
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_roll_mean_
double init_local_orientation_roll_mean_
Definition: plane_supported_cuboid_estimator.h:388
jsk_pcl_ros::max
double max(const OneDataStat &d)
wrapper function for max method for boost::function
Definition: one_data_stat.h:135
v
GLfloat v[8][3]
sample_empty_service_caller.res
res
Definition: sample_empty_service_caller.py:14
ros::Subscriber
jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dz_variance_
double init_dz_variance_
Definition: plane_supported_cuboid_estimator.h:406
jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_dy_variance_
double step_dy_variance_
Definition: plane_supported_cuboid_estimator.h:415
jsk_pcl_ros::PlaneSupportedCuboidEstimator::PolygonSyncPolicy
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > PolygonSyncPolicy
Definition: plane_supported_cuboid_estimator.h:309
jsk_pcl_ros::PlaneSupportedCuboidEstimator::use_init_polygon_likelihood_
bool use_init_polygon_likelihood_
Definition: plane_supported_cuboid_estimator.h:422


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:12:12