Go to the documentation of this file.00001
00002
00003 """
00004 Create posedetection_msgs/Feature0D dataset from assigned images.
00005
00006 Input:
00007
00008 container_path/
00009 category_1_folder/
00010 file_1
00011 file_2
00012 ...
00013 file_42
00014 category_2_folder/
00015 file_43
00016 file_44
00017 ...
00018
00019 Output:
00020
00021 feature0d_dataset.pkl.gz
00022
00023 """
00024 import os
00025 import sys
00026 import gzip
00027 import cPickle as pickle
00028 import argparse
00029 import collections
00030
00031 import cv2
00032 import numpy as np
00033 from sklearn.datasets.base import Bunch
00034 from sklearn.datasets import load_files
00035
00036 import rospy
00037 import cv_bridge
00038 from posedetection_msgs.srv import Feature0DDetect, Feature0DDetectRequest
00039
00040
00041 def create_feature0d_dataset():
00042 rospy.init_node('create_feature0d_dataset')
00043
00044 parser = argparse.ArgumentParser()
00045 parser.add_argument('container_path', help='image data container path')
00046 parser.add_argument('-O', '--output', default='feature0d_dataset.pkl.gz',
00047 help='output filename (default: feature0d_dataset.pkl.gz')
00048 args = parser.parse_args(rospy.myargv(sys.argv[1:]))
00049
00050
00051 bunch_files = load_files(container_path=args.container_path,
00052 description='image data',
00053 shuffle=False,
00054 load_content=False)
00055
00056
00057 client = rospy.ServiceProxy('Feature0DDetect', Feature0DDetect, persistent=True)
00058
00059
00060 bridge = cv_bridge.CvBridge()
00061 targets, pos, scales, ori, desc = [], [], [], [], []
00062 for i, (filename, target) in enumerate(zip(bunch_files.filenames,
00063 bunch_files.target)):
00064 rospy.loginfo(filename)
00065 targets.append(target)
00066
00067 img = cv2.imread(filename)
00068 imgmsg = bridge.cv2_to_imgmsg(img, encoding='bgr8')
00069 client.wait_for_service(timeout=10)
00070 feature0d = client.call(Feature0DDetectRequest(image=imgmsg))
00071
00072 pos.append(np.array(feature0d.features.positions))
00073 scales.append(np.array(feature0d.features.scales))
00074 ori.append(np.array(feature0d.features.orientations))
00075 desc.append(np.array(feature0d.features.descriptors))
00076
00077 dataset = Bunch(target=np.array(targets),
00078 target_names=bunch_files.target_names,
00079 positions=pos,
00080 scales=scales,
00081 orientations=ori,
00082 descriptors=desc)
00083
00084
00085 print('saving feature0d data')
00086 with gzip.open(args.output, 'wb') as f:
00087 pickle.dump(dataset, f)
00088 rospy.loginfo('finished')
00089
00090
00091 if __name__ == '__main__':
00092 create_feature0d_dataset()