41 #ifndef JSK_RECOGNITION_UTILS_PCL_ROS_UTIL_H_ 
   42 #define JSK_RECOGNITION_UTILS_PCL_ROS_UTIL_H_ 
   46 #include <std_msgs/Header.h> 
   47 #include <pcl_msgs/PointIndices.h> 
   49 #include <jsk_recognition_msgs/BoundingBox.h> 
   50 #include <pcl/PointIndices.h> 
   51 #include <pcl/filters/crop_box.h> 
   52 #include <sensor_msgs/PointCloud2.h> 
   64                            const pcl::PointIndices& indices,
 
   65                            const std_msgs::Header& 
header);
 
   71   bool isSameFrameId(
const std::string& a, 
const std::string& b);
 
   77   bool isSameFrameId(
const std_msgs::Header& a, 
const std_msgs::Header& b);
 
   83   template<
class T1, 
class T2>
 
   93   bool hasField(
const std::string& field_name, 
const sensor_msgs::PointCloud2& msg);
 
   99   template<
typename Po
intT>
 
  101   cropPointCloud(
const typename pcl::PointCloud<PointT>::Ptr& cloud,
 
  102                  const jsk_recognition_msgs::BoundingBox& bbox_msg,
 
  103                  std::vector<int>* indices,
 
  104                  bool extract_removed_indices=
false)
 
  106     if (cloud->header.frame_id != bbox_msg.header.frame_id)
 
  108       fprintf(stderr, 
"Frame id of input cloud and bounding box must be same. Cloud: %s, BoundingBox: %s.",
 
  109               cloud->header.frame_id.c_str(), bbox_msg.header.frame_id.c_str());
 
  112     pcl::CropBox<PointT> crop_box(extract_removed_indices);
 
  114     crop_box.setInputCloud(cloud);
 
  116     Eigen::Affine3f box_pose;
 
  118     crop_box.setTranslation(box_pose.translation());
 
  119     float roll, pitch, yaw;
 
  120     pcl::getEulerAngles(box_pose, roll, pitch, yaw);
 
  121     crop_box.setRotation(Eigen::Vector3f(roll, pitch, yaw));
 
  123     Eigen::Vector4f max_point(bbox_msg.dimensions.x / 2,
 
  124                               bbox_msg.dimensions.y / 2,
 
  125                               bbox_msg.dimensions.z / 2,
 
  127     Eigen::Vector4f min_point(-bbox_msg.dimensions.x / 2,
 
  128                               -bbox_msg.dimensions.y / 2,
 
  129                               -bbox_msg.dimensions.z / 2,
 
  131     crop_box.setMax(max_point);
 
  132     crop_box.setMin(min_point);
 
  134     crop_box.filter(*indices);
 
  139 #endif  // JSK_RECOGNITION_UTILS_PCL_ROS_UTIL_H_