15     import roslib;roslib.load_manifest(PKG)
 
   18 from sensor_msgs.msg 
import PointCloud2
 
   22 from std_srvs 
import srv
 
   24 teacher_pose_stamped = 
None 
   27     global teacher_pose_stamped
 
   28     teacher_pose_stamped = pose_stamped
 
   29     InputPosePub.publish(teacher_pose_stamped)
 
   32     return concatenate_matrices(
 
   33       translation_matrix([pose.position.x, pose.position.y, pose.position.z]),
 
   34       quaternion_matrix([pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w])
 
   37     translation = translation_from_matrix(mat)
 
   38     rotation = quaternion_from_matrix(mat)
 
   40     pose.position.x = translation[0]
 
   41     pose.position.y = translation[1]
 
   42     pose.position.z = translation[2]
 
   43     pose.orientation.x = rotation[0]
 
   44     pose.orientation.y = rotation[1]
 
   45     pose.orientation.z = rotation[2]
 
   46     pose.orientation.w = rotation[3]
 
   50     global teacher_pose_stamped, renew_flag
 
   52     if (
not teacher_pose_stamped):
 
   53         rospy.loginfo(
"teacher is empty")
 
   56         teacher_pose_stamped.header.stamp = rospy.Time(0)
 
   57         teacher_pose_stamped_recog_frame = listener.transformPose(pose_stamped.header.frame_id, teacher_pose_stamped)
 
   59         print(
"tf error: %s" % e)
 
   63     new_pose_mat = concatenate_matrices(diff_pose_mat, teacher_pose_mat)
 
   64     new_pose_stamped = PoseStamped()
 
   66     new_pose_stamped.header = pose_stamped.header
 
   67     OutputPosePub.publish(new_pose_stamped)
 
   71             new_pose_stamped.header.stamp = rospy.Time(0)
 
   72             new_pose_stamped_for_renew = listener.transformPose(teacher_pose_stamped.header.frame_id, new_pose_stamped)
 
   74             print(
"tf error: %s" % e)
 
   81     return srv.EmptyResponse()
 
   82 if __name__ == 
"__main__":
 
   83     rospy.init_node(
"in_hand_recognition_manager")
 
   84     InputPosePub = rospy.Publisher(
 
   85         "~output/recognition", PoseStamped, queue_size=1)
 
   86     OutputPosePub = rospy.Publisher(
"~output", PoseStamped, queue_size=1)
 
   88     rospy.Subscriber(
"~input", PoseStamped, pose_teacher_cb)
 
   89     rospy.Subscriber(
"~input/result", PoseStamped, pose_diff_cb)
 
   90     rospy.Service(
"~renew", srv.Empty, renew_cb)