37 #ifndef JSK_PCL_ROS_COLLISION_DETECTOR_H_ 
   38 #define JSK_PCL_ROS_COLLISION_DETECTOR_H_ 
   40 #include <jsk_topic_tools/diagnostic_nodelet.h> 
   41 #include <sensor_msgs/PointCloud2.h> 
   42 #include <jsk_recognition_msgs/CheckCollision.h> 
   44 #include <pcl/point_types.h> 
   48 #include <std_msgs/Bool.h> 
   67                                 const geometry_msgs::PoseStamped& pose);
 
   70                                  jsk_recognition_msgs::CheckCollision::Response &
res);
 
   79     pcl::PointCloud<pcl::PointXYZ> 
cloud_;