├── README.md
├── generate_hmb3.py
├── guided
├── chauffeur_guided.py
├── epoch_guided.py
├── ncoverage.py
└── rambo_guided.py
├── install.sh
├── models
├── chauffeur_reproduce.py
├── epoch_reproduce.py
└── rambo_reproduce.py
└── testgen
├── chauffeur_testgen_coverage.py
├── chauffeur_testgen_driver.sh
├── epoch_testgen_coverage.py
├── epoch_testgen_driver.sh
├── ncoverage.py
└── rambo_testgen_coverage.py
/README.md:
--------------------------------------------------------------------------------
1 | # DeepTest: Automated testing of deep-neural-network-driven autonomous cars
2 |
3 | DeepTest is a systematic testing tool for automatically detecting erroneous behaviors of DNN-driven vehicles that can potentially lead to fatal crashes.
4 |
5 | ## Install Required Packages
6 |
7 | OS: Ubuntu 16.04
8 | Read through and run [./install.sh](./install.sh)
9 |
10 | ## Code Directories
11 |
12 | [models/](models/)
13 |
14 | * Reproducing Udacity self-driving car Challenge2[1] results for Rambo, Chauffeur and Epoch models.
15 | * [Models and weights files](https://github.com/ARiSE-Lab/deepTest#models-and-saved-weights) are required to run these scripts.
16 | * For Rambo model, Keras backend should be changed to theano.
17 |
18 | [testgen/](testgen/)
19 | * Generate synthetic images, calculate cumulative coverage and record predicted outputs.
20 | * [ncoverage.py](testgen/ncoverage.py): define NCoverage class for computing neuron coverage.
21 |
22 | [guided/](guided/)
23 | * Combine different transformations and leverage neuron coverage to guide the search.
24 | * Re-runing the script will continue the search instead of starting from the beginning except deleting all pkl files.
25 |
26 | [metamorphictesting/](metamorphictesting/)
27 |
28 | ## Models and [Saved Weights](https://github.com/udacity/self-driving-car/tree/master/steering-models/evaluation)
29 | * Rambo [2]
30 | * Chauffeur [3]
31 | * Epoch [4]
32 |
33 |
34 | ## Datasets
35 |
36 | * [HMB_3.bag](https://github.com/udacity/self-driving-car/blob/master/datasets/CH2/HMB_3.bag.tar.gz.torrent): Test dataset
37 | * [CH2_001](https://github.com/udacity/self-driving-car/tree/master/datasets/CH2): Final Test Data for challenge2
38 | * [CH2_001 labels](https://github.com/udacity/self-driving-car/blob/master/challenges/challenge-2/CH2_final_evaluation.csv)
39 |
40 | ### Generate hmb3 dataset from HMB_3.bag
41 |
42 | ```
43 | mkdir hmb3
44 | python generate_hmb3.py --bagfile HMB_3.bag
45 | ```
46 | The following commands are to install python-rosbag api.
47 | ```
48 | sudo apt-get install python-rosbag
49 | sudo apt-get install python-genmsg
50 | sudo apt-get install python-genpy
51 | sudo apt-get install python-rosgraph-msgs
52 | ```
53 | ## Reproducing experiments
54 |
55 | ### Dataset directory structure:
56 | ./Dataset/
57 | ├── hmb3/
58 | └── hmb3_steering.csv
59 | └── images
60 | └── Ch2_001/
61 | └── center/
62 | └── images
63 | └── CH2_final_evaluation.csv
64 |
65 | ### Evaluating models' accuracy on existing test data
66 | ```
67 | cd models/
68 | python epoch_reproduce.py --dataset DATA_PATH/Dataset/
69 | python chauffeur_reproduce.py --dataset DATA_PATH/Dataset/
70 | python rambo_reproduce.py --dataset DATA_PATH/Dataset/
71 | ```
72 | ### Generate synthetic images and compute cumulative neuron coverage
73 | ```
74 | cd testgen/
75 | ./epoch_testgen_driver.sh 'DATA_PATH/Dataset/'
76 | ./chauffeur_testgen_driver.sh 'DATA_PATH/Dataset/'
77 | python rambo_testgen_coverage.py --dataset DATA_PATH/Dataset/
78 | ```
79 | ### Combine transformations and synthesize images by guided search
80 | ```
81 | cd guided/
82 | mkdir new/
83 | rm -rf *.pkl
84 | python epoch_guided.py --dataset DATA_PATH/Dataset/
85 | python chauffeur_guided.py --dataset DATA_PATH/Dataset/
86 | python rambo_guided.py --dataset DATA_PATH/Dataset/
87 | ```
88 |
89 |
90 | ## Detected erroneous behaviors
91 | https://deeplearningtest.github.io/deepTest/
92 |
93 | ## Citation
94 | If you find DeepTest useful for your research, please cite the following [paper](https://arxiv.org/pdf/1708.08559.pdf):
95 |
96 | ```
97 | @article{tian2017deeptest,
98 | title={DeepTest: Automated testing of deep-neural-network-driven autonomous cars},
99 | author={Tian, Yuchi and Pei, Kexin and Jana, Suman and Ray, Baishakhi},
100 | journal={arXiv preprint arXiv:1708.08559},
101 | year={2017}
102 | }
103 |
104 | ```
105 | ## References
106 |
107 | 1. **Udacity self driving car challenge 2**.
108 | https://github.com/udacity/self-driving-car/tree/master/challenges/challenge-2. (2016).
109 | 2. **Rambo model**.
110 | https://github.com/udacity/self-driving-car/tree/master/steering-models/community-models/rambo. (2016).
111 | 3. **Chauffeur model**.
112 | https://github.com/udacity/self-driving-car/tree/master/steering-models/community-models/chauffeur. (2016).
113 | 4. **Epoch model**.
114 | https://github.com/udacity/self-driving-car/tree/master/steering-models/community-models/cg23. (2016).
115 |
116 |
--------------------------------------------------------------------------------
/generate_hmb3.py:
--------------------------------------------------------------------------------
1 | '''
2 | Generate images and steering angles from hmb3.bag
3 | Modified from
4 | https://github.com/udacity/self-driving-car/blob/master/steering-models/evaluation/generator.py
5 | '''
6 | import argparse
7 | import rosbag
8 | from StringIO import StringIO
9 | from scipy import misc
10 | import numpy as np
11 | import csv
12 |
13 | KEY_NAME = {
14 | '/vehicle/steering_report': 'steering',
15 | '/center_camera/image_color/c': 'image',
16 | }
17 |
18 | def update(msg, d):
19 | key = KEY_NAME.get(msg[0])
20 | if key is None: return
21 | d[key] = msg
22 |
23 | def gen(bag):
24 | print 'Getting bag'
25 | bag = rosbag.Bag(bag)
26 | print 'Got bag'
27 |
28 | image = {}
29 | total = bag.get_message_count()
30 | count = 0
31 | for e in bag.read_messages():
32 |
33 | count += 1
34 | if count % 10000 == 0:
35 | print count, '/', total
36 | if e[0] in ['/center_camera/image_color/compressed']:
37 | #print(e)
38 | if len({'steering'} - set(image.keys())):
39 | continue
40 | if image['steering'][1].speed < 5.: continue
41 | s = StringIO(e[1].data)
42 | img = misc.imread(s)
43 | yield img, np.copy(img), image['steering'][1].speed,\
44 | image['steering'][1].steering_wheel_angle, e[2].to_nsec()
45 | last_ts = e[2].to_nsec()
46 | else:
47 | update(e, image)
48 |
49 |
50 | if __name__ == '__main__':
51 | parser = argparse.ArgumentParser(description='generate images from hmb3')
52 | parser.add_argument('--bagfile', type=str, help='Path to ROS bag')
53 | args = parser.parse_args()
54 | data_iter = gen(args.bagfile)
55 | with open('hmb3/hmb3_steering.csv', 'wb',0) as hmb3csv:
56 | writer = csv.writer(hmb3csv, delimiter=',', quotechar='|', quoting=csv.QUOTE_MINIMAL)
57 | writer.writerow(['timestamp','steering angle'])
58 |
59 | for image_pred, image_disp, speed, steering, ts in data_iter:
60 | misc.imsave('hmb3/'+ str(ts) + '.jpg', image_disp)
61 | #print(ts)
62 | csvcontent = []
63 | csvcontent.append(ts)
64 | csvcontent.append(steering)
65 | writer.writerow(csvcontent)
66 |
--------------------------------------------------------------------------------
/guided/chauffeur_guided.py:
--------------------------------------------------------------------------------
1 | '''
2 | Leverage neuron coverage to guide the generation of images from combinations of transformations.
3 | '''
4 | from __future__ import print_function
5 | import argparse
6 | import numpy as np
7 | import os
8 | import sys
9 | from collections import defaultdict
10 | import random
11 | from keras import backend as K
12 | from ncoverage import NCoverage
13 | import csv
14 | import cv2
15 | import pickle
16 | from keras import backend as K
17 | from keras.models import model_from_json
18 | import argparse
19 | from collections import deque
20 |
21 |
22 | reload(sys)
23 | sys.setdefaultencoding('utf8')
24 | # keras 1.2.2 tf:1.2.0
25 | class ChauffeurModel(object):
26 | '''
27 | Chauffeur model with integrated neuron coverage
28 | '''
29 | def __init__(self,
30 | cnn_json_path,
31 | cnn_weights_path,
32 | lstm_json_path,
33 | lstm_weights_path, only_layer=""):
34 |
35 | self.cnn = self.load_from_json(cnn_json_path, cnn_weights_path)
36 | self.encoder = self.load_encoder(cnn_json_path, cnn_weights_path)
37 | self.lstm = self.load_from_json(lstm_json_path, lstm_weights_path)
38 |
39 | # hardcoded from final submission model
40 | self.scale = 16.
41 | self.timesteps = 100
42 |
43 | self.threshold_cnn = 0.1
44 | self.threshold_lstm = 0.4
45 | self.timestepped_x = np.empty((1, self.timesteps, 8960))
46 | self.nc_lstm = NCoverage(self.lstm, self.threshold_lstm)
47 | self.nc_encoder = NCoverage(self.encoder, self.threshold_cnn, exclude_layer=['pool', 'fc', 'flatten'], only_layer=only_layer)
48 | self.steps = deque()
49 | #print(self.lstm.summary())
50 | #self.nc = NCoverage(self.lstm,self.threshold)
51 |
52 | def load_encoder(self, cnn_json_path, cnn_weights_path):
53 | model = self.load_from_json(cnn_json_path, cnn_weights_path)
54 | model.load_weights(cnn_weights_path)
55 |
56 | model.layers.pop()
57 | model.outputs = [model.layers[-1].output]
58 | model.layers[-1].outbound_nodes = []
59 |
60 | return model
61 |
62 | def load_from_json(self, json_path, weights_path):
63 | model = model_from_json(open(json_path, 'r').read())
64 | model.load_weights(weights_path)
65 | return model
66 |
67 | def make_cnn_only_predictor(self):
68 | def predict_fn(img):
69 | img = cv2.resize(img, (320, 240))
70 | img = cv2.cvtColor(img, cv2.COLOR_BGR2YUV)
71 | img = img[120:240, :, :]
72 | img[:, :, 0] = cv2.equalizeHist(img[:, :, 0])
73 | img = ((img-(255.0/2))/255.0)
74 |
75 | return self.cnn.predict_on_batch(img.reshape((1, 120, 320, 3)))[0, 0] / self.scale
76 |
77 | return predict_fn
78 |
79 | #def make_stateful_predictor(self):
80 | #steps = deque()
81 |
82 | def predict_fn(self, img, test=0):
83 | # test == 0: update the coverage only
84 | # test == 1: test if the input image will increase the current coverage
85 | steps = self.steps
86 | img = cv2.resize(img, (320, 240))
87 | img = cv2.cvtColor(img, cv2.COLOR_BGR2YUV)
88 | img = img[120:240, :, :]
89 | img[:, :, 0] = cv2.equalizeHist(img[:, :, 0])
90 | img = ((img-(255.0/2))/255.0)
91 | img1 = img
92 |
93 | if test == 1:
94 | return self.nc_encoder.is_testcase_increase_coverage(img1.reshape((1, 120, 320, 3)))
95 | else:
96 | cnn_ndict = self.nc_encoder.update_coverage(img1.reshape((1, 120, 320, 3)))
97 | cnn_covered_neurons, cnn_total_neurons, cnn_p = self.nc_encoder.curr_neuron_cov()
98 | return cnn_covered_neurons, cnn_total_neurons, cnn_p
99 |
100 | #return predict_fn
101 | def save_object(obj, filename):
102 | with open(filename, 'wb') as output:
103 | pickle.dump(obj, output, pickle.HIGHEST_PROTOCOL)
104 |
105 |
106 |
107 | def image_translation(img, params):
108 | if not isinstance(params, list):
109 | params = [params, params]
110 | rows, cols, ch = img.shape
111 |
112 | M = np.float32([[1, 0, params[0]], [0, 1, params[1]]])
113 | dst = cv2.warpAffine(img, M, (cols, rows))
114 | return dst
115 |
116 | def image_scale(img, params):
117 | if not isinstance(params, list):
118 | params = [params, params]
119 | res = cv2.resize(img, None, fx=params[0], fy=params[1], interpolation=cv2.INTER_CUBIC)
120 | return res
121 |
122 | def image_shear(img, params):
123 | rows, cols, ch = img.shape
124 | factor = params*(-1.0)
125 | M = np.float32([[1, factor, 0], [0, 1, 0]])
126 | dst = cv2.warpAffine(img, M, (cols, rows))
127 | return dst
128 |
129 | def image_rotation(img, params):
130 | rows, cols, ch = img.shape
131 | M = cv2.getRotationMatrix2D((cols/2, rows/2), params, 1)
132 | dst = cv2.warpAffine(img, M, (cols, rows))
133 | return dst
134 |
135 | def image_contrast(img, params):
136 | alpha = params
137 | new_img = cv2.multiply(img, np.array([alpha])) # mul_img = img*alpha
138 | #new_img = cv2.add(mul_img, beta) # new_img = img*alpha + beta
139 |
140 | return new_img
141 |
142 | def image_brightness(img, params):
143 | beta = params
144 | new_img = cv2.add(img, beta) # new_img = img*alpha + beta
145 |
146 | return new_img
147 |
148 | def image_blur(img, params):
149 | blur = []
150 | if params == 1:
151 | blur = cv2.blur(img, (3, 3))
152 | if params == 2:
153 | blur = cv2.blur(img, (4, 4))
154 | if params == 3:
155 | blur = cv2.blur(img, (5, 5))
156 | if params == 4:
157 | blur = cv2.GaussianBlur(img, (3, 3), 0)
158 | if params == 5:
159 | blur = cv2.GaussianBlur(img, (5, 5), 0)
160 | if params == 6:
161 | blur = cv2.GaussianBlur(img, (7, 7), 0)
162 | if params == 7:
163 | blur = cv2.medianBlur(img, 3)
164 | if params == 8:
165 | blur = cv2.medianBlur(img, 5)
166 | if params == 9:
167 | blur = cv2.blur(img, (6, 6))
168 | if params == 10:
169 | blur = cv2.bilateralFilter(img, 9, 75, 75)
170 | return blur
171 |
172 | def rotation(img, params):
173 |
174 | rows,cols,ch = img.shape
175 | M = cv2.getRotationMatrix2D((cols/2, rows/2), params[0], 1)
176 | dst = cv2.warpAffine(img, M, (cols, rows))
177 | return dst
178 |
179 | def image_brightness1(img, params):
180 | w = img.shape[1]
181 | h = img.shape[0]
182 | if params > 0:
183 | for xi in xrange(0, w):
184 | for xj in xrange(0, h):
185 | if 255-img[xj, xi, 0] < params:
186 | img[xj, xi, 0] = 255
187 | else:
188 | img[xj, xi, 0] = img[xj, xi, 0] + params
189 | if 255-img[xj, xi, 1] < params:
190 | img[xj, xi, 1] = 255
191 | else:
192 | img[xj, xi, 1] = img[xj, xi, 1] + params
193 | if 255-img[xj, xi, 2] < params:
194 | img[xj, xi, 2] = 255
195 | else:
196 | img[xj, xi, 2] = img[xj, xi, 2] + params
197 | if params < 0:
198 | params = params*(-1)
199 | for xi in xrange(0, w):
200 | for xj in xrange(0, h):
201 | if img[xj, xi, 0] - 0 < params:
202 | img[xj, xi, 0] = 0
203 | else:
204 | img[xj, xi, 0] = img[xj, xi, 0] - params
205 | if img[xj, xi, 1] - 0 < params:
206 | img[xj, xi, 1] = 0
207 | else:
208 | img[xj, xi, 1] = img[xj, xi, 1] - params
209 | if img[xj, xi, 2] - 0 < params:
210 | img[xj, xi, 2] = 0
211 | else:
212 | img[xj, xi, 2] = img[xj, xi, 2] - params
213 |
214 | return img
215 |
216 | def image_brightness2(img, params):
217 | beta = params
218 | b, g, r = cv2.split(img)
219 | b = cv2.add(b, beta)
220 | g = cv2.add(g, beta)
221 | r = cv2.add(r, beta)
222 | new_img = cv2.merge((b, g, r))
223 | return new_img
224 |
225 | def chauffeur_guided(dataset_path):
226 | model_name = "cnn"
227 | image_size = (128, 128)
228 | threshold = 0.2
229 |
230 | root = ""
231 | seed_inputs1 = os.path.join(dataset_path, "hmb3/")
232 | seed_labels1 = os.path.join(dataset_path, "hmb3/hmb3_steering.csv")
233 | seed_inputs2 = os.path.join(dataset_path, "Ch2_001/center/")
234 | seed_labels2 = os.path.join(dataset_path, "Ch2_001/CH2_final_evaluation.csv")
235 | new_input = "./new/"
236 | # Model build
237 | # ---------------------------------------------------------------------------------
238 | cnn_json_path = "./cnn.json"
239 | cnn_weights_path = "./cnn.weights"
240 | lstm_json_path = "./lstm.json"
241 | lstm_weights_path = "./lstm.weights"
242 |
243 | K.set_learning_phase(0)
244 | model = ChauffeurModel(
245 | cnn_json_path,
246 | cnn_weights_path,
247 | lstm_json_path,
248 | lstm_weights_path)
249 |
250 |
251 | filelist1 = []
252 | for file in sorted(os.listdir(seed_inputs1)):
253 | if file.endswith(".jpg"):
254 | filelist1.append(file)
255 |
256 | newlist = []
257 | for file in sorted(os.listdir(new_input)):
258 | if file.endswith(".jpg"):
259 | newlist.append(file)
260 | flag = 0
261 | #flag:0 start from beginning
262 | #flag:1 initialize from pickle files
263 |
264 | '''
265 | Pickle files are used for continuing the search after rerunning the script.
266 | Delete all pkl files and generated images for starting from the beginnning.
267 | '''
268 | if os.path.isfile("chauffeur_covdict2.pkl") and \
269 | os.path.isfile("chauffeur_stack.pkl") and \
270 | os.path.isfile("chauffeur_queue.pkl") and \
271 | os.path.isfile("generated.pkl"):
272 | with open('chauffeur_covdict2.pkl', 'rb') as input:
273 | covdict = pickle.load(input)
274 | with open('chauffeur_stack.pkl', 'rb') as input:
275 | chauffeur_stack = pickle.load(input)
276 | with open('chauffeur_queue.pkl', 'rb') as input:
277 | chauffeur_queue = pickle.load(input)
278 | with open('generated.pkl', 'rb') as input:
279 | generated = pickle.load(input)
280 | flag = 1
281 |
282 |
283 | if flag == 0:
284 | filewrite = "wb"
285 | chauffeur_queue = deque()
286 | chauffeur_stack = []
287 | generated = 0
288 | else:
289 | model.nc_encoder.set_covdict(covdict)
290 | filewrite = "ab"
291 | print("initialize from files")
292 |
293 | C = 0 # covered neurons
294 | P = 0 # covered percentage
295 | T = 0 # total neurons
296 | transformations = [image_translation, image_scale, image_shear,
297 | image_rotation, image_contrast, image_brightness2, image_blur]
298 | params = []
299 | params.append(list(xrange(-50, 50)))
300 | params.append(list(map(lambda x: x*0.1, list(xrange(5, 20)))))
301 | params.append(list(map(lambda x: x*0.1, list(xrange(-5, 5)))))
302 | params.append(list(xrange(-30, 30)))
303 | params.append(list(map(lambda x: x*0.1, list(xrange(1, 20)))))
304 | params.append(list(xrange(-21, 21)))
305 | params.append(list(xrange(1, 11)))
306 |
307 | maxtrynumber = 10
308 | cache = deque()
309 | #load nc, generation, population
310 | with open('result/chauffeur_rq3_100_2.csv', filewrite, 0) as csvfile:
311 | writer = csv.writer(csvfile, delimiter=',',
312 | quotechar='|', quoting=csv.QUOTE_MINIMAL)
313 | if flag == 0:
314 | writer.writerow(['id', 'seed image(root)', 'parent image', 'generated images',
315 | 'total_covered','total_neurons', 'coverage_percentage'])
316 | #initialize population and coverage
317 | print("compute coverage of original population")
318 | input_images = xrange(0, 100)
319 | for i in input_images:
320 | j = 2100 + i * 10
321 | chauffeur_queue.append(os.path.join(seed_inputs1, filelist1[j]))
322 | #exitcount = 0
323 | while len(chauffeur_queue) > 0:
324 | current_seed_image = chauffeur_queue[0]
325 | print(str(len(chauffeur_queue)) + " images are left.")
326 | if len(chauffeur_stack) == 0:
327 | chauffeur_stack.append(current_seed_image)
328 |
329 | while len(chauffeur_stack) > 0:
330 | try:
331 | image_file = chauffeur_stack[-1]
332 | print("current image in stack " + image_file)
333 | image = cv2.imread(image_file)
334 | covered, total, p = model.predict_fn(image)
335 | new_generated = False
336 | for i in xrange(maxtrynumber):
337 |
338 | #exitcount = exitcount + 1
339 | tid = random.sample([0,1,2,3,4,5,6], 2)
340 | if len(cache) > 0:
341 | tid[0] = cache.popleft()
342 | for j in xrange(2):
343 | new_image = image
344 | transformation = transformations[tid[j]]
345 | #random choose parameter
346 | param = random.sample(params[tid[j]], 1)
347 | param = param[0]
348 | print("transformation " + str(transformation) + " parameter " + str(param))
349 | new_image = transformation(new_image,param)
350 |
351 | if model.predict_fn(new_image, test = 1):
352 | print("Generated image increases coverage and will be added to population.")
353 | cache.append(tid[0])
354 | cache.append(tid[1])
355 | generated = generated + 1
356 | name = os.path.basename(current_seed_image)+'_' + str(generated)+'.jpg'
357 | name = os.path.join(new_input,name)
358 | cv2.imwrite(name,new_image)
359 | chauffeur_stack.append(name)
360 |
361 | covered, total, p = model.predict_fn(image)
362 | C = covered
363 | T = total
364 | P = p
365 | csvrecord = []
366 | csvrecord.append(100-len(chauffeur_queue))
367 | csvrecord.append(os.path.basename(current_seed_image))
368 | if len(chauffeur_stack) >= 2:
369 | parent = os.path.basename(chauffeur_stack[-2])
370 | else:
371 | parent = os.path.basename(current_seed_image)
372 | csvrecord.append(parent)
373 | csvrecord.append(generated)
374 | csvrecord.append(C)
375 | csvrecord.append(T)
376 | csvrecord.append(P)
377 | print(csvrecord)
378 | writer.writerow(csvrecord)
379 | new_generated = True
380 | break
381 | else:
382 | print("Generated image does not increase coverage.")
383 | '''
384 | # If the memory is not enough, the following code can be used to exit.
385 | # Re-runing the script will continue from previous progree.
386 | print("exitcount: " + str(exitcount))
387 | if exitcount % 30 == 0:
388 | exit()
389 | '''
390 |
391 | if not new_generated:
392 | chauffeur_stack.pop()
393 |
394 | save_object(chauffeur_stack, 'chauffeur_stack.pkl')
395 | save_object(chauffeur_queue, 'chauffeur_queue.pkl')
396 | save_object(model.nc_encoder.cov_dict, 'chauffeur_covdict2.pkl')
397 | save_object(generated, 'generated.pkl')
398 | '''
399 | # If the memory is not enough, the following code can be used to exit.
400 | # Re-runing the script will continue from previous progree.
401 | print("exitcount: " + str(exitcount))
402 | if exitcount % 30 == 0:
403 | exit()
404 | '''
405 |
406 | except:
407 | print("value error")
408 | chauffeur_stack.pop()
409 | save_object(chauffeur_stack, 'chauffeur_stack.pkl')
410 | save_object(chauffeur_queue, 'chauffeur_queue.pkl')
411 |
412 | chauffeur_queue.popleft()
413 | #maxtrynumber = maxtrynumber + 10
414 |
415 | if __name__ == '__main__':
416 | parser = argparse.ArgumentParser()
417 | parser.add_argument('--dataset', type=str, default='/media/yuchi/345F-2D0F/',
418 | help='path for dataset')
419 | args = parser.parse_args()
420 | chauffeur_guided(args.dataset)
421 |
--------------------------------------------------------------------------------
/guided/epoch_guided.py:
--------------------------------------------------------------------------------
1 | from __future__ import print_function
2 | import os
3 | import argparse
4 | import numpy as np
5 | import time
6 | import random
7 | from collections import deque
8 | from keras import backend as K
9 | from epoch_model import build_cnn, build_InceptionV3
10 | from scipy.misc import imread, imresize, imsave
11 | from scipy.misc import imshow
12 | from ncoverage import NCoverage
13 | import csv
14 | import cv2
15 | import pickle
16 |
17 | def save_object(obj, filename):
18 | with open(filename, 'wb') as output:
19 | pickle.dump(obj, output, pickle.HIGHEST_PROTOCOL)
20 |
21 | def preprocess_input_InceptionV3(x):
22 | x /= 255.
23 | x -= 0.5
24 | x *= 2.
25 | return x
26 |
27 | def exact_output(y):
28 | return y
29 |
30 | def normalize_input(x):
31 | return x / 255.
32 |
33 | def read_image(image_file, image_size):
34 |
35 | img = imread(image_file)
36 | # Cropping
37 | crop_img = img[200:, :]
38 | # Resizing
39 | img = imresize(crop_img, size=image_size)
40 | imgs = []
41 | imgs.append(img)
42 | if len(imgs) < 1:
43 | print('Error no image at timestamp')
44 |
45 | img_block = np.stack(imgs, axis=0)
46 | if K.image_dim_ordering() == 'th':
47 | img_block = np.transpose(img_block, axes=(0, 3, 1, 2))
48 | return img_block
49 |
50 | def read_images(seed_inputs, seed_labels, image_size):
51 |
52 | img_blocks = []
53 | for file in os.listdir(seed_inputs):
54 | if file.endswith(".jpg"):
55 | img_block = read_image(os.path.join(seed_inputs, file), image_size)
56 | img_blocks.append(img_block)
57 | return img_blocks
58 |
59 | def read_transformed_image(image, image_size):
60 |
61 | img = image
62 | # Cropping
63 | crop_img = img[200:, :]
64 | # Resizing
65 | img = imresize(crop_img, size=image_size)
66 | imgs = []
67 | imgs.append(img)
68 | if len(imgs) < 1:
69 | print('Error no image at timestamp')
70 |
71 | img_block = np.stack(imgs, axis=0)
72 | if K.image_dim_ordering() == 'th':
73 | img_block = np.transpose(img_block, axes=(0, 3, 1, 2))
74 | return img_block
75 |
76 | def image_translation(img, params):
77 | if not isinstance(params, list):
78 | params = [params, params]
79 | rows, cols, ch = img.shape
80 |
81 | M = np.float32([[1, 0, params[0]], [0, 1, params[1]]])
82 | dst = cv2.warpAffine(img, M, (cols, rows))
83 | return dst
84 |
85 | def image_scale(img, params):
86 | if not isinstance(params, list):
87 | params = [params, params]
88 | res = cv2.resize(img, None, fx=params[0], fy=params[1], interpolation=cv2.INTER_CUBIC)
89 | return res
90 |
91 | def image_shear(img, params):
92 | rows, cols, ch = img.shape
93 | factor = params*(-1.0)
94 | M = np.float32([[1, factor, 0], [0, 1, 0]])
95 | dst = cv2.warpAffine(img, M, (cols, rows))
96 | return dst
97 |
98 | def image_rotation(img, params):
99 | rows, cols, ch = img.shape
100 | M = cv2.getRotationMatrix2D((cols/2, rows/2), params, 1)
101 | dst = cv2.warpAffine(img, M, (cols, rows))
102 | return dst
103 |
104 | def image_contrast(img, params):
105 | alpha = params
106 | new_img = cv2.multiply(img, np.array([alpha])) # mul_img = img*alpha
107 | #new_img = cv2.add(mul_img, beta) # new_img = img*alpha + beta
108 |
109 | return new_img
110 |
111 | def image_brightness(img, params):
112 | beta = params
113 | new_img = cv2.add(img, beta) # new_img = img*alpha + beta
114 |
115 | return new_img
116 |
117 | def image_blur(img, params):
118 | blur = []
119 | if params == 1:
120 | blur = cv2.blur(img, (3, 3))
121 | if params == 2:
122 | blur = cv2.blur(img, (4, 4))
123 | if params == 3:
124 | blur = cv2.blur(img, (5, 5))
125 | if params == 4:
126 | blur = cv2.GaussianBlur(img, (3, 3), 0)
127 | if params == 5:
128 | blur = cv2.GaussianBlur(img, (5, 5), 0)
129 | if params == 6:
130 | blur = cv2.GaussianBlur(img, (7, 7), 0)
131 | if params == 7:
132 | blur = cv2.medianBlur(img, 3)
133 | if params == 8:
134 | blur = cv2.medianBlur(img, 5)
135 | if params == 9:
136 | blur = cv2.blur(img, (6, 6))
137 | if params == 10:
138 | blur = cv2.bilateralFilter(img, 9, 75, 75)
139 | return blur
140 |
141 | def rotation(img, params):
142 |
143 | rows, cols, ch = img.shape
144 | M = cv2.getRotationMatrix2D((cols/2, rows/2), params[0], 1)
145 | dst = cv2.warpAffine(img, M, (cols, rows))
146 | return dst
147 |
148 | def image_brightness1(img, params):
149 | w = img.shape[1]
150 | h = img.shape[0]
151 | if params > 0:
152 | for xi in xrange(0, w):
153 | for xj in xrange(0, h):
154 | if 255-img[xj, xi, 0] < params:
155 | img[xj, xi, 0] = 255
156 | else:
157 | img[xj, xi, 0] = img[xj, xi, 0] + params
158 | if 255-img[xj, xi, 1] < params:
159 | img[xj, xi, 1] = 255
160 | else:
161 | img[xj, xi, 1] = img[xj, xi, 1] + params
162 | if 255-img[xj, xi, 2] < params:
163 | img[xj, xi, 2] = 255
164 | else:
165 | img[xj, xi, 2] = img[xj, xi, 2] + params
166 | if params < 0:
167 | params = params*(-1)
168 | for xi in xrange(0, w):
169 | for xj in xrange(0, h):
170 | if img[xj, xi, 0] - 0 < params:
171 | img[xj, xi, 0] = 0
172 | else:
173 | img[xj, xi, 0] = img[xj, xi, 0] - params
174 | if img[xj, xi, 1] - 0 < params:
175 | img[xj, xi, 1] = 0
176 | else:
177 | img[xj, xi, 1] = img[xj, xi, 1] - params
178 | if img[xj, xi, 2] - 0 < params:
179 | img[xj, xi, 2] = 0
180 | else:
181 | img[xj, xi, 2] = img[xj, xi, 2] - params
182 |
183 | return img
184 |
185 | def image_brightness2(img, params):
186 | beta = params
187 | b, g, r = cv2.split(img)
188 | b = cv2.add(b, beta)
189 | g = cv2.add(g, beta)
190 | r = cv2.add(r, beta)
191 | new_img = cv2.merge((b, g, r))
192 | return new_img
193 |
194 |
195 | def epoch_guided(dataset_path):
196 | model_name = "cnn"
197 | image_size = (128, 128)
198 | threshold = 0.2
199 | weights_path = './weights_HMB_2.hdf5' # Change to your model weights
200 |
201 | seed_inputs1 = os.path.join(dataset_path, "hmb3/")
202 | seed_labels1 = os.path.join(dataset_path, "hmb3/hmb3_steering.csv")
203 | seed_inputs2 = os.path.join(dataset_path, "Ch2_001/center/")
204 | seed_labels2 = os.path.join(dataset_path, "Ch2_001/CH2_final_evaluation.csv")
205 |
206 | new_inputs = "./new/"
207 | # Model build
208 | # ---------------------------------------------------------------------------------
209 | model_builders = {
210 | 'V3': (build_InceptionV3, preprocess_input_InceptionV3, exact_output)
211 | , 'cnn': (build_cnn, normalize_input, exact_output)}
212 |
213 | if model_name not in model_builders:
214 | raise ValueError("unsupported model %s" % model_name)
215 | model_builder, input_processor, output_processor = model_builders[model_name]
216 | model = model_builder(image_size, weights_path)
217 | print('model %s built...' % model_name)
218 |
219 |
220 | filelist1 = []
221 | for file in sorted(os.listdir(seed_inputs1)):
222 | if file.endswith(".jpg"):
223 | filelist1.append(file)
224 |
225 | truth = {}
226 | with open(seed_labels1, 'rb') as csvfile1:
227 | label1 = list(csv.reader(csvfile1, delimiter=',', quotechar='|'))
228 | label1 = label1[1:]
229 | for i in label1:
230 | truth[i[0]+".jpg"] = i[1]
231 |
232 |
233 | newlist = []
234 | for file in sorted(os.listdir(new_inputs)):
235 | if file.endswith(".jpg"):
236 | newlist.append(file)
237 |
238 | flag = 0
239 | #flag:0 start from beginning
240 | #flag:1 initialize from pickle files
241 |
242 | '''
243 | Pickle files are used for continuing the search after rerunning the script.
244 | Delete all pkl files and generated images for starting from the beginnning.
245 | '''
246 | if os.path.isfile("epoch_covdict2.pkl") and \
247 | os.path.isfile("epoch_stack.pkl") and \
248 | os.path.isfile("epoch_queue.pkl") and \
249 | os.path.isfile("generated.pkl"):
250 | with open('epoch_covdict2.pkl', 'rb') as input:
251 | covdict = pickle.load(input)
252 | with open('epoch_stack.pkl', 'rb') as input:
253 | epoch_stack = pickle.load(input)
254 | with open('epoch_queue.pkl', 'rb') as input:
255 | epoch_queue = pickle.load(input)
256 | with open('generated.pkl', 'rb') as input:
257 | generated = pickle.load(input)
258 | flag = 1
259 |
260 | nc = NCoverage(model, threshold)
261 |
262 | if flag == 0:
263 | filewrite = "wb"
264 | epoch_queue = deque()
265 | epoch_stack = []
266 | generated = 0
267 | else:
268 | nc.set_covdict(covdict)
269 | filewrite = "ab"
270 | print("initialize from files and continue from previous progress")
271 |
272 | C = 0 # covered neurons
273 | P = 0 # covered percentage
274 | T = 0 # total neurons
275 | transformations = [image_translation, image_scale, image_shear, image_rotation,
276 | image_contrast, image_brightness2, image_blur]
277 | params = []
278 | params.append(list(xrange(-50, 50)))
279 | params.append(list(map(lambda x: x*0.1, list(xrange(5, 20)))))
280 | params.append(list(map(lambda x: x*0.1, list(xrange(-5, 5)))))
281 | params.append(list(xrange(-30, 30)))
282 | params.append(list(map(lambda x: x*0.1, list(xrange(1, 20)))))
283 | params.append(list(xrange(-21, 21)))
284 | params.append(list(xrange(1, 11)))
285 |
286 | maxtrynumber = 10
287 | maximages = 200
288 | cache = deque()
289 | image_count = 0
290 | #load nc, generation, population
291 | with open('result/epoch_rq3_100_2.csv', filewrite, 0) as csvfile:
292 | writer = csv.writer(csvfile, delimiter=',',
293 | quotechar='|', quoting=csv.QUOTE_MINIMAL)
294 | if flag == 0:
295 | writer.writerow(['id', 'seed image(root)', 'parent image', 'new generated image',
296 | 'number of generated images', 'total_covered', 'total_neurons',
297 | 'coverage_percentage', 'transformations', 'yhat', 'baseline', 'label'])
298 | #initialize population and coverage
299 | print("compute coverage of original population")
300 | input_images = xrange(1, 101)
301 | for i in input_images:
302 | j = i * 50
303 | epoch_queue.append(os.path.join(seed_inputs1, filelist1[j]))
304 |
305 | while len(epoch_queue) > 0:
306 | current_seed_image = epoch_queue[0]
307 | print(str(len(epoch_queue)) + " images are left.")
308 | if len(epoch_stack) == 0:
309 | epoch_stack.append(current_seed_image)
310 | image = cv2.imread(current_seed_image)
311 | test_x = read_transformed_image(image, image_size)
312 | test_x = input_processor(test_x.astype(np.float32))
313 | nc.update_coverage(test_x)
314 | baseline_yhat = model.predict(test_x)
315 | #image_count = 0
316 | while len(epoch_stack) > 0:
317 | try:
318 |
319 | image_file = epoch_stack[-1]
320 | print("current image in stack " + image_file)
321 | image = cv2.imread(image_file)
322 | new_generated = False
323 | for i in xrange(maxtrynumber):
324 |
325 | tid = random.sample([0,1,2,3,4,5,6], 2)
326 | if len(cache) > 0:
327 | tid[0] = cache.popleft()
328 | transinfo = ""
329 | new_image = image
330 | for j in xrange(2):
331 | transformation = transformations[tid[j]]
332 | #random choose parameter
333 | param = random.sample(params[tid[j]], 1)
334 | param = param[0]
335 | transinfo = transinfo + transformation.__name__ + ':' + str(param) + ';'
336 | print("transformation " + transformation.__name__ + " parameter " + str(param))
337 | new_image = transformation(new_image, param)
338 |
339 | new_x = read_transformed_image(new_image, image_size)
340 |
341 | test_x = input_processor(new_x.astype(np.float32))
342 | if nc.is_testcase_increase_coverage(test_x):
343 | print("Generated image increases coverage and will be added to population.")
344 | cache.append(tid[0])
345 | cache.append(tid[1])
346 | generated = generated + 1
347 | #image_count = image_count + 1
348 | name = os.path.basename(current_seed_image)+'_' + str(generated)+'.jpg'
349 | name = os.path.join(new_inputs, name)
350 | cv2.imwrite(name, new_image)
351 | epoch_stack.append(name)
352 |
353 | nc.update_coverage(test_x)
354 | yhat = model.predict(test_x)
355 | covered, total, p = nc.curr_neuron_cov()
356 | C = covered
357 | T = total
358 | P = p
359 | csvrecord = []
360 | csvrecord.append(100-len(epoch_queue))
361 | csvrecord.append(os.path.basename(current_seed_image))
362 | if len(epoch_stack) >= 2:
363 | parent = os.path.basename(epoch_stack[-2])
364 | else:
365 | parent = os.path.basename(current_seed_image)
366 | child = os.path.basename(current_seed_image)+'_' + str(generated)+'.jpg'
367 | csvrecord.append(parent)
368 | csvrecord.append(child)
369 | csvrecord.append(generated)
370 | csvrecord.append(C)
371 | csvrecord.append(T)
372 | csvrecord.append(P)
373 | csvrecord.append(transinfo)
374 | csvrecord.append(yhat[0][0])
375 | csvrecord.append(baseline_yhat[0][0])
376 | csvrecord.append(truth[os.path.basename(current_seed_image)])
377 | print(csvrecord)
378 | writer.writerow(csvrecord)
379 | new_generated = True
380 | break
381 | else:
382 | print("Generated image does not increase coverage.")
383 | if not new_generated:
384 | epoch_stack.pop()
385 |
386 | save_object(epoch_stack, 'epoch_stack.pkl')
387 | save_object(epoch_queue, 'epoch_queue.pkl')
388 | save_object(nc.cov_dict, 'epoch_covdict2.pkl')
389 | save_object(generated, 'generated.pkl')
390 |
391 | except ValueError:
392 | print("value error")
393 | epoch_stack.pop()
394 | save_object(epoch_stack, 'epoch_stack.pkl')
395 | save_object(epoch_queue, 'epoch_queue.pkl')
396 |
397 | epoch_queue.popleft()
398 |
399 | if __name__ == '__main__':
400 |
401 | parser = argparse.ArgumentParser()
402 | parser.add_argument('--dataset', type=str, default='/media/yuchi/345F-2D0F/',
403 | help='path for dataset')
404 | args = parser.parse_args()
405 | epoch_guided(args.dataset)
406 |
--------------------------------------------------------------------------------
/guided/ncoverage.py:
--------------------------------------------------------------------------------
1 | from __future__ import print_function
2 | import numpy as np
3 | from keras.models import Model
4 |
5 | class NCoverage():
6 |
7 | def __init__(self, model, threshold=0.1, exclude_layer=['pool', 'fc', 'flatten'], only_layer=""):
8 | '''
9 | Initialize the model to be tested
10 | :param threshold: threshold to determine if the neuron is activated
11 | :param model_name: ImageNet Model name, can have ('vgg16','vgg19','resnet50')
12 | :param neuron_layer: Only these layers are considered for neuron coverage
13 | '''
14 | self.threshold = float(threshold)
15 | self.model = model
16 |
17 | print('models loaded')
18 |
19 | # the layers that are considered in neuron coverage computation
20 | self.layer_to_compute = []
21 | for layer in self.model.layers:
22 | if all(ex not in layer.name for ex in exclude_layer):
23 | self.layer_to_compute.append(layer.name)
24 |
25 | if only_layer != "":
26 | self.layer_to_compute = [only_layer]
27 |
28 | # init coverage table
29 | self.cov_dict = {}
30 |
31 | for layer_name in self.layer_to_compute:
32 | for index in xrange(self.model.get_layer(layer_name).output_shape[-1]):
33 | self.cov_dict[(layer_name, index)] = False
34 |
35 | def scale(self, layer_outputs, rmax=1, rmin=0):
36 | '''
37 | scale the intermediate layer's output between 0 and 1
38 | :param layer_outputs: the layer's output tensor
39 | :param rmax: the upper bound of scale
40 | :param rmin: the lower bound of scale
41 | :return:
42 | '''
43 | divider = (layer_outputs.max() - layer_outputs.min())
44 | if divider == 0:
45 | return np.zeros(shape=layer_outputs.shape)
46 | X_std = (layer_outputs - layer_outputs.min()) / divider
47 | X_scaled = X_std * (rmax - rmin) + rmin
48 | return X_scaled
49 |
50 |
51 | def set_covdict(self, covdict):
52 | self.cov_dict = dict(covdict)
53 |
54 | def get_neuron_coverage(self, input_data):
55 | '''
56 | Given the input, return the covered neurons by the input data without marking the covered neurons.
57 | '''
58 |
59 | covered_neurons = []
60 | for layer_name in self.layer_to_compute:
61 | layer_model = Model(input=self.model.input,
62 | output=self.model.get_layer(layer_name).output)
63 | layer_outputs = layer_model.predict(input_data)
64 | for layer_output in layer_outputs:
65 | scaled = self.scale(layer_output)
66 | for neuron_idx in xrange(scaled.shape[-1]):
67 | if np.mean(scaled[..., neuron_idx]) > self.threshold:
68 | if (layer_name, neuron_idx) not in covered_neurons:
69 | covered_neurons.append((layer_name, neuron_idx))
70 | return covered_neurons
71 |
72 |
73 | def update_coverage(self, input_data):
74 | '''
75 | Given the input, update the neuron covered in the model by this input.
76 | This includes mark the neurons covered by this input as "covered"
77 | :param input_data: the input image
78 | :return: the neurons that can be covered by the input
79 | '''
80 | for layer_name in self.layer_to_compute:
81 | layer_model = Model(input=self.model.inputs,
82 | output=self.model.get_layer(layer_name).output)
83 |
84 | layer_outputs = layer_model.predict(input_data)
85 |
86 | for layer_output in layer_outputs:
87 | scaled = self.scale(layer_output)
88 | #print(scaled.shape)
89 | for neuron_idx in xrange(scaled.shape[-1]):
90 | if np.mean(scaled[..., neuron_idx]) > self.threshold:
91 | self.cov_dict[(layer_name, neuron_idx)] = True
92 | del layer_outputs
93 | del layer_model
94 |
95 |
96 | return self.cov_dict
97 |
98 | def is_testcase_increase_coverage(self, input_data):
99 | '''
100 | Given the input, check if new neuron is covered without marking the covered neurons.
101 | If a previously not covered neuron is covered by the input, return True.
102 | Otherwise return False.
103 | '''
104 | for layer_name in self.layer_to_compute:
105 | layer_model = Model(input=self.model.inputs,
106 | output=self.model.get_layer(layer_name).output)
107 |
108 | layer_outputs = layer_model.predict(input_data)
109 |
110 | for layer_output in layer_outputs:
111 | scaled = self.scale(layer_output)
112 | #print(scaled.shape)
113 | for neuron_idx in xrange(scaled.shape[-1]):
114 | if np.mean(scaled[..., neuron_idx]) > self.threshold:
115 | if not self.cov_dict[(layer_name, neuron_idx)]:
116 | return True
117 |
118 | return False
119 |
120 |
121 | def curr_neuron_cov(self):
122 | '''
123 | Get current coverage information of MUT
124 | :return: number of covered neurons,
125 | number of total neurons,
126 | number of neuron coverage rate
127 | '''
128 | covered_neurons = len([v for v in self.cov_dict.values() if v])
129 | total_neurons = len(self.cov_dict)
130 | return covered_neurons, total_neurons, covered_neurons / float(total_neurons)
131 |
132 |
133 | def activated(self, layer_name, idx, input_data):
134 | '''
135 | Test if the neuron is activated by this input
136 | :param layer_name: the layer name
137 | :param idx: the neuron index in the layer
138 | :param input_data: the input
139 | :return: True/False
140 | '''
141 | layer_model = Model(input=self.model.input,
142 | output=self.model.get_layer(layer_name).output)
143 | layer_output = layer_model.predict(input_data)[0]
144 | scaled = self.scale(layer_output)
145 | if np.mean(scaled[..., idx]) > self.threshold:
146 | return True
147 | return False
148 |
149 | def reset_cov_dict(self):
150 | '''
151 | Reset the coverage table
152 | :return:
153 | '''
154 | for layer_name in self.layer_to_compute:
155 | for index in xrange(self.model.get_layer(layer_name).output_shape[-1]):
156 | self.cov_dict[(layer_name, index)] = False
157 |
--------------------------------------------------------------------------------
/guided/rambo_guided.py:
--------------------------------------------------------------------------------
1 | '''
2 | Leverage neuron coverage to guide the generation of images from combinations of transformations.
3 | '''
4 | from __future__ import print_function
5 | import argparse
6 | import sys
7 | import os
8 | import numpy as np
9 | from collections import deque
10 | from keras.models import load_model
11 | from keras.models import Model as Kmodel
12 | from keras.preprocessing.image import load_img, img_to_array
13 | from skimage.exposure import rescale_intensity
14 | import random
15 | import pickle
16 | from scipy import misc
17 | from ncoverage import NCoverage
18 | import csv
19 | import cv2
20 | from PIL import Image
21 | reload(sys)
22 | sys.setdefaultencoding('ISO-8859-1')
23 |
24 | class Model(object):
25 | '''
26 | Rambo model with integrated neuron coverage
27 | '''
28 | def __init__(self,
29 | model_path,
30 | X_train_mean_path):
31 |
32 | self.model = load_model(model_path)
33 | self.model.compile(optimizer="adam", loss="mse")
34 | self.X_mean = np.load(X_train_mean_path)
35 | self.mean_angle = np.array([-0.004179079])
36 | print (self.mean_angle)
37 | self.img0 = None
38 | self.state = deque(maxlen=2)
39 |
40 | self.threshold = 0.2
41 | #self.nc = NCoverage(self.model,self.threshold)
42 | s1 = self.model.get_layer('sequential_1')
43 | self.nc1 = NCoverage(s1, self.threshold)
44 | #print(s1.summary())
45 |
46 |
47 | s2 = self.model.get_layer('sequential_2')
48 | #print(s2.summary())
49 | self.nc2 = NCoverage(s2, self.threshold)
50 |
51 |
52 | s3 = self.model.get_layer('sequential_3')
53 | #print(s3.summary())
54 | self.nc3 = NCoverage(s3, self.threshold)
55 |
56 |
57 | i1 = self.model.get_layer('input_1')
58 |
59 | self.i1_model = Kmodel(input=self.model.inputs, output=i1.output)
60 |
61 |
62 |
63 | def predict(self, img):
64 | img_path = 'test.jpg'
65 | misc.imsave(img_path, img)
66 | img1 = load_img(img_path, grayscale=True, target_size=(192, 256))
67 | img1 = img_to_array(img1)
68 |
69 | if self.img0 is None:
70 | self.img0 = img1
71 | return self.mean_angle[0]
72 |
73 | elif len(self.state) < 1:
74 | img = img1 - self.img0
75 | img = rescale_intensity(img, in_range=(-255, 255), out_range=(0, 255))
76 | img = np.array(img, dtype=np.uint8) # to replicate initial model
77 | self.state.append(img)
78 | self.img0 = img1
79 |
80 | return self.mean_angle[0]
81 |
82 | else:
83 | img = img1 - self.img0
84 | img = rescale_intensity(img, in_range=(-255, 255), out_range=(0, 255))
85 | img = np.array(img, dtype=np.uint8) # to replicate initial model
86 | self.state.append(img)
87 | self.img0 = img1
88 |
89 | X = np.concatenate(self.state, axis=-1)
90 | X = X[:, :, ::-1]
91 | X = np.expand_dims(X, axis=0)
92 | X = X.astype('float32')
93 | X -= self.X_mean
94 | X /= 255.0
95 | return self.model.predict(X)[0][0]
96 |
97 | def predict1(self, img, transform, params):
98 | '''
99 | Rewrite predict method for computing and updating neuron coverage.
100 | '''
101 | img_path = 'test.jpg'
102 | misc.imsave(img_path, img)
103 | img1 = load_img(img_path, grayscale=True, target_size=(192, 256))
104 | img1 = img_to_array(img1)
105 |
106 | if self.img0 is None:
107 | self.img0 = img1
108 | return 0, 0, self.mean_angle[0],0,0,0,0,0,0,0,0,0
109 |
110 | elif len(self.state) < 1:
111 | img = img1 - self.img0
112 | img = rescale_intensity(img, in_range=(-255, 255), out_range=(0, 255))
113 | img = np.array(img, dtype=np.uint8) # to replicate initial model
114 | self.state.append(img)
115 | self.img0 = img1
116 |
117 | return 0, 0, self.mean_angle[0],0,0,0,0,0,0,0,0,0
118 |
119 | else:
120 | img = img1 - self.img0
121 | img = rescale_intensity(img, in_range=(-255, 255), out_range=(0, 255))
122 | img = np.array(img, dtype=np.uint8) # to replicate initial model
123 | self.state.append(img)
124 | self.img0 = img1
125 |
126 | X = np.concatenate(self.state, axis=-1)
127 |
128 | if transform != None and params != None:
129 | X = transform(X, params)
130 |
131 | X = X[:, :, ::-1]
132 | X = np.expand_dims(X, axis=0)
133 | X = X.astype('float32')
134 | X -= self.X_mean
135 | X /= 255.0
136 |
137 |
138 | #print(self.model.summary())
139 | #for layer in self.model.layers:
140 | #print (layer.name)
141 |
142 | i1_outputs = self.i1_model.predict(X)
143 |
144 | d1 = self.nc1.update_coverage(i1_outputs)
145 | covered_neurons1, total_neurons1, p1 = self.nc1.curr_neuron_cov()
146 | c1 = covered_neurons1
147 | t1 = total_neurons1
148 |
149 | d2 = self.nc2.update_coverage(i1_outputs)
150 | covered_neurons2, total_neurons2, p2 = self.nc2.curr_neuron_cov()
151 | c2 = covered_neurons2
152 | t2 = total_neurons2
153 |
154 | d3 = self.nc3.update_coverage(i1_outputs)
155 | covered_neurons3, total_neurons3, p3 = self.nc3.curr_neuron_cov()
156 | c3 = covered_neurons3
157 | t3 = total_neurons3
158 | covered_neurons = covered_neurons1 + covered_neurons2 + covered_neurons3
159 | total_neurons = total_neurons1 + total_neurons2 + total_neurons3
160 |
161 | return covered_neurons, total_neurons, self.model.predict(X)[0][0],c1,t1,d1,c2,t2,d2,c3,t3,d3
162 | #return 0, 0, self.model.predict(X)[0][0],rs1[0][0],rs2[0][0],rs3[0][0],0,0,0
163 |
164 | def hard_reset(self):
165 | '''
166 | Reset the coverage of three cnn sub-models
167 | '''
168 | self.mean_angle = np.array([-0.004179079])
169 | #print self.mean_angle
170 | self.img0 = None
171 | self.state = deque(maxlen=2)
172 | self.threshold = 0.2
173 | #self.nc.reset_cov_dict()
174 | self.nc1.reset_cov_dict()
175 | self.nc2.reset_cov_dict()
176 | self.nc3.reset_cov_dict()
177 |
178 |
179 | def soft_reset(self):
180 |
181 | self.mean_angle = np.array([-0.004179079])
182 | print (self.mean_angle)
183 | self.img0 = None
184 | self.state = deque(maxlen=2)
185 | self.threshold = 0.2
186 |
187 | def image_translation(img, params):
188 | if not isinstance(params, list):
189 | params = [params, params]
190 | rows, cols, ch = img.shape
191 |
192 | M = np.float32([[1, 0, params[0]], [0, 1, params[1]]])
193 | dst = cv2.warpAffine(img, M, (cols, rows))
194 | return dst
195 |
196 | def image_scale(img, params):
197 | if not isinstance(params, list):
198 | params = [params, params]
199 | res = cv2.resize(img, None, fx=params[0], fy=params[1], interpolation = cv2.INTER_CUBIC)
200 | return res
201 |
202 | def image_shear(img, params):
203 | rows, cols, ch = img.shape
204 | factor = params*(-1.0)
205 | M = np.float32([[1, factor, 0], [0, 1, 0]])
206 | dst = cv2.warpAffine(img, M, (cols, rows))
207 | return dst
208 |
209 | def image_rotation(img, params):
210 | rows, cols, ch = img.shape
211 | M = cv2.getRotationMatrix2D((cols/2, rows/2), params, 1)
212 | dst = cv2.warpAffine(img, M, (cols, rows))
213 | return dst
214 |
215 | def image_contrast(img, params):
216 | alpha = params
217 | new_img = cv2.multiply(img, np.array([alpha])) # mul_img = img*alpha
218 | #new_img = cv2.add(mul_img, beta) # new_img = img*alpha + beta
219 |
220 | return new_img
221 |
222 | def image_brightness(img, params):
223 | beta = params
224 | b, g, r = cv2.split(img)
225 | b = cv2.add(b, beta)
226 | g = cv2.add(g, beta)
227 | r = cv2.add(r, beta)
228 | new_img = cv2.merge((b, g, r))
229 | return new_img
230 |
231 | def image_blur(img, params):
232 | blur = []
233 | if params == 1:
234 | blur = cv2.blur(img, (3, 3))
235 | if params == 2:
236 | blur = cv2.blur(img, (4, 4))
237 | if params == 3:
238 | blur = cv2.blur(img, (5, 5))
239 | if params == 4:
240 | blur = cv2.GaussianBlur(img, (3, 3), 0)
241 | if params == 5:
242 | blur = cv2.GaussianBlur(img, (5, 5), 0)
243 | if params == 6:
244 | blur = cv2.GaussianBlur(img, (7, 7), 0)
245 | if params == 7:
246 | blur = cv2.medianBlur(img, 3)
247 | if params == 8:
248 | blur = cv2.medianBlur(img, 5)
249 | if params == 9:
250 | blur = cv2.blur(img, (6, 6))
251 | if params == 10:
252 | blur = cv2.blur(img, (7, 7))
253 | return blur
254 |
255 | def update_dict(dict1, covdict):
256 | '''
257 | Update neuron coverage dictionary dict1 with covered neurons in covdict
258 | '''
259 | r = False
260 | for k in covdict.keys():
261 | if covdict[k] and not dict1[k]:
262 | dict1[k] = True
263 | r = True
264 | return r
265 |
266 | def is_update_dict(dict1, covdict):
267 | '''
268 | Return True if there are neurons covered in dictionary covdict but not covered in dict1
269 | '''
270 | for k in covdict.keys():
271 | if covdict[k] and not dict1[k]:
272 | return True
273 | return False
274 |
275 | def get_current_coverage(covdict):
276 | '''
277 | Extract the covered neurons from the neuron coverage dictionary defined in ncoverage.py.
278 | '''
279 | covered_neurons = len([v for v in covdict.values() if v])
280 | total_neurons = len(covdict)
281 | return covered_neurons, total_neurons, covered_neurons / float(total_neurons)
282 |
283 | def save_object(obj, filename):
284 | with open(filename, 'wb') as output:
285 | pickle.dump(obj, output, pickle.HIGHEST_PROTOCOL)
286 |
287 | def rambo_guided(dataset_path):
288 | model_name = "cnn"
289 | image_size = (128, 128)
290 | threshold = 0.2
291 |
292 | seed_inputs1 = os.path.join(dataset_path, "hmb3/")
293 | seed_labels1 = os.path.join(dataset_path, "hmb3/hmb3_steering.csv")
294 | seed_inputs2 = os.path.join(dataset_path, "Ch2_001/center/")
295 | seed_labels2 = os.path.join(dataset_path, "Ch2_001/CH2_final_evaluation.csv")
296 |
297 | new_input = "./new/"
298 |
299 | model = Model("./final_model.hdf5", "./X_train_mean.npy")
300 |
301 | Image.warnings.simplefilter('error', Image.DecompressionBombWarning)
302 |
303 | filelist1 = []
304 | for file in sorted(os.listdir(seed_inputs1)):
305 | if file.endswith(".jpg"):
306 | filelist1.append(file)
307 |
308 | newlist = []
309 | newlist = [os.path.join(new_input, o) for o in os.listdir(new_input) if os.path.isdir(os.path.join(new_input, o))]
310 |
311 | dict1 = dict(model.nc1.cov_dict)
312 | dict2 = dict(model.nc2.cov_dict)
313 | dict3 = dict(model.nc3.cov_dict)
314 |
315 | flag = 0
316 | #flag:0 start from beginning
317 | #flag:1 initialize from pickle files
318 |
319 | '''
320 | Pickle files are used for continuing the search after rerunning the script.
321 | Delete all pkl files and generated images for starting from the beginnning.
322 | '''
323 | if os.path.isfile("rambo_stack.pkl") and os.path.isfile("rambo_queue.pkl") \
324 | and os.path.isfile("generated.pkl") and os.path.isfile("covdict1.pkl") \
325 | and os.path.isfile("covdict2.pkl") and os.path.isfile("covdict3.pkl"):
326 | with open('rambo_stack.pkl', 'rb') as input:
327 | rambo_stack = pickle.load(input)
328 | with open('rambo_queue.pkl', 'rb') as input:
329 | rambo_queue = pickle.load(input)
330 | with open('generated.pkl', 'rb') as input:
331 | generated = pickle.load(input)
332 | with open('covdict1.pkl', 'rb') as input:
333 | dict1 = pickle.load(input)
334 | with open('covdict2.pkl', 'rb') as input:
335 | dict2 = pickle.load(input)
336 | with open('covdict3.pkl', 'rb') as input:
337 | dict3 = pickle.load(input)
338 | flag = 1
339 |
340 | if flag == 0:
341 | rambo_queue = deque()
342 | rambo_stack = []
343 | generated = 0
344 | filewrite = "wb"
345 | else:
346 |
347 | filewrite = "ab"
348 | print("initialize from files")
349 |
350 | C = 0 # covered neurons
351 | P = 0 # covered percentage
352 | T = 0 # total neurons
353 | maxtrynumber = 10
354 | cache = deque()
355 | transformations = [image_translation, image_scale, image_shear, image_rotation,
356 | image_contrast, image_brightness, image_blur]
357 | params = []
358 | params.append(list(xrange(-50, 50)))
359 | params.append(list(map(lambda x: x*0.1, list(xrange(5, 20)))))
360 | params.append(list(map(lambda x: x*0.1, list(xrange(-5, 5)))))
361 | params.append(list(xrange(-30, 30)))
362 | params.append(list(map(lambda x: x*0.1, list(xrange(1, 20)))))
363 | params.append(list(xrange(-21, 21)))
364 | params.append(list(xrange(1, 11)))
365 |
366 | '''
367 | Considering that Rambo model uses queue of length 2 to keep the predicting status,
368 | we took three continuous images as an image group and applied same transformations on
369 | all of the three images in an image group.
370 | '''
371 |
372 | with open('result/rambo_rq3_100_2_1.csv', filewrite, 0) as csvfile:
373 | writer = csv.writer(csvfile, delimiter=',',
374 | quotechar='|', quoting=csv.QUOTE_MINIMAL)
375 | if flag == 0:
376 | writer.writerow(['id', 'seed image(root)', 'parent image', 'generated images',
377 | 'total_covered', 'total_neurons', 'coverage_percentage',
378 | 's1_covered', 's1_total', 's1_percentage',
379 | 's2_covered', 's2_total', 's2_percentage',
380 | 's3_covered', 's3_total', 's3_percentage'])
381 | #initialize population and coverage
382 | print("compute coverage of original population")
383 | input_images = xrange(1, 101)
384 | for i in input_images:
385 | j = i * 50
386 | image_file_group = []
387 | image_file_group.append(os.path.join(seed_inputs1, filelist1[j-2]))
388 | image_file_group.append(os.path.join(seed_inputs1, filelist1[j-1]))
389 | image_file_group.append(os.path.join(seed_inputs1, filelist1[j]))
390 | rambo_queue.append(image_file_group)
391 | #exitcount = 0
392 | #rambo_queue stores seed images group
393 | while len(rambo_queue) > 0:
394 | current_seed_image = rambo_queue[0]
395 | print(str(len(rambo_queue)) + " images are left.")
396 | if len(rambo_stack) == 0:
397 | rambo_stack.append(current_seed_image)
398 |
399 | #rambo_stack enable the depth first search
400 | while len(rambo_stack) > 0:
401 | try:
402 | image_file_group = rambo_stack[-1]
403 | image_group = []
404 | print("current image in stack " + image_file_group[2])
405 | seed_image1 = cv2.imread(image_file_group[0])
406 | image_group.append(seed_image1)
407 | seed_image2 = cv2.imread(image_file_group[1])
408 | image_group.append(seed_image2)
409 | seed_image3 = cv2.imread(image_file_group[2])
410 | image_group.append(seed_image3)
411 |
412 | model.predict1(seed_image1, None, None)
413 | model.predict1(seed_image2, None, None)
414 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image3, None, None)
415 |
416 | #update cumulative coverage, dict1, dict2, dict3
417 | update_dict(dict1, d1)
418 | update_dict(dict2, d2)
419 | update_dict(dict3, d3)
420 | #get cumulative coverage
421 | covered1, total1, p1 = get_current_coverage(dict1)
422 | covered2, total2, p2 = get_current_coverage(dict2)
423 | covered3, total3, p3 = get_current_coverage(dict3)
424 | #reset model
425 | model.hard_reset()
426 |
427 | new_generated = False
428 |
429 | for i in xrange(maxtrynumber):
430 | tid = random.sample([0,1,2,3,4,5,6], 2)
431 | new_image_group = []
432 | params_group = []
433 |
434 | #exitcount = exitcount + 1
435 | if len(cache) > 0:
436 | tid[0] = cache.popleft()
437 | for j in xrange(2):
438 |
439 | #random choose parameter for three images in a group. The parameters are slightly different.
440 | param = random.sample(params[tid[j]], 1)
441 | param = param[0]
442 | param_id = params[tid[j]].index(param)
443 | if param_id + 2 >= len(params[tid[j]]):
444 | params_group.append([params[tid[j]][param_id-2], params[tid[j]][param_id-1], params[tid[j]][param_id]])
445 | else:
446 | params_group.append([params[tid[j]][param_id], params[tid[j]][param_id+1], params[tid[j]][param_id+2]])
447 |
448 | transformation = transformations[tid[j]]
449 | print("transformation " + str(transformation) + " parameter " + str(param))
450 |
451 |
452 | for k in xrange(3):
453 | # transform all three images in a group
454 | new_image = image_group[k]
455 | for l in xrange(2):
456 | transformation = transformations[tid[l]]
457 | new_image = transformation(new_image, params_group[l][k])
458 | new_image_group.append(new_image)
459 |
460 | #Get coverage for this group
461 | model.predict1(new_image_group[0], None, None)
462 | model.predict1(new_image_group[1], None, None)
463 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(new_image_group[2], None, None)
464 |
465 | #check if some cumulative coverage is increased
466 | b1 = is_update_dict(dict1, d1)
467 | b2 = is_update_dict(dict2, d2)
468 | b3 = is_update_dict(dict3, d3)
469 | model.hard_reset()
470 |
471 | new_image_file_group = []
472 |
473 | if b1 or b2 or b3:
474 | # if the coverage is increased, write these three images to files,
475 | # add the name of the new group to stack.
476 | print("Generated image group increases coverage and will be added to population.")
477 | cache.append(tid[0])
478 | cache.append(tid[1])
479 | new_generated = True
480 | generated = generated + 1
481 | foldername = str(generated)
482 | folder = os.path.join(new_input, foldername)
483 | if not os.path.exists(folder):
484 | os.makedirs(folder)
485 |
486 | for j in xrange(3):
487 | filename = str(j)+'.jpg'
488 | name = os.path.join(folder, filename)
489 | new_image_file_group.append(name)
490 | cv2.imwrite(name, new_image_group[j])
491 |
492 | rambo_stack.append(new_image_file_group)
493 |
494 |
495 | model.predict1(new_image_group[0], None, None)
496 | model.predict1(new_image_group[1], None, None)
497 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(new_image_group[2], None, None)
498 | #update cumulative coverage
499 | update_dict(dict1, d1)
500 | update_dict(dict2, d2)
501 | update_dict(dict3, d3)
502 | #get cumulative coverage for output
503 | covered1, total1, p1 = get_current_coverage(dict1)
504 | covered2, total2, p2 = get_current_coverage(dict2)
505 | covered3, total3, p3 = get_current_coverage(dict3)
506 | model.hard_reset()
507 | C = covered1 + covered2 + covered3
508 | T = total1 + total2 + total3
509 | P = C / float(T)
510 |
511 | csvrecord = []
512 | csvrecord.append(100-len(rambo_queue))
513 | csvrecord.append(current_seed_image[2])
514 | if len(rambo_stack) >= 2:
515 | parent = rambo_stack[-2][2]
516 | else:
517 | parent = current_seed_image[2]
518 | csvrecord.append(parent)
519 | csvrecord.append(generated)
520 | csvrecord.append(C)
521 | csvrecord.append(T)
522 | csvrecord.append(P)
523 | csvrecord.append(covered1)
524 | csvrecord.append(total1)
525 | csvrecord.append(p1)
526 | csvrecord.append(covered2)
527 | csvrecord.append(total2)
528 | csvrecord.append(p2)
529 | csvrecord.append(covered3)
530 | csvrecord.append(total3)
531 | csvrecord.append(p3)
532 | print(csvrecord)
533 | writer.writerow(csvrecord)
534 | save_object(generated, 'generated.pkl')
535 | save_object(rambo_stack, 'rambo_stack.pkl')
536 | save_object(rambo_queue, 'rambo_queue.pkl')
537 | save_object(dict1, 'covdict1.pkl')
538 | save_object(dict2, 'covdict2.pkl')
539 | save_object(dict3, 'covdict3.pkl')
540 | '''
541 | # If the memory is not enough, the following code can be used to exit.
542 | # Re-runing the script will continue from previous progree.
543 | if generated % 100 == 0 or exitcount % 200 == 0:
544 | exit()
545 | '''
546 | break
547 | else:
548 | print("Generated image group does not increase coverage.")
549 | '''
550 | # If the memory is not enough, the following code can be used to exit.
551 | # Re-runing the script will continue from previous progree.
552 | if generated % 100 == 0 or exitcount % 100 == 0:
553 | exit()
554 | '''
555 | if not new_generated:
556 | rambo_stack.pop()
557 | save_object(rambo_stack, 'rambo_stack.pkl')
558 | save_object(rambo_queue, 'rambo_queue.pkl')
559 | except:
560 | print("value error")
561 | rambo_stack.pop()
562 | save_object(rambo_stack, 'rambo_stack.pkl')
563 | save_object(rambo_queue, 'rambo_queue.pkl')
564 | rambo_queue.popleft()
565 |
566 |
567 | if __name__ == '__main__':
568 | parser = argparse.ArgumentParser()
569 | parser.add_argument('--dataset', type=str, default='/media/yuchi/345F-2D0F/',
570 | help='path for dataset')
571 | args = parser.parse_args()
572 | rambo_guided(args.dataset)
573 |
--------------------------------------------------------------------------------
/install.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 | sudo apt-get update
3 | sudo apt-get upgrade
4 | sudo apt-get install build-essential cmake pkg-config
5 | sudo apt-get install libjpeg8-dev libtiff5-dev libjasper-dev libpng12-dev
6 | sudo apt-get install libavcodec-dev libavformat-dev libswscale-dev libv4l-dev
7 | sudo apt-get install libxvidcore-dev libx264-dev
8 | sudo apt-get install libgtk-3-dev
9 | sudo apt-get install libatlas-base-dev gfortran
10 | sudo apt-get install python2.7-dev python3.5-dev
11 | sudo apt-get install unzip
12 | wget https://bootstrap.pypa.io/get-pip.py
13 | sudo python get-pip.py
14 | sudo python -m pip install -U pip==8.0.1
15 | pip install --user numpy
16 | sudo apt-get install python-opencv
17 | pip install --user scipy
18 | pip install --user scikit-learn
19 | pip install --user pillow
20 | pip install --user h5py
21 | pip install --user Theano==0.9
22 | pip install --user tensorflow
23 | pip install --user keras==1.2.2
24 | pip install --user scikit-image
25 | pip install --user objgraph
26 | sudo apt-get install python-tk
27 |
--------------------------------------------------------------------------------
/models/chauffeur_reproduce.py:
--------------------------------------------------------------------------------
1 | """
2 | This is an example script for reproducing chauffeur model in predicting hmb3 dataset
3 | and udacity autonomous car challenge2 test dataset.
4 | """
5 | from __future__ import print_function
6 | import os
7 | import sys
8 | import argparse
9 | from collections import deque
10 | import csv
11 | import cv2
12 | import numpy as np
13 | #import rospy
14 | from keras import backend as K
15 | from keras.models import model_from_json
16 |
17 |
18 |
19 | reload(sys)
20 | sys.setdefaultencoding('utf8')
21 | # keras 1.2.2 tf:1.2.0
22 | class ChauffeurModel(object):
23 | def __init__(self,
24 | cnn_json_path,
25 | cnn_weights_path,
26 | lstm_json_path,
27 | lstm_weights_path):
28 |
29 | self.cnn = self.load_from_json(cnn_json_path, cnn_weights_path)
30 | self.encoder = self.load_encoder(cnn_json_path, cnn_weights_path)
31 | self.lstm = self.load_from_json(lstm_json_path, lstm_weights_path)
32 |
33 | self.scale = 16.
34 | self.timesteps = 100
35 |
36 |
37 | self.timestepped_x = np.empty((1, self.timesteps, 8960))
38 |
39 |
40 | def load_encoder(self, cnn_json_path, cnn_weights_path):
41 | model = self.load_from_json(cnn_json_path, cnn_weights_path)
42 | model.load_weights(cnn_weights_path)
43 |
44 | model.layers.pop()
45 | model.outputs = [model.layers[-1].output]
46 | model.layers[-1].outbound_nodes = []
47 |
48 | return model
49 |
50 | def load_from_json(self, json_path, weights_path):
51 | model = model_from_json(open(json_path, 'r').read())
52 | model.load_weights(weights_path)
53 | return model
54 |
55 | def make_cnn_only_predictor(self):
56 | def predict_fn(img):
57 | img = cv2.resize(img, (320, 240))
58 | img = cv2.cvtColor(img, cv2.COLOR_BGR2YUV)
59 | img = img[120:240, :, :]
60 | img[:, :, 0] = cv2.equalizeHist(img[:, :, 0])
61 | img = ((img-(255.0/2))/255.0)
62 |
63 | return self.cnn.predict_on_batch(img.reshape((1, 120, 320, 3)))[0, 0] / self.scale
64 |
65 | return predict_fn
66 |
67 | def make_stateful_predictor(self):
68 | steps = deque()
69 |
70 | def predict_fn(img):
71 | # preprocess image to be YUV 320x120 and equalize Y histogram
72 | img = cv2.resize(img, (320, 240))
73 | img = cv2.cvtColor(img, cv2.COLOR_BGR2YUV)
74 | img = img[120:240, :, :]
75 | img[:, :, 0] = cv2.equalizeHist(img[:, :, 0])
76 | img = ((img-(255.0/2))/255.0)
77 |
78 | # apply feature extractor
79 | img = self.encoder.predict_on_batch(img.reshape((1, 120, 320, 3)))
80 |
81 | # initial fill of timesteps
82 | if not len(steps):
83 | for _ in xrange(self.timesteps):
84 | steps.append(img)
85 |
86 | # put most recent features at end
87 | steps.popleft()
88 | steps.append(img)
89 |
90 | timestepped_x = np.empty((1, self.timesteps, img.shape[1]))
91 | for i, img in enumerate(steps):
92 | timestepped_x[0, i] = img
93 |
94 | return self.lstm.predict_on_batch(timestepped_x)[0, 0] / self.scale
95 |
96 | return predict_fn
97 |
98 | def calc_rmse(yhat, label):
99 | mse = 0.
100 | count = 0
101 | if len(yhat) != len(label):
102 | print ("yhat and label have different lengths")
103 | return -1
104 | for i in xrange(len(yhat)):
105 | count += 1
106 | predicted_steering = yhat[i]
107 | steering = label[i]
108 | #print(predicted_steering)
109 | #print(steering)
110 | mse += (float(steering) - float(predicted_steering))**2.
111 | return (mse/count) ** 0.5
112 |
113 | def chauffeur_reproduce(dataset_path):
114 | seed_inputs1 = os.path.join(dataset_path, "hmb3/")
115 | seed_labels1 = os.path.join(dataset_path, "hmb3/hmb3_steering.csv")
116 | seed_inputs2 = os.path.join(dataset_path, "Ch2_001/center/")
117 | seed_labels2 = os.path.join(dataset_path, "Ch2_001/CH2_final_evaluation.csv")
118 | cnn_json_path = "./cnn.json"
119 | cnn_weights_path = "./cnn.weights"
120 | lstm_json_path = "./lstm.json"
121 | lstm_weights_path = "./lstm.weights"
122 |
123 | def make_predictor():
124 | K.set_learning_phase(0)
125 | model = ChauffeurModel(
126 | cnn_json_path,
127 | cnn_weights_path,
128 | lstm_json_path,
129 | lstm_weights_path)
130 | return model.make_stateful_predictor()
131 |
132 | model = make_predictor()
133 |
134 | filelist1 = []
135 | for image_file in sorted(os.listdir(seed_inputs1)):
136 | if image_file.endswith(".jpg"):
137 | filelist1.append(image_file)
138 | truth = {}
139 | with open(seed_labels1, 'rb') as csvfile1:
140 | label1 = list(csv.reader(csvfile1, delimiter=',', quotechar='|'))
141 | label1 = label1[1:]
142 | for i in label1:
143 | truth[i[0]+".jpg"] = i[1]
144 |
145 | filelist2 = []
146 | for image_file in sorted(os.listdir(seed_inputs2)):
147 | if image_file.endswith(".jpg"):
148 | filelist2.append(image_file)
149 | with open(seed_labels2, 'rb') as csvfile2:
150 | label2 = list(csv.reader(csvfile2, delimiter=',', quotechar='|'))
151 | label2 = label2[1:]
152 |
153 | for i in label2:
154 | truth[i[0]+".jpg"] = i[1]
155 |
156 | yhats = []
157 | labels = []
158 | count = 0
159 | total = len(filelist1) + len(filelist2)
160 | for f in filelist1:
161 | seed_image = cv2.imread(os.path.join(seed_inputs1, f))
162 | yhat = model(seed_image)
163 | yhats.append(yhat)
164 | labels.append(truth[f])
165 | if count % 500 == 0:
166 | print ("processed images: " + str(count) + " total: " + str(total))
167 | count = count + 1
168 |
169 | for f in filelist2:
170 | seed_image = cv2.imread(os.path.join(seed_inputs2, f))
171 | yhat = model(seed_image)
172 | yhats.append(yhat)
173 | labels.append(truth[f])
174 | if count % 500 == 0:
175 | print ("processed images: " + str(count) + " total: " + str(total))
176 | count = count + 1
177 | mse = calc_rmse(yhats, labels)
178 | print("mse: " + str(mse))
179 |
180 |
181 | if __name__ == '__main__':
182 | parser = argparse.ArgumentParser()
183 | parser.add_argument('--dataset', type=str, default='/media/yuchi/345F-2D0F/',
184 | help='path for dataset')
185 | args = parser.parse_args()
186 | chauffeur_reproduce(args.dataset)
187 |
--------------------------------------------------------------------------------
/models/epoch_reproduce.py:
--------------------------------------------------------------------------------
1 | """
2 | This is an example script for reproducing epoch model in predicting hmb3 dataset
3 | and udacity autonomous car challenge2 test dataset.
4 | """
5 | from __future__ import print_function
6 | import os
7 | import argparse
8 | import csv
9 | import cv2
10 | import numpy as np
11 | from epoch_model import build_cnn, build_InceptionV3
12 | from keras import backend as K
13 | from scipy.misc import imresize
14 |
15 |
16 | def preprocess_input_InceptionV3(x):
17 | x /= 255.
18 | x -= 0.5
19 | x *= 2.
20 | return x
21 |
22 | def exact_output(y):
23 | return y
24 |
25 | def normalize_input(x):
26 | return x / 255.
27 |
28 |
29 | def preprocess_image(image, image_size):
30 |
31 | img = image
32 | # Cropping
33 | crop_img = img[200:, :]
34 | # Resizing
35 | img = imresize(crop_img, size=image_size)
36 | imgs = []
37 | imgs.append(img)
38 | if len(imgs) < 1:
39 | print('Error no image at timestamp')
40 |
41 | img_block = np.stack(imgs, axis=0)
42 | if K.image_dim_ordering() == 'th':
43 | img_block = np.transpose(img_block, axes=(0, 3, 1, 2))
44 | return img_block
45 |
46 | def calc_rmse(yhat, label):
47 | mse = 0.
48 | count = 0
49 | if len(yhat) != len(label):
50 | print("yhat and label have different lengths")
51 | return -1
52 | for i in xrange(len(yhat)):
53 | count += 1
54 | predicted_steering = yhat[i]
55 | steering = label[i]
56 | #print(predicted_steering)
57 | #print(steering)
58 | mse += (float(steering) - float(predicted_steering))**2.
59 | return (mse/count) ** 0.5
60 |
61 | def epoch_reproduce(dataset_path):
62 | seed_inputs1 = os.path.join(dataset_path, "hmb3/")
63 | seed_labels1 = os.path.join(dataset_path, "hmb3/hmb3_steering.csv")
64 | seed_inputs2 = os.path.join(dataset_path, "Ch2_001/center/")
65 | seed_labels2 = os.path.join(dataset_path, "Ch2_001/CH2_final_evaluation.csv")
66 |
67 | model_name = "cnn"
68 | image_size = (128, 128)
69 | weights_path = 'weights_HMB_2.hdf5' # Change to your model weights
70 |
71 | # Model build
72 | # ---------------------------------------------------------------------------------
73 | model_builders = {
74 | 'V3': (build_InceptionV3, preprocess_input_InceptionV3, exact_output)
75 | , 'cnn': (build_cnn, normalize_input, exact_output)}
76 |
77 | if model_name not in model_builders:
78 | raise ValueError("unsupported model %s" % model_name)
79 | model_builder, input_processor, output_processor = model_builders[model_name]
80 | model = model_builder(image_size, weights_path)
81 | print('model %s built...' % model_name)
82 |
83 | filelist1 = []
84 | for image_file in sorted(os.listdir(seed_inputs1)):
85 | if image_file.endswith(".jpg"):
86 | filelist1.append(image_file)
87 | truth = {}
88 | with open(seed_labels1, 'rb') as csvfile1:
89 | label1 = list(csv.reader(csvfile1, delimiter=',', quotechar='|'))
90 | label1 = label1[1:]
91 | for i in label1:
92 | truth[i[0]+".jpg"] = i[1]
93 |
94 | filelist2 = []
95 | for image_file in sorted(os.listdir(seed_inputs2)):
96 | if image_file.endswith(".jpg"):
97 | filelist2.append(image_file)
98 | with open(seed_labels2, 'rb') as csvfile2:
99 | label2 = list(csv.reader(csvfile2, delimiter=',', quotechar='|'))
100 | label2 = label2[1:]
101 |
102 | for i in label2:
103 | truth[i[0]+".jpg"] = i[1]
104 |
105 | yhats = []
106 | labels = []
107 | count = 0
108 | total = len(filelist1) + len(filelist2)
109 | for f in filelist1:
110 | seed_image = cv2.imread(os.path.join(seed_inputs1, f))
111 | seed_image = preprocess_image(seed_image, image_size)
112 | test_x = input_processor(seed_image.astype(np.float32))
113 | yhat = model.predict(test_x)
114 | yhat = yhat[0][0]
115 | yhats.append(yhat)
116 | labels.append(truth[f])
117 | if count % 500 == 0:
118 | print("processed images: " + str(count) + " total: " + str(total))
119 | count = count + 1
120 |
121 | for f in filelist2:
122 | seed_image = cv2.imread(os.path.join(seed_inputs2, f))
123 | seed_image = preprocess_image(seed_image, image_size)
124 | test_x = input_processor(seed_image.astype(np.float32))
125 | yhat = model.predict(test_x)
126 | yhat = yhat[0][0]
127 | yhats.append(yhat)
128 | labels.append(truth[f])
129 | if count % 500 == 0:
130 | print("processed images: " + str(count) + " total: " + str(total))
131 | count = count + 1
132 | mse = calc_rmse(yhats, labels)
133 | print("mse: " + str(mse))
134 |
135 | if __name__ == '__main__':
136 |
137 | parser = argparse.ArgumentParser()
138 | parser.add_argument('--dataset', type=str, default='/media/yuchi/345F-2D0F/',
139 | help='path for dataset')
140 | args = parser.parse_args()
141 | epoch_reproduce(args.dataset)
142 |
--------------------------------------------------------------------------------
/models/rambo_reproduce.py:
--------------------------------------------------------------------------------
1 | """
2 | This is an example script for reproducing rambo model in predicting hmb3 dataset
3 | and udacity autonomous car challenge2 test dataset.
4 | """
5 | from __future__ import print_function
6 | import sys
7 | import os
8 | import argparse
9 | import csv
10 | import numpy as np
11 | from collections import deque
12 | from keras.models import load_model
13 | from keras.preprocessing.image import load_img, img_to_array
14 | from skimage.exposure import rescale_intensity
15 | import cv2
16 |
17 | reload(sys)
18 | sys.setdefaultencoding('ISO-8859-1')
19 |
20 | class Model(object):
21 | def __init__(self,
22 | model_path,
23 | X_train_mean_path):
24 |
25 | self.model = load_model(model_path)
26 | self.model.compile(optimizer="adam", loss="mse")
27 | self.X_mean = np.load(X_train_mean_path)
28 | self.mean_angle = np.array([-0.004179079])
29 | print (self.mean_angle)
30 | self.img0 = None
31 | self.state = deque(maxlen=2)
32 |
33 | def predict(self, img_path):
34 | #img_path = 'test.jpg'
35 | #misc.imsave(img_path, img)
36 | img1 = load_img(img_path, grayscale=True, target_size=(192, 256))
37 | img1 = img_to_array(img1)
38 |
39 | if self.img0 is None:
40 | self.img0 = img1
41 | return self.mean_angle
42 |
43 | elif len(self.state) < 1:
44 | img = img1 - self.img0
45 | img = rescale_intensity(img, in_range=(-255, 255), out_range=(0, 255))
46 | img = np.array(img, dtype=np.uint8) # to replicate initial model
47 | self.state.append(img)
48 | self.img0 = img1
49 |
50 | return self.mean_angle
51 |
52 | else:
53 | img = img1 - self.img0
54 | img = rescale_intensity(img, in_range=(-255, 255), out_range=(0, 255))
55 | img = np.array(img, dtype=np.uint8) # to replicate initial model
56 | self.state.append(img)
57 | self.img0 = img1
58 |
59 | X = np.concatenate(self.state, axis=-1)
60 | X = X[:, :, ::-1]
61 | X = np.expand_dims(X, axis=0)
62 | X = X.astype('float32')
63 | X -= self.X_mean
64 | X /= 255.0
65 | return self.model.predict(X)[0]
66 |
67 | def calc_rmse(yhat, label):
68 | mse = 0.
69 | count = 0
70 | if len(yhat) != len(label):
71 | print ("yhat and label have different lengths")
72 | return -1
73 | for i in xrange(len(yhat)):
74 | count += 1
75 | predicted_steering = yhat[i]
76 | steering = label[i]
77 | #print(predicted_steering)
78 | #print(steering)
79 | mse += (float(steering) - float(predicted_steering))**2.
80 | return (mse/count) ** 0.5
81 |
82 | def rambo_reproduce(dataset_path):
83 | seed_inputs1 = os.path.join(dataset_path, "hmb3/")
84 | seed_labels1 = os.path.join(dataset_path, "hmb3/hmb3_steering.csv")
85 | seed_inputs2 = os.path.join(dataset_path, "Ch2_001/center/")
86 | seed_labels2 = os.path.join(dataset_path, "Ch2_001/CH2_final_evaluation.csv")
87 |
88 | model = Model("./final_model.hdf5", "./X_train_mean.npy")
89 | filelist1 = []
90 | for image_file in sorted(os.listdir(seed_inputs1)):
91 | if image_file.endswith(".jpg"):
92 | filelist1.append(image_file)
93 | truth = {}
94 | with open(seed_labels1, 'rb') as csvfile1:
95 | label1 = list(csv.reader(csvfile1, delimiter=',', quotechar='|'))
96 | label1 = label1[1:]
97 | for i in label1:
98 | truth[i[0]+".jpg"] = i[1]
99 |
100 | filelist2 = []
101 | for image_file in sorted(os.listdir(seed_inputs2)):
102 | if image_file.endswith(".jpg"):
103 | filelist2.append(image_file)
104 | with open(seed_labels2, 'rb') as csvfile2:
105 | label2 = list(csv.reader(csvfile2, delimiter=',', quotechar='|'))
106 | label2 = label2[1:]
107 |
108 | for i in label2:
109 | truth[i[0]+".jpg"] = i[1]
110 |
111 | yhats = []
112 | labels = []
113 | count = 0
114 | total = len(filelist1) + len(filelist2)
115 | for f in filelist1:
116 | yhat = model.predict(os.path.join(seed_inputs1, f))
117 | yhats.append(yhat)
118 | labels.append(truth[f])
119 | if count % 500 == 0:
120 | print ("processed images: " + str(count) + " total: " + str(total))
121 | count = count + 1
122 |
123 | for f in filelist2:
124 | yhat = model.predict(os.path.join(seed_inputs2, f))
125 | yhats.append(yhat)
126 | labels.append(truth[f])
127 | if count % 500 == 0:
128 | print ("processed images: " + str(count) + " total: " + str(total))
129 | count = count + 1
130 | mse = calc_rmse(yhats, labels)
131 | print("mse: " + str(mse))
132 |
133 | if __name__ == "__main__":
134 |
135 | parser = argparse.ArgumentParser()
136 | parser.add_argument('--dataset', type=str, default='/media/yuchi/345F-2D0F/',
137 | help='path for dataset')
138 | args = parser.parse_args()
139 | rambo_reproduce(args.dataset)
140 |
--------------------------------------------------------------------------------
/testgen/chauffeur_testgen_coverage.py:
--------------------------------------------------------------------------------
1 | from __future__ import print_function
2 | from keras import backend as K
3 | from keras import metrics
4 | from keras.models import model_from_json
5 | import argparse
6 | from collections import deque
7 | from scipy import misc
8 | import csv
9 | import os
10 | import sys
11 | from ncoverage import NCoverage
12 | import cv2
13 | import numpy as np
14 |
15 | reload(sys)
16 | sys.setdefaultencoding('utf8')
17 | # keras 1.2.2 tf:1.2.0
18 | class ChauffeurModel(object):
19 | def __init__(self,
20 | cnn_json_path,
21 | cnn_weights_path,
22 | lstm_json_path,
23 | lstm_weights_path, only_layer=""):
24 |
25 | self.cnn = self.load_from_json(cnn_json_path, cnn_weights_path)
26 | self.encoder = self.load_encoder(cnn_json_path, cnn_weights_path)
27 | self.lstm = self.load_from_json(lstm_json_path, lstm_weights_path)
28 |
29 | # hardcoded from final submission model
30 | self.scale = 16.
31 | self.timesteps = 100
32 |
33 | self.threshold_cnn = 0.1
34 | self.threshold_lstm = 0.4
35 | self.timestepped_x = np.empty((1, self.timesteps, 8960))
36 | self.nc_lstm = NCoverage(self.lstm, self.threshold_lstm)
37 | self.nc_encoder = NCoverage(self.encoder, self.threshold_cnn,
38 | exclude_layer=['pool', 'fc', 'flatten'],
39 | only_layer=only_layer)
40 | self.steps = deque()
41 | #print(self.lstm.summary())
42 | #self.nc = NCoverage(self.lstm,self.threshold)
43 |
44 | def load_encoder(self, cnn_json_path, cnn_weights_path):
45 | model = self.load_from_json(cnn_json_path, cnn_weights_path)
46 | model.load_weights(cnn_weights_path)
47 |
48 | model.layers.pop()
49 | model.outputs = [model.layers[-1].output]
50 | model.layers[-1].outbound_nodes = []
51 |
52 | return model
53 |
54 | def load_from_json(self, json_path, weights_path):
55 | model = model_from_json(open(json_path, 'r').read())
56 | model.load_weights(weights_path)
57 | return model
58 |
59 | def make_cnn_only_predictor(self):
60 | def predict_fn(img):
61 | img = cv2.resize(img, (320, 240))
62 | img = cv2.cvtColor(img, cv2.COLOR_BGR2YUV)
63 | img = img[120:240, :, :]
64 | img[:, :, 0] = cv2.equalizeHist(img[:, :, 0])
65 | img = ((img-(255.0/2))/255.0)
66 |
67 | return self.cnn.predict_on_batch(img.reshape((1, 120, 320, 3)))[0, 0] / self.scale
68 |
69 | return predict_fn
70 |
71 | #def make_stateful_predictor(self):
72 | #steps = deque()
73 |
74 | def predict_fn(self, img, dummy=2):
75 | # preprocess image to be YUV 320x120 and equalize Y histogram
76 | steps = self.steps
77 | img = cv2.resize(img, (320, 240))
78 | img = cv2.cvtColor(img, cv2.COLOR_BGR2YUV)
79 | img = img[120:240, :, :]
80 | img[:, :, 0] = cv2.equalizeHist(img[:, :, 0])
81 | img = ((img-(255.0/2))/255.0)
82 | img1 = img
83 | # apply feature extractor
84 | img = self.encoder.predict_on_batch(img.reshape((1, 120, 320, 3)))
85 |
86 | # initial fill of timesteps
87 | if not len(steps):
88 | for _ in xrange(self.timesteps):
89 | steps.append(img)
90 |
91 | # put most recent features at end
92 | steps.popleft()
93 | steps.append(img)
94 | #print(len(steps))
95 | #timestepped_x = np.empty((1, self.timesteps, img.shape[1]))
96 | if dummy == 0:
97 | return 0, 0, 0, 0, 0, 0, 0
98 | for i, img in enumerate(steps):
99 | self.timestepped_x[0, i] = img
100 |
101 | '''
102 | self.nc.update_coverage(timestepped_x)
103 | covered_neurons, total_neurons, p = self.nc.curr_neuron_cov()
104 | print('input covered {} neurons'.format(covered_neurons))
105 | print('total {} neurons'.format(total_neurons))
106 | print('percentage {}'.format(p))
107 | '''
108 | cnn_ndict = self.nc_encoder.update_coverage(img1.reshape((1, 120, 320, 3)))
109 | cnn_covered_neurons, cnn_total_neurons, p = self.nc_encoder.curr_neuron_cov()
110 | if dummy == 1:
111 | return cnn_ndict, cnn_covered_neurons, cnn_total_neurons, 0, 0, 0, 0
112 | lstm_ndict = self.nc_lstm.update_coverage(self.timestepped_x)
113 | lstm_covered_neurons, lstm_total_neurons, p = self.nc_lstm.curr_neuron_cov()
114 | return cnn_ndict, cnn_covered_neurons, cnn_total_neurons, lstm_ndict,\
115 | lstm_covered_neurons, lstm_total_neurons,\
116 | self.lstm.predict_on_batch(self.timestepped_x)[0, 0] / self.scale
117 |
118 | #return predict_fn
119 |
120 | def image_translation(img, params):
121 |
122 | rows, cols, ch = img.shape
123 |
124 | M = np.float32([[1, 0, params[0]], [0, 1, params[1]]])
125 | dst = cv2.warpAffine(img, M, (cols, rows))
126 | return dst
127 |
128 | def image_scale(img, params):
129 |
130 | res = cv2.resize(img, None, fx=params[0], fy=params[1], interpolation=cv2.INTER_CUBIC)
131 | return res
132 |
133 | def image_shear(img, params):
134 | rows, cols, ch = img.shape
135 | factor = params*(-1.0)
136 | M = np.float32([[1, factor, 0], [0, 1, 0]])
137 | dst = cv2.warpAffine(img, M, (cols, rows))
138 | return dst
139 |
140 | def image_rotation(img, params):
141 | rows, cols, ch = img.shape
142 | M = cv2.getRotationMatrix2D((cols/2, rows/2), params, 1)
143 | dst = cv2.warpAffine(img, M, (cols, rows))
144 | return dst
145 |
146 | def image_contrast(img, params):
147 | alpha = params
148 | new_img = cv2.multiply(img, np.array([alpha])) # mul_img = img*alpha
149 | #new_img = cv2.add(mul_img, beta) # new_img = img*alpha + beta
150 |
151 | return new_img
152 |
153 | def image_brightness(img, params):
154 | beta = params
155 | new_img = cv2.add(img, beta) # new_img = img*alpha + beta
156 |
157 | return new_img
158 |
159 | def image_blur(img, params):
160 | blur = []
161 | if params == 1:
162 | blur = cv2.blur(img, (3, 3))
163 | if params == 2:
164 | blur = cv2.blur(img, (4, 4))
165 | if params == 3:
166 | blur = cv2.blur(img, (5, 5))
167 | if params == 4:
168 | blur = cv2.GaussianBlur(img, (3, 3), 0)
169 | if params == 5:
170 | blur = cv2.GaussianBlur(img, (5, 5), 0)
171 | if params == 6:
172 | blur = cv2.GaussianBlur(img, (7, 7), 0)
173 | if params == 7:
174 | blur = cv2.medianBlur(img, 3)
175 | if params == 8:
176 | blur = cv2.medianBlur(img, 5)
177 | if params == 9:
178 | blur = cv2.blur(img, (6, 6))
179 | if params == 10:
180 | blur = cv2.bilateralFilter(img, 9, 75, 75)
181 | return blur
182 |
183 | def rmse(y_true, y_pred):
184 | '''Calculates RMSE
185 | '''
186 | return K.sqrt(K.mean(K.square(y_pred - y_true)))
187 |
188 | metrics.rmse = rmse
189 |
190 | def chauffeur_testgen_coverage(index, dataset_path):
191 | cnn_json_path = "./cnn.json"
192 | cnn_weights_path = "./cnn.weights"
193 | lstm_json_path = "./lstm.json"
194 | lstm_weights_path = "./lstm.weights"
195 | K.set_learning_phase(0)
196 | model = ChauffeurModel(
197 | cnn_json_path,
198 | cnn_weights_path,
199 | lstm_json_path,
200 | lstm_weights_path)
201 |
202 | seed_inputs1 = os.path.join(dataset_path, "hmb3/")
203 | seed_labels1 = os.path.join(dataset_path, "hmb3/hmb3_steering.csv")
204 | seed_inputs2 = os.path.join(dataset_path, "Ch2_001/center/")
205 | seed_labels2 = os.path.join(dataset_path, "Ch2_001/CH2_final_evaluation.csv")
206 |
207 |
208 | filelist1 = []
209 | for file in sorted(os.listdir(seed_inputs1)):
210 | if file.endswith(".jpg"):
211 | filelist1.append(file)
212 |
213 | filelist2 = []
214 | for file in sorted(os.listdir(seed_inputs2)):
215 | if file.endswith(".jpg"):
216 | filelist2.append(file)
217 |
218 | with open(seed_labels1, 'rb') as csvfile1:
219 | label1 = list(csv.reader(csvfile1, delimiter=',', quotechar='|'))
220 | label1 = label1[1:]
221 |
222 | with open(seed_labels2, 'rb') as csvfile2:
223 | label2 = list(csv.reader(csvfile2, delimiter=',', quotechar='|'))
224 | label2 = label2[1:]
225 |
226 | index = int(index)
227 |
228 | #seed inputs
229 | with open('result/chauffeur_rq2_70000_images.csv', 'ab', 0) as csvfile:
230 | writer = csv.writer(csvfile, delimiter=',',
231 | quotechar='|', quoting=csv.QUOTE_MINIMAL)
232 | writer.writerow(['index', 'image', 'tranformation', 'param_name', 'param_value',
233 | 'cnn_threshold', 'cnn_covered_neurons', 'cnn_total_neurons',
234 | 'cnn_covered_detail', 'lstm_threshold', 'lstm_covered_neurons',
235 | 'lstm_total_neurons', 'lstm_covered_detail', 'y_hat', 'label'])
236 | if index/2 == 0:
237 | if index%2 == 0:
238 | for j in xrange(2000, 2100):
239 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
240 | model.predict_fn(seed_image, dummy=0)
241 | else:
242 | for j in xrange(2500, 2600):
243 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
244 | model.predict_fn(seed_image, dummy=0)
245 |
246 | if index%2 == 0:
247 | input_images = xrange(2100, 2600)
248 | else:
249 | input_images = xrange(2600, 3100)
250 | for i in input_images:
251 | j = i * 1
252 | csvrecord = []
253 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
254 |
255 | cnn_ndict, cnn_covered_neurons, cnn_total_neurons, lstm_ndict, \
256 | lstm_covered_neurons, lstm_total_neurons, yhat = model.predict_fn(seed_image)
257 |
258 |
259 | tempk = []
260 | for k in cnn_ndict.keys():
261 | if cnn_ndict[k]:
262 | tempk.append(k)
263 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
264 | cnn_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
265 |
266 |
267 | tempk = []
268 | for k in lstm_ndict.keys():
269 | if lstm_ndict[k]:
270 | tempk.append(k)
271 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
272 | lstm_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
273 |
274 | model.nc_encoder.reset_cov_dict()
275 | model.nc_lstm.reset_cov_dict()
276 | #print(covered_neurons)
277 | #covered_neurons = nc.get_neuron_coverage(test_x)
278 | #print('input covered {} neurons'.format(covered_neurons))
279 | #print('total {} neurons'.format(total_neurons))
280 |
281 |
282 | filename, ext = os.path.splitext(str(filelist1[j]))
283 | if label1[j][0] != filename:
284 | print(filename + " not found in the label file")
285 | continue
286 |
287 |
288 | csvrecord.append(j-2)
289 | csvrecord.append(str(filelist1[j]))
290 | csvrecord.append('-')
291 | csvrecord.append('-')
292 | csvrecord.append('-')
293 | csvrecord.append(model.threshold_cnn)
294 |
295 |
296 | csvrecord.append(cnn_covered_neurons)
297 | csvrecord.append(cnn_total_neurons)
298 | csvrecord.append(cnn_covered_detail)
299 | csvrecord.append(model.threshold_lstm)
300 |
301 | csvrecord.append(lstm_covered_neurons)
302 | csvrecord.append(lstm_total_neurons)
303 | csvrecord.append(lstm_covered_detail)
304 |
305 |
306 |
307 | csvrecord.append(yhat)
308 | csvrecord.append(label1[j][1])
309 | print(csvrecord[:8])
310 | writer.writerow(csvrecord)
311 |
312 | print("seed input done")
313 |
314 | #Translation
315 |
316 | if index/2 >= 1 and index/2 <= 10:
317 | #for p in xrange(1,11):
318 | p = index/2
319 | params = [p*10, p*10]
320 |
321 | if index%2 == 0:
322 | for j in xrange(2000, 2100):
323 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
324 | seed_image = image_translation(seed_image, params)
325 | model.predict_fn(seed_image, dummy=0)
326 | else:
327 | for j in xrange(2500, 2600):
328 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
329 | seed_image = image_translation(seed_image, params)
330 | model.predict_fn(seed_image, dummy=0)
331 |
332 | if index%2 == 0:
333 | input_images = xrange(2100, 2600)
334 | else:
335 | input_images = xrange(2600, 3100)
336 |
337 | for i in input_images:
338 | j = i * 1
339 | csvrecord = []
340 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
341 | seed_image = image_translation(seed_image, params)
342 |
343 | cnn_ndict, cnn_covered_neurons, cnn_total_neurons, lstm_ndict, lstm_covered_neurons, lstm_total_neurons, yhat = model.predict_fn(seed_image)
344 |
345 |
346 | tempk = []
347 | for k in cnn_ndict.keys():
348 | if cnn_ndict[k]:
349 | tempk.append(k)
350 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
351 | cnn_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
352 |
353 |
354 | tempk = []
355 | for k in lstm_ndict.keys():
356 | if lstm_ndict[k]:
357 | tempk.append(k)
358 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
359 | lstm_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
360 |
361 | model.nc_encoder.reset_cov_dict()
362 | model.nc_lstm.reset_cov_dict()
363 | #print(covered_neurons)
364 | #covered_neurons = nc.get_neuron_coverage(test_x)
365 | #print('input covered {} neurons'.format(covered_neurons))
366 | #print('total {} neurons'.format(total_neurons))
367 |
368 |
369 | filename, ext = os.path.splitext(str(filelist1[j]))
370 | if label1[j][0] != filename:
371 | print(filename + " not found in the label file")
372 | continue
373 |
374 |
375 |
376 |
377 | csvrecord.append(j-2)
378 | csvrecord.append(str(filelist1[j]))
379 | csvrecord.append('translation')
380 | csvrecord.append('x:y')
381 | csvrecord.append(':'.join(str(x) for x in params))
382 | csvrecord.append(model.threshold_cnn)
383 |
384 |
385 |
386 | csvrecord.append(cnn_covered_neurons)
387 | csvrecord.append(cnn_total_neurons)
388 | csvrecord.append(cnn_covered_detail)
389 | csvrecord.append(model.threshold_lstm)
390 |
391 | csvrecord.append(lstm_covered_neurons)
392 | csvrecord.append(lstm_total_neurons)
393 | csvrecord.append(lstm_covered_detail)
394 |
395 |
396 |
397 | csvrecord.append(yhat)
398 | csvrecord.append(label1[j][1])
399 | print(csvrecord[:8])
400 | writer.writerow(csvrecord)
401 |
402 | print("translation done")
403 |
404 | #Scale
405 | if index/2 >= 11 and index/2 <= 20:
406 | #for p in xrange(1,11):
407 | p = index/2-10
408 | params = [p*0.5+1, p*0.5+1]
409 | if index%2 == 0:
410 | for j in xrange(2000, 2100):
411 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
412 | seed_image = image_scale(seed_image, params)
413 | model.predict_fn(seed_image, dummy=0)
414 | else:
415 | for j in xrange(2500, 2600):
416 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
417 | seed_image = image_scale(seed_image, params)
418 | model.predict_fn(seed_image, dummy=0)
419 |
420 | if index%2 == 0:
421 | input_images = xrange(2100, 2600)
422 | else:
423 | input_images = xrange(2600, 3100)
424 |
425 | for i in input_images:
426 | j = i * 1
427 | csvrecord = []
428 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
429 | seed_image = image_scale(seed_image, params)
430 |
431 | cnn_ndict, cnn_covered_neurons, cnn_total_neurons, lstm_ndict, lstm_covered_neurons, lstm_total_neurons, yhat = model.predict_fn(seed_image)
432 |
433 |
434 | tempk = []
435 | for k in cnn_ndict.keys():
436 | if cnn_ndict[k]:
437 | tempk.append(k)
438 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
439 | cnn_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
440 |
441 |
442 | tempk = []
443 | for k in lstm_ndict.keys():
444 | if lstm_ndict[k]:
445 | tempk.append(k)
446 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
447 | lstm_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
448 |
449 | model.nc_encoder.reset_cov_dict()
450 |
451 | model.nc_lstm.reset_cov_dict()
452 | #print(covered_neurons)
453 | #covered_neurons = nc.get_neuron_coverage(test_x)
454 | #print('input covered {} neurons'.format(covered_neurons))
455 | #print('total {} neurons'.format(total_neurons))
456 |
457 |
458 | filename, ext = os.path.splitext(str(filelist1[j]))
459 | if label1[j][0] != filename:
460 | print(filename + " not found in the label file")
461 | continue
462 |
463 |
464 | csvrecord.append(j-2)
465 | csvrecord.append(str(filelist1[j]))
466 | csvrecord.append('scale')
467 | csvrecord.append('x:y')
468 | csvrecord.append(':'.join(str(x) for x in params))
469 | csvrecord.append(model.threshold_cnn)
470 |
471 |
472 |
473 | csvrecord.append(cnn_covered_neurons)
474 | csvrecord.append(cnn_total_neurons)
475 | csvrecord.append(cnn_covered_detail)
476 | csvrecord.append(model.threshold_lstm)
477 |
478 | csvrecord.append(lstm_covered_neurons)
479 | csvrecord.append(lstm_total_neurons)
480 | csvrecord.append(lstm_covered_detail)
481 |
482 |
483 |
484 | csvrecord.append(yhat)
485 | csvrecord.append(label1[j][1])
486 | print(csvrecord[:8])
487 | writer.writerow(csvrecord)
488 |
489 |
490 |
491 | print("scale done")
492 |
493 |
494 | #Shear 42-61
495 | if index/2 >= 21 and index/2 <= 30:
496 | #for p in xrange(1,11):
497 | p = index/2-20
498 | #for p in xrange(1,11):
499 | params = 0.1*p
500 |
501 | if index%2 == 0:
502 | for j in xrange(2000, 2100):
503 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
504 | seed_image = image_shear(seed_image, params)
505 | model.predict_fn(seed_image, dummy=0)
506 | else:
507 | for j in xrange(2500, 2600):
508 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
509 | seed_image = image_shear(seed_image, params)
510 | model.predict_fn(seed_image, dummy=0)
511 |
512 | if index%2 == 0:
513 | input_images = xrange(2100, 2600)
514 | else:
515 | input_images = xrange(2600, 3100)
516 |
517 |
518 | for i in input_images:
519 | j = i * 1
520 | csvrecord = []
521 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
522 | seed_image = image_shear(seed_image, params)
523 |
524 | cnn_ndict, cnn_covered_neurons, cnn_total_neurons, lstm_ndict, lstm_covered_neurons, lstm_total_neurons, yhat = model.predict_fn(seed_image)
525 |
526 |
527 | tempk = []
528 | for k in cnn_ndict.keys():
529 | if cnn_ndict[k]:
530 | tempk.append(k)
531 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
532 | cnn_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
533 |
534 |
535 | tempk = []
536 | for k in lstm_ndict.keys():
537 | if lstm_ndict[k]:
538 | tempk.append(k)
539 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
540 | lstm_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
541 |
542 | model.nc_encoder.reset_cov_dict()
543 |
544 | model.nc_lstm.reset_cov_dict()
545 | #print(covered_neurons)
546 | #covered_neurons = nc.get_neuron_coverage(test_x)
547 | #print('input covered {} neurons'.format(covered_neurons))
548 | #print('total {} neurons'.format(total_neurons))
549 |
550 |
551 | filename, ext = os.path.splitext(str(filelist1[j]))
552 | if label1[j][0] != filename:
553 | print(filename + " not found in the label file")
554 | continue
555 |
556 | csvrecord.append(j-2)
557 | csvrecord.append(str(filelist1[j]))
558 | csvrecord.append('shear')
559 | csvrecord.append('factor')
560 | csvrecord.append(params)
561 | csvrecord.append(model.threshold_cnn)
562 |
563 | csvrecord.append(cnn_covered_neurons)
564 | csvrecord.append(cnn_total_neurons)
565 | csvrecord.append(cnn_covered_detail)
566 | csvrecord.append(model.threshold_lstm)
567 |
568 | csvrecord.append(lstm_covered_neurons)
569 | csvrecord.append(lstm_total_neurons)
570 | csvrecord.append(lstm_covered_detail)
571 |
572 | csvrecord.append(yhat)
573 | csvrecord.append(label1[j][1])
574 | print(csvrecord[:8])
575 | writer.writerow(csvrecord)
576 |
577 | print("sheer done")
578 |
579 | #Rotation 62-81
580 | if index/2 >= 31 and index/2 <= 40:
581 | p = index/2-30
582 | #for p in xrange(1,11):
583 | params = p*3
584 |
585 | if index%2 == 0:
586 | for j in xrange(2000, 2100):
587 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
588 | seed_image = image_rotation(seed_image, params)
589 | model.predict_fn(seed_image, dummy=0)
590 | else:
591 | for j in xrange(2500, 2600):
592 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
593 | seed_image = image_rotation(seed_image, params)
594 | model.predict_fn(seed_image, dummy=0)
595 |
596 | if index%2 == 0:
597 | input_images = xrange(2100, 2600)
598 | else:
599 | input_images = xrange(2600, 3100)
600 |
601 | for i in input_images:
602 | j = i * 1
603 | csvrecord = []
604 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
605 | seed_image = image_rotation(seed_image, params)
606 |
607 | cnn_ndict, cnn_covered_neurons, cnn_total_neurons, lstm_ndict, lstm_covered_neurons, lstm_total_neurons, yhat = model.predict_fn(seed_image)
608 |
609 | tempk = []
610 | for k in cnn_ndict.keys():
611 | if cnn_ndict[k]:
612 | tempk.append(k)
613 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
614 | cnn_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
615 |
616 | tempk = []
617 | for k in lstm_ndict.keys():
618 | if lstm_ndict[k]:
619 | tempk.append(k)
620 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
621 | lstm_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
622 |
623 | model.nc_encoder.reset_cov_dict()
624 |
625 | model.nc_lstm.reset_cov_dict()
626 | #print(covered_neurons)
627 | #covered_neurons = nc.get_neuron_coverage(test_x)
628 | #print('input covered {} neurons'.format(covered_neurons))
629 | #print('total {} neurons'.format(total_neurons))
630 |
631 |
632 | filename, ext = os.path.splitext(str(filelist1[j]))
633 | if label1[j][0] != filename:
634 | print(filename + " not found in the label file")
635 | continue
636 |
637 | csvrecord.append(j-2)
638 | csvrecord.append(str(filelist1[j]))
639 | csvrecord.append('rotation')
640 | csvrecord.append('angle')
641 | csvrecord.append(params)
642 | csvrecord.append(model.threshold_cnn)
643 |
644 |
645 | csvrecord.append(cnn_covered_neurons)
646 | csvrecord.append(cnn_total_neurons)
647 | csvrecord.append(cnn_covered_detail)
648 | csvrecord.append(model.threshold_lstm)
649 |
650 | csvrecord.append(lstm_covered_neurons)
651 | csvrecord.append(lstm_total_neurons)
652 | csvrecord.append(lstm_covered_detail)
653 |
654 | csvrecord.append(yhat)
655 | csvrecord.append(label1[j][1])
656 | print(csvrecord[:8])
657 | writer.writerow(csvrecord)
658 |
659 |
660 | print("rotation done")
661 |
662 | #Contrast 82-101
663 | if index/2 >= 41 and index/2 <= 50:
664 | p = index/2-40
665 | #or p in xrange(1,11):
666 | params = 1 + p*0.2
667 |
668 | if index%2 == 0:
669 | for j in xrange(2000, 2100):
670 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
671 | seed_image = image_contrast(seed_image, params)
672 | model.predict_fn(seed_image, dummy=0)
673 | else:
674 | for j in xrange(2500, 2600):
675 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
676 | seed_image = image_contrast(seed_image, params)
677 | model.predict_fn(seed_image, dummy=0)
678 |
679 | if index%2 == 0:
680 | input_images = xrange(2100, 2600)
681 | else:
682 | input_images = xrange(2600, 3100)
683 |
684 | for i in input_images:
685 | j = i * 1
686 | csvrecord = []
687 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
688 | seed_image = image_contrast(seed_image, params)
689 |
690 | cnn_ndict, cnn_covered_neurons, cnn_total_neurons, lstm_ndict, lstm_covered_neurons, lstm_total_neurons, yhat = model.predict_fn(seed_image)
691 |
692 | tempk = []
693 | for k in cnn_ndict.keys():
694 | if cnn_ndict[k]:
695 | tempk.append(k)
696 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
697 | cnn_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
698 |
699 | tempk = []
700 | for k in lstm_ndict.keys():
701 | if lstm_ndict[k]:
702 | tempk.append(k)
703 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
704 | lstm_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
705 |
706 | model.nc_encoder.reset_cov_dict()
707 |
708 | model.nc_lstm.reset_cov_dict()
709 | #print(covered_neurons)
710 | #covered_neurons = nc.get_neuron_coverage(test_x)
711 | #print('input covered {} neurons'.format(covered_neurons))
712 | #print('total {} neurons'.format(total_neurons))
713 |
714 | filename, ext = os.path.splitext(str(filelist1[j]))
715 | if label1[j][0] != filename:
716 | print(filename + " not found in the label file")
717 | continue
718 |
719 | csvrecord.append(j-2)
720 | csvrecord.append(str(filelist1[j]))
721 | csvrecord.append('contrast')
722 | csvrecord.append('gain')
723 | csvrecord.append(params)
724 | csvrecord.append(model.threshold_cnn)
725 |
726 | csvrecord.append(cnn_covered_neurons)
727 | csvrecord.append(cnn_total_neurons)
728 | csvrecord.append(cnn_covered_detail)
729 | csvrecord.append(model.threshold_lstm)
730 |
731 | csvrecord.append(lstm_covered_neurons)
732 | csvrecord.append(lstm_total_neurons)
733 | csvrecord.append(lstm_covered_detail)
734 |
735 | csvrecord.append(yhat)
736 | csvrecord.append(label1[j][1])
737 | print(csvrecord[:8])
738 | writer.writerow(csvrecord)
739 |
740 | print("contrast done")
741 |
742 |
743 | #Brightness 102-121
744 | if index/2 >= 51 and index/2 <= 60:
745 | p = index/2-50
746 | #for p in xrange(1,11):
747 | params = p * 10
748 |
749 | if index%2 == 0:
750 | for j in xrange(2000, 2100):
751 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
752 | seed_image = image_brightness(seed_image, params)
753 | model.predict_fn(seed_image, dummy=0)
754 | else:
755 | for j in xrange(2500, 2600):
756 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
757 | seed_image = image_brightness(seed_image, params)
758 | model.predict_fn(seed_image, dummy=0)
759 |
760 | if index%2 == 0:
761 | input_images = xrange(2100, 2600)
762 | else:
763 | input_images = xrange(2600, 3100)
764 |
765 | for i in input_images:
766 | j = i * 1
767 | csvrecord = []
768 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
769 | seed_image = image_brightness(seed_image, params)
770 |
771 | cnn_ndict, cnn_covered_neurons, cnn_total_neurons, lstm_ndict, lstm_covered_neurons, lstm_total_neurons, yhat = model.predict_fn(seed_image)
772 |
773 |
774 | tempk = []
775 | for k in cnn_ndict.keys():
776 | if cnn_ndict[k]:
777 | tempk.append(k)
778 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
779 | cnn_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
780 |
781 |
782 | tempk = []
783 | for k in lstm_ndict.keys():
784 | if lstm_ndict[k]:
785 | tempk.append(k)
786 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
787 | lstm_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
788 |
789 | model.nc_encoder.reset_cov_dict()
790 |
791 | model.nc_lstm.reset_cov_dict()
792 | #print(covered_neurons)
793 | #covered_neurons = nc.get_neuron_coverage(test_x)
794 | #print('input covered {} neurons'.format(covered_neurons))
795 | #print('total {} neurons'.format(total_neurons))
796 |
797 |
798 | filename, ext = os.path.splitext(str(filelist1[j]))
799 | if label1[j][0] != filename:
800 | print(filename + " not found in the label file")
801 | continue
802 |
803 | csvrecord.append(j-2)
804 | csvrecord.append(str(filelist1[j]))
805 | csvrecord.append('brightness')
806 | csvrecord.append('bias')
807 | csvrecord.append(params)
808 | csvrecord.append(model.threshold_cnn)
809 |
810 | csvrecord.append(cnn_covered_neurons)
811 | csvrecord.append(cnn_total_neurons)
812 | csvrecord.append(cnn_covered_detail)
813 | csvrecord.append(model.threshold_lstm)
814 |
815 | csvrecord.append(lstm_covered_neurons)
816 | csvrecord.append(lstm_total_neurons)
817 | csvrecord.append(lstm_covered_detail)
818 |
819 | csvrecord.append(yhat)
820 | csvrecord.append(label1[j][1])
821 | print(csvrecord[:8])
822 | writer.writerow(csvrecord)
823 |
824 |
825 | print("brightness done")
826 |
827 | #blur 122-141
828 | if index/2 >= 61 and index/2 <= 70:
829 | p = index/2-60
830 | #for p in xrange(1,11):
831 | params = p
832 |
833 | if index%2 == 0:
834 | for j in xrange(2000, 2100):
835 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
836 | seed_image = image_blur(seed_image, params)
837 | model.predict_fn(seed_image, dummy=0)
838 | else:
839 | for j in xrange(2500, 2600):
840 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
841 | seed_image = image_blur(seed_image, params)
842 | model.predict_fn(seed_image, dummy=0)
843 |
844 | if index%2 == 0:
845 | input_images = xrange(2100, 2600)
846 | else:
847 | input_images = xrange(2600, 3100)
848 |
849 |
850 | for i in input_images:
851 | j = i * 1
852 | csvrecord = []
853 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
854 | seed_image = image_blur(seed_image, params)
855 |
856 | cnn_ndict, cnn_covered_neurons, cnn_total_neurons, lstm_ndict, lstm_covered_neurons, lstm_total_neurons, yhat = model.predict_fn(seed_image)
857 |
858 | tempk = []
859 | for k in cnn_ndict.keys():
860 | if cnn_ndict[k]:
861 | tempk.append(k)
862 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
863 | cnn_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
864 |
865 |
866 | tempk = []
867 | for k in lstm_ndict.keys():
868 | if lstm_ndict[k]:
869 | tempk.append(k)
870 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
871 | lstm_covered_detail = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
872 |
873 | model.nc_encoder.reset_cov_dict()
874 |
875 | model.nc_lstm.reset_cov_dict()
876 | #print(covered_neurons)
877 | #covered_neurons = nc.get_neuron_coverage(test_x)
878 | #print('input covered {} neurons'.format(covered_neurons))
879 | #print('total {} neurons'.format(total_neurons))
880 |
881 | filename, ext = os.path.splitext(str(filelist1[j]))
882 | if label1[j][0] != filename:
883 | print(filename + " not found in the label file")
884 | continue
885 |
886 |
887 | param_name = ""
888 | if params == 1:
889 | param_name = "averaging:3:3"
890 | if params == 2:
891 | param_name = "averaging:4:4"
892 | if params == 3:
893 | param_name = "averaging:5:5"
894 | if params == 4:
895 | param_name = "GaussianBlur:3:3"
896 | if params == 5:
897 | param_name = "GaussianBlur:5:5"
898 | if params == 6:
899 | param_name = "GaussianBlur:7:7"
900 | if params == 7:
901 | param_name = "medianBlur:3"
902 | if params == 8:
903 | param_name = "medianBlur:5"
904 | if params == 9:
905 | param_name = "averaging:6:6"
906 | if params == 10:
907 | param_name = "bilateralFilter:9:75:75"
908 |
909 | csvrecord.append(j-2)
910 | csvrecord.append(str(filelist1[j]))
911 | csvrecord.append('blur')
912 | csvrecord.append(param_name)
913 | csvrecord.append('-')
914 | csvrecord.append(model.threshold_cnn)
915 |
916 |
917 | csvrecord.append(cnn_covered_neurons)
918 | csvrecord.append(cnn_total_neurons)
919 | csvrecord.append(cnn_covered_detail)
920 | csvrecord.append(model.threshold_lstm)
921 |
922 | csvrecord.append(lstm_covered_neurons)
923 | csvrecord.append(lstm_total_neurons)
924 | csvrecord.append(lstm_covered_detail)
925 |
926 |
927 |
928 | csvrecord.append(yhat)
929 |
930 | csvrecord.append(label1[j][1])
931 | print(csvrecord[:8])
932 | writer.writerow(csvrecord)
933 |
934 | print("all done")
935 |
936 |
937 | if __name__ == '__main__':
938 |
939 | parser = argparse.ArgumentParser()
940 | parser.add_argument('--dataset', type=str, default='/media/yuchi/345F-2D0F/',
941 | help='path for dataset')
942 | parser.add_argument('--index', type=int, default=0,
943 | help='different indice mapped to different transformations and params')
944 | args = parser.parse_args()
945 | chauffeur_testgen_coverage(args.index, args.dataset)
946 |
--------------------------------------------------------------------------------
/testgen/chauffeur_testgen_driver.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 | mkdir result
3 | mv result/chauffeur_rq2_70000_images.csv result/chauffeur_rq2_70000_images.csv.bak
4 | touch result/chauffeur_rq2_70000_images.csv
5 | for i in `seq 0 141`;
6 | do
7 | echo $i
8 | python chauffeur_testgen_coverage.py --index $i --dataset $1
9 | done
10 |
--------------------------------------------------------------------------------
/testgen/epoch_testgen_coverage.py:
--------------------------------------------------------------------------------
1 | from __future__ import print_function
2 | import argparse
3 | import numpy as np
4 | import os
5 | from epoch_model import build_cnn, build_InceptionV3
6 | from scipy.misc import imread, imresize
7 | from keras import backend as K
8 | from ncoverage import NCoverage
9 | import csv
10 | import cv2
11 |
12 | def preprocess_input_InceptionV3(x):
13 | x /= 255.
14 | x -= 0.5
15 | x *= 2.
16 | return x
17 |
18 | def exact_output(y):
19 | return y
20 |
21 | def normalize_input(x):
22 | return x / 255.
23 |
24 | def read_image(image_file, image_size):
25 |
26 | img = imread(image_file)
27 | # Cropping
28 | crop_img = img[200:, :]
29 | # Resizing
30 | img = imresize(crop_img, size=image_size)
31 | imgs = []
32 | imgs.append(img)
33 | if len(imgs) < 1:
34 | print('Error no image at timestamp')
35 |
36 | img_block = np.stack(imgs, axis=0)
37 | if K.image_dim_ordering() == 'th':
38 | img_block = np.transpose(img_block, axes=(0, 3, 1, 2))
39 | return img_block
40 |
41 | def read_images(seed_inputs, seed_labels, image_size):
42 |
43 | img_blocks = []
44 | for file in os.listdir(seed_inputs):
45 | if file.endswith(".jpg"):
46 | img_block = read_image(os.path.join(seed_inputs, file), image_size)
47 | img_blocks.append(img_block)
48 | return img_blocks
49 |
50 | def read_transformed_image(image, image_size):
51 |
52 | img = image
53 | # Cropping
54 | crop_img = img[200:, :]
55 | # Resizing
56 | img = imresize(crop_img, size=image_size)
57 | imgs = []
58 | imgs.append(img)
59 | if len(imgs) < 1:
60 | print('Error no image at timestamp')
61 |
62 | img_block = np.stack(imgs, axis=0)
63 | if K.image_dim_ordering() == 'th':
64 | img_block = np.transpose(img_block, axes=(0, 3, 1, 2))
65 | return img_block
66 |
67 | def image_translation(img, params):
68 |
69 | rows, cols, ch = img.shape
70 |
71 | M = np.float32([[1, 0, params[0]], [0, 1, params[1]]])
72 | dst = cv2.warpAffine(img, M, (cols, rows))
73 | return dst
74 |
75 | def image_scale(img, params):
76 |
77 | res = cv2.resize(img, None, fx=params[0], fy=params[1], interpolation=cv2.INTER_CUBIC)
78 | return res
79 |
80 | def image_shear(img, params):
81 | rows, cols, ch = img.shape
82 | factor = params*(-1.0)
83 | M = np.float32([[1, factor, 0], [0, 1, 0]])
84 | dst = cv2.warpAffine(img, M, (cols, rows))
85 | return dst
86 |
87 | def image_rotation(img, params):
88 | rows, cols, ch = img.shape
89 | M = cv2.getRotationMatrix2D((cols/2, rows/2), params, 1)
90 | dst = cv2.warpAffine(img, M, (cols, rows))
91 | return dst
92 |
93 | def image_contrast(img, params):
94 | alpha = params
95 | new_img = cv2.multiply(img, np.array([alpha])) # mul_img = img*alpha
96 | #new_img = cv2.add(mul_img, beta) # new_img = img*alpha + beta
97 |
98 | return new_img
99 |
100 | def image_brightness(img, params):
101 | beta = params
102 | new_img = cv2.add(img, beta) # new_img = img*alpha + beta
103 |
104 | return new_img
105 |
106 | def image_blur(img, params):
107 | blur = []
108 | if params == 1:
109 | blur = cv2.blur(img, (3, 3))
110 | if params == 2:
111 | blur = cv2.blur(img, (4, 4))
112 | if params == 3:
113 | blur = cv2.blur(img, (5, 5))
114 | if params == 4:
115 | blur = cv2.GaussianBlur(img, (3, 3), 0)
116 | if params == 5:
117 | blur = cv2.GaussianBlur(img, (5, 5), 0)
118 | if params == 6:
119 | blur = cv2.GaussianBlur(img, (7, 7), 0)
120 | if params == 7:
121 | blur = cv2.medianBlur(img, 3)
122 | if params == 8:
123 | blur = cv2.medianBlur(img, 5)
124 | if params == 9:
125 | blur = cv2.blur(img, (6, 6))
126 | if params == 10:
127 | blur = cv2.bilateralFilter(img, 9, 75, 75)
128 | return blur
129 |
130 | def rotation(img, params):
131 |
132 | rows, cols, ch = img.shape
133 | M = cv2.getRotationMatrix2D((cols/2, rows/2), params[0], 1)
134 | dst = cv2.warpAffine(img, M, (cols, rows))
135 | return dst
136 |
137 | def image_brightness1(img, params):
138 | w = img.shape[1]
139 | h = img.shape[0]
140 | if params > 0:
141 | for xi in xrange(0, w):
142 | for xj in xrange(0, h):
143 | if 255-img[xj, xi, 0] < params:
144 | img[xj, xi, 0] = 255
145 | else:
146 | img[xj, xi, 0] = img[xj, xi, 0] + params
147 | if 255-img[xj, xi, 1] < params:
148 | img[xj, xi, 1] = 255
149 | else:
150 | img[xj, xi, 1] = img[xj, xi, 1] + params
151 | if 255-img[xj, xi, 2] < params:
152 | img[xj, xi, 2] = 255
153 | else:
154 | img[xj, xi, 2] = img[xj, xi, 2] + params
155 | if params < 0:
156 | params = params*(-1)
157 | for xi in xrange(0, w):
158 | for xj in xrange(0, h):
159 | if img[xj, xi, 0] - 0 < params:
160 | img[xj, xi, 0] = 0
161 | else:
162 | img[xj, xi, 0] = img[xj, xi, 0] - params
163 | if img[xj, xi, 1] - 0 < params:
164 | img[xj, xi, 1] = 0
165 | else:
166 | img[xj, xi, 1] = img[xj, xi, 1] - params
167 | if img[xj, xi, 2] - 0 < params:
168 | img[xj, xi, 2] = 0
169 | else:
170 | img[xj, xi, 2] = img[xj, xi, 2] - params
171 |
172 | return img
173 |
174 | def image_brightness2(img, params):
175 | beta = params
176 | b, g, r = cv2.split(img)
177 | b = cv2.add(b, beta)
178 | g = cv2.add(g, beta)
179 | r = cv2.add(r, beta)
180 | new_img = cv2.merge((b, g, r))
181 | return new_img
182 |
183 | def main():
184 | pass
185 |
186 |
187 |
188 | def epoch_testgen_coverage(index, dataset_path):
189 | model_name = "cnn"
190 | image_size = (128, 128)
191 | threshold = 0.2
192 | weights_path = './weights_HMB_2.hdf5' # Change to your model weights
193 |
194 |
195 | seed_inputs1 = os.path.join(dataset_path, "hmb3/")
196 | seed_labels1 = os.path.join(dataset_path, "hmb3/hmb3_steering.csv")
197 | seed_inputs2 = os.path.join(dataset_path, "Ch2_001/center/")
198 | seed_labels2 = os.path.join(dataset_path, "Ch2_001/CH2_final_evaluation.csv")
199 | # Model build
200 | # ---------------------------------------------------------------------------------
201 | model_builders = {
202 | 'V3': (build_InceptionV3, preprocess_input_InceptionV3, exact_output)
203 | , 'cnn': (build_cnn, normalize_input, exact_output)}
204 |
205 | if model_name not in model_builders:
206 | raise ValueError("unsupported model %s" % model_name)
207 | model_builder, input_processor, output_processor = model_builders[model_name]
208 | model = model_builder(image_size, weights_path)
209 | print('model %s built...' % model_name)
210 |
211 |
212 | filelist1 = []
213 | for file in sorted(os.listdir(seed_inputs1)):
214 | if file.endswith(".jpg"):
215 | filelist1.append(file)
216 |
217 | filelist2 = []
218 | for file in sorted(os.listdir(seed_inputs2)):
219 | if file.endswith(".jpg"):
220 | filelist2.append(file)
221 |
222 | with open(seed_labels1, 'rb') as csvfile1:
223 | label1 = list(csv.reader(csvfile1, delimiter=',', quotechar='|'))
224 | label1 = label1[1:]
225 |
226 | with open(seed_labels2, 'rb') as csvfile2:
227 | label2 = list(csv.reader(csvfile2, delimiter=',', quotechar='|'))
228 | label2 = label2[1:]
229 |
230 |
231 | nc = NCoverage(model, threshold)
232 | index = int(index)
233 | #seed inputs
234 | with open('result/epoch_coverage_70000_images.csv', 'ab', 0) as csvfile:
235 | writer = csv.writer(csvfile, delimiter=',',
236 | quotechar='|', quoting=csv.QUOTE_MINIMAL)
237 | if index == 0:
238 | writer.writerow(['index', 'image', 'tranformation', 'param_name', 'param_value',
239 | 'threshold', 'covered_neurons', 'total_neurons',
240 | 'covered_detail', 'y_hat', 'label'])
241 | if index/2 == 0:
242 | if index%2 == 0:
243 | input_images = xrange(1, 501)
244 | else:
245 | input_images = xrange(501, 1001)
246 | for i in input_images:
247 | j = i * 5
248 | csvrecord = []
249 |
250 |
251 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
252 | seed_image = read_transformed_image(seed_image, image_size)
253 |
254 | test_x = input_processor(seed_image.astype(np.float32))
255 | #print('test data shape:', test_x.shape)
256 | yhat = model.predict(test_x)
257 | #print('steering angle: ', yhat)
258 |
259 | ndict = nc.update_coverage(test_x)
260 | new_covered1, new_total1, p = nc.curr_neuron_cov()
261 |
262 | tempk = []
263 | for k in ndict.keys():
264 | if ndict[k]:
265 | tempk.append(k)
266 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
267 | covered_detail = ';'.join(str(x) for x in tempk).replace(',', ':')
268 | nc.reset_cov_dict()
269 | #print(covered_neurons)
270 | #covered_neurons = nc.get_neuron_coverage(test_x)
271 | #print('input covered {} neurons'.format(covered_neurons))
272 | #print('total {} neurons'.format(total_neurons))
273 |
274 |
275 | filename, ext = os.path.splitext(str(filelist1[j]))
276 | if label1[j][0] != filename:
277 | print(filename + " not found in the label file")
278 | continue
279 |
280 | if j < 2:
281 | continue
282 |
283 | csvrecord.append(j-2)
284 | csvrecord.append(str(filelist1[j]))
285 | csvrecord.append('-')
286 | csvrecord.append('-')
287 | csvrecord.append('-')
288 | csvrecord.append(threshold)
289 |
290 | csvrecord.append(new_covered1)
291 | csvrecord.append(new_total1)
292 | csvrecord.append(covered_detail)
293 |
294 |
295 | csvrecord.append(yhat[0][0])
296 | csvrecord.append(label1[j][1])
297 | print(csvrecord)
298 | writer.writerow(csvrecord)
299 |
300 | print("seed input done")
301 |
302 | #Translation
303 | if index/2 >= 1 and index/2 <= 10:
304 | #for p in xrange(1,11):
305 | p = index/2
306 | params = [p*10, p*10]
307 | if index%2 == 0:
308 | input_images = xrange(1, 501)
309 | else:
310 | input_images = xrange(501, 1001)
311 |
312 | for i in input_images:
313 | j = i * 5
314 | csvrecord = []
315 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
316 | seed_image = image_translation(seed_image, params)
317 | seed_image = read_transformed_image(seed_image, image_size)
318 | #seed_image = read_image(os.path.join(seed_inputs1, filelist1[j]),image_size)
319 | #new_covered1, new_total1, result = model.predict_fn(seed_image)
320 | test_x = input_processor(seed_image.astype(np.float32))
321 | #print('test data shape:', test_x.shape)
322 | yhat = model.predict(test_x)
323 | #print('steering angle: ', yhat)
324 |
325 | ndict = nc.update_coverage(test_x)
326 | new_covered1, new_total1, p = nc.curr_neuron_cov()
327 |
328 | tempk = []
329 | for k in ndict.keys():
330 | if ndict[k] == True:
331 | tempk.append(k)
332 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
333 | covered_detail = ';'.join(str(x) for x in tempk).replace(',', ':')
334 | nc.reset_cov_dict()
335 | #print(covered_neurons)
336 | #covered_neurons = nc.get_neuron_coverage(test_x)
337 | #print('input covered {} neurons'.format(covered_neurons))
338 | #print('total {} neurons'.format(total_neurons))
339 |
340 |
341 | filename, ext = os.path.splitext(str(filelist1[j]))
342 | if label1[j][0] != filename:
343 | print(filename + " not found in the label file")
344 | continue
345 |
346 | if j < 2:
347 | continue
348 |
349 | csvrecord.append(j-2)
350 | csvrecord.append(str(filelist1[j]))
351 | csvrecord.append('translation')
352 | csvrecord.append('x:y')
353 | csvrecord.append(':'.join(str(x) for x in params))
354 | csvrecord.append(threshold)
355 |
356 | csvrecord.append(new_covered1)
357 | csvrecord.append(new_total1)
358 | csvrecord.append(covered_detail)
359 |
360 | csvrecord.append(yhat[0][0])
361 | csvrecord.append(label1[j][1])
362 | print(csvrecord)
363 | writer.writerow(csvrecord)
364 | print("translation done")
365 |
366 | #Scale
367 | if index/2 >= 11 and index/2 <= 20:
368 | #for p in xrange(1,11):
369 | p = index/2-10
370 | params = [p*0.5+1, p*0.5+1]
371 |
372 | if index%2 == 0:
373 | input_images = xrange(1, 501)
374 | else:
375 | input_images = xrange(501, 1001)
376 |
377 | for i in input_images:
378 | j = i * 5
379 | csvrecord = []
380 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
381 | seed_image = image_scale(seed_image, params)
382 | seed_image = read_transformed_image(seed_image, image_size)
383 |
384 | #new_covered1, new_total1, result = model.predict_fn(seed_image)
385 | test_x = input_processor(seed_image.astype(np.float32))
386 | #print('test data shape:', test_x.shape)
387 | yhat = model.predict(test_x)
388 | #print('steering angle: ', yhat)
389 |
390 | ndict = nc.update_coverage(test_x)
391 | new_covered1, new_total1, p = nc.curr_neuron_cov()
392 |
393 | tempk = []
394 | for k in ndict.keys():
395 | if ndict[k] == True:
396 | tempk.append(k)
397 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
398 | covered_detail = ';'.join(str(x) for x in tempk).replace(',', ':')
399 | nc.reset_cov_dict()
400 | #print(covered_neurons)
401 | #covered_neurons = nc.get_neuron_coverage(test_x)
402 | #print('input covered {} neurons'.format(covered_neurons))
403 | #print('total {} neurons'.format(total_neurons))
404 |
405 |
406 | filename, ext = os.path.splitext(str(filelist1[j]))
407 | if label1[j][0] != filename:
408 | print(filename + " not found in the label file")
409 | continue
410 | if j < 2:
411 | continue
412 |
413 | csvrecord.append(j-2)
414 | csvrecord.append(str(filelist1[j]))
415 | csvrecord.append('scale')
416 | csvrecord.append('x:y')
417 | csvrecord.append(':'.join(str(x) for x in params))
418 | csvrecord.append(threshold)
419 |
420 | csvrecord.append(new_covered1)
421 | csvrecord.append(new_total1)
422 | csvrecord.append(covered_detail)
423 |
424 |
425 | csvrecord.append(yhat[0][0])
426 | csvrecord.append(label1[j][1])
427 | print(csvrecord)
428 | writer.writerow(csvrecord)
429 |
430 | print("scale done")
431 |
432 | #Shear
433 | if index/2 >= 21 and index/2 <= 30:
434 | #for p in xrange(1,11):
435 | p = index/2-20
436 | #for p in xrange(1,11):
437 | params = 0.1*p
438 | if index%2 == 0:
439 | input_images = xrange(1, 501)
440 | else:
441 | input_images = xrange(501, 1001)
442 |
443 | for i in input_images:
444 | j = i * 5
445 | csvrecord = []
446 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
447 | seed_image = image_shear(seed_image, params)
448 | seed_image = read_transformed_image(seed_image, image_size)
449 |
450 | #new_covered1, new_total1, result = model.predict_fn(seed_image)
451 | test_x = input_processor(seed_image.astype(np.float32))
452 | #print('test data shape:', test_x.shape)
453 | yhat = model.predict(test_x)
454 | #print('steering angle: ', yhat)
455 |
456 | ndict = nc.update_coverage(test_x)
457 | new_covered1, new_total1, p = nc.curr_neuron_cov()
458 |
459 | tempk = []
460 | for k in ndict.keys():
461 | if ndict[k] == True:
462 | tempk.append(k)
463 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
464 | covered_detail = ';'.join(str(x) for x in tempk).replace(',', ':')
465 | nc.reset_cov_dict()
466 | #print(covered_neurons)
467 | #covered_neurons = nc.get_neuron_coverage(test_x)
468 | #print('input covered {} neurons'.format(covered_neurons))
469 | #print('total {} neurons'.format(total_neurons))
470 |
471 | filename, ext = os.path.splitext(str(filelist1[j]))
472 | if label1[j][0] != filename:
473 | print(filename + " not found in the label file")
474 | continue
475 | if j < 2:
476 | continue
477 |
478 | csvrecord.append(j-2)
479 | csvrecord.append(str(filelist1[j]))
480 | csvrecord.append('shear')
481 | csvrecord.append('factor')
482 | csvrecord.append(params)
483 | csvrecord.append(threshold)
484 |
485 | csvrecord.append(new_covered1)
486 | csvrecord.append(new_total1)
487 | csvrecord.append(covered_detail)
488 |
489 |
490 | csvrecord.append(yhat[0][0])
491 | csvrecord.append(label1[j][1])
492 | print(csvrecord)
493 | writer.writerow(csvrecord)
494 | print("sheer done")
495 |
496 | #Rotation
497 | if index/2 >= 31 and index/2 <= 40:
498 | p = index/2-30
499 | params = p*3
500 | if index%2 == 0:
501 | input_images = xrange(1, 501)
502 | else:
503 | input_images = xrange(501, 1001)
504 | for i in input_images:
505 | j = i * 5
506 | csvrecord = []
507 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
508 | seed_image = image_rotation(seed_image, params)
509 | seed_image = read_transformed_image(seed_image, image_size)
510 | #new_covered1, new_total1, result = model.predict_fn(seed_image)
511 | test_x = input_processor(seed_image.astype(np.float32))
512 | #print('test data shape:', test_x.shape)
513 | yhat = model.predict(test_x)
514 | #print('steering angle: ', yhat)
515 |
516 | ndict = nc.update_coverage(test_x)
517 | new_covered1, new_total1, p = nc.curr_neuron_cov()
518 |
519 | tempk = []
520 | for k in ndict.keys():
521 | if ndict[k] == True:
522 | tempk.append(k)
523 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
524 | covered_detail = ';'.join(str(x) for x in tempk).replace(',', ':')
525 | nc.reset_cov_dict()
526 | #print(covered_neurons)
527 | #covered_neurons = nc.get_neuron_coverage(test_x)
528 | #print('input covered {} neurons'.format(covered_neurons))
529 | #print('total {} neurons'.format(total_neurons))
530 |
531 | filename, ext = os.path.splitext(str(filelist1[j]))
532 | if label1[j][0] != filename:
533 | print(filename + " not found in the label file")
534 | continue
535 |
536 | if j < 2:
537 | continue
538 |
539 | csvrecord.append(j-2)
540 | csvrecord.append(str(filelist1[j]))
541 | csvrecord.append('rotation')
542 | csvrecord.append('angle')
543 | csvrecord.append(params)
544 | csvrecord.append(threshold)
545 |
546 | csvrecord.append(new_covered1)
547 | csvrecord.append(new_total1)
548 | csvrecord.append(covered_detail)
549 |
550 | csvrecord.append(yhat[0][0])
551 | csvrecord.append(label1[j][1])
552 | print(csvrecord)
553 | writer.writerow(csvrecord)
554 |
555 | print("rotation done")
556 |
557 | #Contrast
558 | if index/2 >= 41 and index/2 <= 50:
559 | p = index/2 - 40
560 | params = 1 + p*0.2
561 | if index%2 == 0:
562 | input_images = xrange(1, 501)
563 | else:
564 | input_images = xrange(501, 1001)
565 | for i in input_images:
566 | j = i * 5
567 | csvrecord = []
568 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
569 | seed_image = image_contrast(seed_image, params)
570 | seed_image = read_transformed_image(seed_image, image_size)
571 |
572 | #new_covered1, new_total1, result = model.predict_fn(seed_image)
573 | test_x = input_processor(seed_image.astype(np.float32))
574 | #print('test data shape:', test_x.shape)
575 | yhat = model.predict(test_x)
576 | #print('steering angle: ', yhat)
577 |
578 | ndict = nc.update_coverage(test_x)
579 | new_covered1, new_total1, p = nc.curr_neuron_cov()
580 |
581 | tempk = []
582 | for k in ndict.keys():
583 | if ndict[k] == True:
584 | tempk.append(k)
585 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
586 | covered_detail = ';'.join(str(x) for x in tempk).replace(',', ':')
587 | nc.reset_cov_dict()
588 | #print(covered_neurons)
589 | #covered_neurons = nc.get_neuron_coverage(test_x)
590 | #print('input covered {} neurons'.format(covered_neurons))
591 | #print('total {} neurons'.format(total_neurons))
592 |
593 | filename, ext = os.path.splitext(str(filelist1[j]))
594 | if label1[j][0] != filename:
595 | print(filename + " not found in the label file")
596 | continue
597 |
598 | if j < 2:
599 | continue
600 |
601 | csvrecord.append(j-2)
602 | csvrecord.append(str(filelist1[j]))
603 | csvrecord.append('contrast')
604 | csvrecord.append('gain')
605 | csvrecord.append(params)
606 | csvrecord.append(threshold)
607 |
608 | csvrecord.append(new_covered1)
609 | csvrecord.append(new_total1)
610 | csvrecord.append(covered_detail)
611 |
612 | csvrecord.append(yhat[0][0])
613 | csvrecord.append(label1[j][1])
614 | print(csvrecord)
615 | writer.writerow(csvrecord)
616 |
617 | print("contrast done")
618 |
619 | #Brightness
620 | if index/2 >= 51 and index/2 <= 60:
621 | p = index/2 - 50
622 | params = p * 10
623 | if index%2 == 0:
624 | input_images = xrange(1, 501)
625 | else:
626 | input_images = xrange(501, 1001)
627 | for i in input_images:
628 | j = i * 5
629 | csvrecord = []
630 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
631 | seed_image = image_brightness2(seed_image, params)
632 | seed_image = read_transformed_image(seed_image, image_size)
633 |
634 | #new_covered1, new_total1, result = model.predict_fn(seed_image)
635 | test_x = input_processor(seed_image.astype(np.float32))
636 | #print('test data shape:', test_x.shape)
637 | yhat = model.predict(test_x)
638 | #print('steering angle: ', yhat)
639 |
640 | ndict = nc.update_coverage(test_x)
641 | new_covered1, new_total1, p = nc.curr_neuron_cov()
642 |
643 | tempk = []
644 | for k in ndict.keys():
645 | if ndict[k] == True:
646 | tempk.append(k)
647 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
648 | covered_detail = ';'.join(str(x) for x in tempk).replace(',', ':')
649 | nc.reset_cov_dict()
650 | #print(covered_neurons)
651 | #covered_neurons = nc.get_neuron_coverage(test_x)
652 | #print('input covered {} neurons'.format(covered_neurons))
653 | #print('total {} neurons'.format(total_neurons))
654 |
655 |
656 | filename, ext = os.path.splitext(str(filelist1[j]))
657 | if label1[j][0] != filename:
658 | print(filename + " not found in the label file")
659 | continue
660 | if j < 2:
661 | continue
662 |
663 | csvrecord.append(j-2)
664 | csvrecord.append(str(filelist1[j]))
665 | csvrecord.append('brightness')
666 | csvrecord.append('bias')
667 | csvrecord.append(params)
668 | csvrecord.append(threshold)
669 |
670 | csvrecord.append(new_covered1)
671 | csvrecord.append(new_total1)
672 | csvrecord.append(covered_detail)
673 |
674 |
675 | csvrecord.append(yhat[0][0])
676 | csvrecord.append(label1[j][1])
677 | print(csvrecord)
678 | writer.writerow(csvrecord)
679 | print("brightness done")
680 |
681 | #blur
682 | if index/2 >= 61 and index/2 <= 70:
683 | p = index/2 - 60
684 | params = p
685 | if index%2 == 0:
686 | input_images = xrange(1, 501)
687 | else:
688 | input_images = xrange(501, 1001)
689 | for i in input_images:
690 | j = i * 5
691 | csvrecord = []
692 | seed_image = cv2.imread(os.path.join(seed_inputs1, filelist1[j]))
693 | seed_image = image_blur(seed_image, params)
694 | seed_image = read_transformed_image(seed_image, image_size)
695 |
696 | #new_covered1, new_total1, result = model.predict_fn(seed_image)
697 | test_x = input_processor(seed_image.astype(np.float32))
698 | #print('test data shape:', test_x.shape)
699 | yhat = model.predict(test_x)
700 | #print('steering angle: ', yhat)
701 |
702 | ndict = nc.update_coverage(test_x)
703 | new_covered1, new_total1, p = nc.curr_neuron_cov()
704 |
705 | tempk = []
706 | for k in ndict.keys():
707 | if ndict[k] == True:
708 | tempk.append(k)
709 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
710 | covered_detail = ';'.join(str(x) for x in tempk).replace(',', ':')
711 | nc.reset_cov_dict()
712 | #print(covered_neurons)
713 | #covered_neurons = nc.get_neuron_coverage(test_x)
714 | #print('input covered {} neurons'.format(covered_neurons))
715 | #print('total {} neurons'.format(total_neurons))
716 |
717 | filename, ext = os.path.splitext(str(filelist1[j]))
718 | if label1[j][0] != filename:
719 | print(filename + " not found in the label file")
720 | continue
721 |
722 | if j < 2:
723 | continue
724 | param_name = ""
725 | if params == 1:
726 | param_name = "averaging:3:3"
727 | if params == 2:
728 | param_name = "averaging:4:4"
729 | if params == 3:
730 | param_name = "averaging:5:5"
731 | if params == 4:
732 | param_name = "GaussianBlur:3:3"
733 | if params == 5:
734 | param_name = "GaussianBlur:5:5"
735 | if params == 6:
736 | param_name = "GaussianBlur:7:7"
737 | if params == 7:
738 | param_name = "medianBlur:3"
739 | if params == 8:
740 | param_name = "medianBlur:5"
741 | if params == 9:
742 | param_name = "averaging:6:6"
743 | if params == 10:
744 | param_name = "bilateralFilter:9:75:75"
745 | csvrecord.append(j-2)
746 | csvrecord.append(str(filelist1[j]))
747 | csvrecord.append('blur')
748 | csvrecord.append(param_name)
749 | csvrecord.append(param_name)
750 | csvrecord.append(threshold)
751 |
752 | csvrecord.append(new_covered1)
753 | csvrecord.append(new_total1)
754 | csvrecord.append(covered_detail)
755 |
756 | csvrecord.append(yhat[0][0])
757 | csvrecord.append(label1[j][1])
758 | print(csvrecord)
759 | writer.writerow(csvrecord)
760 | print("all done")
761 |
762 |
763 |
764 | if __name__ == '__main__':
765 | parser = argparse.ArgumentParser()
766 | parser.add_argument('--dataset', type=str, default='/media/yuchi/345F-2D0F/',
767 | help='path for dataset')
768 | parser.add_argument('--index', type=int, default=0,
769 | help='different indice mapped to different transformations and params')
770 | args = parser.parse_args()
771 | epoch_testgen_coverage(args.index, args.dataset)
772 |
--------------------------------------------------------------------------------
/testgen/epoch_testgen_driver.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 | mkdir result
3 | mv result/epoch_coverage_70000_images.csv result/epoch_coverage_70000_images.csv.bak
4 | touch result/epoch_coverage_70000_images.csv
5 | for i in `seq 0 141`;
6 | do
7 | echo $i
8 | python epoch_testgen_coverage.py --index $i --dataset $1
9 | done
10 |
--------------------------------------------------------------------------------
/testgen/ncoverage.py:
--------------------------------------------------------------------------------
1 | from __future__ import print_function
2 | import numpy as np
3 | from keras.models import Model
4 |
5 | class NCoverage():
6 |
7 | def __init__(self, model, threshold=0.1, exclude_layer=['pool', 'fc', 'flatten'], only_layer=""):
8 | '''
9 | Initialize the model to be tested
10 | :param threshold: threshold to determine if the neuron is activated
11 | :param model_name: ImageNet Model name, can have ('vgg16','vgg19','resnet50')
12 | :param neuron_layer: Only these layers are considered for neuron coverage
13 | '''
14 | self.threshold = float(threshold)
15 | self.model = model
16 |
17 | print('models loaded')
18 |
19 | # the layers that are considered in neuron coverage computation
20 | self.layer_to_compute = []
21 | for layer in self.model.layers:
22 | if all(ex not in layer.name for ex in exclude_layer):
23 | self.layer_to_compute.append(layer.name)
24 |
25 | if only_layer != "":
26 | self.layer_to_compute = [only_layer]
27 |
28 | # init coverage table
29 | self.cov_dict = {}
30 |
31 | for layer_name in self.layer_to_compute:
32 | for index in xrange(self.model.get_layer(layer_name).output_shape[-1]):
33 | self.cov_dict[(layer_name, index)] = False
34 |
35 | def scale(self, layer_outputs, rmax=1, rmin=0):
36 | '''
37 | scale the intermediate layer's output between 0 and 1
38 | :param layer_outputs: the layer's output tensor
39 | :param rmax: the upper bound of scale
40 | :param rmin: the lower bound of scale
41 | :return:
42 | '''
43 | divider = (layer_outputs.max() - layer_outputs.min())
44 | if divider == 0:
45 | return np.zeros(shape=layer_outputs.shape)
46 | X_std = (layer_outputs - layer_outputs.min()) / divider
47 | X_scaled = X_std * (rmax - rmin) + rmin
48 | return X_scaled
49 |
50 |
51 | def set_covdict(self, covdict):
52 | self.cov_dict = dict(covdict)
53 |
54 | def get_neuron_coverage(self, input_data):
55 | '''
56 | Given the input, return the covered neurons by the input data without marking the covered neurons.
57 | '''
58 |
59 | covered_neurons = []
60 | for layer_name in self.layer_to_compute:
61 | layer_model = Model(input=self.model.input,
62 | output=self.model.get_layer(layer_name).output)
63 | layer_outputs = layer_model.predict(input_data)
64 | for layer_output in layer_outputs:
65 | scaled = self.scale(layer_output)
66 | for neuron_idx in xrange(scaled.shape[-1]):
67 | if np.mean(scaled[..., neuron_idx]) > self.threshold:
68 | if (layer_name, neuron_idx) not in covered_neurons:
69 | covered_neurons.append((layer_name, neuron_idx))
70 | return covered_neurons
71 |
72 |
73 | def update_coverage(self, input_data):
74 | '''
75 | Given the input, update the neuron covered in the model by this input.
76 | This includes mark the neurons covered by this input as "covered"
77 | :param input_data: the input image
78 | :return: the neurons that can be covered by the input
79 | '''
80 | for layer_name in self.layer_to_compute:
81 | layer_model = Model(input=self.model.inputs,
82 | output=self.model.get_layer(layer_name).output)
83 |
84 | layer_outputs = layer_model.predict(input_data)
85 |
86 | for layer_output in layer_outputs:
87 | scaled = self.scale(layer_output)
88 | #print(scaled.shape)
89 | for neuron_idx in xrange(scaled.shape[-1]):
90 | if np.mean(scaled[..., neuron_idx]) > self.threshold:
91 | self.cov_dict[(layer_name, neuron_idx)] = True
92 | del layer_outputs
93 | del layer_model
94 |
95 |
96 | return self.cov_dict
97 |
98 | def is_testcase_increase_coverage(self, input_data):
99 | '''
100 | Given the input, check if new neuron is covered without marking the covered neurons.
101 | If a previously not covered neuron is covered by the input, return True.
102 | Otherwise return False.
103 | '''
104 | for layer_name in self.layer_to_compute:
105 | layer_model = Model(input=self.model.inputs,
106 | output=self.model.get_layer(layer_name).output)
107 |
108 | layer_outputs = layer_model.predict(input_data)
109 |
110 | for layer_output in layer_outputs:
111 | scaled = self.scale(layer_output)
112 | #print(scaled.shape)
113 | for neuron_idx in xrange(scaled.shape[-1]):
114 | if np.mean(scaled[..., neuron_idx]) > self.threshold:
115 | if not self.cov_dict[(layer_name, neuron_idx)]:
116 | return True
117 |
118 | return False
119 |
120 |
121 | def curr_neuron_cov(self):
122 | '''
123 | Get current coverage information of MUT
124 | :return: number of covered neurons,
125 | number of total neurons,
126 | number of neuron coverage rate
127 | '''
128 | covered_neurons = len([v for v in self.cov_dict.values() if v])
129 | total_neurons = len(self.cov_dict)
130 | return covered_neurons, total_neurons, covered_neurons / float(total_neurons)
131 |
132 |
133 | def activated(self, layer_name, idx, input_data):
134 | '''
135 | Test if the neuron is activated by this input
136 | :param layer_name: the layer name
137 | :param idx: the neuron index in the layer
138 | :param input_data: the input
139 | :return: True/False
140 | '''
141 | layer_model = Model(input=self.model.input,
142 | output=self.model.get_layer(layer_name).output)
143 | layer_output = layer_model.predict(input_data)[0]
144 | scaled = self.scale(layer_output)
145 | if np.mean(scaled[..., idx]) > self.threshold:
146 | return True
147 | return False
148 |
149 | def reset_cov_dict(self):
150 | '''
151 | Reset the coverage table
152 | :return:
153 | '''
154 | for layer_name in self.layer_to_compute:
155 | for index in xrange(self.model.get_layer(layer_name).output_shape[-1]):
156 | self.cov_dict[(layer_name, index)] = False
157 |
--------------------------------------------------------------------------------
/testgen/rambo_testgen_coverage.py:
--------------------------------------------------------------------------------
1 | import glob
2 | import argparse
3 | import numpy as np
4 | from collections import deque
5 | from keras.models import load_model
6 | from keras.models import Model as Kmodel
7 | from keras.preprocessing.image import load_img, img_to_array
8 | from skimage.exposure import rescale_intensity
9 | from scipy import misc
10 | from scipy.misc import imread, imresize, imsave
11 | import sys
12 | import os
13 | from ncoverage import NCoverage
14 | import csv
15 | import cv2
16 | import matplotlib.pyplot as plt
17 | from scipy.misc import imshow
18 |
19 | reload(sys)
20 | sys.setdefaultencoding('ISO-8859-1')
21 |
22 | class Model(object):
23 | def __init__(self,
24 | model_path,
25 | X_train_mean_path):
26 |
27 | self.model = load_model(model_path)
28 | self.model.compile(optimizer="adam", loss="mse")
29 | self.X_mean = np.load(X_train_mean_path)
30 | self.mean_angle = np.array([-0.004179079])
31 | print self.mean_angle
32 | self.img0 = None
33 | self.state = deque(maxlen=2)
34 |
35 | self.threshold = 0.2
36 | #self.nc = NCoverage(self.model,self.threshold)
37 | s1 = self.model.get_layer('sequential_1')
38 | self.nc1 = NCoverage(s1,self.threshold)
39 | #print(s1.summary())
40 |
41 |
42 | s2 = self.model.get_layer('sequential_2')
43 | #print(s2.summary())
44 | self.nc2 = NCoverage(s2,self.threshold)
45 |
46 |
47 | s3 = self.model.get_layer('sequential_3')
48 | #print(s3.summary())
49 | self.nc3 = NCoverage(s3,self.threshold)
50 |
51 |
52 | i1 = self.model.get_layer('input_1')
53 |
54 | self.i1_model = Kmodel(input = self.model.inputs, output = i1.output)
55 |
56 |
57 |
58 | def predict(self, img):
59 | img_path = 'test.jpg'
60 | misc.imsave(img_path, img)
61 | img1 = load_img(img_path, grayscale=True, target_size=(192, 256))
62 | img1 = img_to_array(img1)
63 |
64 | if self.img0 is None:
65 | self.img0 = img1
66 | return 0, 0, self.mean_angle[0],0,0,0,0,0,0
67 |
68 | elif len(self.state) < 1:
69 | img = img1 - self.img0
70 | img = rescale_intensity(img, in_range=(-255, 255), out_range=(0, 255))
71 | img = np.array(img, dtype=np.uint8) # to replicate initial model
72 | self.state.append(img)
73 | self.img0 = img1
74 |
75 | return 0, 0, self.mean_angle[0],0,0,0,0,0,0
76 |
77 | else:
78 | img = img1 - self.img0
79 | img = rescale_intensity(img, in_range=(-255, 255), out_range=(0, 255))
80 | img = np.array(img, dtype=np.uint8) # to replicate initial model
81 | self.state.append(img)
82 | self.img0 = img1
83 |
84 | X = np.concatenate(self.state, axis=-1)
85 | X = X[:,:,::-1]
86 | X = np.expand_dims(X, axis=0)
87 | X = X.astype('float32')
88 | X -= self.X_mean
89 | X /= 255.0
90 |
91 |
92 | #print(self.model.summary())
93 | #for layer in self.model.layers:
94 | #print (layer.name)
95 |
96 | i1_outputs = self.i1_model.predict(X)
97 | '''
98 | layerlist1 = self.nc1.update_coverage(i1_outputs)
99 | covered_neurons1, total_neurons1, p = self.nc1.curr_neuron_cov()
100 | c1 = covered_neurons1
101 | t1 = total_neurons1
102 |
103 | layerlist2 = self.nc2.update_coverage(i1_outputs)
104 | covered_neurons2, total_neurons2, p = self.nc2.curr_neuron_cov()
105 | c2 = covered_neurons2
106 | t2 = total_neurons2
107 |
108 | layerlist3 = self.nc3.update_coverage(i1_outputs)
109 | covered_neurons3, total_neurons3, p = self.nc3.curr_neuron_cov()
110 | c3 = covered_neurons3
111 | t3 = total_neurons3
112 | covered_neurons = covered_neurons1 + covered_neurons2 + covered_neurons3
113 | total_neurons = total_neurons1 + total_neurons2 + total_neurons3
114 | '''
115 | rs1 = self.s1_model.predict(i1_outputs)
116 | rs2 = self.s2_model.predict(i1_outputs)
117 | rs3 = self.s3_model.predict(i1_outputs)
118 | #return covered_neurons, total_neurons, self.model.predict(X)[0][0],c1,t1,c2,t2,c3,t3
119 | return 0, 0, self.model.predict(X)[0][0],rs1[0][0],rs2[0][0],rs3[0][0],0,0,0
120 |
121 | def predict1(self, img, transform, params):
122 | img_path = 'test.jpg'
123 | misc.imsave(img_path, img)
124 | img1 = load_img(img_path, grayscale=True, target_size=(192, 256))
125 | img1 = img_to_array(img1)
126 |
127 | if self.img0 is None:
128 | self.img0 = img1
129 | return 0, 0, self.mean_angle[0],0,0,0,0,0,0,0,0,0
130 |
131 | elif len(self.state) < 1:
132 | img = img1 - self.img0
133 | img = rescale_intensity(img, in_range=(-255, 255), out_range=(0, 255))
134 | img = np.array(img, dtype=np.uint8) # to replicate initial model
135 | self.state.append(img)
136 | self.img0 = img1
137 |
138 | return 0, 0, self.mean_angle[0],0,0,0,0,0,0,0,0,0
139 |
140 | else:
141 | img = img1 - self.img0
142 | img = rescale_intensity(img, in_range=(-255, 255), out_range=(0, 255))
143 | img = np.array(img, dtype=np.uint8) # to replicate initial model
144 | self.state.append(img)
145 | self.img0 = img1
146 |
147 | X = np.concatenate(self.state, axis=-1)
148 |
149 | if transform != None and params != None:
150 | X = transform(X, params)
151 |
152 | X = X[:,:,::-1]
153 | X = np.expand_dims(X, axis=0)
154 | X = X.astype('float32')
155 | X -= self.X_mean
156 | X /= 255.0
157 |
158 |
159 | #print(self.model.summary())
160 | #for layer in self.model.layers:
161 | #print (layer.name)
162 |
163 | i1_outputs = self.i1_model.predict(X)
164 |
165 | d1 = self.nc1.update_coverage(i1_outputs)
166 | covered_neurons1, total_neurons1, p = self.nc1.curr_neuron_cov()
167 | c1 = covered_neurons1
168 | t1 = total_neurons1
169 |
170 | d2 = self.nc2.update_coverage(i1_outputs)
171 | covered_neurons2, total_neurons2, p = self.nc2.curr_neuron_cov()
172 | c2 = covered_neurons2
173 | t2 = total_neurons2
174 |
175 | d3 = self.nc3.update_coverage(i1_outputs)
176 | covered_neurons3, total_neurons3, p = self.nc3.curr_neuron_cov()
177 | c3 = covered_neurons3
178 | t3 = total_neurons3
179 | covered_neurons = covered_neurons1 + covered_neurons2 + covered_neurons3
180 | total_neurons = total_neurons1 + total_neurons2 + total_neurons3
181 |
182 | return covered_neurons, total_neurons, self.model.predict(X)[0][0],c1,t1,d1,c2,t2,d2,c3,t3,d3
183 | #return 0, 0, self.model.predict(X)[0][0],rs1[0][0],rs2[0][0],rs3[0][0],0,0,0
184 |
185 | def hard_reset(self):
186 |
187 | self.mean_angle = np.array([-0.004179079])
188 | #print self.mean_angle
189 | self.img0 = None
190 | self.state = deque(maxlen=2)
191 | self.threshold = 0.2
192 | #self.nc.reset_cov_dict()
193 | self.nc1.reset_cov_dict()
194 | self.nc2.reset_cov_dict()
195 | self.nc3.reset_cov_dict()
196 |
197 |
198 | def soft_reset(self):
199 |
200 | self.mean_angle = np.array([-0.004179079])
201 | print self.mean_angle
202 | self.img0 = None
203 | self.state = deque(maxlen=2)
204 | self.threshold = 0.2
205 |
206 | def image_translation(img, params):
207 |
208 | rows,cols,ch = img.shape
209 |
210 | M = np.float32([[1,0,params[0]],[0,1,params[1]]])
211 | dst = cv2.warpAffine(img,M,(cols,rows))
212 | return dst
213 |
214 | def image_scale(img, params):
215 |
216 | res = cv2.resize(img,None,fx=params[0], fy=params[1], interpolation = cv2.INTER_CUBIC)
217 | return res
218 |
219 | def image_shear(img, params):
220 | rows,cols,ch = img.shape
221 | factor = params*(-1.0)
222 | M = np.float32([[1,factor,0],[0,1,0]])
223 | dst = cv2.warpAffine(img,M,(cols,rows))
224 | return dst
225 |
226 | def image_rotation(img, params):
227 | rows,cols,ch = img.shape
228 | M = cv2.getRotationMatrix2D((cols/2,rows/2),params,1)
229 | dst = cv2.warpAffine(img,M,(cols,rows))
230 | return dst
231 |
232 | def image_contrast(img, params):
233 | alpha = params
234 | new_img = cv2.multiply(img, np.array([alpha])) # mul_img = img*alpha
235 | #new_img = cv2.add(mul_img, beta) # new_img = img*alpha + beta
236 |
237 | return new_img
238 |
239 | def image_brightness(img, params):
240 | beta = params
241 | new_img = cv2.add(img, beta) # new_img = img*alpha + beta
242 |
243 | return new_img
244 |
245 | def image_blur(img, params):
246 | blur = []
247 | if params == 1:
248 | blur = cv2.blur(img,(3,3))
249 | if params == 2:
250 | blur = cv2.blur(img,(4,4))
251 | if params == 3:
252 | blur = cv2.blur(img,(5,5))
253 | if params == 4:
254 | blur = cv2.GaussianBlur(img,(3,3),0)
255 | if params == 5:
256 | blur = cv2.GaussianBlur(img,(4,4),0)
257 | if params == 6:
258 | blur = cv2.GaussianBlur(img,(5,5),0)
259 | if params == 7:
260 | blur = cv2.medianBlur(img,3)
261 | if params == 8:
262 | blur = cv2.medianBlur(img,4)
263 | if params == 9:
264 | blur = cv2.medianBlur(img,5)
265 | if params == 10:
266 | blur = cv2.bilateralFilter(img,9,75,75)
267 | return blur
268 |
269 |
270 |
271 | def rambo_testgen_coverage(dataset_path):
272 | seed_inputs1 = os.path.join(dataset_path, "hmb3/")
273 | seed_labels1 = os.path.join(dataset_path, "hmb3/hmb3_steering.csv")
274 | seed_inputs2 = os.path.join(dataset_path, "Ch2_001/center/")
275 | seed_labels2 = os.path.join(dataset_path, "Ch2_001/CH2_final_evaluation.csv")
276 |
277 |
278 | model = Model("./final_model.hdf5", "./X_train_mean.npy")
279 | filelist1 = []
280 | for file in sorted(os.listdir(seed_inputs1)):
281 | if file.endswith(".jpg"):
282 | filelist1.append(file)
283 |
284 | filelist2 = []
285 | for file in sorted(os.listdir(seed_inputs2)):
286 | if file.endswith(".jpg"):
287 | filelist2.append(file)
288 |
289 | with open(seed_labels1, 'rb') as csvfile1:
290 | label1 = list(csv.reader(csvfile1, delimiter=',', quotechar='|'))
291 | label1 = label1[1:]
292 |
293 | with open(seed_labels2, 'rb') as csvfile2:
294 | label2 = list(csv.reader(csvfile2, delimiter=',', quotechar='|'))
295 | label2 = label2[1:]
296 |
297 |
298 | with open('result/rambo_rq2_70000_images.csv', 'wb',0) as csvfile:
299 | writer = csv.writer(csvfile, delimiter=',',
300 | quotechar='|', quoting=csv.QUOTE_MINIMAL)
301 | writer.writerow(['index', 'image', 'tranformation', 'param_name',
302 | 'param_value','threshold','covered_neurons', 'total_neurons',
303 | 's1_covered', 's1_total','s1_detail',
304 | 's2_covered', 's2_total','s2_detail',
305 | 's3_covered', 's3_total','s3_detail',
306 | 'y_hat','label'])
307 |
308 |
309 | #seed input
310 | input_images = xrange(1, 1001)
311 | for i in input_images:
312 | j = i * 5
313 | csvrecord = []
314 |
315 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-2]))
316 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,None,None)
317 |
318 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-1]))
319 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,None,None)
320 |
321 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j]))
322 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,None,None)
323 | filename, ext = os.path.splitext(str(filelist1[j]))
324 |
325 | if label1[j][0] != filename:
326 | print(filename + " not found in the label file")
327 | continue
328 |
329 |
330 |
331 | tempk = []
332 | for k in d1.keys():
333 | if d1[k]:
334 | tempk.append(k)
335 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
336 | #covered_detail1 = ';'.join(str(x) for x in tempk).replace(',', ':')
337 | covered_detail1 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
338 | tempk = []
339 | for k in d2.keys():
340 | if d2[k]:
341 | tempk.append(k)
342 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
343 | covered_detail2 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
344 |
345 | tempk = []
346 | for k in d3.keys():
347 | if d3[k]:
348 | tempk.append(k)
349 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
350 | covered_detail3 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
351 |
352 | csvrecord.append(j-2)
353 | csvrecord.append(str(filelist1[j]))
354 | csvrecord.append('-')
355 | csvrecord.append('-')
356 | csvrecord.append('-')
357 | csvrecord.append(model.threshold)
358 |
359 | csvrecord.append(new_covered)
360 | csvrecord.append(new_total)
361 | csvrecord.append(c1)
362 | csvrecord.append(t1)
363 | csvrecord.append(covered_detail1)
364 | csvrecord.append(c2)
365 | csvrecord.append(t2)
366 | csvrecord.append(covered_detail2)
367 | csvrecord.append(c3)
368 | csvrecord.append(t3)
369 | csvrecord.append(covered_detail3)
370 |
371 |
372 | csvrecord.append(result)
373 | csvrecord.append(label1[j][1])
374 | print(csvrecord)
375 | writer.writerow(csvrecord)
376 | model.hard_reset()
377 |
378 | print("seed input done")
379 |
380 | #Translation
381 |
382 | input_images = xrange(1, 1001)
383 | for p in xrange(1, 11):
384 | params = [p*10, p*10]
385 | for i in input_images:
386 | j = i * 5
387 | csvrecord = []
388 |
389 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-2]))
390 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_translation,params)
391 |
392 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-1]))
393 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_translation,params)
394 |
395 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j]))
396 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_translation,params)
397 | filename, ext = os.path.splitext(str(filelist1[j]))
398 |
399 | if label1[j][0] != filename:
400 | print(filename + " not found in the label file")
401 | continue
402 |
403 |
404 |
405 | tempk = []
406 | for k in d1.keys():
407 | if d1[k]:
408 | tempk.append(k)
409 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
410 | covered_detail1 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
411 |
412 | tempk = []
413 | for k in d2.keys():
414 | if d2[k]:
415 | tempk.append(k)
416 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
417 | covered_detail2 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
418 |
419 | tempk = []
420 | for k in d3.keys():
421 | if d3[k]:
422 | tempk.append(k)
423 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
424 | covered_detail3 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
425 |
426 | csvrecord.append(j-2)
427 | csvrecord.append(str(filelist1[j]))
428 | csvrecord.append('translation')
429 | csvrecord.append('x:y')
430 | csvrecord.append(':'.join(str(x) for x in params))
431 | csvrecord.append(model.threshold)
432 |
433 | csvrecord.append(new_covered)
434 | csvrecord.append(new_total)
435 | csvrecord.append(c1)
436 | csvrecord.append(t1)
437 | csvrecord.append(covered_detail1)
438 | csvrecord.append(c2)
439 | csvrecord.append(t2)
440 | csvrecord.append(covered_detail2)
441 | csvrecord.append(c3)
442 | csvrecord.append(t3)
443 | csvrecord.append(covered_detail3)
444 |
445 |
446 | csvrecord.append(result)
447 | csvrecord.append(label1[j][1])
448 | #print(csvrecord)
449 | print(csvrecord[:5])
450 | writer.writerow(csvrecord)
451 | model.hard_reset()
452 |
453 | print("translation done")
454 |
455 | #Scale
456 | input_images = xrange(1, 1001)
457 | for p in xrange(1, 11):
458 | params = [p*0.5+1, p*0.5+1]
459 |
460 | for i in input_images:
461 | j = i * 5
462 | csvrecord = []
463 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-2]))
464 | seed_image = image_scale(seed_image,map(lambda x:x+0, params))
465 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,None,None)
466 |
467 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-1]))
468 | seed_image = image_scale(seed_image,map(lambda x:x+0.1, params))
469 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,None,None)
470 |
471 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j]))
472 | seed_image = image_scale(seed_image,map(lambda x:x+0.2, params))
473 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,None,None)
474 | filename, ext = os.path.splitext(str(filelist1[j]))
475 |
476 |
477 | if label1[j][0] != filename:
478 | print(filename + " not found in the label file")
479 | continue
480 |
481 |
482 |
483 | tempk = []
484 | for k in d1.keys():
485 | if d1[k]:
486 | tempk.append(k)
487 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
488 | covered_detail1 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
489 |
490 | tempk = []
491 | for k in d2.keys():
492 | if d2[k]:
493 | tempk.append(k)
494 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
495 | covered_detail2 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
496 |
497 | tempk = []
498 | for k in d3.keys():
499 | if d3[k]:
500 | tempk.append(k)
501 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
502 | covered_detail3 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
503 |
504 |
505 |
506 |
507 | csvrecord.append(j-2)
508 | csvrecord.append(str(filelist1[j]))
509 | csvrecord.append('scale')
510 | csvrecord.append('x:y')
511 | csvrecord.append(':'.join(str(x) for x in params))
512 | csvrecord.append(model.threshold)
513 |
514 | csvrecord.append(new_covered)
515 | csvrecord.append(new_total)
516 | csvrecord.append(c1)
517 | csvrecord.append(t1)
518 | csvrecord.append(covered_detail1)
519 | csvrecord.append(c2)
520 | csvrecord.append(t2)
521 | csvrecord.append(covered_detail2)
522 | csvrecord.append(c3)
523 | csvrecord.append(t3)
524 | csvrecord.append(covered_detail3)
525 |
526 |
527 | csvrecord.append(result)
528 | csvrecord.append(label1[j][1])
529 | #print(csvrecord)
530 | print(csvrecord[:5])
531 | writer.writerow(csvrecord)
532 | model.hard_reset()
533 |
534 | print("scale done")
535 |
536 |
537 | #Shear
538 | input_images = xrange(1, 1001)
539 | for p in xrange(1, 11):
540 | params = 0.1*p
541 | for i in input_images:
542 | j = i * 5
543 | csvrecord = []
544 |
545 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-2]))
546 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_shear,params)
547 |
548 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-1]))
549 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_shear,params)
550 |
551 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j]))
552 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_shear,params)
553 | filename, ext = os.path.splitext(str(filelist1[j]))
554 |
555 |
556 | if label1[j][0] != filename:
557 | print(filename + " not found in the label file")
558 | continue
559 |
560 |
561 |
562 | tempk = []
563 | for k in d1.keys():
564 | if d1[k]:
565 | tempk.append(k)
566 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
567 | covered_detail1 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
568 |
569 | tempk = []
570 | for k in d2.keys():
571 | if d2[k]:
572 | tempk.append(k)
573 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
574 | covered_detail2 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
575 |
576 | tempk = []
577 | for k in d3.keys():
578 | if d3[k]:
579 | tempk.append(k)
580 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
581 | covered_detail3 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
582 |
583 | csvrecord.append(j-2)
584 | csvrecord.append(str(filelist1[j]))
585 | csvrecord.append('shear')
586 | csvrecord.append('factor')
587 | csvrecord.append(params)
588 | csvrecord.append(model.threshold)
589 |
590 | csvrecord.append(new_covered)
591 | csvrecord.append(new_total)
592 | csvrecord.append(c1)
593 | csvrecord.append(t1)
594 | csvrecord.append(covered_detail1)
595 | csvrecord.append(c2)
596 | csvrecord.append(t2)
597 | csvrecord.append(covered_detail2)
598 | csvrecord.append(c3)
599 | csvrecord.append(t3)
600 | csvrecord.append(covered_detail3)
601 |
602 |
603 | csvrecord.append(result)
604 | csvrecord.append(label1[j][1])
605 | #print(csvrecord)
606 | print(csvrecord[:5])
607 | writer.writerow(csvrecord)
608 | model.hard_reset()
609 | print("sheer done")
610 |
611 |
612 | #Rotation
613 | input_images = xrange(1, 1001)
614 | for p in xrange(1, 11):
615 | params = p*3
616 | for i in input_images:
617 | j = i * 5
618 | csvrecord = []
619 |
620 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-2]))
621 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_rotation,params)
622 |
623 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-1]))
624 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_rotation,params)
625 |
626 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j]))
627 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_rotation,params)
628 | filename, ext = os.path.splitext(str(filelist1[j]))
629 |
630 |
631 | if label1[j][0] != filename:
632 | print(filename + " not found in the label file")
633 | continue
634 |
635 |
636 |
637 | tempk = []
638 | for k in d1.keys():
639 | if d1[k]:
640 | tempk.append(k)
641 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
642 | covered_detail1 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
643 |
644 | tempk = []
645 | for k in d2.keys():
646 | if d2[k]:
647 | tempk.append(k)
648 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
649 | covered_detail2 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
650 |
651 | tempk = []
652 | for k in d3.keys():
653 | if d3[k]:
654 | tempk.append(k)
655 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
656 | covered_detail3 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
657 |
658 | csvrecord.append(j-2)
659 | csvrecord.append(str(filelist1[j]))
660 | csvrecord.append('rotation')
661 | csvrecord.append('angle')
662 | csvrecord.append(params)
663 | csvrecord.append(model.threshold)
664 |
665 | csvrecord.append(new_covered)
666 | csvrecord.append(new_total)
667 | csvrecord.append(c1)
668 | csvrecord.append(t1)
669 | csvrecord.append(covered_detail1)
670 | csvrecord.append(c2)
671 | csvrecord.append(t2)
672 | csvrecord.append(covered_detail2)
673 | csvrecord.append(c3)
674 | csvrecord.append(t3)
675 | csvrecord.append(covered_detail3)
676 |
677 |
678 | csvrecord.append(result)
679 | csvrecord.append(label1[j][1])
680 | #print(csvrecord)
681 | print(csvrecord[:5])
682 | writer.writerow(csvrecord)
683 | model.hard_reset()
684 |
685 | print("rotation done")
686 |
687 |
688 | #Contrast
689 | input_images = xrange(1, 1001)
690 | for p in xrange(1, 11):
691 | params = 1 + p*0.2
692 | for i in input_images:
693 | j = i * 5
694 | csvrecord = []
695 |
696 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-2]))
697 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_contrast,params)
698 |
699 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-1]))
700 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_contrast,params)
701 |
702 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j]))
703 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_contrast,params)
704 | filename, ext = os.path.splitext(str(filelist1[j]))
705 |
706 |
707 | if label1[j][0] != filename:
708 | print(filename + " not found in the label file")
709 | continue
710 |
711 |
712 |
713 | tempk = []
714 | for k in d1.keys():
715 | if d1[k]:
716 | tempk.append(k)
717 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
718 | covered_detail1 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
719 |
720 | tempk = []
721 | for k in d2.keys():
722 | if d2[k]:
723 | tempk.append(k)
724 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
725 | covered_detail2 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
726 |
727 | tempk = []
728 | for k in d3.keys():
729 | if d3[k]:
730 | tempk.append(k)
731 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
732 | covered_detail3 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
733 |
734 | csvrecord.append(j-2)
735 | csvrecord.append(str(filelist1[j]))
736 | csvrecord.append('contrast')
737 | csvrecord.append('gain')
738 | csvrecord.append(params)
739 | csvrecord.append(model.threshold)
740 |
741 | csvrecord.append(new_covered)
742 | csvrecord.append(new_total)
743 | csvrecord.append(c1)
744 | csvrecord.append(t1)
745 | csvrecord.append(covered_detail1)
746 | csvrecord.append(c2)
747 | csvrecord.append(t2)
748 | csvrecord.append(covered_detail2)
749 | csvrecord.append(c3)
750 | csvrecord.append(t3)
751 | csvrecord.append(covered_detail3)
752 |
753 |
754 | csvrecord.append(result)
755 | csvrecord.append(label1[j][1])
756 | #print(csvrecord)
757 | print(csvrecord[:5])
758 | writer.writerow(csvrecord)
759 | model.hard_reset()
760 |
761 | print("contrast done")
762 |
763 |
764 |
765 | #Brightness
766 | input_images = xrange(1, 1001)
767 | for p in xrange(1, 11):
768 | params = p * 10
769 | for i in input_images:
770 | j = i * 5
771 | csvrecord = []
772 |
773 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-2]))
774 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_brightness,params)
775 |
776 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-1]))
777 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_brightness,params)
778 |
779 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j]))
780 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_brightness,params)
781 | filename, ext = os.path.splitext(str(filelist1[j]))
782 |
783 |
784 | if label1[j][0] != filename:
785 | print(filename + " not found in the label file")
786 | continue
787 |
788 |
789 |
790 | tempk = []
791 | for k in d1.keys():
792 | if d1[k]:
793 | tempk.append(k)
794 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
795 | covered_detail1 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
796 |
797 | tempk = []
798 | for k in d2.keys():
799 | if d2[k]:
800 | tempk.append(k)
801 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
802 | covered_detail2 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
803 |
804 | tempk = []
805 | for k in d3.keys():
806 | if d3[k]:
807 | tempk.append(k)
808 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
809 | covered_detail3 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
810 |
811 | csvrecord.append(j-2)
812 | csvrecord.append(str(filelist1[j]))
813 | csvrecord.append('brightness')
814 | csvrecord.append('bias')
815 | csvrecord.append(params)
816 | csvrecord.append(model.threshold)
817 |
818 | csvrecord.append(new_covered)
819 | csvrecord.append(new_total)
820 | csvrecord.append(c1)
821 | csvrecord.append(t1)
822 | csvrecord.append(covered_detail1)
823 | csvrecord.append(c2)
824 | csvrecord.append(t2)
825 | csvrecord.append(covered_detail2)
826 | csvrecord.append(c3)
827 | csvrecord.append(t3)
828 | csvrecord.append(covered_detail3)
829 |
830 |
831 | csvrecord.append(result)
832 | csvrecord.append(label1[j][1])
833 | #print(csvrecord)
834 | print(csvrecord[:5])
835 | writer.writerow(csvrecord)
836 | model.hard_reset()
837 | print("brightness done")
838 |
839 |
840 | #blur
841 | input_images = xrange(1, 1001)
842 | for p in xrange(1, 11):
843 | params = p
844 | for i in input_images:
845 | j = i * 5
846 | csvrecord = []
847 |
848 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-2]))
849 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_blur,params)
850 |
851 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j-1]))
852 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_blur,params)
853 |
854 | seed_image = imread(os.path.join(seed_inputs1, filelist1[j]))
855 | new_covered, new_total, result,c1,t1,d1,c2,t2,d2,c3,t3,d3 = model.predict1(seed_image,image_blur,params)
856 | filename, ext = os.path.splitext(str(filelist1[j]))
857 |
858 |
859 | if label1[j][0] != filename:
860 | print(filename + " not found in the label file")
861 | continue
862 |
863 |
864 |
865 | tempk = []
866 | for k in d1.keys():
867 | if d1[k]:
868 | tempk.append(k)
869 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
870 | covered_detail1 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
871 |
872 | tempk = []
873 | for k in d2.keys():
874 | if d2[k]:
875 | tempk.append(k)
876 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
877 | covered_detail2 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
878 |
879 | tempk = []
880 | for k in d3.keys():
881 | if d3[k]:
882 | tempk.append(k)
883 | tempk = sorted(tempk, key=lambda element: (element[0], element[1]))
884 | covered_detail3 = ';'.join("('" + str(x[0]) + "', " + str(x[1]) + ')' for x in tempk).replace(',', ':')
885 |
886 |
887 | param_name = ""
888 | if params == 1:
889 | param_name = "averaging:3:3"
890 | if params == 2:
891 | param_name = "averaging:4:4"
892 | if params == 3:
893 | param_name = "averaging:5:5"
894 | if params == 4:
895 | param_name = "GaussianBlur:3:3"
896 | if params == 5:
897 | param_name = "GaussianBlur:4:4"
898 | if params == 6:
899 | param_name = "GaussianBlur:5:5"
900 | if params == 7:
901 | param_name = "medianBlur:3"
902 | if params == 8:
903 | param_name = "medianBlur:4"
904 | if params == 9:
905 | param_name = "medianBlur:5"
906 | if params == 10:
907 | param_name = "bilateralFilter:9:75:75"
908 |
909 | csvrecord.append(j-2)
910 | csvrecord.append(str(filelist1[j]))
911 | csvrecord.append('blur')
912 | csvrecord.append(param_name)
913 | csvrecord.append('-')
914 | csvrecord.append(model.threshold)
915 |
916 | csvrecord.append(new_covered)
917 | csvrecord.append(new_total)
918 | csvrecord.append(c1)
919 | csvrecord.append(t1)
920 | csvrecord.append(covered_detail1)
921 | csvrecord.append(c2)
922 | csvrecord.append(t2)
923 | csvrecord.append(covered_detail2)
924 | csvrecord.append(c3)
925 | csvrecord.append(t3)
926 | csvrecord.append(covered_detail3)
927 |
928 |
929 | csvrecord.append(result)
930 | csvrecord.append(label1[j][1])
931 | #print(csvrecord)
932 | print(csvrecord[:5])
933 | writer.writerow(csvrecord)
934 | model.hard_reset()
935 | print("all done")
936 |
937 |
938 |
939 | if __name__ == "__main__":
940 |
941 | parser = argparse.ArgumentParser()
942 | parser.add_argument('--dataset', type=str, default='/media/yuchi/345F-2D0F/',
943 | help='path for dataset')
944 | args = parser.parse_args()
945 | rambo_testgen_coverage(args.dataset)
--------------------------------------------------------------------------------