00001
00002
00003
00004 import rospy
00005 import cv2
00006 import glob
00007 import rospkg
00008 from sensor_msgs.msg import Image
00009 from cv_bridge import CvBridge
00010 from rail_object_detection_msgs.srv import ImageQuery, ImageQueryRequest, ImageQueryResponse
00011
00012 COLORS = [(10,10,10), (100,10,10), (200,10,10), (10,100,10), (10,200,10),
00013 (10,10,100), (10,10,200), (100,100,100), (200,100,100), (100,200,100),
00014 (100,100,200)]
00015
00016 def main():
00017 bridge = CvBridge()
00018
00019 rospack = rospkg.RosPack()
00020 images = glob.glob(rospack.get_path('rail_object_detector') + '/libs/darknet/data/*.jpg')
00021 service_proxy = rospy.ServiceProxy('/darknet_node/objects_in_image', ImageQuery)
00022
00023 for image in images:
00024 img = cv2.imread(image)
00025 img_msg = bridge.cv2_to_imgmsg(img, "bgr8")
00026 resp = service_proxy(ImageQueryRequest(img_msg))
00027
00028
00029 resp_cv = bridge.imgmsg_to_cv2(resp.image, "bgr8")
00030 for idx,obj in enumerate(resp.objects):
00031 cv2.rectangle(
00032 resp_cv,
00033 (obj.left_bot_x, obj.left_bot_y),
00034 (obj.right_top_x, obj.right_top_y),
00035 COLORS[idx],
00036 3
00037 )
00038 print "Objects in scene:", ",".join([x.label for x in resp.objects])
00039
00040 cv2.imshow('image', resp_cv)
00041 cv2.waitKey(5000)
00042
00043 if __name__ == '__main__':
00044 main()