43 #include <pcl/common/centroid.h>
44 #include <pcl/features/boundary.h>
45 #include <pcl/filters/extract_indices.h>
46 #include <pcl/filters/project_inliers.h>
47 #include <pcl/sample_consensus/method_types.h>
48 #include <pcl/sample_consensus/model_types.h>
49 #include <pcl/segmentation/sac_segmentation.h>
56 DiagnosticNodelet::onInit();
58 srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
59 dynamic_reconfigure::Server<Config>::CallbackType
f =
63 pub_class_ = advertise<jsk_recognition_msgs::ClassificationResult>(*pnh_,
"output", 1);
65 advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_,
"debug/boundary_indices", 1);
67 advertise<sensor_msgs::PointCloud2>(*pnh_,
"debug/projected_cloud", 1);
90 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(
queue_size_);
110 if (
config.sac_radius_limit_min <
config.sac_radius_limit_max) {
123 if (isSubscribed()) {
132 const sensor_msgs::PointCloud2::ConstPtr& ros_normal,
133 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& ros_indices,
134 const jsk_recognition_msgs::PolygonArray::ConstPtr& ros_polygons)
158 const sensor_msgs::PointCloud2::ConstPtr& ros_normal,
159 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& ros_indices,
160 const jsk_recognition_msgs::PolygonArray::ConstPtr& ros_polygons)
164 if (!
checkFrameId(ros_cloud, ros_normal, ros_indices, ros_polygons))
return;
166 pcl::PointCloud<PointT>::Ptr
input(
new pcl::PointCloud<PointT>);
169 pcl::PointCloud<pcl::Normal>::Ptr normal(
new pcl::PointCloud<pcl::Normal>);
172 pcl::ExtractIndices<PointT> ext_input;
173 ext_input.setInputCloud(
input);
174 pcl::ExtractIndices<pcl::Normal> ext_normal;
175 ext_normal.setInputCloud(normal);
177 std::vector<jsk_recognition_utils::Polygon::Ptr>
polygons
180 jsk_recognition_msgs::ClassificationResult
result;
181 result.header = ros_cloud->header;
182 result.classifier =
"primitive_shape_classifier";
183 result.target_names.push_back(
"box");
184 result.target_names.push_back(
"circle");
185 result.target_names.push_back(
"other");
187 pcl::PointCloud<PointT>::Ptr projected_cloud(
new pcl::PointCloud<PointT>);
188 std::vector<pcl::PointIndices::Ptr> boundary_indices;
191 for (
size_t i = 0;
i < ros_indices->cluster_indices.size(); ++
i)
193 pcl::PointIndices::Ptr indices(
new pcl::PointIndices);
194 indices->indices = ros_indices->cluster_indices[
i].indices;
195 NODELET_DEBUG_STREAM(
"Estimating cluster #" << i <<
" (" << indices->indices.size() <<
" points)");
197 pcl::PointCloud<PointT>::Ptr cluster_cloud(
new pcl::PointCloud<PointT>);
198 ext_input.setIndices(indices);
199 ext_input.filter(*cluster_cloud);
201 pcl::PointCloud<pcl::Normal>::Ptr cluster_normal(
new pcl::PointCloud<pcl::Normal>);
202 ext_normal.setIndices(indices);
203 ext_normal.filter(*cluster_normal);
205 pcl::ModelCoefficients::Ptr support_plane(
new pcl::ModelCoefficients);
212 pcl::PointIndices::Ptr
b(
new pcl::PointIndices);
213 pcl::PointCloud<PointT>::Ptr pc(
new pcl::PointCloud<PointT>);
214 float circle_likelihood, box_likelihood;
215 estimate(cluster_cloud, cluster_normal, support_plane,
217 circle_likelihood, box_likelihood);
218 boundary_indices.push_back(std::move(b));
219 *projected_cloud += *pc;
223 result.labels.push_back(1);
224 result.label_names.push_back(
"circle");
225 result.label_proba.push_back(circle_likelihood);
228 result.labels.push_back(0);
229 result.label_names.push_back(
"box");
230 result.label_proba.push_back(box_likelihood);
233 result.labels.push_back(3);
234 result.label_names.push_back(
"other");
235 result.label_proba.push_back(0.0);
241 sensor_msgs::PointCloud2 ros_projected_cloud;
243 ros_projected_cloud.header = ros_cloud->header;
248 jsk_recognition_msgs::ClusterPointIndices ros_boundary_indices;
249 ros_boundary_indices.header = ros_cloud->header;
250 for (
size_t i = 0;
i < boundary_indices.size(); ++
i)
252 pcl_msgs::PointIndices ri;
254 ros_boundary_indices.cluster_indices.push_back(ri);
264 const pcl::PointCloud<pcl::Normal>::Ptr& normal,
265 const pcl::ModelCoefficients::Ptr& plane,
266 pcl::PointIndices::Ptr& boundary_indices,
267 pcl::PointCloud<PointT>::Ptr& projected_cloud,
268 float& circle_likelihood,
269 float& box_likelihood)
272 pcl::PointCloud<pcl::Boundary>::Ptr boundaries(
new pcl::PointCloud<pcl::Boundary>);
273 pcl::BoundaryEstimation<PointT, pcl::Normal, pcl::Boundary>
b;
274 b.setInputCloud(cloud);
275 b.setInputNormals(normal);
276 b.setSearchMethod(
typename pcl::search::KdTree<PointT>::Ptr(
new pcl::search::KdTree<PointT>));
278 b.setRadiusSearch(0.03);
279 b.compute(*boundaries);
282 for (
size_t i = 0;
i < boundaries->points.size(); ++
i)
283 if ((
int)boundaries->points[i].boundary_point)
284 boundary_indices->indices.push_back(i);
287 pcl::PointCloud<PointT>::Ptr boundary_cloud(
new pcl::PointCloud<PointT>);
288 pcl::ExtractIndices<PointT> ext;
289 ext.setInputCloud(cloud);
290 ext.setIndices(boundary_indices);
291 ext.filter(*boundary_cloud);
298 pcl::ProjectInliers<PointT> proj;
299 proj.setModelType(pcl::SACMODEL_PLANE);
300 proj.setInputCloud(boundary_cloud);
301 proj.setModelCoefficients(plane);
302 proj.filter(*projected_cloud);
305 pcl::PointIndices::Ptr circle_inliers(
new pcl::PointIndices);
306 pcl::ModelCoefficients::Ptr circle_coeffs(
new pcl::ModelCoefficients);
307 pcl::PointIndices::Ptr line_inliers(
new pcl::PointIndices);
308 pcl::ModelCoefficients::Ptr line_coeffs(
new pcl::ModelCoefficients);
310 pcl::SACSegmentation<PointT> seg;
311 seg.setInputCloud(projected_cloud);
313 seg.setOptimizeCoefficients(
true);
314 seg.setMethodType(pcl::SAC_RANSAC);
316 seg.setModelType(pcl::SACMODEL_CIRCLE3D);
319 seg.segment(*circle_inliers, *circle_coeffs);
321 seg.setOptimizeCoefficients(
true);
322 seg.setMethodType(pcl::SAC_RANSAC);
324 seg.setModelType(pcl::SACMODEL_LINE);
326 seg.segment(*line_inliers, *line_coeffs);
330 1.0f * circle_inliers->indices.size() / projected_cloud->points.size();
332 1.0f * line_inliers->indices.size() / projected_cloud->points.size();
345 const std::vector<jsk_recognition_utils::Polygon::Ptr>& polygons,
346 pcl::ModelCoefficients::Ptr& coeff)
349 pcl::compute3DCentroid(*cloud,
c);
350 Eigen::Vector3f centroid(
c[0],
c[1],
c[2]);
351 Eigen::Vector3f projected;
355 p->project(centroid, projected);
356 if (
p->isInside(projected)) {
357 p->toCoefficients(coeff->values);