37 #include <pcl/point_types.h> 
   38 #include <pcl/filters/passthrough.h> 
   39 #include <pcl/filters/voxel_grid.h> 
   40 #include <pcl/io/io.h> 
   42 #include <boost/format.hpp> 
   43 #include "jsk_recognition_msgs/SlicedPointCloud.h" 
   57     pcl::PointCloud<pcl::PointXYZRGB>::Ptr 
cloud (
new pcl::PointCloud<pcl::PointXYZRGB>);
 
   58     pcl::PointCloud<pcl::PointXYZRGB>::Ptr output_cloud (
new pcl::PointCloud<pcl::PointXYZRGB>);
 
   59     if (
grid_.size() == 0) {
 
   60       NODELET_DEBUG(
"the number of registered grids is 0, skipping");
 
   64     for (
size_t i = 0; 
i < 
grid_.size(); 
i++)
 
   66       visualization_msgs::Marker::ConstPtr target_grid = 
grid_[
i];
 
   68       int id = target_grid->id;
 
   72       pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed_cloud (
new pcl::PointCloud<pcl::PointXYZRGB>);
 
   77       double center_x = target_grid->pose.position.x;
 
   78       double center_y = target_grid->pose.position.y;
 
   79       double center_z = target_grid->pose.position.z;
 
   80       double range_x = target_grid->scale.x * 1.0; 
 
   81       double range_y = target_grid->scale.y * 1.0;
 
   82       double range_z = target_grid->scale.z * 1.0;
 
   83       double min_x = center_x - range_x / 2.0;
 
   84       double max_x = center_x + range_x / 2.0;
 
   85       double min_y = center_y - range_y / 2.0;
 
   86       double max_y = center_y + range_y / 2.0;
 
   87       double min_z = center_z - range_z / 2.0;
 
   88       double max_z = center_z + range_z / 2.0;
 
   91       pcl::PassThrough<pcl::PointXYZRGB> pass_x;
 
   92       pass_x.setFilterFieldName(
"x");
 
   93       pass_x.setFilterLimits(min_x, max_x);
 
   95       pcl::PassThrough<pcl::PointXYZRGB> pass_y;
 
   96       pass_y.setFilterFieldName(
"y");
 
   97       pass_y.setFilterLimits(min_y, max_y);
 
   98       pcl::PassThrough<pcl::PointXYZRGB> pass_z;
 
   99       pass_z.setFilterFieldName(
"z");
 
  100       pass_z.setFilterLimits(min_z, max_z);
 
  106       pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_after_x (
new pcl::PointCloud<pcl::PointXYZRGB>);
 
  107       pass_x.setInputCloud (transformed_cloud);
 
  108       pass_x.filter(*cloud_after_x);
 
  110       pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_after_y (
new pcl::PointCloud<pcl::PointXYZRGB>);
 
  111       pass_y.setInputCloud (cloud_after_x);
 
  112       pass_y.filter(*cloud_after_y);
 
  114       pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_after_z (
new pcl::PointCloud<pcl::PointXYZRGB>);
 
  115       pass_z.setInputCloud (cloud_after_y);
 
  116       pass_z.filter(*cloud_after_z);
 
  119       pcl::VoxelGrid<pcl::PointXYZRGB> sor;
 
  120       sor.setInputCloud (cloud_after_z);
 
  121       sor.setLeafSize (resolution, resolution, resolution);
 
  122       pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_filtered (
new pcl::PointCloud<pcl::PointXYZRGB>);
 
  123       sor.filter (*cloud_filtered);
 
  126       pcl::PointCloud<pcl::PointXYZRGB>::Ptr reverse_transformed_cloud (
new pcl::PointCloud<pcl::PointXYZRGB>);
 
  129                                    *reverse_transformed_cloud,
 
  138       NODELET_DEBUG_STREAM(
id << 
" includes " << reverse_transformed_cloud->points.size() << 
" points");
 
  139       for (
size_t i = 0; 
i < reverse_transformed_cloud->points.size(); 
i++) {
 
  140         output_cloud->points.push_back(reverse_transformed_cloud->points[i]);
 
  143     sensor_msgs::PointCloud2 out;
 
  145     out.header = 
input->header;
 
  149     size_t cluster_num = output_cloud->points.size() / 
max_points_ + 1;
 
  151     for (
size_t i = 0; 
i < cluster_num; 
i++) {
 
  153       size_t end_index = 
max_points_ * (
i + 1) > output_cloud->points.size() ?
 
  155       sensor_msgs::PointCloud2 cluster_out_ros;
 
  156       pcl::PointCloud<pcl::PointXYZRGB>::Ptr
 
  157         cluster_out_pcl(
new pcl::PointCloud<pcl::PointXYZRGB>);
 
  158       cluster_out_pcl->points.resize(end_index - start_index);
 
  161       for (
size_t j = start_index; j < end_index; j++) {
 
  162         cluster_out_pcl->points[j - start_index] = output_cloud->points[j];
 
  165       toROSMsg(*cluster_out_pcl, cluster_out_ros);
 
  166       jsk_recognition_msgs::SlicedPointCloud publish_point_cloud;
 
  167       cluster_out_ros.header = 
input->header;
 
  168       publish_point_cloud.point_cloud = cluster_out_ros;
 
  169       publish_point_cloud.slice_index = 
i;
 
  175     catch (std::runtime_error e) { 
 
  176       NODELET_WARN_STREAM(
"error has occured in VoxelGridDownsampleManager but ignore it: " << e.what());
 
  185     if (new_box->id == -1) {
 
  191       for (
size_t i = 0; 
i < 
grid_.size(); 
i++) {
 
  192         if (
grid_[i]->
id == new_box->id) {
 
  198       grid_.push_back(new_box);
 
  203     visualization_msgs::Marker::Ptr 
box (
new visualization_msgs::Marker);
 
  206     box->pose.position.x = 2.0;
 
  207     box->pose.position.y = 0.0;
 
  208     box->pose.position.z = -0.5;
 
  221     ConnectionBasedNodelet::onInit();
 
  222     pnh_->param(
"base_frame", 
base_frame_, std::string(
"pelvis"));
 
  227     int max_points_param;
 
  228     pnh_->param(
"max_points", max_points_param, 300);
 
  229     pnh_->param(
"rate", 
rate_, 1.0);
 
  232     pub_ = advertise<sensor_msgs::PointCloud2>(
 
  235       *pnh_, 
"output_encoded", 1);