evaluate_box_segmentation_by_gt_box.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 from jsk_recognition_msgs.msg import Accuracy
00004 from jsk_recognition_msgs.msg import BoundingBox
00005 import jsk_recognition_utils
00006 import rospy
00007 from jsk_topic_tools import ConnectionBasedTransport
00008 
00009 
00010 class EvaluateBoxSegmentationByGTBox(ConnectionBasedTransport):
00011 
00012     def __init__(self):
00013         super(EvaluateBoxSegmentationByGTBox, self).__init__()
00014         self.box_gt = None
00015         self.pub = self.advertise('~output', Accuracy, queue_size=1)
00016         self.sub_box_gt = rospy.Subscriber(
00017             '~input/box_gt', BoundingBox, self._cb_box_gt)
00018 
00019     def subscribe(self):
00020         self.sub_voxels = rospy.Subscriber(
00021             '~input/box', BoundingBox, self._cb_box)
00022 
00023     def unsubscribe(self):
00024         self.sub_voxels.unregister()
00025 
00026     def _cb_box_gt(self, box_msg):
00027         self.box_gt = jsk_recognition_utils.bounding_box_msg_to_aabb(box_msg)
00028 
00029     def _cb_box(self, box_msg):
00030         if self.box_gt is None:
00031             rospy.logwarn('GT. box is not set, skipping.')
00032             return
00033         box = jsk_recognition_utils.bounding_box_msg_to_aabb(box_msg)
00034         iu = jsk_recognition_utils.get_overlap_of_aabb(self.box_gt, box)
00035 
00036         out_msg = Accuracy(header=box_msg.header, accuracy=iu)
00037         self.pub.publish(out_msg)
00038 
00039 
00040 if __name__ == '__main__':
00041     rospy.init_node('evaluate_box_segmentation_by_gt_box')
00042     EvaluateBoxSegmentationByGTBox()
00043     rospy.spin()


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:04