39 #include <pcl/filters/extract_indices.h> 40 #include <pcl/common/centroid.h> 41 #include <pcl/common/common.h> 42 #include <boost/format.hpp> 43 #include <boost/range/adaptors.hpp> 44 #include <boost/range/algorithm.hpp> 45 #include <boost/range/irange.hpp> 46 #include <pcl/registration/ia_ransac.h> 47 #include <pcl/filters/project_inliers.h> 48 #include <pcl/common/pca.h> 51 #include <Eigen/Geometry> 52 #include <geometry_msgs/PoseArray.h> 68 DiagnosticNodelet::onInit();
86 NODELET_WARN(
"~output%%02d are not published before subscribed, you should subscribe ~debug_output in debuging.");
91 }
else if (
pnh_->hasParam(
"align_boxes_with_plane")) {
92 NODELET_WARN(
"Rosparam ~align_boxes_with_plane is used only with ~align_boxes:=true, so ignoring it.");
101 }
else if (
pnh_->hasParam(
"target_frame_id")) {
102 NODELET_WARN(
"Rosparam ~target_frame_id is used only with ~align_boxes:=true and ~align_boxes_with_plane:=true, so ignoring it.");
105 pnh_->param<std::string>(
"sort_by",
sort_by_,
"input_indices");
107 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
108 dynamic_reconfigure::Server<Config>::CallbackType
f =
110 srv_->setCallback(f);
113 pc_pub_ = advertise<sensor_msgs::PointCloud2>(*
pnh_,
"debug_output", 1);
114 box_pub_ = advertise<jsk_recognition_msgs::BoundingBoxArray>(*
pnh_,
"boxes", 1);
117 centers_pub_ = advertise<geometry_msgs::PoseArray>(*
pnh_,
"centroid_pose_array", 1);
118 indices_pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*
pnh_,
"cluster_indices", 1);
125 boost::mutex::scoped_lock(
mutex_);
152 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(
queue_size_);
157 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(
queue_size_);
175 const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
176 const std::vector<pcl::IndicesPtr> indices_array,
177 std::vector<size_t>* argsort)
180 bool reverse =
false;
181 if (sort_by.compare(0, 1,
"-") == 0)
184 sort_by = sort_by.substr(1, sort_by.size() - 1);
186 if (sort_by ==
"input_indices")
190 else if (sort_by ==
"z_axis")
194 else if (sort_by ==
"cloud_size")
201 "so using the default: 'input_indices'",
sort_by_.c_str());
207 std::reverse((*argsort).begin(), (*argsort).end());
212 const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
213 const std::vector<pcl::IndicesPtr> indices_array,
214 std::vector<size_t>* argsort)
216 (*argsort).resize(indices_array.size());
217 for (
size_t i = 0; i < indices_array.size(); i++)
224 const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
225 const std::vector<pcl::IndicesPtr> indices_array,
226 std::vector<size_t>* argsort)
228 std::vector<double> z_values;
229 pcl::ExtractIndices<pcl::PointXYZ>
ex;
230 ex.setInputCloud(input);
231 for (
size_t i = 0; i < indices_array.size(); i++)
233 Eigen::Vector4f center;
234 ex.setIndices(indices_array[i]);
235 pcl::PointCloud<pcl::PointXYZ>::Ptr
cloud(
new pcl::PointCloud<pcl::PointXYZ>);
238 std::vector<int> nan_indices;
239 pcl::removeNaNFromPointCloud(*cloud, *cloud, nan_indices);
241 pcl::compute3DCentroid(*cloud, center);
242 z_values.push_back(center[2]);
247 (*argsort).resize(indices_array.size());
248 std::iota(argsort->begin(), argsort->end(), 0);
249 std::sort(argsort->begin(), argsort->end(),
250 [&z_values](
size_t i1,
size_t i2) {
return z_values[i1] < z_values[i2];});
254 const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
255 const std::vector<pcl::IndicesPtr> indices_array,
256 std::vector<size_t>* argsort)
258 std::vector<double> cloud_sizes;
259 pcl::ExtractIndices<pcl::PointXYZ>
ex;
260 ex.setInputCloud(input);
261 for (
size_t i = 0; i < indices_array.size(); i++)
263 Eigen::Vector4f center;
264 ex.setIndices(indices_array[i]);
265 pcl::PointCloud<pcl::PointXYZ>::Ptr
cloud(
new pcl::PointCloud<pcl::PointXYZ>);
268 std::vector<int> nan_indices;
269 pcl::removeNaNFromPointCloud(*cloud, *cloud, nan_indices);
271 double cloud_size =
static_cast<double>(cloud->points.size());
272 cloud_sizes.push_back(cloud_size);
276 (*argsort).resize(indices_array.size());
277 std::iota(argsort->begin(), argsort->end(), 0);
278 std::sort(argsort->begin(), argsort->end(),
279 [&cloud_sizes](
size_t i1,
size_t i2) {
return cloud_sizes[i1] < cloud_sizes[i2];});
286 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
287 "ClusterPointIndicesDecomposer running");
299 DiagnosticNodelet::updateDiagnostic(stat);
303 const Eigen::Vector4f& center,
304 const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
305 const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients)
307 double min_distance = DBL_MAX;
308 int nearest_index = -1;
309 for (
size_t i = 0; i < coefficients->coefficients.size(); i++) {
310 geometry_msgs::PolygonStamped
polygon_msg = planes->polygons[i];
312 for (
size_t j = 0; j < polygon_msg.polygon.points.size(); j++) {
314 v[0] = polygon_msg.polygon.points[j].x;
315 v[1] = polygon_msg.polygon.points[j].y;
316 v[2] = polygon_msg.polygon.points[j].z;
317 vertices.push_back(v);
321 if (distance < min_distance) {
322 min_distance = distance;
326 return nearest_index;
330 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
331 pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud_transformed,
332 const Eigen::Vector4f center,
333 const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
334 const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
336 Eigen::Quaternionf& q,
337 int& nearest_plane_index)
340 if (nearest_plane_index == -1) {
341 segmented_cloud_transformed = segmented_cloud;
345 Eigen::Vector3f normal, z_axis;
347 normal[0] = - coefficients->coefficients[nearest_plane_index].values[0];
348 normal[1] = - coefficients->coefficients[nearest_plane_index].values[1];
349 normal[2] = - coefficients->coefficients[nearest_plane_index].values[2];
352 normal[0] = coefficients->coefficients[nearest_plane_index].values[0];
353 normal[1] = coefficients->coefficients[nearest_plane_index].values[1];
354 normal[2] = coefficients->coefficients[nearest_plane_index].values[2];
356 normal = normal.normalized();
357 Eigen::Quaternionf
rot;
358 rot.setFromTwoVectors(Eigen::Vector3f::UnitZ(), normal);
359 Eigen::AngleAxisf rotation_angle_axis(rot);
360 Eigen::Vector3f rotation_axis = rotation_angle_axis.axis();
361 double theta = rotation_angle_axis.angle();
362 if (std::isnan(theta) ||
363 std::isnan(rotation_axis[0]) ||
364 std::isnan(rotation_axis[1]) ||
365 std::isnan(rotation_axis[2])) {
366 segmented_cloud_transformed = segmented_cloud;
367 NODELET_ERROR(
"cannot compute angle to align the point cloud: [%f, %f, %f], [%f, %f, %f]",
368 z_axis[0], z_axis[1], z_axis[2],
369 normal[0], normal[1], normal[2]);
372 Eigen::Matrix3f m = Eigen::Matrix3f::Identity() * rot;
375 pcl::PointCloud<pcl::PointXYZRGB>::Ptr projected_cloud
376 (
new pcl::PointCloud<pcl::PointXYZRGB>);
377 pcl::ProjectInliers<pcl::PointXYZRGB> proj;
378 proj.setModelType (pcl::SACMODEL_PLANE);
379 pcl::ModelCoefficients::Ptr
380 plane_coefficients (
new pcl::ModelCoefficients);
381 plane_coefficients->values
382 = coefficients->coefficients[nearest_plane_index].values;
383 proj.setModelCoefficients(plane_coefficients);
384 proj.setInputCloud(segmented_cloud);
385 proj.filter(*projected_cloud);
386 if (projected_cloud->points.size() >= 3) {
387 pcl::PCA<pcl::PointXYZRGB> pca;
388 pca.setInputCloud(projected_cloud);
389 Eigen::Matrix3f eigen = pca.getEigenVectors();
390 m.col(0) = eigen.col(0);
391 m.col(1) = eigen.col(1);
393 if (m.col(0).cross(m.col(1)).
dot(m.col(2)) < 0) {
394 m.col(0) = - m.col(0);
396 if (m.col(0).dot(Eigen::Vector3f::UnitX()) < 0) {
398 m = m * Eigen::AngleAxisf(
M_PI, Eigen::Vector3f::UnitZ());
407 for (
size_t row = 0; row < 3; row++) {
408 for (
size_t column = 0; column < 3; column++) {
409 m4(row, column) = m(row, column);
414 Eigen::Matrix4f inv_m = m4.inverse();
415 pcl::transformPointCloud(*segmented_cloud, *segmented_cloud_transformed, inv_m);
422 (
const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
423 const std_msgs::Header
header,
424 const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
425 const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
426 geometry_msgs::Pose& center_pose_msg,
427 jsk_recognition_msgs::BoundingBox& bounding_box)
429 bounding_box.header =
header;
430 if (segmented_cloud->points.size() == 0) {
435 bool is_center_valid =
false;
436 Eigen::Vector4f center;
437 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
438 segmented_cloud_transformed (
new pcl::PointCloud<pcl::PointXYZRGB>);
439 segmented_cloud_transformed->is_dense = segmented_cloud->is_dense;
441 Eigen::Matrix4f m4 = Eigen::Matrix4f::Identity();
442 Eigen::Quaternionf
q = Eigen::Quaternionf::Identity();
443 int nearest_plane_index = 0;
446 is_center_valid = pcl::compute3DCentroid(*segmented_cloud, center) != 0;
448 center, planes, coefficients, m4, q,
449 nearest_plane_index);
469 Eigen::Affine3f transform;
471 pcl::transformPointCloud(*segmented_cloud, *segmented_cloud, transform);
473 is_center_valid = pcl::compute3DCentroid(*segmented_cloud, center) != 0;
476 pcl::PointXYZRGB min_pt, max_pt;
477 pcl::getMinMax3D(*segmented_cloud, min_pt, max_pt);
479 pcl_msgs::ModelCoefficients coef_by_frame;
480 coef_by_frame.values.push_back(0);
481 coef_by_frame.values.push_back(0);
482 coef_by_frame.values.push_back(1);
483 coef_by_frame.values.push_back(- min_pt.z);
484 jsk_recognition_msgs::ModelCoefficientsArray::Ptr coefficients_by_frame(
485 new jsk_recognition_msgs::ModelCoefficientsArray);
487 coefficients_by_frame->coefficients.push_back(coef_by_frame);
489 geometry_msgs::PolygonStamped plane_by_frame;
491 geometry_msgs::Point32
point;
495 plane_by_frame.polygon.points.push_back(point);
498 plane_by_frame.polygon.points.push_back(point);
501 plane_by_frame.polygon.points.push_back(point);
504 plane_by_frame.polygon.points.push_back(point);
505 jsk_recognition_msgs::PolygonArray::Ptr planes_by_frame(
506 new jsk_recognition_msgs::PolygonArray);
508 planes_by_frame->polygons.push_back(plane_by_frame);
511 center, planes_by_frame, coefficients_by_frame, m4, q,
512 nearest_plane_index);
520 if (segmented_cloud->points.size() >= 3) {
521 Eigen::Vector4f pca_centroid;
522 pcl::compute3DCentroid(*segmented_cloud, pca_centroid);
523 Eigen::Matrix3f covariance;
524 pcl::computeCovarianceMatrixNormalized(*segmented_cloud, pca_centroid, covariance);
525 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eigen_solver(covariance, Eigen::ComputeEigenvectors);
526 Eigen::Matrix3f eigen_vectors_pca = eigen_solver.eigenvectors();
529 eigen_vectors_pca.col(2) = eigen_vectors_pca.col(0).cross(eigen_vectors_pca.col(1));
531 eigen_vectors_pca = eigen_vectors_pca * Eigen::AngleAxisf(
M_PI / 2.0, Eigen::Vector3f::UnitY());
533 if (eigen_vectors_pca.col(2).dot(Eigen::Vector3f::UnitZ()) < 0) {
534 eigen_vectors_pca = eigen_vectors_pca * Eigen::AngleAxisf(
M_PI, Eigen::Vector3f::UnitX());
537 Eigen::Matrix4f projection_transform(Eigen::Matrix4f::Identity());
538 projection_transform.block<3,3>(0,0) = eigen_vectors_pca.transpose();
539 pcl::transformPointCloud(*segmented_cloud, *segmented_cloud_transformed, projection_transform);
540 m4.block<3, 3>(0, 0) = eigen_vectors_pca;
541 q = eigen_vectors_pca;
543 is_center_valid = pcl::compute3DCentroid(*segmented_cloud_transformed, center) != 0;
544 center = m4 * center;
547 segmented_cloud_transformed = segmented_cloud;
550 segmented_cloud_transformed = segmented_cloud;
551 is_center_valid = pcl::compute3DCentroid(*segmented_cloud_transformed, center) != 0;
556 Eigen::Vector4f minpt, maxpt;
557 pcl::getMinMax3D<pcl::PointXYZRGB>(*segmented_cloud_transformed, minpt, maxpt);
559 double xwidth = maxpt[0] - minpt[0];
560 double ywidth = maxpt[1] - minpt[1];
561 double zwidth = maxpt[2] - minpt[2];
562 if (!pcl_isfinite(xwidth) || !pcl_isfinite(ywidth) || !pcl_isfinite(zwidth))
565 xwidth = ywidth = zwidth = 0;
568 Eigen::Vector4f center2((maxpt[0] + minpt[0]) / 2.0, (maxpt[1] + minpt[1]) / 2.0, (maxpt[2] + minpt[2]) / 2.0, 1.0);
569 Eigen::Vector4f center_transformed = m4 * center2;
572 if (is_center_valid) {
573 center_pose_msg.position.x = center[0];
574 center_pose_msg.position.y = center[1];
575 center_pose_msg.position.z = center[2];
576 center_pose_msg.orientation.x = q.x();
577 center_pose_msg.orientation.y = q.y();
578 center_pose_msg.orientation.z = q.z();
579 center_pose_msg.orientation.w = q.w();
583 center_pose_msg = geometry_msgs::Pose();
587 bounding_box.pose.position.x = center_transformed[0];
588 bounding_box.pose.position.y = center_transformed[1];
589 bounding_box.pose.position.z = center_transformed[2];
590 bounding_box.pose.orientation.x = q.x();
591 bounding_box.pose.orientation.y = q.y();
592 bounding_box.pose.orientation.z = q.z();
593 bounding_box.pose.orientation.w = q.w();
594 bounding_box.dimensions.x = xwidth;
595 bounding_box.dimensions.y = ywidth;
596 bounding_box.dimensions.z = zwidth;
600 bounding_box.label = nearest_plane_index;
606 (
const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
608 pcl::PointCloud<pcl::PointXYZRGB>& debug_output)
611 for (
size_t j = 0; j < segmented_cloud->points.size(); j++) {
613 p.x= segmented_cloud->points[j].x;
614 p.y= segmented_cloud->points[j].y;
615 p.z= segmented_cloud->points[j].z;
616 p.rgb = *
reinterpret_cast<float*
>(&rgb);
617 debug_output.points.push_back(p);
622 const sensor_msgs::PointCloud2ConstPtr &input,
623 const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
628 std::vector<int> all_indices;
631 boost::irange(0, (
int)(input->width * input->height)),
632 std::inserter(all_indices, all_indices.begin()));
634 for (
size_t i = 0; i < indices_input->cluster_indices.size(); i++) {
635 for (
size_t j = 0; j < indices_input->cluster_indices[i].indices.size(); ++j) {
636 all_indices[indices_input->cluster_indices[i].indices[j]] = -1;
639 all_indices.erase(std::remove(all_indices.begin(), all_indices.end(), -1), all_indices.end());
642 pcl_msgs::PointIndices ros_indices;
643 ros_indices.indices = std::vector<int>(all_indices.begin(), all_indices.end());
644 ros_indices.header = input->header;
649 const sensor_msgs::PointCloud2ConstPtr &input,
650 const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input,
651 const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
652 const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients)
659 pcl::ExtractIndices<pcl::PointXYZRGB>
extract;
660 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
cloud (
new pcl::PointCloud<pcl::PointXYZRGB>);
661 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_xyz (
new pcl::PointCloud<pcl::PointXYZ>);
666 std::vector<pcl::IndicesPtr> converted_indices;
668 for (
size_t i = 0; i < indices_input->cluster_indices.size(); i++)
670 pcl::IndicesPtr vindices;
673 indices_input->cluster_indices[i].indices.size() <
min_size_) {
674 vindices.reset (
new std::vector<int> ());
675 converted_indices.push_back(vindices);
679 indices_input->cluster_indices[i].indices.size() >
max_size_) {
680 vindices.reset (
new std::vector<int> ());
681 converted_indices.push_back(vindices);
684 vindices.reset (
new std::vector<int> (indices_input->cluster_indices[i].indices));
685 converted_indices.push_back(vindices);
688 std::vector<size_t> argsort;
690 extract.setInputCloud(cloud);
693 bool is_sensed_with_camera = (input->height != 1);
695 cv::Mat mask = cv::Mat::zeros(input->height, input->width, CV_8UC1);
696 cv::Mat
label = cv::Mat::zeros(input->height, input->width, CV_32SC1);
697 pcl::PointCloud<pcl::PointXYZRGB> debug_output;
698 jsk_recognition_msgs::BoundingBoxArray bounding_box_array;
699 jsk_recognition_msgs::ClusterPointIndices out_cluster_indices;
700 bounding_box_array.header = input->header;
701 geometry_msgs::PoseArray center_pose_array;
702 center_pose_array.header = input->header;
703 out_cluster_indices.header = input->header;
704 for (
size_t i = 0; i < argsort.size(); i++)
706 pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud (
new pcl::PointCloud<pcl::PointXYZRGB>);
707 segmented_cloud->is_dense = cloud->is_dense;
709 pcl_msgs::PointIndices out_indices_msg;
710 out_indices_msg.header = input->header;
711 out_indices_msg.indices = *(converted_indices[argsort[i]]);
712 out_cluster_indices.cluster_indices.push_back(out_indices_msg);
714 pcl::PointIndices::Ptr segmented_indices (
new pcl::PointIndices);
715 extract.setIndices(converted_indices[argsort[i]]);
716 extract.filter(*segmented_cloud);
718 sensor_msgs::PointCloud2::Ptr out_cloud(
new sensor_msgs::PointCloud2);
720 out_cloud->header = input->header;
724 if (is_sensed_with_camera) {
726 for (
size_t j = 0; j < converted_indices[argsort[i]]->size(); j++) {
727 int index = converted_indices[argsort[i]]->data()[j];
728 int width_index = index % input->width;
729 int height_index = index / input->width;
730 mask.at<uchar>(height_index, width_index) = 255;
733 label.at<
int>(height_index, width_index) = (
int)i + 1;
740 geometry_msgs::Pose pose_msg;
741 jsk_recognition_msgs::BoundingBox bounding_box;
742 bounding_box.label =
static_cast<int>(argsort[i]);
744 if (!segmented_cloud->is_dense) {
745 std::vector<int> nan_indices;
746 pcl::removeNaNFromPointCloud(*segmented_cloud, *segmented_cloud, nan_indices);
750 segmented_cloud, input->header, planes, coefficients, pose_msg, bounding_box);
759 target_frame = input->header.frame_id;
761 center_pose_array.poses.push_back(pose_msg);
762 bounding_box.header.frame_id = target_frame;
763 bounding_box_array.boxes.push_back(bounding_box);
766 transform.
setOrigin(
tf::Vector3(pose_msg.position.x, pose_msg.position.y, pose_msg.position.z));
769 tf_prefix_ + (boost::format(
"output%02u") % (i)).str()));
779 if (is_sensed_with_camera) {
792 sensor_msgs::PointCloud2 debug_ros_output;
794 debug_ros_output.header = input->header;
795 debug_ros_output.is_dense =
false;
803 (
const sensor_msgs::PointCloud2ConstPtr &input,
804 const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
807 jsk_recognition_msgs::PolygonArrayConstPtr(),
808 jsk_recognition_msgs::ModelCoefficientsArrayConstPtr());
817 std::string topic_name = (boost::format(
"output%02u") % (i)).str();
bool force_to_flip_z_axis_
ros::Publisher centers_pub_
static uint32_t colorRGBAToUInt32(std_msgs::ColorRGBA c)
#define NODELET_ERROR(...)
virtual bool computeCenterAndBoundingBox(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud, const std_msgs::Header header, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients, geometry_msgs::Pose ¢er_pose_msg, jsk_recognition_msgs::BoundingBox &bounding_box)
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
virtual void configCallback(Config &config, uint32_t level)
ros::Publisher label_pub_
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
void summary(unsigned char lvl, const std::string s)
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
void sortIndicesOrderByZAxis(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
const std::string & getName() const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
bool fill_boxes_label_with_nearest_plane_index_
T dot(T *pf1, T *pf2, int length)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncAlignPolicy > > async_align_
static tf::Quaternion createIdentityQuaternion()
virtual bool transformPointCloudToAlignWithPlane(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud, pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud_transformed, const Eigen::Vector4f center, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients, Eigen::Matrix4f &m4, Eigen::Quaternionf &q, int &nearest_plane_index)
virtual void unsubscribe()
jsk_recognition_utils::Counter cluster_counter_
ros::Publisher indices_pub_
virtual void allocatePublishers(size_t num)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ClusterPointIndicesDecomposer, nodelet::Nodelet)
void sortIndicesOrderByCloudSize(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
jsk_recognition_msgs::PolygonArray::ConstPtr polygon_msg
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
tf::TransformListener * tf_listener_
std::vector< ros::Publisher > publishers_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
boost::shared_ptr< tf::TransformBroadcaster > br_
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_target_
#define NODELET_WARN_ONCE(...)
virtual void add(double v)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
virtual void publishNegativeIndices(const sensor_msgs::PointCloud2ConstPtr &input, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
jsk_pcl_ros::ClusterPointIndicesDecomposerConfig Config
virtual int findNearestPlane(const Eigen::Vector4f ¢er, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients)
void sortIndicesOrderByIndices(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
#define NODELET_INFO(...)
uint32_t getNumSubscribers() const
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)
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
std::string target_frame_id_
void addToDebugPointCloud(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud, size_t i, pcl::PointCloud< pcl::PointXYZRGB > &debug_output)
virtual void sortIndicesOrder(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
ros::Publisher negative_indices_pub_
void add(const std::string &key, const T &val)
static tf::TransformListener * getInstance()
virtual void extract(const sensor_msgs::PointCloud2ConstPtr &point, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients)
#define NODELET_FATAL(...)
boost::shared_ptr< message_filters::Synchronizer< SyncAlignPolicy > > sync_align_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
double distance(const urdf::Pose &transform)
const std::string TYPE_32SC1
sensor_msgs::ImagePtr toImageMsg() const
bool align_boxes_with_plane_
virtual double distanceToPoint(const Eigen::Vector4f p)