37 #ifndef JSK_PCL_ROS_PLANE_SUPPORTED_CUBOID_ESTIMATOR_H_
38 #define JSK_PCL_ROS_PLANE_SUPPORTED_CUBOID_ESTIMATOR_H_
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
44 #include <boost/random.hpp>
45 #include <dynamic_reconfigure/server.h>
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>
62 #include <pcl/tracking/tracking.h>
65 #include <pcl/kdtree/kdtree_flann.h>
88 template <
class Config>
90 pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloud,
91 const std::vector<Polygon::Ptr>& planes,
96 if (
p.plane_index == -1) {
100 Eigen::Vector3f projected_point;
101 plane->project(Eigen::Vector3f(
p.getVector3fMap()), projected_point);
102 if (plane->isInside(projected_point)) {
109 float local_z = plane->distanceToPoint(Eigen::Vector3f(
p.getVector3fMap()));
114 template <
class Config>
117 const std::vector<Polygon::Ptr>& planes,
118 const Config& config)
121 if (
config.use_support_plane_angular_likelihood) {
123 double cos_likelihood = (
p.toEigenMatrix().rotation() * Eigen::Vector3f::UnitX()).
dot(plane->getNormal());
125 return pow(std::abs(cos_likelihood),
126 config.support_plane_angular_likelihood_weight_power);
134 template <
class Config>
137 const Config& config)
139 if (
config.use_surface_area_likelihood) {
141 return 1.0 / (1.0 + pow(v,
config.surface_area_error_power));
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)
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();
167 tree.radiusSearch(xyz_point,
r +
config.outlier_distance, candidate_point_indices, candidate_point_distances);
168 if (candidate_point_indices.size() <
config.min_inliers) {
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) {
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) {
199 if (d <=
config.outlier_distance) {
201 error += pow(d,
config.plane_distance_error_power);
208 size_t expected_num =
p.volume() /
config.expected_density /
config.expected_density /
config.expected_density;
210 if (inliers <
config.min_inliers) {
214 double non_inlier_value = 1 / (1 +
error / inliers);
219 double inlier_likelihood = 1 / (1 + pow(expected_num - inliers,
config.inliers_power));
221 return non_inlier_value * inlier_likelihood;
224 return non_inlier_value;
230 template <
class Config>
232 const std::vector<float>& polygon_likelihood,
233 const Config& config)
235 if (
config.use_polygon_likelihood) {
236 return polygon_likelihood[
p.plane_index];
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)
252 double range_likelihood = 1.0;
253 if (
config.use_range_likelihood) {
257 if (range_likelihood == 0.0) {
258 return range_likelihood;
268 class PlaneSupportedCuboidEstimator:
public jsk_topic_tools::DiagnosticNodelet
274 typedef PlaneSupportedCuboidEstimatorConfig
Config;
276 jsk_recognition_msgs::PolygonArray,
286 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
287 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coef_msg);
289 const sensor_msgs::PointCloud2::ConstPtr&
msg);
291 const sensor_msgs::PointCloud2::ConstPtr&
msg);
293 const sensor_msgs::PointCloud2::ConstPtr&
msg);
294 virtual pcl::PointCloud<pcl::tracking::ParticleCuboid>::Ptr
initParticles();
301 virtual void likelihood(pcl::PointCloud<pcl::PointXYZ>::ConstPtr
input,
307 std_srvs::EmptyResponse&
res);
315 const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& polygons);
399 pcl::KdTreeFLANN<pcl::PointXYZ>
tree_;