refactor
This commit is contained in:
parent
2b23bb9c9e
commit
6e6fb05341
@ -6,7 +6,8 @@ import logging
|
|||||||
from collections import defaultdict
|
from collections import defaultdict
|
||||||
import datetime
|
import datetime
|
||||||
|
|
||||||
from utils.misc import get_iou_matches, get_task_error
|
from utils.iou import get_iou_matches
|
||||||
|
from utils.misc import get_task_error
|
||||||
from utils.kitti import check_conditions, get_category, split_training, parse_ground_truth
|
from utils.kitti import check_conditions, get_category, split_training, parse_ground_truth
|
||||||
from visuals.results import print_results
|
from visuals.results import print_results
|
||||||
|
|
||||||
|
|||||||
@ -7,11 +7,12 @@ import logging
|
|||||||
from collections import defaultdict
|
from collections import defaultdict
|
||||||
import json
|
import json
|
||||||
import datetime
|
import datetime
|
||||||
import torch
|
|
||||||
|
|
||||||
from utils.kitti import get_calibration, split_training, parse_ground_truth
|
from utils.kitti import get_calibration, split_training, parse_ground_truth
|
||||||
from utils.pifpaf import get_network_inputs, preprocess_pif
|
from utils.monoloco import get_monoloco_inputs
|
||||||
from utils.misc import get_iou_matches, append_cluster
|
from utils.pifpaf import preprocess_pif
|
||||||
|
from utils.iou import get_iou_matches
|
||||||
|
from utils.misc import append_cluster
|
||||||
|
|
||||||
|
|
||||||
class PreprocessKitti:
|
class PreprocessKitti:
|
||||||
@ -89,7 +90,7 @@ class PreprocessKitti:
|
|||||||
with open(os.path.join(self.dir_ann, basename + '.png.pifpaf.json'), 'r') as f:
|
with open(os.path.join(self.dir_ann, basename + '.png.pifpaf.json'), 'r') as f:
|
||||||
annotations = json.load(f)
|
annotations = json.load(f)
|
||||||
boxes, keypoints = preprocess_pif(annotations, im_size=(1238, 374))
|
boxes, keypoints = preprocess_pif(annotations, im_size=(1238, 374))
|
||||||
inputs = get_network_inputs(keypoints, kk).tolist()
|
inputs = get_monoloco_inputs(keypoints, kk).tolist()
|
||||||
|
|
||||||
except FileNotFoundError:
|
except FileNotFoundError:
|
||||||
boxes = []
|
boxes = []
|
||||||
@ -130,4 +131,3 @@ class PreprocessKitti:
|
|||||||
else:
|
else:
|
||||||
flag = True
|
flag = True
|
||||||
return phase, flag
|
return phase, flag
|
||||||
|
|
||||||
|
|||||||
@ -8,14 +8,17 @@ import json
|
|||||||
import logging
|
import logging
|
||||||
from collections import defaultdict
|
from collections import defaultdict
|
||||||
import datetime
|
import datetime
|
||||||
|
|
||||||
import numpy as np
|
import numpy as np
|
||||||
|
|
||||||
from nuscenes.nuscenes import NuScenes
|
from nuscenes.nuscenes import NuScenes
|
||||||
from nuscenes.utils import splits
|
from nuscenes.utils import splits
|
||||||
from utils.misc import get_iou_matches, append_cluster
|
from utils.iou import get_iou_matches
|
||||||
|
from utils.misc import append_cluster
|
||||||
from utils.nuscenes import select_categories
|
from utils.nuscenes import select_categories
|
||||||
from utils.camera import project_3d
|
from utils.camera import project_3d
|
||||||
from utils.pifpaf import preprocess_pif, get_network_inputs
|
from utils.pifpaf import preprocess_pif
|
||||||
|
from utils.monoloco import get_monoloco_inputs
|
||||||
|
|
||||||
|
|
||||||
class PreprocessNuscenes:
|
class PreprocessNuscenes:
|
||||||
@ -71,7 +74,8 @@ class PreprocessNuscenes:
|
|||||||
else:
|
else:
|
||||||
time_left = str((end_scene-start_scene)/60 * (len(self.scenes) - ii))[:4]
|
time_left = str((end_scene-start_scene)/60 * (len(self.scenes) - ii))[:4]
|
||||||
|
|
||||||
sys.stdout.write('\r' + 'Elaborating scene {}, remaining time {} minutes'.format(cnt_scenes, time_left) + '\t\n')
|
sys.stdout.write('\r' + 'Elaborating scene {}, remaining time {} minutes'
|
||||||
|
.format(cnt_scenes, time_left) + '\t\n')
|
||||||
start_scene = time.time()
|
start_scene = time.time()
|
||||||
if scene['name'] in self.split_train:
|
if scene['name'] in self.split_train:
|
||||||
phase = 'train'
|
phase = 'train'
|
||||||
@ -124,7 +128,7 @@ class PreprocessNuscenes:
|
|||||||
boxes, keypoints = preprocess_pif(annotations, im_size=(1600, 900))
|
boxes, keypoints = preprocess_pif(annotations, im_size=(1600, 900))
|
||||||
|
|
||||||
if keypoints:
|
if keypoints:
|
||||||
inputs = get_network_inputs(keypoints, kk).tolist()
|
inputs = get_monoloco_inputs(keypoints, kk).tolist()
|
||||||
|
|
||||||
matches = get_iou_matches(boxes, boxes_gt, self.iou_min)
|
matches = get_iou_matches(boxes, boxes_gt, self.iou_min)
|
||||||
for (idx, idx_gt) in matches:
|
for (idx, idx_gt) in matches:
|
||||||
|
|||||||
@ -1,6 +1,4 @@
|
|||||||
|
|
||||||
import numpy as np
|
|
||||||
import torch
|
|
||||||
import torch.nn as nn
|
import torch.nn as nn
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@ -2,8 +2,6 @@
|
|||||||
import json
|
import json
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import torch
|
import torch
|
||||||
import os
|
|
||||||
from collections import defaultdict
|
|
||||||
|
|
||||||
from torch.utils.data import Dataset
|
from torch.utils.data import Dataset
|
||||||
|
|
||||||
|
|||||||
@ -8,7 +8,6 @@ import sys
|
|||||||
import time
|
import time
|
||||||
|
|
||||||
import matplotlib.pyplot as plt
|
import matplotlib.pyplot as plt
|
||||||
|
|
||||||
import torch
|
import torch
|
||||||
import torch.nn as nn
|
import torch.nn as nn
|
||||||
from torch.utils.data import DataLoader
|
from torch.utils.data import DataLoader
|
||||||
@ -16,8 +15,9 @@ from torch.optim import lr_scheduler
|
|||||||
|
|
||||||
from models.datasets import NuScenesDataset
|
from models.datasets import NuScenesDataset
|
||||||
from models.architectures import LinearModel
|
from models.architectures import LinearModel
|
||||||
from utils.misc import set_logger
|
|
||||||
from models.losses import LaplacianLoss
|
from models.losses import LaplacianLoss
|
||||||
|
from utils.logs import set_logger
|
||||||
|
from utils.monoloco import epistemic_variance, laplace_sampling, unnormalize_bi
|
||||||
|
|
||||||
|
|
||||||
class Trainer:
|
class Trainer:
|
||||||
@ -60,12 +60,6 @@ class Trainer:
|
|||||||
self.n_samples = n_samples
|
self.n_samples = n_samples
|
||||||
self.r_seed = r_seed
|
self.r_seed = r_seed
|
||||||
|
|
||||||
from utils.normalize import unnormalize_bi
|
|
||||||
self.unnormalize_bi = unnormalize_bi
|
|
||||||
from utils.misc import epistemic_variance, laplace_sampling
|
|
||||||
self.epistemic_variance = epistemic_variance
|
|
||||||
self.laplace_sampling = laplace_sampling
|
|
||||||
|
|
||||||
# Loss functions and output names
|
# Loss functions and output names
|
||||||
now = datetime.datetime.now()
|
now = datetime.datetime.now()
|
||||||
now_time = now.strftime("%Y%m%d-%H%M")[2:]
|
now_time = now.strftime("%Y%m%d-%H%M")[2:]
|
||||||
@ -86,9 +80,8 @@ class Trainer:
|
|||||||
self.logger.info("Training arguments: \nepochs: {} \nbatch_size: {} \ndropout: {}"
|
self.logger.info("Training arguments: \nepochs: {} \nbatch_size: {} \ndropout: {}"
|
||||||
"\nbaseline: {} \nlearning rate: {} \nscheduler step: {} \nscheduler gamma: {} "
|
"\nbaseline: {} \nlearning rate: {} \nscheduler step: {} \nscheduler gamma: {} "
|
||||||
"\ninput_size: {} \nhidden_size: {} \nn_stages: {} \nr_seed: {}"
|
"\ninput_size: {} \nhidden_size: {} \nn_stages: {} \nr_seed: {}"
|
||||||
"\ninput_file: {}"
|
"\ninput_file: {}", epochs, bs, dropout, baseline, lr, sched_step, sched_gamma, input_size,
|
||||||
.format(epochs, bs, dropout, baseline, lr, sched_step, sched_gamma, input_size,
|
hidden_size, n_stage, r_seed, self.joints)
|
||||||
hidden_size, n_stage, r_seed, self.joints))
|
|
||||||
else:
|
else:
|
||||||
logging.basicConfig(level=logging.INFO)
|
logging.basicConfig(level=logging.INFO)
|
||||||
self.logger = logging.getLogger(__name__)
|
self.logger = logging.getLogger(__name__)
|
||||||
@ -111,7 +104,7 @@ class Trainer:
|
|||||||
for phase in ['train', 'val', 'test']}
|
for phase in ['train', 'val', 'test']}
|
||||||
|
|
||||||
# Define the model
|
# Define the model
|
||||||
self.logger.info('Sizes of the dataset: {}'.format(self.dataset_sizes))
|
self.logger.info('Sizes of the dataset: {}',self.dataset_sizes)
|
||||||
print(">>> creating model")
|
print(">>> creating model")
|
||||||
self.model = LinearModel(input_size=input_size, output_size=self.output_size, linear_size=hidden_size,
|
self.model = LinearModel(input_size=input_size, output_size=self.output_size, linear_size=hidden_size,
|
||||||
p_dropout=dropout, num_stage=self.n_stage)
|
p_dropout=dropout, num_stage=self.n_stage)
|
||||||
@ -259,8 +252,8 @@ class Trainer:
|
|||||||
if self.n_dropout > 0:
|
if self.n_dropout > 0:
|
||||||
for ii in range(self.n_dropout):
|
for ii in range(self.n_dropout):
|
||||||
outputs = self.model(inputs)
|
outputs = self.model(inputs)
|
||||||
outputs = self.unnormalize_bi(outputs)
|
outputs = unnormalize_bi(outputs)
|
||||||
samples = self.laplace_sampling(outputs, self.n_samples)
|
samples = laplace_sampling(outputs, self.n_samples)
|
||||||
total_outputs = torch.cat((total_outputs, samples), 0)
|
total_outputs = torch.cat((total_outputs, samples), 0)
|
||||||
varss = total_outputs.std(0)
|
varss = total_outputs.std(0)
|
||||||
else:
|
else:
|
||||||
@ -273,7 +266,7 @@ class Trainer:
|
|||||||
outputs = self.model(inputs)
|
outputs = self.model(inputs)
|
||||||
|
|
||||||
if not self.baseline:
|
if not self.baseline:
|
||||||
outputs = self.unnormalize_bi(outputs)
|
outputs = unnormalize_bi(outputs)
|
||||||
|
|
||||||
avg_distance = float(self.criterion_eval(outputs[:, 0:1], labels).item())
|
avg_distance = float(self.criterion_eval(outputs[:, 0:1], labels).item())
|
||||||
|
|
||||||
@ -300,7 +293,7 @@ class Trainer:
|
|||||||
# Forward pass on each cluster
|
# Forward pass on each cluster
|
||||||
outputs = self.model(inputs)
|
outputs = self.model(inputs)
|
||||||
if not self.baseline:
|
if not self.baseline:
|
||||||
outputs = self.unnormalize_bi(outputs)
|
outputs = unnormalize_bi(outputs)
|
||||||
|
|
||||||
dic_err[phase][clst] = self.compute_stats(outputs, labels, [0], dic_err[phase][clst], size_eval)
|
dic_err[phase][clst] = self.compute_stats(outputs, labels, [0], dic_err[phase][clst], size_eval)
|
||||||
|
|
||||||
@ -313,7 +306,7 @@ class Trainer:
|
|||||||
if self.save and not load:
|
if self.save and not load:
|
||||||
torch.save(self.model.state_dict(), self.path_model)
|
torch.save(self.model.state_dict(), self.path_model)
|
||||||
print('-'*120)
|
print('-'*120)
|
||||||
self.logger.info("model saved: {} \n".format(self.path_model))
|
self.logger.info("model saved: {} \n", self.path_model)
|
||||||
else:
|
else:
|
||||||
self.logger.info("model not saved\n")
|
self.logger.info("model not saved\n")
|
||||||
|
|
||||||
|
|||||||
@ -1,11 +1,8 @@
|
|||||||
|
|
||||||
import json
|
import json
|
||||||
import os
|
import os
|
||||||
from collections import defaultdict
|
|
||||||
from openpifpaf import show
|
from openpifpaf import show
|
||||||
from visuals.printer import Printer
|
from visuals.printer import Printer
|
||||||
from utils.misc import get_iou_matches, reorder_matches
|
|
||||||
from utils.camera import get_keypoints, pixel_to_camera, xyz_from_distance
|
|
||||||
|
|
||||||
|
|
||||||
def factory_for_gt(im_size, name=None, path_gt=None):
|
def factory_for_gt(im_size, name=None, path_gt=None):
|
||||||
@ -73,68 +70,16 @@ def factory_outputs(args, images_outputs, output_path, pifpaf_outputs, monoloco_
|
|||||||
skeleton_painter.keypoints(ax, keypoint_sets, scores=scores)
|
skeleton_painter.keypoints(ax, keypoint_sets, scores=scores)
|
||||||
|
|
||||||
if 'monoloco' in args.networks:
|
if 'monoloco' in args.networks:
|
||||||
dic_out = monoloco_post_process(monoloco_outputs)
|
|
||||||
if any((xx in args.output_types for xx in ['front', 'bird', 'combined'])):
|
if any((xx in args.output_types for xx in ['front', 'bird', 'combined'])):
|
||||||
epistemic = False
|
epistemic = False
|
||||||
if args.n_dropout > 0:
|
if args.n_dropout > 0:
|
||||||
epistemic = True
|
epistemic = True
|
||||||
|
|
||||||
if dic_out['boxes']: # Only print in case of detections
|
if monoloco_outputs['boxes']: # Only print in case of detections
|
||||||
printer = Printer(images_outputs[1], output_path, dic_out, kk, output_types=args.output_types,
|
printer = Printer(images_outputs[1], output_path, monoloco_outputs, kk, output_types=args.output_types,
|
||||||
show=args.show, z_max=args.z_max, epistemic=epistemic)
|
show=args.show, z_max=args.z_max, epistemic=epistemic)
|
||||||
printer.print()
|
printer.print()
|
||||||
|
|
||||||
if 'json' in args.output_types:
|
if 'json' in args.output_types:
|
||||||
with open(os.path.join(output_path + '.monoloco.json'), 'w') as ff:
|
with open(os.path.join(output_path + '.monoloco.json'), 'w') as ff:
|
||||||
json.dump(monoloco_outputs, ff)
|
json.dump(monoloco_outputs, ff)
|
||||||
|
|
||||||
|
|
||||||
def monoloco_post_process(monoloco_outputs, iou_min=0.25):
|
|
||||||
"""Post process monoloco to output final dictionary with all information for visualizations"""
|
|
||||||
|
|
||||||
outputs, varss, boxes, keypoints, kk, dic_gt = monoloco_outputs[:]
|
|
||||||
dic_out = defaultdict(list)
|
|
||||||
if outputs is None:
|
|
||||||
return dic_out
|
|
||||||
|
|
||||||
if dic_gt:
|
|
||||||
boxes_gt, dds_gt = dic_gt['boxes'], dic_gt['dds']
|
|
||||||
matches = get_iou_matches(boxes, boxes_gt, thresh=iou_min)
|
|
||||||
else:
|
|
||||||
matches = [(idx, idx) for idx, _ in enumerate(boxes)] # Replicate boxes
|
|
||||||
|
|
||||||
matches = reorder_matches(matches, boxes, mode='left_right')
|
|
||||||
uv_shoulders = get_keypoints(keypoints, mode='shoulder')
|
|
||||||
uv_centers = get_keypoints(keypoints, mode='center')
|
|
||||||
xy_centers = pixel_to_camera(uv_centers, kk, 1)
|
|
||||||
|
|
||||||
# Match with ground truth if available
|
|
||||||
for idx, idx_gt in matches:
|
|
||||||
dd_pred = float(outputs[idx][0])
|
|
||||||
ale = float(outputs[idx][1])
|
|
||||||
var_y = float(varss[idx])
|
|
||||||
dd_real = dds_gt[idx_gt] if dic_gt else dd_pred
|
|
||||||
|
|
||||||
kps = keypoints[idx]
|
|
||||||
box = boxes[idx]
|
|
||||||
uu_s, vv_s = uv_shoulders.tolist()[idx][0:2]
|
|
||||||
uu_c, vv_c = uv_centers.tolist()[idx][0:2]
|
|
||||||
uv_shoulder = [round(uu_s), round(vv_s)]
|
|
||||||
uv_center = [round(uu_c), round(vv_c)]
|
|
||||||
xyz_real = xyz_from_distance(dd_real, xy_centers[idx])
|
|
||||||
xyz_pred = xyz_from_distance(dd_pred, xy_centers[idx])
|
|
||||||
dic_out['boxes'].append(box)
|
|
||||||
dic_out['dds_real'].append(dd_real)
|
|
||||||
dic_out['dds_pred'].append(dd_pred)
|
|
||||||
dic_out['stds_ale'].append(ale)
|
|
||||||
dic_out['stds_epi'].append(var_y)
|
|
||||||
dic_out['xyz_real'].append(xyz_real.squeeze().tolist())
|
|
||||||
dic_out['xyz_pred'].append(xyz_pred.squeeze().tolist())
|
|
||||||
dic_out['uv_kps'].append(kps)
|
|
||||||
dic_out['uv_centers'].append(uv_center)
|
|
||||||
dic_out['uv_shoulders'].append(uv_shoulder)
|
|
||||||
|
|
||||||
return dic_out
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@ -4,13 +4,14 @@ Monoloco predictor. It receives pifpaf joints and outputs distances
|
|||||||
"""
|
"""
|
||||||
|
|
||||||
import logging
|
import logging
|
||||||
|
from collections import defaultdict
|
||||||
|
|
||||||
import torch
|
import torch
|
||||||
|
|
||||||
|
from utils.iou import get_iou_matches, reorder_matches
|
||||||
|
from utils.camera import get_keypoints, pixel_to_camera, xyz_from_distance
|
||||||
|
from utils.monoloco import get_monoloco_inputs, unnormalize_bi, laplace_sampling
|
||||||
from models.architectures import LinearModel
|
from models.architectures import LinearModel
|
||||||
from utils.misc import laplace_sampling
|
|
||||||
from utils.normalize import unnormalize_bi
|
|
||||||
from utils.pifpaf import get_network_inputs
|
|
||||||
|
|
||||||
|
|
||||||
class MonoLoco:
|
class MonoLoco:
|
||||||
@ -26,7 +27,7 @@ class MonoLoco:
|
|||||||
|
|
||||||
self.device = device
|
self.device = device
|
||||||
self.n_dropout = n_dropout
|
self.n_dropout = n_dropout
|
||||||
self.epistemic = True if self.n_dropout > 0 else False
|
self.epistemic = bool(self.n_dropout > 0)
|
||||||
|
|
||||||
# load the model parameters
|
# load the model parameters
|
||||||
self.model = LinearModel(p_dropout=p_dropout,
|
self.model = LinearModel(p_dropout=p_dropout,
|
||||||
@ -42,7 +43,7 @@ class MonoLoco:
|
|||||||
return None, None
|
return None, None
|
||||||
|
|
||||||
with torch.no_grad():
|
with torch.no_grad():
|
||||||
inputs = get_network_inputs(torch.tensor(keypoints).to(self.device), torch.tensor(kk).to(self.device))
|
inputs = get_monoloco_inputs(torch.tensor(keypoints).to(self.device), torch.tensor(kk).to(self.device))
|
||||||
if self.n_dropout > 0:
|
if self.n_dropout > 0:
|
||||||
self.model.dropout.training = True # Manually reactivate dropout in eval
|
self.model.dropout.training = True # Manually reactivate dropout in eval
|
||||||
total_outputs = torch.empty((0, inputs.size()[0])).to(self.device)
|
total_outputs = torch.empty((0, inputs.size()[0])).to(self.device)
|
||||||
@ -61,3 +62,50 @@ class MonoLoco:
|
|||||||
outputs = self.model(inputs)
|
outputs = self.model(inputs)
|
||||||
outputs = unnormalize_bi(outputs)
|
outputs = unnormalize_bi(outputs)
|
||||||
return outputs, varss
|
return outputs, varss
|
||||||
|
|
||||||
|
@staticmethod
|
||||||
|
def post_process(outputs, varss, boxes, keypoints, kk, dic_gt, iou_min=0.25):
|
||||||
|
"""Post process monoloco to output final dictionary with all information for visualizations"""
|
||||||
|
|
||||||
|
dic_out = defaultdict(list)
|
||||||
|
if outputs is None:
|
||||||
|
return dic_out
|
||||||
|
|
||||||
|
if dic_gt:
|
||||||
|
boxes_gt, dds_gt = dic_gt['boxes'], dic_gt['dds']
|
||||||
|
matches = get_iou_matches(boxes, boxes_gt, thresh=iou_min)
|
||||||
|
else:
|
||||||
|
matches = [(idx, idx) for idx, _ in enumerate(boxes)] # Replicate boxes
|
||||||
|
|
||||||
|
matches = reorder_matches(matches, boxes, mode='left_right')
|
||||||
|
uv_shoulders = get_keypoints(keypoints, mode='shoulder')
|
||||||
|
uv_centers = get_keypoints(keypoints, mode='center')
|
||||||
|
xy_centers = pixel_to_camera(uv_centers, kk, 1)
|
||||||
|
|
||||||
|
# Match with ground truth if available
|
||||||
|
for idx, idx_gt in matches:
|
||||||
|
dd_pred = float(outputs[idx][0])
|
||||||
|
ale = float(outputs[idx][1])
|
||||||
|
var_y = float(varss[idx])
|
||||||
|
dd_real = dds_gt[idx_gt] if dic_gt else dd_pred
|
||||||
|
|
||||||
|
kps = keypoints[idx]
|
||||||
|
box = boxes[idx]
|
||||||
|
uu_s, vv_s = uv_shoulders.tolist()[idx][0:2]
|
||||||
|
uu_c, vv_c = uv_centers.tolist()[idx][0:2]
|
||||||
|
uv_shoulder = [round(uu_s), round(vv_s)]
|
||||||
|
uv_center = [round(uu_c), round(vv_c)]
|
||||||
|
xyz_real = xyz_from_distance(dd_real, xy_centers[idx])
|
||||||
|
xyz_pred = xyz_from_distance(dd_pred, xy_centers[idx])
|
||||||
|
dic_out['boxes'].append(box)
|
||||||
|
dic_out['dds_real'].append(dd_real)
|
||||||
|
dic_out['dds_pred'].append(dd_pred)
|
||||||
|
dic_out['stds_ale'].append(ale)
|
||||||
|
dic_out['stds_epi'].append(var_y)
|
||||||
|
dic_out['xyz_real'].append(xyz_real.squeeze().tolist())
|
||||||
|
dic_out['xyz_pred'].append(xyz_pred.squeeze().tolist())
|
||||||
|
dic_out['uv_kps'].append(kps)
|
||||||
|
dic_out['uv_centers'].append(uv_center)
|
||||||
|
dic_out['uv_shoulders'].append(uv_shoulder)
|
||||||
|
|
||||||
|
return dic_out
|
||||||
|
|||||||
@ -1,7 +1,6 @@
|
|||||||
|
|
||||||
import glob
|
import glob
|
||||||
import os
|
import os
|
||||||
import sys
|
|
||||||
|
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import torchvision
|
import torchvision
|
||||||
@ -151,14 +150,13 @@ def predict(args):
|
|||||||
# Preprocess pifpaf outputs and run monoloco
|
# Preprocess pifpaf outputs and run monoloco
|
||||||
boxes, keypoints = preprocess_pif(pifpaf_out, im_size)
|
boxes, keypoints = preprocess_pif(pifpaf_out, im_size)
|
||||||
outputs, varss = monoloco.forward(keypoints, kk)
|
outputs, varss = monoloco.forward(keypoints, kk)
|
||||||
monoloco_outputs = [outputs, varss, boxes, keypoints, kk, dic_gt]
|
dic_out = monoloco.post_process(outputs, varss, boxes, keypoints, kk, dic_gt)
|
||||||
|
|
||||||
else:
|
else:
|
||||||
monoloco_outputs = None
|
dic_out = None
|
||||||
kk = None
|
kk = None
|
||||||
|
|
||||||
factory_outputs(args, images_outputs, output_path, pifpaf_outputs, monoloco_outputs=monoloco_outputs, kk=kk)
|
factory_outputs(args, images_outputs, output_path, pifpaf_outputs, monoloco_outputs=dic_out, kk=kk)
|
||||||
print('Image {}\n'.format(cnt) + '-' * 120)
|
print('Image {}\n'.format(cnt) + '-' * 120)
|
||||||
cnt += 1
|
cnt += 1
|
||||||
return keypoints_whole
|
return keypoints_whole
|
||||||
|
|
||||||
|
|||||||
@ -1,6 +1,5 @@
|
|||||||
|
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import math
|
|
||||||
import torch
|
import torch
|
||||||
import torch.nn.functional as F
|
import torch.nn.functional as F
|
||||||
|
|
||||||
|
|||||||
72
src/utils/iou.py
Normal file
72
src/utils/iou.py
Normal file
@ -0,0 +1,72 @@
|
|||||||
|
|
||||||
|
import numpy as np
|
||||||
|
|
||||||
|
|
||||||
|
def calculate_iou(box1, box2):
|
||||||
|
|
||||||
|
# Calculate the (x1, y1, x2, y2) coordinates of the intersection of box1 and box2. Calculate its Area.
|
||||||
|
xi1 = max(box1[0], box2[0])
|
||||||
|
yi1 = max(box1[1], box2[1])
|
||||||
|
xi2 = min(box1[2], box2[2])
|
||||||
|
yi2 = min(box1[3], box2[3])
|
||||||
|
inter_area = max((xi2 - xi1), 0) * max((yi2 - yi1), 0) # Max keeps into account not overlapping box
|
||||||
|
|
||||||
|
# Calculate the Union area by using Formula: Union(A,B) = A + B - Inter(A,B)
|
||||||
|
box1_area = (box1[2] - box1[0]) * (box1[3] - box1[1])
|
||||||
|
box2_area = (box2[2] - box2[0]) * (box2[3] - box2[1])
|
||||||
|
union_area = box1_area + box2_area - inter_area
|
||||||
|
|
||||||
|
# compute the IoU
|
||||||
|
iou = inter_area / union_area
|
||||||
|
|
||||||
|
return iou
|
||||||
|
|
||||||
|
|
||||||
|
def get_iou_matrix(boxes, boxes_gt):
|
||||||
|
"""
|
||||||
|
Get IoU matrix between predicted and ground truth boxes
|
||||||
|
Dim: (boxes, boxes_gt)
|
||||||
|
"""
|
||||||
|
iou_matrix = np.zeros((len(boxes), len(boxes_gt)))
|
||||||
|
for idx, box in enumerate(boxes):
|
||||||
|
for idx_gt, box_gt in enumerate(boxes_gt):
|
||||||
|
iou_matrix[idx, idx_gt] = calculate_iou(box, box_gt)
|
||||||
|
return iou_matrix
|
||||||
|
|
||||||
|
|
||||||
|
def get_iou_matches(boxes, boxes_gt, thresh):
|
||||||
|
"""From 2 sets of boxes and a minimum threshold, compute the matching indices for IoU matchings"""
|
||||||
|
|
||||||
|
iou_matrix = get_iou_matrix(boxes, boxes_gt)
|
||||||
|
if not iou_matrix.size:
|
||||||
|
return []
|
||||||
|
|
||||||
|
matches = []
|
||||||
|
iou_max = np.max(iou_matrix)
|
||||||
|
while iou_max > thresh:
|
||||||
|
# Extract the indeces of the max
|
||||||
|
args_max = np.unravel_index(np.argmax(iou_matrix, axis=None), iou_matrix.shape)
|
||||||
|
matches.append(args_max)
|
||||||
|
iou_matrix[args_max[0], :] = 0
|
||||||
|
iou_matrix[:, args_max[1]] = 0
|
||||||
|
iou_max = np.max(iou_matrix)
|
||||||
|
return matches
|
||||||
|
|
||||||
|
|
||||||
|
def reorder_matches(matches, boxes, mode='left_rigth'):
|
||||||
|
"""
|
||||||
|
Reorder a list of (idx, idx_gt) matches based on position of the detections in the image
|
||||||
|
ordered_boxes = (5, 6, 7, 0, 1, 4, 2, 4)
|
||||||
|
matches = [(0, x), (2,x), (4,x), (3,x), (5,x)]
|
||||||
|
Output --> [(5, x), (0, x), (3, x), (2, x), (5, x)]
|
||||||
|
"""
|
||||||
|
|
||||||
|
assert mode == 'left_right'
|
||||||
|
|
||||||
|
# Order the boxes based on the left-right position in the image and
|
||||||
|
ordered_boxes = np.argsort([box[0] for box in boxes]) # indices of boxes ordered from left to right
|
||||||
|
matches_left = [idx for (idx, _) in matches]
|
||||||
|
|
||||||
|
return [matches[matches_left.index(idx_boxes)] for idx_boxes in ordered_boxes if idx_boxes in matches_left]
|
||||||
|
|
||||||
|
|
||||||
26
src/utils/logs.py
Normal file
26
src/utils/logs.py
Normal file
@ -0,0 +1,26 @@
|
|||||||
|
|
||||||
|
import logging
|
||||||
|
|
||||||
|
|
||||||
|
def set_logger(log_path):
|
||||||
|
"""Set the logger to log info in terminal and file `log_path`.
|
||||||
|
```
|
||||||
|
logging.info("Starting training...")
|
||||||
|
```
|
||||||
|
Args:
|
||||||
|
log_path: (string) where to log
|
||||||
|
"""
|
||||||
|
logger = logging.getLogger(__name__)
|
||||||
|
logger.setLevel(logging.INFO)
|
||||||
|
|
||||||
|
# Logging to a file
|
||||||
|
file_handler = logging.FileHandler(log_path)
|
||||||
|
file_handler.setFormatter(logging.Formatter('%(asctime)s:%(levelname)s: %(message)s'))
|
||||||
|
logger.addHandler(file_handler)
|
||||||
|
|
||||||
|
# Logging to console
|
||||||
|
stream_handler = logging.StreamHandler()
|
||||||
|
stream_handler.setFormatter(logging.Formatter('%(message)s'))
|
||||||
|
logger.addHandler(stream_handler)
|
||||||
|
|
||||||
|
return logger
|
||||||
@ -1,160 +1,6 @@
|
|||||||
|
|
||||||
import numpy as np
|
|
||||||
import torch
|
|
||||||
import time
|
|
||||||
import logging
|
|
||||||
|
|
||||||
|
|
||||||
def set_logger(log_path):
|
|
||||||
"""Set the logger to log info in terminal and file `log_path`.
|
|
||||||
```
|
|
||||||
logging.info("Starting training...")
|
|
||||||
```
|
|
||||||
Args:
|
|
||||||
log_path: (string) where to log
|
|
||||||
"""
|
|
||||||
logger = logging.getLogger(__name__)
|
|
||||||
logger.setLevel(logging.INFO)
|
|
||||||
|
|
||||||
# Logging to a file
|
|
||||||
file_handler = logging.FileHandler(log_path)
|
|
||||||
file_handler.setFormatter(logging.Formatter('%(asctime)s:%(levelname)s: %(message)s'))
|
|
||||||
logger.addHandler(file_handler)
|
|
||||||
|
|
||||||
# Logging to console
|
|
||||||
stream_handler = logging.StreamHandler()
|
|
||||||
stream_handler.setFormatter(logging.Formatter('%(message)s'))
|
|
||||||
logger.addHandler(stream_handler)
|
|
||||||
|
|
||||||
return logger
|
|
||||||
|
|
||||||
|
|
||||||
def calculate_iou(box1, box2):
|
|
||||||
|
|
||||||
# Calculate the (x1, y1, x2, y2) coordinates of the intersection of box1 and box2. Calculate its Area.
|
|
||||||
xi1 = max(box1[0], box2[0])
|
|
||||||
yi1 = max(box1[1], box2[1])
|
|
||||||
xi2 = min(box1[2], box2[2])
|
|
||||||
yi2 = min(box1[3], box2[3])
|
|
||||||
inter_area = max((xi2 - xi1), 0) * max((yi2 - yi1), 0) # Max keeps into account not overlapping box
|
|
||||||
|
|
||||||
# Calculate the Union area by using Formula: Union(A,B) = A + B - Inter(A,B)
|
|
||||||
box1_area = (box1[2] - box1[0]) * (box1[3] - box1[1])
|
|
||||||
box2_area = (box2[2] - box2[0]) * (box2[3] - box2[1])
|
|
||||||
union_area = box1_area + box2_area - inter_area
|
|
||||||
|
|
||||||
# compute the IoU
|
|
||||||
iou = inter_area / union_area
|
|
||||||
|
|
||||||
return iou
|
|
||||||
|
|
||||||
|
|
||||||
def get_idx_max(box, boxes_gt):
|
|
||||||
|
|
||||||
"""Compute and save errors between a single box and the gt box which match"""
|
|
||||||
|
|
||||||
iou_max = 0
|
|
||||||
idx_max = 0
|
|
||||||
for idx_gt, box_gt in enumerate(boxes_gt):
|
|
||||||
iou = calculate_iou(box, box_gt)
|
|
||||||
if iou > iou_max:
|
|
||||||
idx_max = idx_gt
|
|
||||||
iou_max = iou
|
|
||||||
|
|
||||||
return idx_max, iou_max
|
|
||||||
|
|
||||||
|
|
||||||
def get_iou_matrix(boxes, boxes_gt):
|
|
||||||
"""
|
|
||||||
Get IoU matrix between predicted and ground truth boxes
|
|
||||||
Dim: (boxes, boxes_gt)
|
|
||||||
"""
|
|
||||||
iou_matrix = np.zeros((len(boxes), len(boxes_gt)))
|
|
||||||
for idx, box in enumerate(boxes):
|
|
||||||
for idx_gt, box_gt in enumerate(boxes_gt):
|
|
||||||
iou_matrix[idx, idx_gt] = calculate_iou(box, box_gt)
|
|
||||||
return iou_matrix
|
|
||||||
|
|
||||||
|
|
||||||
def get_iou_matches(boxes, boxes_gt, thresh):
|
|
||||||
"""From 2 sets of boxes and a minimum threshold, compute the matching indices for IoU matchings"""
|
|
||||||
|
|
||||||
iou_matrix = get_iou_matrix(boxes, boxes_gt)
|
|
||||||
if not iou_matrix.size:
|
|
||||||
return []
|
|
||||||
|
|
||||||
matches = []
|
|
||||||
iou_max = np.max(iou_matrix)
|
|
||||||
while iou_max > thresh:
|
|
||||||
# Extract the indeces of the max
|
|
||||||
args_max = np.unravel_index(np.argmax(iou_matrix, axis=None), iou_matrix.shape)
|
|
||||||
matches.append(args_max)
|
|
||||||
iou_matrix[args_max[0], :] = 0
|
|
||||||
iou_matrix[:, args_max[1]] = 0
|
|
||||||
iou_max = np.max(iou_matrix)
|
|
||||||
return matches
|
|
||||||
|
|
||||||
|
|
||||||
def reorder_matches(matches, boxes, mode='left_rigth'):
|
|
||||||
"""
|
|
||||||
Reorder a list of (idx, idx_gt) matches based on position of the detections in the image
|
|
||||||
ordered_boxes = (5, 6, 7, 0, 1, 4, 2, 4)
|
|
||||||
matches = [(0, x), (2,x), (4,x), (3,x), (5,x)]
|
|
||||||
Output --> [(5, x), (0, x), (3, x), (2, x), (5, x)]
|
|
||||||
"""
|
|
||||||
|
|
||||||
assert mode == 'left_right'
|
|
||||||
|
|
||||||
# Order the boxes based on the left-right position in the image and
|
|
||||||
ordered_boxes = np.argsort([box[0] for box in boxes]) # indices of boxes ordered from left to right
|
|
||||||
matches_left = [idx for (idx, _) in matches]
|
|
||||||
|
|
||||||
return [matches[matches_left.index(idx_boxes)] for idx_boxes in ordered_boxes if idx_boxes in matches_left]
|
|
||||||
|
|
||||||
|
|
||||||
def laplace_sampling(outputs, n_samples):
|
|
||||||
|
|
||||||
# np.random.seed(1)
|
|
||||||
t0 = time.time()
|
|
||||||
mu = outputs[:, 0]
|
|
||||||
bi = torch.abs(outputs[:, 1])
|
|
||||||
|
|
||||||
# Analytical
|
|
||||||
# uu = np.random.uniform(low=-0.5, high=0.5, size=mu.shape[0])
|
|
||||||
# xx = mu - bi * np.sign(uu) * np.log(1 - 2 * np.abs(uu))
|
|
||||||
|
|
||||||
# Sampling
|
|
||||||
cuda_check = outputs.is_cuda
|
|
||||||
|
|
||||||
if cuda_check:
|
|
||||||
get_device = outputs.get_device()
|
|
||||||
device = torch.device(type="cuda", index=get_device)
|
|
||||||
else:
|
|
||||||
device = torch.device("cpu")
|
|
||||||
|
|
||||||
xxs = torch.empty((0, mu.shape[0])).to(device)
|
|
||||||
laplace = torch.distributions.Laplace(mu, bi)
|
|
||||||
for ii in range(1):
|
|
||||||
xx = laplace.sample((n_samples,))
|
|
||||||
xxs = torch.cat((xxs, xx.view(n_samples, -1)), 0)
|
|
||||||
|
|
||||||
return xxs
|
|
||||||
|
|
||||||
|
|
||||||
def epistemic_variance(total_outputs):
|
|
||||||
"""Compute epistemic variance"""
|
|
||||||
|
|
||||||
# var_y = np.sum(total_outputs**2, axis=0) / total_outputs.shape[0] - (np.mean(total_outputs, axis=0))**2
|
|
||||||
var_y = np.var(total_outputs, axis=0)
|
|
||||||
lb = np.quantile(a=total_outputs, q=0.25, axis=0)
|
|
||||||
up = np.quantile(a=total_outputs, q=0.75, axis=0)
|
|
||||||
var_new = (up-lb)
|
|
||||||
|
|
||||||
return var_y, var_new
|
|
||||||
|
|
||||||
|
|
||||||
def append_cluster(dic_jo, phase, xx, dd, kps):
|
def append_cluster(dic_jo, phase, xx, dd, kps):
|
||||||
|
|
||||||
"""Append the annotation based on its distance"""
|
"""Append the annotation based on its distance"""
|
||||||
|
|
||||||
if dd <= 10:
|
if dd <= 10:
|
||||||
@ -184,3 +30,5 @@ def get_task_error(dd):
|
|||||||
return mm_gender * dd
|
return mm_gender * dd
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
66
src/utils/monoloco.py
Normal file
66
src/utils/monoloco.py
Normal file
@ -0,0 +1,66 @@
|
|||||||
|
|
||||||
|
import numpy as np
|
||||||
|
import torch
|
||||||
|
from utils.camera import get_keypoints, pixel_to_camera
|
||||||
|
|
||||||
|
|
||||||
|
def get_monoloco_inputs(keypoints, kk):
|
||||||
|
|
||||||
|
""" Preprocess batches of inputs
|
||||||
|
keypoints = torch tensors of (m, 3, 17) or list [3,17]
|
||||||
|
Outputs = torch tensors of (m, 34) in meters normalized (z=1) and zero-centered using the center of the box
|
||||||
|
"""
|
||||||
|
if isinstance(keypoints, list):
|
||||||
|
keypoints = torch.tensor(keypoints)
|
||||||
|
if isinstance(kk, list):
|
||||||
|
kk = torch.tensor(kk)
|
||||||
|
# Projection in normalized image coordinates and zero-center with the center of the bounding box
|
||||||
|
uv_center = get_keypoints(keypoints, mode='center')
|
||||||
|
xy1_center = pixel_to_camera(uv_center, kk, 1) * 10
|
||||||
|
xy1_all = pixel_to_camera(keypoints[:, 0:2, :], kk, 1) * 10
|
||||||
|
kps_norm = xy1_all - xy1_center.unsqueeze(1) # (m, 17, 3) - (m, 1, 3)
|
||||||
|
kps_out = kps_norm[:, :, 0:2].reshape(kps_norm.size()[0], -1) # no contiguous for view
|
||||||
|
return kps_out
|
||||||
|
|
||||||
|
|
||||||
|
def laplace_sampling(outputs, n_samples):
|
||||||
|
|
||||||
|
# np.random.seed(1)
|
||||||
|
mu = outputs[:, 0]
|
||||||
|
bi = torch.abs(outputs[:, 1])
|
||||||
|
|
||||||
|
# Analytical
|
||||||
|
# uu = np.random.uniform(low=-0.5, high=0.5, size=mu.shape[0])
|
||||||
|
# xx = mu - bi * np.sign(uu) * np.log(1 - 2 * np.abs(uu))
|
||||||
|
|
||||||
|
# Sampling
|
||||||
|
cuda_check = outputs.is_cuda
|
||||||
|
if cuda_check:
|
||||||
|
get_device = outputs.get_device()
|
||||||
|
device = torch.device(type="cuda", index=get_device)
|
||||||
|
else:
|
||||||
|
device = torch.device("cpu")
|
||||||
|
|
||||||
|
laplace = torch.distributions.Laplace(mu, bi)
|
||||||
|
xx = laplace.sample((n_samples,)).to(device)
|
||||||
|
|
||||||
|
return xx
|
||||||
|
|
||||||
|
|
||||||
|
def epistemic_variance(total_outputs):
|
||||||
|
"""Compute epistemic variance"""
|
||||||
|
|
||||||
|
# var_y = np.sum(total_outputs**2, axis=0) / total_outputs.shape[0] - (np.mean(total_outputs, axis=0))**2
|
||||||
|
var_y = np.var(total_outputs, axis=0)
|
||||||
|
lower_b = np.quantile(a=total_outputs, q=0.25, axis=0)
|
||||||
|
upper_b = np.quantile(a=total_outputs, q=0.75, axis=0)
|
||||||
|
var_new = (upper_b - lower_b)
|
||||||
|
|
||||||
|
return var_y, var_new
|
||||||
|
|
||||||
|
|
||||||
|
def unnormalize_bi(outputs):
|
||||||
|
"""Unnormalize relative bi of a nunmpy array"""
|
||||||
|
|
||||||
|
outputs[:, 1] = torch.exp(outputs[:, 1]) * outputs[:, 0]
|
||||||
|
return outputs
|
||||||
@ -1,42 +0,0 @@
|
|||||||
|
|
||||||
import torch
|
|
||||||
import numpy as np
|
|
||||||
|
|
||||||
|
|
||||||
def normalize_labels(labels, dic_norm):
|
|
||||||
"""Apply the log to remove right-skewness and then apply Gaussian Normalization"""
|
|
||||||
|
|
||||||
labels_new = torch.div(torch.log(labels) - dic_norm['mean']['Y'], dic_norm['std']['Y'])
|
|
||||||
return labels_new
|
|
||||||
|
|
||||||
|
|
||||||
def unnormalize_labels(labels, dic_norm):
|
|
||||||
"""Apply the log to remove right-skewness and then apply Gaussian Normalization"""
|
|
||||||
|
|
||||||
return torch.exp(labels * dic_norm['std']['Y'] + dic_norm['mean']['Y'])
|
|
||||||
|
|
||||||
|
|
||||||
def unnormalize_outputs(outputs, dic_norm, dim, normalize):
|
|
||||||
"""Unnnormalize outputs, with an option to only pass from si to bi"""
|
|
||||||
|
|
||||||
if dim == 1:
|
|
||||||
assert normalize, "Inconsistency"
|
|
||||||
return unnormalize_labels(outputs, dic_norm)
|
|
||||||
|
|
||||||
else:
|
|
||||||
mu = outputs[:, 0:1]
|
|
||||||
si = outputs[:, 1:2]
|
|
||||||
bi = torch.exp(si)
|
|
||||||
|
|
||||||
if normalize:
|
|
||||||
mu = unnormalize_labels(mu, dic_norm)
|
|
||||||
bi = torch.exp(bi * dic_norm['std']['Y'])
|
|
||||||
|
|
||||||
return torch.cat((mu, bi), 1)
|
|
||||||
|
|
||||||
|
|
||||||
def unnormalize_bi(outputs):
|
|
||||||
"""Unnormalize relative bi of a nunmpy array"""
|
|
||||||
|
|
||||||
outputs[:, 1] = torch.exp(outputs[:, 1]) * outputs[:, 0]
|
|
||||||
return outputs
|
|
||||||
@ -99,12 +99,3 @@ def update_with_box(dict_gt, box):
|
|||||||
flag_child = True
|
flag_child = True
|
||||||
|
|
||||||
return dict_gt, flag_child
|
return dict_gt, flag_child
|
||||||
|
|
||||||
# def merge_gt_pif(dic_gt, im_path):
|
|
||||||
#
|
|
||||||
# # Extract ground truth boxes
|
|
||||||
# boxes_2d, _ = self.project_3d(dic_gt, mode='box_center') # Project the 3D gt into the image plane
|
|
||||||
# boxes_gt = [np.array([box[0][0], box[0][1], box[1][0], box[1][1]]) for box in boxes_2d]
|
|
||||||
# # Match each annotation and save them in the json file
|
|
||||||
# self.merge_gt_pif_single(dic_gt, boxes_gt, boxes_pif, keypoints, basename,
|
|
||||||
# iou_thresh=self.iou_thresh)
|
|
||||||
|
|||||||
@ -1,68 +1,5 @@
|
|||||||
|
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import torch
|
|
||||||
from utils.camera import get_keypoints, pixel_to_camera
|
|
||||||
|
|
||||||
|
|
||||||
def preprocess_pif(annotations, im_size=None):
|
|
||||||
"""
|
|
||||||
Preprocess pif annotations:
|
|
||||||
1. enlarge the box of 10%
|
|
||||||
2. Constraint it inside the image (if image_size provided)
|
|
||||||
"""
|
|
||||||
|
|
||||||
boxes = []
|
|
||||||
keypoints = []
|
|
||||||
|
|
||||||
for dic in annotations:
|
|
||||||
box = dic['bbox']
|
|
||||||
if box[3] < 0.5: # Check for no detections (boxes 0,0,0,0)
|
|
||||||
return [], []
|
|
||||||
|
|
||||||
else:
|
|
||||||
kps = prepare_pif_kps(dic['keypoints'])
|
|
||||||
conf = float(np.mean(np.array(kps[2])))
|
|
||||||
|
|
||||||
# Add 10% for y
|
|
||||||
delta_h = (box[3] - box[1]) / 10
|
|
||||||
delta_w = (box[2] - box[0]) / 10
|
|
||||||
assert delta_h > 0 and delta_w > 0, "Bounding box <=0"
|
|
||||||
box[0] -= delta_w
|
|
||||||
box[1] -= delta_h
|
|
||||||
box[2] += delta_w
|
|
||||||
box[3] += delta_h
|
|
||||||
|
|
||||||
# Put the box inside the image
|
|
||||||
if im_size is not None:
|
|
||||||
box[0] = max(0, box[0])
|
|
||||||
box[1] = max(0, box[1])
|
|
||||||
box[2] = min(box[2], im_size[0])
|
|
||||||
box[3] = min(box[3], im_size[1])
|
|
||||||
|
|
||||||
box.append(conf)
|
|
||||||
boxes.append(box)
|
|
||||||
keypoints.append(kps)
|
|
||||||
|
|
||||||
return boxes, keypoints
|
|
||||||
|
|
||||||
|
|
||||||
def get_network_inputs(keypoints, kk):
|
|
||||||
|
|
||||||
""" Preprocess batches of inputs
|
|
||||||
keypoints = torch tensors of (m, 3, 17) or list [3,17]
|
|
||||||
Outputs = torch tensors of (m, 34) in meters normalized (z=1) and zero-centered using the center of the box
|
|
||||||
"""
|
|
||||||
if type(keypoints) == list:
|
|
||||||
keypoints = torch.tensor(keypoints)
|
|
||||||
if type(kk) == list:
|
|
||||||
kk = torch.tensor(kk)
|
|
||||||
# Projection in normalized image coordinates and zero-center with the center of the bounding box
|
|
||||||
uv_center = get_keypoints(keypoints, mode='center')
|
|
||||||
xy1_center = pixel_to_camera(uv_center, kk, 1) * 10
|
|
||||||
xy1_all = pixel_to_camera(keypoints[:, 0:2, :], kk, 1) * 10
|
|
||||||
kps_norm = xy1_all - xy1_center.unsqueeze(1) # (m, 17, 3) - (m, 1, 3)
|
|
||||||
kps_out = kps_norm[:, :, 0:2].reshape(kps_norm.size()[0], -1) # no contiguous for view
|
|
||||||
return kps_out
|
|
||||||
|
|
||||||
|
|
||||||
def preprocess_pif(annotations, im_size=None):
|
def preprocess_pif(annotations, im_size=None):
|
||||||
|
|||||||
@ -1,6 +1,6 @@
|
|||||||
|
|
||||||
|
|
||||||
from utils.misc import get_iou_matrix
|
from utils.iou import get_iou_matrix
|
||||||
|
|
||||||
|
|
||||||
def test_iou():
|
def test_iou():
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user