forked from rendezvue/PyDope
-
Notifications
You must be signed in to change notification settings - Fork 0
/
train.py
1424 lines (1153 loc) · 47.3 KB
/
train.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#!/usr/bin/env python3
# Copyright (c) 2018 NVIDIA Corporation. All rights reserved.
# This work is licensed under a Creative Commons Attribution-NonCommercial-ShareAlike 4.0 International License.
# https://creativecommons.org/licenses/by-nc-sa/4.0/legalcode
"""
Revision Part for training at server 33
Feb 2021
Jiwon Gim
The original network uses 8 gpus for training. Currently Pytorch doesn't support RTX 3080. I used only one gpu (RTX 2060).
That means DataParallel (Pytorch module for using several gpus to accelerate calculation) should be turned off.
Those changes are reflected on line 99, line 1320.
The original code assigning img_size is not appropriate. It was revisied. (line 453)
"""
from __future__ import print_function
######################################################
"""
REQUIREMENTS:
simplejson==3.16.0
numpy==1.14.1
opencv_python==3.4.3.18
horovod==0.13.5
photutils==0.5
scipy==1.1.0
torch==0.4.0
pyquaternion==0.9.2
tqdm==4.25.0
pyrr==0.9.2
Pillow==5.2.0
torchvision==0.2.1
PyYAML==3.13
"""
######################################################
"""
HOW TO TRAIN DOPE
This is the DOPE training code.
It is provided as a convenience for researchers, but it is otherwise unsupported.
Please refer to `python3 train.py --help` for specific details about the
training code.
If you download the FAT dataset
(https://research.nvidia.com/publication/2018-06_Falling-Things)
you can train a YCB object DOPE detector as follows:
```
python3 train.py --data path/to/FAT --object soup --outf soup
--gpuids 0 1 2 3 4 5 6 7
```
This will create a folder called `train_soup` where the weights will be saved
after each epoch. It will use the 8 gpus using pytorch data parallel.
"""
import argparse
import configparser as ConfigParser
#import configparser
import random
import numpy as np
import torch
import torch.nn as nn
import torch.nn.parallel
import torch.optim as optim
import torch.utils.data
import torchvision.transforms as transforms
from torch.autograd import Variable
import torch.utils.data as data
import torchvision.models as models
import datetime
import json
import glob
import os
from PIL import Image
from PIL import ImageDraw
from PIL import ImageEnhance
from math import acos
from math import sqrt
from math import pi
from os.path import exists
import cv2
import colorsys,math
import warnings
warnings.filterwarnings("ignore")
# os.environ["CUDA_VISIBLE_DEVICES"]="0,1,2,3,4,5,6,7"
os.environ["CUDA_VISIBLE_DEVICES"]="1" # for the server 33, use RTX2060 (GPU id = 1).
# Currently, Pytorch doesnt' support RTX3080.
##################################################
# NEURAL NETWORK MODEL
##################################################
class DopeNetwork(nn.Module):
def __init__(
self,
pretrained=False,
numBeliefMap=9,
numAffinity=16,
stop_at_stage=6 # number of stages to process (if less than total number of stages)
):
super(DopeNetwork, self).__init__()
self.stop_at_stage = stop_at_stage
if pretrained is False:
print("Training network without imagenet weights.")
else:
print("Training network pretrained on imagenet.")
vgg_full = models.vgg19(pretrained=pretrained).features
self.vgg = nn.Sequential()
for i_layer in range(24):
self.vgg.add_module(str(i_layer), vgg_full[i_layer])
# Add some layers
i_layer = 23
self.vgg.add_module(str(i_layer), nn.Conv2d(512, 256, kernel_size=3, stride=1, padding=1))
self.vgg.add_module(str(i_layer+1), nn.ReLU(inplace=True))
self.vgg.add_module(str(i_layer+2), nn.Conv2d(256, 128, kernel_size=3, stride=1, padding=1))
self.vgg.add_module(str(i_layer+3), nn.ReLU(inplace=True))
print('---Belief------------------------------------------------')
# _2 are the belief map stages
self.m1_2 = DopeNetwork.create_stage(128, numBeliefMap, True)
self.m2_2 = DopeNetwork.create_stage(128 + numBeliefMap + numAffinity,
numBeliefMap, False)
self.m3_2 = DopeNetwork.create_stage(128 + numBeliefMap + numAffinity,
numBeliefMap, False)
self.m4_2 = DopeNetwork.create_stage(128 + numBeliefMap + numAffinity,
numBeliefMap, False)
self.m5_2 = DopeNetwork.create_stage(128 + numBeliefMap + numAffinity,
numBeliefMap, False)
self.m6_2 = DopeNetwork.create_stage(128 + numBeliefMap + numAffinity,
numBeliefMap, False)
print('---Affinity----------------------------------------------')
# _1 are the affinity map stages
self.m1_1 = DopeNetwork.create_stage(128, numAffinity, True)
self.m2_1 = DopeNetwork.create_stage(128 + numBeliefMap + numAffinity,
numAffinity, False)
self.m3_1 = DopeNetwork.create_stage(128 + numBeliefMap + numAffinity,
numAffinity, False)
self.m4_1 = DopeNetwork.create_stage(128 + numBeliefMap + numAffinity,
numAffinity, False)
self.m5_1 = DopeNetwork.create_stage(128 + numBeliefMap + numAffinity,
numAffinity, False)
self.m6_1 = DopeNetwork.create_stage(128 + numBeliefMap + numAffinity,
numAffinity, False)
def forward(self, x):
'''Runs inference on the neural network'''
out1 = self.vgg(x)
out1_2 = self.m1_2(out1)
out1_1 = self.m1_1(out1)
if self.stop_at_stage == 1:
return [out1_2],\
[out1_1]
out2 = torch.cat([out1_2, out1_1, out1], 1)
out2_2 = self.m2_2(out2)
out2_1 = self.m2_1(out2)
if self.stop_at_stage == 2:
return [out1_2, out2_2],\
[out1_1, out2_1]
out3 = torch.cat([out2_2, out2_1, out1], 1)
out3_2 = self.m3_2(out3)
out3_1 = self.m3_1(out3)
if self.stop_at_stage == 3:
return [out1_2, out2_2, out3_2],\
[out1_1, out2_1, out3_1]
out4 = torch.cat([out3_2, out3_1, out1], 1)
out4_2 = self.m4_2(out4)
out4_1 = self.m4_1(out4)
if self.stop_at_stage == 4:
return [out1_2, out2_2, out3_2, out4_2],\
[out1_1, out2_1, out3_1, out4_1]
out5 = torch.cat([out4_2, out4_1, out1], 1)
out5_2 = self.m5_2(out5)
out5_1 = self.m5_1(out5)
if self.stop_at_stage == 5:
return [out1_2, out2_2, out3_2, out4_2, out5_2],\
[out1_1, out2_1, out3_1, out4_1, out5_1]
out6 = torch.cat([out5_2, out5_1, out1], 1)
out6_2 = self.m6_2(out6)
out6_1 = self.m6_1(out6)
return [out1_2, out2_2, out3_2, out4_2, out5_2, out6_2],\
[out1_1, out2_1, out3_1, out4_1, out5_1, out6_1]
@staticmethod
def create_stage(in_channels, out_channels, first=False):
'''Create the neural network layers for a single stage.'''
model = nn.Sequential()
mid_channels = 128
if first:
padding = 1
kernel = 3
count = 6
final_channels = 512
else:
padding = 3
kernel = 7
count = 10
final_channels = mid_channels
# First convolution
model.add_module("0",
nn.Conv2d(
in_channels,
mid_channels,
kernel_size=kernel,
stride=1,
padding=padding)
)
# Middle convolutions
i = 1
while i < count - 1:
model.add_module(str(i), nn.ReLU(inplace=True))
i += 1
model.add_module(str(i),
nn.Conv2d(
mid_channels,
mid_channels,
kernel_size=kernel,
stride=1,
padding=padding))
i += 1
# Penultimate convolution
model.add_module(str(i), nn.ReLU(inplace=True))
i += 1
model.add_module(str(i), nn.Conv2d(mid_channels, final_channels, kernel_size=1, stride=1))
i += 1
# Last convolution
model.add_module(str(i), nn.ReLU(inplace=True))
i += 1
model.add_module(str(i), nn.Conv2d(final_channels, out_channels, kernel_size=1, stride=1))
i += 1
return model
##################################################
# UTILS CODE FOR LOADING THE DATA
##################################################
def default_loader(path):
return Image.open(path).convert('RGB')
def loadjson(path, objectsofinterest, img):
"""
Loads the data from a json file.
If there are no objects of interest, then load all the objects.
"""
with open(path) as data_file:
data = json.load(data_file)
# print (path)
pointsBelief = []
boxes = []
points_keypoints_3d = []
points_keypoints_2d = []
pointsBoxes = []
poses = []
centroids = []
translations = []
rotations = []
points = []
for i_line in range(len(data['objects'])):
info = data['objects'][i_line]
if not objectsofinterest is None and \
not objectsofinterest in info['class'].lower():
continue
box = info['bounding_box']
boxToAdd = []
boxToAdd.append(float(box['top_left'][0]))
boxToAdd.append(float(box['top_left'][1]))
boxToAdd.append(float(box["bottom_right"][0]))
boxToAdd.append(float(box['bottom_right'][1]))
boxes.append(boxToAdd)
boxpoint = [(boxToAdd[0],boxToAdd[1]),(boxToAdd[0],boxToAdd[3]),
(boxToAdd[2],boxToAdd[1]),(boxToAdd[2],boxToAdd[3])]
pointsBoxes.append(boxpoint)
# 3dbbox with belief maps
points3d = []
pointdata = info['projected_cuboid']
for p in pointdata:
points3d.append((p[0],p[1]))
# Get the centroids
pcenter = info['projected_cuboid_centroid']
points3d.append ((pcenter[0],pcenter[1]))
pointsBelief.append(points3d)
points.append (points3d + [(pcenter[0],pcenter[1])])
centroids.append((pcenter[0],pcenter[1]))
# load translations
location = info['location']
translations.append([location[0],location[1],location[2]])
# quaternion
rot = info["quaternion_xyzw"]
rotations.append(rot)
return {
"pointsBelief":pointsBelief,
"rotations":rotations,
"translations":translations,
"centroids":centroids,
"points":points,
"keypoints_2d":points_keypoints_2d,
"keypoints_3d":points_keypoints_3d,
}
def loadimages(root):
"""
Find all the images in the path and folders, return them in imgs.
"""
imgs = []
def add_json_files(path,):
for imgpath in glob.glob(path+"/*.png"):
if exists(imgpath) and exists(imgpath.replace('png',"json")):
imgs.append((imgpath,imgpath.replace(path,"").replace("/",""),
imgpath.replace('png',"json")))
for imgpath in glob.glob(path+"/*.jpg"):
if exists(imgpath) and exists(imgpath.replace('jpg',"json")):
imgs.append((imgpath,imgpath.replace(path,"").replace("/",""),
imgpath.replace('jpg',"json")))
def explore(path):
if not os.path.isdir(path):
return
folders = [os.path.join(path, o) for o in os.listdir(path)
if os.path.isdir(os.path.join(path,o))]
if len(folders)>0:
for path_entry in folders:
explore(path_entry)
else:
add_json_files(path)
explore(root)
return imgs
class MultipleVertexJson(data.Dataset):
"""
Dataloader for the data generated by NDDS (https://github.com/NVIDIA/Dataset_Synthesizer).
This is the same data as the data used in FAT.
"""
def __init__(self, root,transform=None, nb_vertex = 8,
keep_orientation = True,
normal = None, test=False,
target_transform = None,
loader = default_loader,
objectsofinterest = "",
img_size = 400,
save = False,
noise = 2,
data_size = None,
sigma = 16,
random_translation = (25.0,25.0),
random_rotation = 15.0,
):
###################
self.objectsofinterest = objectsofinterest
self.img_size = img_size
self.loader = loader
self.transform = transform
self.target_transform = target_transform
self.root = root
self.imgs = []
self.test = test
self.normal = normal
self.keep_orientation = keep_orientation
self.save = save
self.noise = noise
self.data_size = data_size
self.sigma = sigma
self.random_translation = random_translation
self.random_rotation = random_rotation
def load_data(path):
'''Recursively load the data. This is useful to load all of the FAT dataset.'''
imgs = loadimages(path)
# Check all the folders in path
for name in os.listdir(str(path)):
imgs += loadimages(path +"/"+name)
return imgs
self.imgs = load_data(root)
# Shuffle the data, this is useful when we want to use a subset.
np.random.shuffle(self.imgs)
def __len__(self):
# When limiting the number of data
if not self.data_size is None:
return int(self.data_size)
return len(self.imgs)
def __getitem__(self, index):
"""
Depending on how the data loader is configured,
this will return the debug info with the cuboid drawn on it,
this happens when self.save is set to true.
Otherwise, during training this function returns the
belief maps and affinity fields and image as tensors.
"""
path, name, txt = self.imgs[index]
img = self.loader(path)
img_size = (self.img_size, self.img_size)
# img_size = img.size
# img_size = (400,400)
loader = loadjson
data = loader(txt, self.objectsofinterest,img)
pointsBelief = data['pointsBelief']
objects_centroid = data['centroids']
points_all = data['points']
points_keypoints = data['keypoints_2d']
translations = torch.from_numpy(np.array(
data['translations'])).float()
rotations = torch.from_numpy(np.array(
data['rotations'])).float()
if len(points_all) == 0:
points_all = torch.zeros(1, 10, 2).double()
# self.save == true assumes there is only
# one object instance in the scene.
if translations.size()[0] > 1:
translations = translations[0].unsqueeze(0)
rotations = rotations[0].unsqueeze(0)
# If there are no objects, still need to return similar shape array
if len(translations) == 0:
translations = torch.zeros(1,3).float()
rotations = torch.zeros(1,4).float()
# Camera intrinsics
path_cam = path.replace(name,'_camera_settings.json')
with open(path_cam) as data_file:
data = json.load(data_file)
# Assumes one camera
cam = data['camera_settings'][0]['intrinsic_settings']
matrix_camera = np.zeros((3,3))
matrix_camera[0,0] = cam['fx']
matrix_camera[1,1] = cam['fy']
matrix_camera[0,2] = cam['cx']
matrix_camera[1,2] = cam['cy']
matrix_camera[2,2] = 1
# Load the cuboid sizes
path_set = path.replace(name,'_object_settings.json')
with open(path_set) as data_file:
data = json.load(data_file)
cuboid = torch.zeros(1)
if self.objectsofinterest is None:
cuboid = np.array(data['exported_objects'][0]['cuboid_dimensions'])
else:
for info in data["exported_objects"]:
if self.objectsofinterest in info['class']:
cuboid = np.array(info['cuboid_dimensions'])
img_original = img.copy()
def Reproject(points,tm, rm):
"""
Reprojection of points when rotating the image
"""
proj_cuboid = np.array(points)
rmat = np.identity(3)
rmat[0:2] = rm
tmat = np.identity(3)
tmat[0:2] = tm
new_cuboid = np.matmul(
rmat, np.vstack((proj_cuboid.T, np.ones(len(points)))))
new_cuboid = np.matmul(tmat, new_cuboid)
new_cuboid = new_cuboid[0:2].T
return new_cuboid
# Random image manipulation, rotation and translation with zero padding
dx = round(np.random.normal(0, 2) * float(self.random_translation[0]))
dy = round(np.random.normal(0, 2) * float(self.random_translation[1]))
angle = round(np.random.normal(0, 1) * float(self.random_rotation))
tm = np.float32([[1, 0, dx], [0, 1, dy]])
rm = cv2.getRotationMatrix2D(
(img.size[0]/2, img.size[1]/2), angle, 1)
for i_objects in range(len(pointsBelief)):
points = pointsBelief[i_objects]
new_cuboid = Reproject(points, tm, rm)
pointsBelief[i_objects] = new_cuboid.tolist()
objects_centroid[i_objects] = tuple(new_cuboid.tolist()[-1])
pointsBelief[i_objects] = list(map(tuple, pointsBelief[i_objects]))
for i_objects in range(len(points_keypoints)):
points = points_keypoints[i_objects]
new_cuboid = Reproject(points, tm, rm)
points_keypoints[i_objects] = new_cuboid.tolist()
points_keypoints[i_objects] = list(map(tuple, points_keypoints[i_objects]))
image_r = cv2.warpAffine(np.array(img), rm, img.size)
result = cv2.warpAffine(image_r, tm, img.size)
img = Image.fromarray(result)
# Note: All point coordinates are in the image space, e.g., pixel value.
# This is used when we do saving --- helpful for debugging
if self.save or self.test:
# Use the save to debug the data
if self.test:
draw = ImageDraw.Draw(img_original)
else:
draw = ImageDraw.Draw(img)
# PIL drawing functions, here for sharing draw
def DrawKeypoints(points):
for key in points:
DrawDot(key,(12, 115, 170),7)
def DrawLine(point1, point2, lineColor, lineWidth):
if not point1 is None and not point2 is None:
draw.line([point1,point2],fill=lineColor,width=lineWidth)
def DrawDot(point, pointColor, pointRadius):
if not point is None:
xy = [point[0]-pointRadius, point[1]-pointRadius, point[0]+pointRadius, point[1]+pointRadius]
draw.ellipse(xy, fill=pointColor, outline=pointColor)
def DrawCube(points, which_color = 0, color = None):
'''Draw cube with a thick solid line across the front top edge.'''
lineWidthForDrawing = 2
lineColor1 = (255, 215, 0) # yellow-ish
lineColor2 = (12, 115, 170) # blue-ish
lineColor3 = (45, 195, 35) # green-ish
if which_color == 3:
lineColor = lineColor3
else:
lineColor = lineColor1
if not color is None:
lineColor = color
# draw front
DrawLine(points[0], points[1], lineColor, 8) #lineWidthForDrawing)
DrawLine(points[1], points[2], lineColor, lineWidthForDrawing)
DrawLine(points[3], points[2], lineColor, lineWidthForDrawing)
DrawLine(points[3], points[0], lineColor, lineWidthForDrawing)
# draw back
DrawLine(points[4], points[5], lineColor, lineWidthForDrawing)
DrawLine(points[6], points[5], lineColor, lineWidthForDrawing)
DrawLine(points[6], points[7], lineColor, lineWidthForDrawing)
DrawLine(points[4], points[7], lineColor, lineWidthForDrawing)
# draw sides
DrawLine(points[0], points[4], lineColor, lineWidthForDrawing)
DrawLine(points[7], points[3], lineColor, lineWidthForDrawing)
DrawLine(points[5], points[1], lineColor, lineWidthForDrawing)
DrawLine(points[2], points[6], lineColor, lineWidthForDrawing)
# draw dots
DrawDot(points[0], pointColor=(255,255,255), pointRadius = 3)
DrawDot(points[1], pointColor=(0,0,0), pointRadius = 3)
# Draw all the found objects.
for points_belief_objects in pointsBelief:
DrawCube(points_belief_objects)
for keypoint in points_keypoints:
DrawKeypoints(keypoint)
img = self.transform(img)
return {
"img":img,
"translations":translations,
"rot_quaternions":rotations,
'pointsBelief':np.array(points_all[0]),
'matrix_camera':matrix_camera,
'img_original': np.array(img_original),
'cuboid': cuboid,
'file_name':name,
}
# Create the belief map
beliefsImg = CreateBeliefMap(
img,
pointsBelief=pointsBelief,
nbpoints = 9,
sigma = self.sigma)
# Create the image maps for belief
transform = transforms.Compose([transforms.Resize(min(img_size))])
totensor = transforms.Compose([transforms.ToTensor()])
for j in range(len(beliefsImg)):
beliefsImg[j] = self.target_transform(beliefsImg[j])
# beliefsImg[j].save('{}.png'.format(j))
beliefsImg[j] = totensor(beliefsImg[j])
beliefs = torch.zeros((len(beliefsImg),beliefsImg[0].size(1),beliefsImg[0].size(2)))
for j in range(len(beliefsImg)):
beliefs[j] = beliefsImg[j][0]
# Create affinity maps
scale = 8
if min (img.size) / 8.0 != min (img_size)/8.0:
# print (scale)
scale = min (img.size)/(min (img_size)/8.0)
affinities = GenerateMapAffinity(img,8,pointsBelief,objects_centroid,scale)
img = self.transform(img)
# Transform the images for training input
w_crop = np.random.randint(0, img.size[0] - img_size[0]+1)
h_crop = np.random.randint(0, img.size[1] - img_size[1]+1)
transform = transforms.Compose([transforms.Resize(min(img_size))])
totensor = transforms.Compose([transforms.ToTensor()])
if not self.normal is None:
normalize = transforms.Compose([transforms.Normalize
((self.normal[0],self.normal[0],self.normal[0]),
(self.normal[1],self.normal[1],self.normal[1])),
AddNoise(self.noise)])
else:
normalize = transforms.Compose([AddNoise(0.0001)])
img = crop(img,h_crop,w_crop,img_size[1],img_size[0])
img = totensor(img)
img = normalize(img)
w_crop = int(w_crop/8)
h_crop = int(h_crop/8)
affinities = affinities[:,h_crop:h_crop+int(img_size[1]/8),w_crop:w_crop+int(img_size[0]/8)]
beliefs = beliefs[:,h_crop:h_crop+int(img_size[1]/8),w_crop:w_crop+int(img_size[0]/8)]
if affinities.size()[1] == 49 and not self.test:
affinities = torch.cat([affinities,torch.zeros(16,1,50)],dim=1)
if affinities.size()[2] == 49 and not self.test:
affinities = torch.cat([affinities,torch.zeros(16,50,1)],dim=2)
return {
'img':img,
"affinities":affinities,
'beliefs':beliefs,
}
"""
Some simple vector math functions to find the angle
between two points, used by affinity fields.
"""
def length(v):
return sqrt(v[0]**2+v[1]**2)
def dot_product(v,w):
return v[0]*w[0]+v[1]*w[1]
def normalize(v):
norm=np.linalg.norm(v, ord=1)
if norm==0:
norm=np.finfo(v.dtype).eps
return v/norm
def determinant(v,w):
return v[0]*w[1]-v[1]*w[0]
def inner_angle(v,w):
cosx=dot_product(v,w)/(length(v)*length(w))
rad=acos(cosx) # in radians
return rad*180/pi # returns degrees
def py_ang(A, B=(1,0)):
inner=inner_angle(A,B)
det = determinant(A,B)
if det<0: #this is a property of the det. If the det < 0 then B is clockwise of A
return inner
else: # if the det > 0 then A is immediately clockwise of B
return 360-inner
def GenerateMapAffinity(img,nb_vertex,pointsInterest,objects_centroid,scale):
"""
Function to create the affinity maps,
e.g., vector maps pointing toward the object center.
Args:
img: PIL image
nb_vertex: (int) number of points
pointsInterest: list of points
objects_centroid: (x,y) centroids for the obects
scale: (float) by how much you need to scale down the image
return:
return a list of tensors for each point except centroid point
"""
# Apply the downscale right now, so the vectors are correct.
img_affinity = Image.new(img.mode, (int(img.size[0]/scale),int(img.size[1]/scale)), "black")
# Create the empty tensors
totensor = transforms.Compose([transforms.ToTensor()])
affinities = []
for i_points in range(nb_vertex):
affinities.append(torch.zeros(2,int(img.size[1]/scale),int(img.size[0]/scale)))
for i_pointsImage in range(len(pointsInterest)):
pointsImage = pointsInterest[i_pointsImage]
center = objects_centroid[i_pointsImage]
for i_points in range(nb_vertex):
point = pointsImage[i_points]
affinity_pair, img_affinity = getAfinityCenter(int(img.size[0]/scale),
int(img.size[1]/scale),
tuple((np.array(pointsImage[i_points])/scale).tolist()),
tuple((np.array(center)/scale).tolist()),
img_affinity = img_affinity, radius=1)
affinities[i_points] = (affinities[i_points] + affinity_pair)/2
# Normalizing
v = affinities[i_points].numpy()
xvec = v[0]
yvec = v[1]
norms = np.sqrt(xvec * xvec + yvec * yvec)
nonzero = norms > 0
xvec[nonzero]/=norms[nonzero]
yvec[nonzero]/=norms[nonzero]
affinities[i_points] = torch.from_numpy(np.concatenate([[xvec],[yvec]]))
affinities = torch.cat(affinities,0)
return affinities
def getAfinityCenter(width, height, point, center, radius=7, img_affinity=None):
"""
Function to create the affinity maps,
e.g., vector maps pointing toward the object center.
Args:
width: image wight
height: image height
point: (x,y)
center: (x,y)
radius: pixel radius
img_affinity: tensor to add to
return:
return a tensor
"""
tensor = torch.zeros(2,height,width).float()
# Create the canvas for the affinity output
imgAffinity = Image.new("RGB", (width,height), "black")
totensor = transforms.Compose([transforms.ToTensor()])
draw = ImageDraw.Draw(imgAffinity)
r1 = radius
p = point
draw.ellipse((p[0]-r1,p[1]-r1,p[0]+r1,p[1]+r1),(255,255,255))
del draw
# Compute the array to add the affinity
array = (np.array(imgAffinity)/255)[:,:,0]
angle_vector = np.array(center) - np.array(point)
angle_vector = normalize(angle_vector)
affinity = np.concatenate([[array*angle_vector[0]],[array*angle_vector[1]]])
# print (tensor)
if not img_affinity is None:
# Find the angle vector
# print (angle_vector)
if length(angle_vector) >0:
angle=py_ang(angle_vector)
else:
angle = 0
# print(angle)
c = np.array(colorsys.hsv_to_rgb(angle/360,1,1)) * 255
draw = ImageDraw.Draw(img_affinity)
draw.ellipse((p[0]-r1,p[1]-r1,p[0]+r1,p[1]+r1),fill=(int(c[0]),int(c[1]),int(c[2])))
del draw
re = torch.from_numpy(affinity).float() + tensor
return re, img_affinity
def CreateBeliefMap(img,pointsBelief,nbpoints,sigma=16):
"""
Args:
img: image
pointsBelief: list of points in the form of
[nb object, nb points, 2 (x,y)]
nbpoints: (int) number of points, DOPE uses 8 points here
sigma: (int) size of the belief map point
return:
return an array of PIL black and white images representing the
belief maps
"""
beliefsImg = []
sigma = int(sigma)
for numb_point in range(nbpoints):
array = np.zeros(img.size)
out = np.zeros(img.size)
for point in pointsBelief:
p = point[numb_point]
w = int(sigma*2)
if p[0]-w>=0 and p[0]+w<img.size[0] and p[1]-w>=0 and p[1]+w<img.size[1]:
for i in range(int(p[0])-w, int(p[0])+w):
for j in range(int(p[1])-w, int(p[1])+w):
array[i,j] = np.exp(-(((i - p[0])**2 + (j - p[1])**2)/(2*(sigma**2))))
stack = np.stack([array,array,array],axis=0).transpose(2,1,0)
imgBelief = Image.new(img.mode, img.size, "black")
beliefsImg.append(Image.fromarray((stack*255).astype('uint8')))
return beliefsImg
def crop(img, i, j, h, w):
"""
Crop the given PIL.Image.
Args:
img (PIL.Image): Image to be cropped.
i: Upper pixel coordinate.
j: Left pixel coordinate.
h: Height of the cropped image.
w: Width of the cropped image.
Returns:
PIL.Image: Cropped image.
"""
return img.crop((j, i, j + w, i + h))
class AddRandomContrast(object):
"""
Apply some random contrast from PIL
"""
def __init__(self,sigma=0.1):
self.sigma = sigma
def __call__(self, im):
contrast = ImageEnhance.Contrast(im)
im = contrast.enhance( np.random.normal(1,self.sigma) )
return im
class AddRandomBrightness(object):
"""
Apply some random brightness from PIL
"""
def __init__(self,sigma=0.1):
self.sigma = sigma
def __call__(self, im):
bright = ImageEnhance.Brightness(im)
im = bright.enhance( np.random.normal(1,self.sigma) )
return im
class AddNoise(object):
"""
Given mean: (R, G, B) and std: (R, G, B),
will normalize each channel of the torch.*Tensor, i.e.
channel = (channel - mean) / std
"""
def __init__(self,std=0.1):
self.std = std
def __call__(self, tensor):
# TODO: make efficient
# t = torch.FloatTensor(tensor.size()).uniform_(self.min,self.max)
t = torch.FloatTensor(tensor.size()).normal_(0,self.std)
t = tensor.add(t)
t = torch.clamp(t,-1,1) #this is expansive
return t
irange = range
def make_grid(tensor, nrow=8, padding=2,
normalize=False, range=None, scale_each=False, pad_value=0):
"""
Make a grid of images.
Args:
tensor (Tensor or list): 4D mini-batch Tensor of shape (B x C x H x W)
or a list of images all of the same size.
nrow (int, optional): Number of images displayed in each row of the grid.
The Final grid size is (B / nrow, nrow). Default is 8.
padding (int, optional): amount of padding. Default is 2.
normalize (bool, optional): If True, shift the image to the range (0, 1),
by subtracting the minimum and dividing by the maximum pixel value.
range (tuple, optional): tuple (min, max) where min and max are numbers,
then these numbers are used to normalize the image. By default, min and max
are computed from the tensor.
scale_each (bool, optional): If True, scale each image in the batch of
images separately rather than the (min, max) over all images.
pad_value (float, optional): Value for the padded pixels.
"""
if not (torch.is_tensor(tensor) or
(isinstance(tensor, list) and all(torch.is_tensor(t) for t in tensor))):
raise TypeError('tensor or list of tensors expected, got {}'.format(type(tensor)))
# if list of tensors, convert to a 4D mini-batch Tensor
if isinstance(tensor, list):
tensor = torch.stack(tensor, dim=0)
if tensor.dim() == 2: # single image H x W
tensor = tensor.view(1, tensor.size(0), tensor.size(1))
if tensor.dim() == 3: # single image
if tensor.size(0) == 1: # if single-channel, convert to 3-channel
tensor = torch.cat((tensor, tensor, tensor), 0)
tensor = tensor.view(1, tensor.size(0), tensor.size(1), tensor.size(2))
if tensor.dim() == 4 and tensor.size(1) == 1: # single-channel images
tensor = torch.cat((tensor, tensor, tensor), 1)
if normalize == True:
tensor = tensor.clone() # avoid modifying tensor in-place
if range is not None:
assert isinstance(range, tuple), \
"range has to be a tuple (min, max) if specified. min and max are numbers"
def norm_ip(img, min, max):
img.clamp_(min=min, max=max)
img.add_(-min).div_(max - min + 1e-5)
def norm_range(t, range):
if range is not None:
norm_ip(t, range[0], range[1])
else:
norm_ip(t, float(t.min()), float(t.max()))
if scale_each == True:
for t in tensor: # loop over mini-batch dimension
norm_range(t, range)
else:
norm_range(tensor, range)
if tensor.size(0) == 1:
return tensor.squeeze()