|
- """
- # -*- coding: utf-8 -*-
- -----------------------------------------------------------------------------------
- # Author: Nguyen Mau Dung
- # DoC: 2020.08.17
- # email: nguyenmaudung93.kstn@gmail.com
- -----------------------------------------------------------------------------------
- # Description: The utils of the kitti dataset
- """
-
- from __future__ import print_function
- import os
- import sys
-
- import numpy as np
- import cv2
-
- src_dir = os.path.dirname(os.path.realpath(__file__))
- # while not src_dir.endswith("sfa"):
- # src_dir = os.path.dirname(src_dir)
- if src_dir not in sys.path:
- sys.path.append(src_dir)
-
- import config.kitti_config as cnf
-
-
- class Object3d(object):
- ''' 3d object label '''
-
- def __init__(self, label_file_line):
- data = label_file_line.split(' ')
- data[1:] = [float(x) for x in data[1:]]
- # extract label, truncation, occlusion
- self.type = data[0] # 'Car', 'Pedestrian', ...
- self.cls_id = self.cls_type_to_id(self.type)
- self.truncation = data[1] # truncated pixel ratio [0..1]
- self.occlusion = int(data[2]) # 0=visible, 1=partly occluded, 2=fully occluded, 3=unknown
- self.alpha = data[3] # object observation angle [-pi..pi]
-
- # extract 2d bounding box in 0-based coordinates
- self.xmin = data[4] # left
- self.ymin = data[5] # top
- self.xmax = data[6] # right
- self.ymax = data[7] # bottom
- self.box2d = np.array([self.xmin, self.ymin, self.xmax, self.ymax])
-
- # extract 3d bounding box information
- self.h = data[8] # box height
- self.w = data[9] # box width
- self.l = data[10] # box length (in meters)
- self.t = (data[11], data[12], data[13]) # location (x,y,z) in camera coord.
- self.dis_to_cam = np.linalg.norm(self.t)
- self.ry = data[14] # yaw angle (around Y-axis in camera coordinates) [-pi..pi]
- self.score = data[15] if data.__len__() == 16 else -1.0
- self.level_str = None
- self.level = self.get_obj_level()
-
- def cls_type_to_id(self, cls_type):
- if cls_type not in cnf.CLASS_NAME_TO_ID.keys():
- return -1
-
- return cnf.CLASS_NAME_TO_ID[cls_type]
-
- def get_obj_level(self):
- height = float(self.box2d[3]) - float(self.box2d[1]) + 1
-
- if height >= 40 and self.truncation <= 0.15 and self.occlusion <= 0:
- self.level_str = 'Easy'
- return 1 # Easy
- elif height >= 25 and self.truncation <= 0.3 and self.occlusion <= 1:
- self.level_str = 'Moderate'
- return 2 # Moderate
- elif height >= 25 and self.truncation <= 0.5 and self.occlusion <= 2:
- self.level_str = 'Hard'
- return 3 # Hard
- else:
- self.level_str = 'UnKnown'
- return 4
-
- def print_object(self):
- print('Type, truncation, occlusion, alpha: %s, %d, %d, %f' % \
- (self.type, self.truncation, self.occlusion, self.alpha))
- print('2d bbox (x0,y0,x1,y1): %f, %f, %f, %f' % \
- (self.xmin, self.ymin, self.xmax, self.ymax))
- print('3d bbox h,w,l: %f, %f, %f' % \
- (self.h, self.w, self.l))
- print('3d bbox location, ry: (%f, %f, %f), %f' % \
- (self.t[0], self.t[1], self.t[2], self.ry))
-
- def to_kitti_format(self):
- kitti_str = '%s %.2f %d %.2f %.2f %.2f %.2f %.2f %.2f %.2f %.2f %.2f %.2f %.2f %.2f %.2f' \
- % (self.type, self.truncation, int(self.occlusion), self.alpha, self.box2d[0], self.box2d[1],
- self.box2d[2], self.box2d[3], self.h, self.w, self.l, self.t[0], self.t[1], self.t[2],
- self.ry, self.score)
- return kitti_str
-
-
- def read_label(label_filename):
- lines = [line.rstrip() for line in open(label_filename)]
- objects = [Object3d(line) for line in lines]
- return objects
-
-
- class Calibration(object):
- ''' Calibration matrices and utils
- 3d XYZ in <label>.txt are in rect camera coord.
- 2d box xy are in image2 coord
- Points in <lidar>.bin are in Velodyne coord.
-
- y_image2 = P^2_rect * x_rect
- y_image2 = P^2_rect * R0_rect * Tr_velo_to_cam * x_velo
- x_ref = Tr_velo_to_cam * x_velo
- x_rect = R0_rect * x_ref
-
- P^2_rect = [f^2_u, 0, c^2_u, -f^2_u b^2_x;
- 0, f^2_v, c^2_v, -f^2_v b^2_y;
- 0, 0, 1, 0]
- = K * [1|t]
-
- image2 coord:
- ----> x-axis (u)
- |
- |
- v y-axis (v)
-
- velodyne coord:
- front x, left y, up z
-
- rect/ref camera coord:
- right x, down y, front z
-
- Ref (KITTI paper): http://www.cvlibs.net/publications/Geiger2013IJRR.pdf
-
- TODO(rqi): do matrix multiplication only once for each projection.
- '''
-
- def __init__(self, calib_filepath):
- calibs = self.read_calib_file(calib_filepath)
- # Projection matrix from rect camera coord to image2 coord
- self.P2 = calibs['P2']
- self.P2 = np.reshape(self.P2, [3, 4])
- self.P3 = calibs['P3']
- self.P3 = np.reshape(self.P3, [3, 4])
- # Rigid transform from Velodyne coord to reference camera coord
- self.V2C = calibs['Tr_velo2cam']
- self.V2C = np.reshape(self.V2C, [3, 4])
- # Rotation from reference camera coord to rect camera coord
- self.R0 = calibs['R_rect']
- self.R0 = np.reshape(self.R0, [3, 3])
-
- # Camera intrinsics and extrinsics
- self.c_u = self.P2[0, 2]
- self.c_v = self.P2[1, 2]
- self.f_u = self.P2[0, 0]
- self.f_v = self.P2[1, 1]
- self.b_x = self.P2[0, 3] / (-self.f_u) # relative
- self.b_y = self.P2[1, 3] / (-self.f_v)
-
- def read_calib_file(self, filepath):
- with open(filepath) as f:
- lines = f.readlines()
-
- obj = lines[2].strip().split(' ')[1:]
- P2 = np.array(obj, dtype=np.float32)
- obj = lines[3].strip().split(' ')[1:]
- P3 = np.array(obj, dtype=np.float32)
- obj = lines[4].strip().split(' ')[1:]
- R0 = np.array(obj, dtype=np.float32)
- obj = lines[5].strip().split(' ')[1:]
- Tr_velo_to_cam = np.array(obj, dtype=np.float32)
-
- return {'P2': P2.reshape(3, 4),
- 'P3': P3.reshape(3, 4),
- 'R_rect': R0.reshape(3, 3),
- 'Tr_velo2cam': Tr_velo_to_cam.reshape(3, 4)}
-
- def cart2hom(self, pts_3d):
- """
- :param pts: (N, 3 or 2)
- :return pts_hom: (N, 4 or 3)
- """
- pts_hom = np.hstack((pts_3d, np.ones((pts_3d.shape[0], 1), dtype=np.float32)))
- return pts_hom
-
-
- def compute_radius(det_size, min_overlap=0.7):
- height, width = det_size
-
- a1 = 1
- b1 = (height + width)
- c1 = width * height * (1 - min_overlap) / (1 + min_overlap)
- sq1 = np.sqrt(b1 ** 2 - 4 * a1 * c1)
- r1 = (b1 + sq1) / 2
-
- a2 = 4
- b2 = 2 * (height + width)
- c2 = (1 - min_overlap) * width * height
- sq2 = np.sqrt(b2 ** 2 - 4 * a2 * c2)
- r2 = (b2 + sq2) / 2
-
- a3 = 4 * min_overlap
- b3 = -2 * min_overlap * (height + width)
- c3 = (min_overlap - 1) * width * height
- sq3 = np.sqrt(b3 ** 2 - 4 * a3 * c3)
- r3 = (b3 + sq3) / 2
-
- return min(r1, r2, r3)
-
-
- def gaussian2D(shape, sigma=1):
- m, n = [(ss - 1.) / 2. for ss in shape]
- y, x = np.ogrid[-m:m + 1, -n:n + 1]
- h = np.exp(-(x * x + y * y) / (2 * sigma * sigma))
- h[h < np.finfo(h.dtype).eps * h.max()] = 0
-
- return h
-
-
- def gen_hm_radius(heatmap, center, radius, k=1):
- diameter = 2 * radius + 1
- gaussian = gaussian2D((diameter, diameter), sigma=diameter / 6)
-
- x, y = int(center[0]), int(center[1])
-
- height, width = heatmap.shape[0:2]
-
- left, right = min(x, radius), min(width - x, radius + 1)
- top, bottom = min(y, radius), min(height - y, radius + 1)
-
- masked_heatmap = heatmap[y - top:y + bottom, x - left:x + right]
- masked_gaussian = gaussian[radius - top:radius + bottom, radius - left:radius + right]
- if min(masked_gaussian.shape) > 0 and min(masked_heatmap.shape) > 0: # TODO debug
- np.maximum(masked_heatmap, masked_gaussian * k, out=masked_heatmap)
-
- return heatmap
-
-
- def get_filtered_lidar(lidar, boundary, labels=None):
- minX = boundary['minX']
- maxX = boundary['maxX']
- minY = boundary['minY']
- maxY = boundary['maxY']
- minZ = boundary['minZ']
- maxZ = boundary['maxZ']
-
- # Remove the point out of range x,y,z
- mask = np.where((lidar[:, 0] >= minX) & (lidar[:, 0] <= maxX) &
- (lidar[:, 1] >= minY) & (lidar[:, 1] <= maxY) &
- (lidar[:, 2] >= minZ) & (lidar[:, 2] <= maxZ))
- lidar = lidar[mask]
- lidar[:, 2] = lidar[:, 2] - minZ
-
- if labels is not None:
- label_x = (labels[:, 1] >= minX) & (labels[:, 1] < maxX)
- label_y = (labels[:, 2] >= minY) & (labels[:, 2] < maxY)
- label_z = (labels[:, 3] >= minZ) & (labels[:, 3] < maxZ)
- mask_label = label_x & label_y & label_z
- labels = labels[mask_label]
- return lidar, labels
- else:
- return lidar
-
-
- def box3d_corners_to_center(box3d_corner):
- # (N, 8, 3) -> (N, 7)
- assert box3d_corner.ndim == 3
-
- xyz = np.mean(box3d_corner, axis=1)
-
- h = abs(np.mean(box3d_corner[:, 4:, 2] - box3d_corner[:, :4, 2], axis=1, keepdims=True))
- w = (np.sqrt(np.sum((box3d_corner[:, 0, [0, 1]] - box3d_corner[:, 1, [0, 1]]) ** 2, axis=1, keepdims=True)) +
- np.sqrt(np.sum((box3d_corner[:, 2, [0, 1]] - box3d_corner[:, 3, [0, 1]]) ** 2, axis=1, keepdims=True)) +
- np.sqrt(np.sum((box3d_corner[:, 4, [0, 1]] - box3d_corner[:, 5, [0, 1]]) ** 2, axis=1, keepdims=True)) +
- np.sqrt(np.sum((box3d_corner[:, 6, [0, 1]] - box3d_corner[:, 7, [0, 1]]) ** 2, axis=1, keepdims=True))) / 4
-
- l = (np.sqrt(np.sum((box3d_corner[:, 0, [0, 1]] - box3d_corner[:, 3, [0, 1]]) ** 2, axis=1, keepdims=True)) +
- np.sqrt(np.sum((box3d_corner[:, 1, [0, 1]] - box3d_corner[:, 2, [0, 1]]) ** 2, axis=1, keepdims=True)) +
- np.sqrt(np.sum((box3d_corner[:, 4, [0, 1]] - box3d_corner[:, 7, [0, 1]]) ** 2, axis=1, keepdims=True)) +
- np.sqrt(np.sum((box3d_corner[:, 5, [0, 1]] - box3d_corner[:, 6, [0, 1]]) ** 2, axis=1, keepdims=True))) / 4
-
- yaw = (np.arctan2(box3d_corner[:, 2, 1] - box3d_corner[:, 1, 1],
- box3d_corner[:, 2, 0] - box3d_corner[:, 1, 0]) +
- np.arctan2(box3d_corner[:, 3, 1] - box3d_corner[:, 0, 1],
- box3d_corner[:, 3, 0] - box3d_corner[:, 0, 0]) +
- np.arctan2(box3d_corner[:, 2, 0] - box3d_corner[:, 3, 0],
- box3d_corner[:, 3, 1] - box3d_corner[:, 2, 1]) +
- np.arctan2(box3d_corner[:, 1, 0] - box3d_corner[:, 0, 0],
- box3d_corner[:, 0, 1] - box3d_corner[:, 1, 1]))[:, np.newaxis] / 4
-
- return np.concatenate([h, w, l, xyz, yaw], axis=1).reshape(-1, 7)
-
-
- def box3d_center_to_conners(box3d_center):
- h, w, l, x, y, z, yaw = box3d_center
- Box = np.array([[-l / 2, -l / 2, l / 2, l / 2, -l / 2, -l / 2, l / 2, l / 2],
- [w / 2, -w / 2, -w / 2, w / 2, w / 2, -w / 2, -w / 2, w / 2],
- [0, 0, 0, 0, h, h, h, h]])
-
- rotMat = np.array([
- [np.cos(yaw), -np.sin(yaw), 0.0],
- [np.sin(yaw), np.cos(yaw), 0.0],
- [0.0, 0.0, 1.0]])
-
- velo_box = np.dot(rotMat, Box)
- cornerPosInVelo = velo_box + np.tile(np.array([x, y, z]), (8, 1)).T
- box3d_corner = cornerPosInVelo.transpose()
-
- return box3d_corner.astype(np.float32)
-
-
- if __name__ == '__main__':
- heatmap = np.zeros((96, 320))
-
- h, w = 40, 50
- radius = compute_radius((h, w))
- radius = max(0, int(radius))
- print('h: {}, w: {}, radius: {}, sigma: {}'.format(h, w, radius, (2 * radius + 1) / 6.))
- gen_hm_radius(heatmap, center=(200, 50), radius=radius)
- while True:
- cv2.imshow('heatmap', heatmap)
- if cv2.waitKey(0) & 0xff == 27:
- break
- max_pos = np.unravel_index(heatmap.argmax(), shape=heatmap.shape)
- print('max_pos: {}'.format(max_pos))
|