37 #ifndef JSK_PCL_ROS_HINTED_HANDLE_ESTIMATOR_H_ 
   38 #define JSK_PCL_ROS_HINTED_HANDLE_ESTIMATOR_H_ 
   40 #include <jsk_topic_tools/diagnostic_nodelet.h> 
   41 #include <jsk_recognition_msgs/ClusterPointIndices.h> 
   42 #include <jsk_recognition_msgs/SimpleHandle.h> 
   43 #include <geometry_msgs/PointStamped.h> 
   44 #include <geometry_msgs/PoseStamped.h> 
   45 #include <geometry_msgs/Pose.h> 
   46 #include <std_msgs/Float64.h> 
   47 #include <sensor_msgs/PointCloud2.h> 
   48 #include <visualization_msgs/Marker.h> 
   49 #include <visualization_msgs/MarkerArray.h> 
   75   geometry_msgs::Pose 
pose;
 
   78   pose.orientation.x = 
q.getX(); 
pose.orientation.y=
q.getY(); 
pose.orientation.z=
q.getZ(), 
pose.orientation.w=
q.getW();
 
   82 geometry_msgs::Pose 
change_pose(geometry_msgs::Pose base_pose, geometry_msgs::Pose child_pose){
 
   86 visualization_msgs::Marker 
make_box(
float s_x, 
float s_y, 
float s_z, 
float r, 
float g, 
float b, 
float x, 
float y, 
float z)
 
   88   visualization_msgs::Marker 
marker;
 
   89   marker.type = visualization_msgs::Marker::CUBE;
 
  100   marker.pose.orientation.x = 
marker.pose.orientation.y = 
marker.pose.orientation.z = 0;
 
  101   marker.pose.orientation.w = 1.0;
 
  106   visualization_msgs::MarkerArray markerArray_msg;
 
  109   marker_msg.header = 
pose.header;
 
  110   marker_msg.ns = std::string(
"debug_grasp_model");
 
  112   markerArray_msg.markers.push_back(marker_msg);
 
  115   marker_msg.header = 
pose.header;
 
  116   marker_msg.ns = std::string(
"debug_grasp_model");
 
  118   markerArray_msg.markers.push_back(marker_msg);
 
  121   marker_msg.header = 
pose.header;
 
  122   marker_msg.ns = std::string(
"debug_grasp_model");
 
  124   markerArray_msg.markers.push_back(marker_msg);
 
  125   return markerArray_msg;
 
  136       sensor_msgs::PointCloud2,
 
  137       geometry_msgs::PointStamped 
 
  146       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
 
  147       const geometry_msgs::PointStampedConstPtr &point_msg);