35 #define BOOST_PARAMETER_MAX_ARITY 7  
   39 #include <pcl/sample_consensus/method_types.h> 
   40 #include <pcl/sample_consensus/model_types.h> 
   41 #include <pcl/segmentation/sac_segmentation.h> 
   57     Eigen::Vector3f new_delta = segment->toSegment()->getDirection();
 
   58     if (new_delta.dot(
delta_) < 0) {
 
   59       new_delta = - new_delta;
 
   61     delta_ = ((1 - tau) * 
delta_ + tau * new_delta).normalized();
 
   64     pcl::PointCloud<pcl::PointXYZ>::Ptr new_cloud = segment->getPoints();
 
   65     for (
size_t i = 0; 
i < new_cloud->points.size(); 
i++) {
 
   66       points_->points.push_back(new_cloud->points[
i]);
 
   69     pcl::PointCloud<pcl::PointXYZ>::Ptr new_raw_cloud = segment->getRawPoints();
 
   70     for (
size_t i = 0; 
i < new_raw_cloud->points.size(); 
i++) {
 
   88     for (std::vector<LineSegment::Ptr>::iterator it = 
segments_.begin();
 
   90       if (((*it)->header.stamp - 
stamp).toSec() < 0) {
 
  100       points_.reset(
new pcl::PointCloud<pcl::PointXYZ>);
 
  102       raw_points_.reset(
new pcl::PointCloud<pcl::PointXYZ>);
 
  103       for (std::vector<LineSegment::Ptr>::iterator it = 
segments_.begin();
 
  106           pcl::PointCloud<pcl::PointXYZ>::Ptr segment_points = (*it)->getPoints();
 
  107           for (
size_t i = 0; 
i < segment_points->points.size(); 
i++) {
 
  108             points_->points.push_back(segment_points->points[
i]);
 
  112           pcl::PointCloud<pcl::PointXYZ>::Ptr segment_points = (*it)->getRawPoints();
 
  113           for (
size_t i = 0; 
i < segment_points->points.size(); 
i++) {
 
  114             raw_points_->points.push_back(segment_points->points[
i]);
 
  128     DiagnosticNodelet::onInit();
 
  129     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
 
  130     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
  132     srv_->setCallback (
f);
 
  134     std::string rotate_type_str;
 
  135     pnh_->param(
"rotate_type", rotate_type_str, std::string(
"tilt_two_way"));
 
  136     if (rotate_type_str == 
"tilt") {
 
  139     else if (rotate_type_str == 
"tilt_two_way") {
 
  142     else if (rotate_type_str == 
"spindle") {
 
  146       NODELET_ERROR(
"unknown ~rotate_type: %s", rotate_type_str.c_str());
 
  151       = advertise<sensor_msgs::PointCloud2>(*pnh_, 
"output/cloud", 1);
 
  152     pub_inliers_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, 
"output/inliers", 1);
 
  154       = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_, 
"output/coefficients", 1);
 
  156       = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, 
"output/polygons", 1);
 
  158       = advertise<jsk_recognition_msgs::ClusterPointIndices>(
 
  159         *pnh_, 
"debug/connect_segments/inliers", 1);
 
  188     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
 
  211     for (std::vector<LineSegmentCluster::Ptr>::iterator it = 
segment_clusters_.begin();
 
  213       (*it)->removeBefore(
stamp);
 
  214       if ((*it)->isEmpty()) {
 
  224     const jsk_recognition_msgs::TimeRange::ConstPtr& trigger)
 
  232     const std_msgs::Header& 
header,
 
  233     const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
 
  234     const std::vector<pcl::PointIndices::Ptr>& connected_indices)
 
  236     sensor_msgs::PointCloud2 ros_cloud;
 
  238     ros_cloud.header = 
header;
 
  240     jsk_recognition_msgs::ClusterPointIndices ros_indices;
 
  241     ros_indices.header = 
header;
 
  242     ros_indices.cluster_indices
 
  251     double max_dot = - DBL_MAX;
 
  254       Eigen::Vector3f delta_cluster = cluster->getDelta();
 
  255       Eigen::Vector3f delta = segment->toSegment()->getDirection();
 
  256       double delta_dot = std::abs(delta_cluster.dot(delta));
 
  258         if (max_dot < delta_dot) {
 
  269     if (max_index == -1) {
 
  280     const std_msgs::Header& 
header,
 
  281     std::vector<LineSegment::Ptr> new_segments)
 
  283     for (
size_t i = 0; 
i < new_segments.size(); 
i++) {
 
  287         cluster->addLineSegmentEWMA(segment, 
ewma_tau_);
 
  291         cluster->addLineSegmentEWMA(segment, 1.0);
 
  296     pcl::PointCloud<pcl::PointXYZ>::Ptr
 
  297       connected_cloud(
new pcl::PointCloud<pcl::PointXYZ>);
 
  298     std::vector<pcl::PointIndices::Ptr> connected_indices;
 
  299     std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr > clouds_list;
 
  302       pcl::PointIndices::Ptr current_indices (
new pcl::PointIndices);
 
  303       pcl::PointCloud<pcl::PointXYZ>::Ptr current_cloud
 
  304         = cluster->getRawPoints();
 
  305       for (
size_t j = 0; j < current_cloud->points.size(); j++) {
 
  306         current_indices->indices.push_back(connected_cloud->points.size() + j);
 
  308       connected_indices.push_back(current_indices);
 
  309       clouds_list.push_back(current_cloud);
 
  310       *connected_cloud = *connected_cloud + *current_cloud;
 
  320     const std_msgs::Header& 
header,
 
  321     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
 
  322     std::vector<pcl::ModelCoefficients::Ptr> all_coefficients,
 
  323     std::vector<pcl::PointIndices::Ptr> all_indices)
 
  325     jsk_recognition_msgs::ClusterPointIndices ros_indices;
 
  326     ros_indices.header = 
header;
 
  327     ros_indices.cluster_indices
 
  331     jsk_recognition_msgs::ModelCoefficientsArray ros_coefficients;
 
  332     ros_coefficients.header = 
header;
 
  333     ros_coefficients.coefficients
 
  338     jsk_recognition_msgs::PolygonArray ros_polygon;
 
  339     ros_polygon.header = 
header;
 
  340     for (
size_t i = 0; 
i < all_indices.size(); 
i++) {
 
  342         = jsk_recognition_utils::convexFromCoefficientsAndInliers<pcl::PointXYZ>(
 
  343           cloud, all_indices[
i], all_coefficients[
i]);
 
  344       geometry_msgs::PolygonStamped polygon_stamped;
 
  345       polygon_stamped.header = 
header;
 
  346       polygon_stamped.polygon = convex->toROSMsg();
 
  347       ros_polygon.polygons.push_back(polygon_stamped);
 
  353       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
 
  354       const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
 
  355       const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
 
  362     pcl::PointCloud<pcl::PointXYZ>::Ptr
 
  363       input_cloud(
new pcl::PointCloud<pcl::PointXYZ>);
 
  366     std::vector<pcl::PointIndices::Ptr> input_indices
 
  368     std::vector<pcl::ModelCoefficients::Ptr> input_coefficients
 
  370         coefficients_msg->coefficients);
 
  371     std::vector<LineSegment::Ptr> new_segments;
 
  372     for (
size_t i = 0; 
i < indices_msg->cluster_indices.size(); 
i++) {
 
  375                                                 input_coefficients[
i],
 
  378       new_segments.push_back(segment);