def load(self, path): """ Load a viewpoints.json to dataset's structure Todo: datastructure should be more similar to json structure... :return: return false if the dataset is empty. """ # Load viewpoints file and camera file with open(os.path.join(path, "viewpoints.json")) as data_file: data = json.load(data_file) self.camera = Camera.load_from_json(path) self.metadata = data["metaData"] self.set_save_type(self.metadata["save_type"]) count = 0 # todo this is not clean!i while True: try: id = str(count) pose = Transform.from_parameters( *[float(data[id]["vector"][str(x)]) for x in range(6)]) self.add_pose(None, None, pose) if "pairs" in data[id]: for i in range(int(data[id]["pairs"])): pair_id = "{}n{}".format(id, i) pair_pose = Transform.from_parameters(*[ float(data[pair_id]["vector"][str(x)]) for x in range(6) ]) self.add_pair(None, None, pair_pose, count) count += 1 except KeyError: break return self.data_pose
def get_poses(self, path, seq_index, dt, keep_in_ram=False): if self.is_on_disk(): self.load(path) poses = self.poses poseA = Transform.from_matrix(poses[0]) poseB = Transform.from_matrix(poses[1]) delta = delta_transform(poseA, poseB).to_parameters(isDegree=True) delta = torch.tensor(delta).type(torch.FloatTensor) if not keep_in_ram: self.clear() return [delta, poseA, poseB]
def matrices_to_param(matrices): parameters = [] for matrix in matrices: # convert a 4x4 matrix to euler parameters.append( Transform.from_matrix(matrix.reshape(4, 4)).to_parameters()) return np.array(parameters)
def get_frame(self, i): pose = Transform.from_matrix(self.poses[i].reshape(4, 4)) rgb = np.array(Image.open(os.path.join(self.root, "{}.png".format(i)))) depth = np.array( Image.open(os.path.join(self.root, "{}d.png".format(i)))).astype(np.uint16) return pose, rgb, depth
def __call__(self, data): rgbA, depthA, rgbB, depthB, prior = data prior_T = Transform.from_parameters(*prior) if random.uniform(0, 1) < self.proba: rand_id = random.randint(0, self.loader.size() - 1) occluder_rgb, occluder_depth, occ_pose = self.loader.load_image( rand_id) if random.randint(0, 1): occluder_rgb, occluder_depth, _ = self.loader.load_pair( rand_id, 0) occluder_depth = occluder_depth.astype(np.float32) # Z offset of occluder to be closer to the occluded object offset = occ_pose.matrix[2, 3] - prior_T.matrix[2, 3] occluder_depth[occluder_depth != 0] += offset * 1000 occluder_depth[occluder_depth != 0] -= random.randint(0, 500) occluder_rgb = add_hsv_noise(occluder_rgb, 1, 0.1, 0.1) occluder_rgb = imresize(occluder_rgb, depthB.shape, interp='nearest') occluder_depth = imresize(occluder_depth, depthB.shape, interp='nearest', mode="F").astype(np.int16) rgbB, depthB, occluder_mask = depth_blend(rgbB, depthB, occluder_rgb, occluder_depth) else: occluder_mask = None return rgbA, depthA, rgbB, depthB, prior, occluder_mask
def __call__(self, data): rgbA, depthA, rgbB, depthB, prior = data prior_T = Transform.from_parameters(*prior) depthA = self.normalize_depth(depthA, prior_T) depthB = self.normalize_depth(depthB, prior_T) #show_frames(rgbA, depthA, rgbB, depthB) return rgbA.astype(np.float32), depthA, rgbB.astype( np.float32), depthB, prior
def load(self, path): self.camera = Camera.load_from_json(path) self.event_camera = Camera.load_from_json(path, filename='dvs') self.dt_event = 1e8 / 3 self.dt_frame = 1e8 / 3 self.path = path self.load_data() self.raw_events = np.load(os.path.join(path, 'fevents.npz')) self.raw_events = self.raw_events[self.raw_events.files[0]] self.raw_events = pd.DataFrame( data=self.raw_events, columns=['Timestamp', 'X', 'Y', 'Polarity']) self.raw_events.Timestamp *= 1000 self.raw_events = self.raw_events[['Polarity', 'Timestamp', 'X', 'Y']] self.dead_pixel = [(151, 205)] for dead_pixel in self.dead_pixel: self.raw_events = self.raw_events[~( (self.raw_events.X == dead_pixel[0]) & (self.raw_events.Y == dead_pixel[1]))] self.frame_ts = np.load(os.path.join(path, 'ts_frames.npz')) self.frame_ts = self.frame_ts[self.frame_ts.files[0]] self.frame_ts *= 1000 poses_path = os.path.join(path, 'poses.npy') if os.path.exists(poses_path): self.poses = np.load(poses_path) else: print("WARNING: Poses not found") self.poses = None self.matrix_transformation = Transform() np_mat = np.load(os.path.join(path, 'transfo_mat.npy')) np_mat[0:3, -1] /= 1000 self.matrix_transformation.matrix = np_mat self.size = len( self.raw_frames) * self.frame_number - self.frame_number self.unload_data()
def predict(self, frame): try: for _ in range(self.repeat): prediction = self._predict(frame) prediction_transform = Transform.from_parameters( *prediction, is_degree=self.is_degree) self.current_pose = combine_view_transform( self.current_pose, prediction_transform) self.poses.append(self.current_pose.to_parameters(rodrigues=False)) return prediction except ValueError: return None
def random_normal_magnitude(max_T, max_R): #maximum_magnitude_T = np.sqrt(3*(max_T**2)) #maximum_magnitude_R = np.sqrt(3*(max_R**2)) direction_T = UniformSphereSampler.random_direction() magn_T = UniformSphereSampler.normal_clip(max_T) #magn_T = random.uniform(0, max_T) T = angle_axis2euler(magn_T, direction_T) direction_R = UniformSphereSampler.random_direction() magn_R = UniformSphereSampler.normal_clip(max_R) #magn_R = random.uniform(0, max_R) R = angle_axis2euler(magn_R, direction_R) return Transform.from_parameters(T[2], T[1], T[0], R[2], R[1], R[0])
def eval_pose_error(ground_truth, prediction): diffs = [] for pred, gt in zip(prediction, ground_truth): # Comput RT*R rtr = Transform() rtr[0:3, 0:3] = pred.reshape(4, 4)[0:3, 0:3].dot( gt.reshape(4, 4)[0:3, 0:3].transpose()) # Keep rotation and translation differences pred_param = Transform.from_matrix(pred.reshape(4, 4)).to_parameters() gt_param = Transform.from_matrix(gt.reshape(4, 4)).to_parameters() diff = np.zeros(6) diff[3:] = np.abs(Transform.from_matrix(rtr).to_parameters()[3:]) diff[:3] = np.abs(pred_param[:3] - gt_param[:3]) diffs.append(diff) pose_diff = np.array(diffs) pose_diff_t = translation_distance(pose_diff[:, 0], pose_diff[:, 1], pose_diff[:, 2]) pose_diff_r = rotation_distance(pose_diff[:, 3], pose_diff[:, 4], pose_diff[:, 5]) return pose_diff_t, pose_diff_r
def get_random(self): eye = UniformSphereSampler.random_direction() distance = random.uniform(0, 1) * (self.max_radius - self.min_radius) + self.min_radius eye *= distance view = Transform.lookAt(eye, np.zeros(3), self.up) # Random z rotation angle = random.uniform(0, 1) * math.pi * 2 cosa = math.cos(angle) sina = math.sin(angle) rotation = Transform() rotation.matrix[0, 0] = cosa rotation.matrix[1, 0] = -sina rotation.matrix[0, 1] = sina rotation.matrix[1, 1] = cosa ret = view.transpose() ret.rotate(transform=rotation.transpose()) return ret.transpose()
def predict(self, event_frame, rgb_frame): self.tracker_event.current_pose = self.to_event( self.tracker_frame.current_pose) pose = self.tracker_event._predict(event_frame) self.last_event_frame = self.tracker_event.last_frame prediction = Transform.from_parameters( *pose, is_degree=self.tracker_event.is_degree) new_pose_e = combine_view_transform( self.tracker_event.current_pose, prediction) new_pose_f = self.to_frame(new_pose_e) self.tracker_frame.current_pose = new_pose_f self.tracker_event.current_pose = new_pose_e self.tracker_frame.predict(rgb_frame) self.current_pose = (new_pose_f, self.tracker_frame.current_pose) self.poses.append((self.current_pose[0].to_parameters(rodrigues=False), self.current_pose[1].to_parameters(rodrigues=False)))
def _get_poses(self, indexA, indexB, transform=False): if self.poses is None: return None, None, None indexA = indexA indexB = indexB poseA = Transform.from_parameters(*self.poses[indexA], is_degree=True) poseB = Transform.from_parameters(*self.poses[indexB], is_degree=True) if transform: pose_A_flip = Transform.scale(1, -1, -1).combine(poseA) pose_A_flip = self.matrix_transformation.combine(pose_A_flip, copy=True) poseA = Transform().scale(1, -1, -1).combine(pose_A_flip, copy=True) pose_B_flip = Transform.scale(1, -1, -1).combine(poseB) pose_B_flip = self.matrix_transformation.combine(pose_B_flip, copy=True) poseB = Transform().scale(1, -1, -1).combine(pose_B_flip, copy=True) delta = delta_transform( poseA, poseB).to_parameters(isDegree=True).astype(np.float32) return delta, poseA, poseB
metadata["bounding_box_width"] = str(OBJECT_WIDTH) print("Mean object width : {}".format(OBJECT_WIDTH)) # Iterate over all models from config files for model in MODELS: geometry_path = os.path.join(model["path"], "geometry.ply") ao_path = os.path.join(model["path"], "ao.ply") vpRender = ModelRenderer(geometry_path, SHADER_PATH, dataset.camera, [window_size, IMAGE_SIZE]) if os.path.exists(ao_path): vpRender.load_ambiant_occlusion_map(ao_path) for i in tqdm(range(SAMPLE_QUANTITY)): random_pose = sphere_sampler.get_random() if RANDOM_SAMPLING: # Sampling from uniform distribution in the ranges random_transform = Transform.random((-TRANSLATION_RANGE, TRANSLATION_RANGE), (-ROTATION_RANGE, ROTATION_RANGE)) else: # Sampling from gaussian ditribution in the magnitudes random_transform = sphere_sampler.random_normal_magnitude(TRANSLATION_RANGE, ROTATION_RANGE) pair = combine_view_transform(random_pose, random_transform) bb = compute_2Dboundingbox(random_pose, dataset.camera, OBJECT_WIDTH, scale=(1000, -1000, -1000)) left = np.min(bb[:, 1]) right = np.max(bb[:, 1]) top = np.min(bb[:, 0]) bottom = np.max(bb[:, 0]) vpRender.setup_camera(camera, left, right, bottom, top) rgbA, depthA = vpRender.render_image(random_pose, fbo_index=1) light_intensity = np.zeros(3)
def to_frame(self, pose): pose_e_flip = Transform().scale(1, -1, -1).combine(pose, copy=True) pose_f_flip = self.transform.inverse().combine(pose_e_flip, copy=True) new_pose_f = Transform().scale(1, -1, -1).combine(pose_f_flip, copy=True) return new_pose_f
def to_event(self, pose): pose_f_flip = Transform.scale(1, -1, -1).combine(pose, copy=True) pose_e_flip = self.transform.combine(pose_f_flip, copy=True) pose_e = Transform().scale(1, -1, -1).combine(pose_e_flip, copy=True) return pose_e
class RGBDELoader(DeepTrackLoaderBase): def __init__(self, root, data_transform=None, target_transform=None, pre_transform=None, is_frame=True, read_data=True, event_type="raw", pose_type='numpy', ignore_frameA=False): self.is_frame = is_frame super(RGBDELoader, self).__init__(root, event_type, data_transform, target_transform, pre_transform, frame_number=1, read_data=read_data, pose_type=pose_type) self.ignore_frameA = ignore_frameA def from_index(self, index): if self.is_frame: if self.ignore_frameA: id, _ = self.ids[index] _, frameB, _, poses = self.data[id] rgbdB = frameB.get_rgb_depth(self.root) data = [None, rgbdB] poses = poses.get_poses(self.root, 0, self.dt_frame) poseA = poses[2] poses[2] = poses[1] poses[1] = poseA else: data, poses = self.load_rgbd(index) else: data, poses = self.load_events(index) return data, poses def load(self, path): self.camera = Camera.load_from_json(path) self.event_camera = Camera.load_from_json(path, filename='dvs') self.dt_event = 1e8 / 3 self.dt_frame = 1e8 / 3 self.path = path self.load_data() self.raw_events = np.load(os.path.join(path, 'fevents.npz')) self.raw_events = self.raw_events[self.raw_events.files[0]] self.raw_events = pd.DataFrame( data=self.raw_events, columns=['Timestamp', 'X', 'Y', 'Polarity']) self.raw_events.Timestamp *= 1000 self.raw_events = self.raw_events[['Polarity', 'Timestamp', 'X', 'Y']] self.dead_pixel = [(151, 205)] for dead_pixel in self.dead_pixel: self.raw_events = self.raw_events[~( (self.raw_events.X == dead_pixel[0]) & (self.raw_events.Y == dead_pixel[1]))] self.frame_ts = np.load(os.path.join(path, 'ts_frames.npz')) self.frame_ts = self.frame_ts[self.frame_ts.files[0]] self.frame_ts *= 1000 poses_path = os.path.join(path, 'poses.npy') if os.path.exists(poses_path): self.poses = np.load(poses_path) else: print("WARNING: Poses not found") self.poses = None self.matrix_transformation = Transform() np_mat = np.load(os.path.join(path, 'transfo_mat.npy')) np_mat[0:3, -1] /= 1000 self.matrix_transformation.matrix = np_mat self.size = len( self.raw_frames) * self.frame_number - self.frame_number self.unload_data() def load_data(self): self.raw_frames = np.load(os.path.join(self.path, 'frames.npz')) self.raw_frames = self.raw_frames[self.raw_frames.files[0]] def unload_data(self): del self.raw_frames def _get_poses(self, indexA, indexB, transform=False): if self.poses is None: return None, None, None indexA = indexA indexB = indexB poseA = Transform.from_parameters(*self.poses[indexA], is_degree=True) poseB = Transform.from_parameters(*self.poses[indexB], is_degree=True) if transform: pose_A_flip = Transform.scale(1, -1, -1).combine(poseA) pose_A_flip = self.matrix_transformation.combine(pose_A_flip, copy=True) poseA = Transform().scale(1, -1, -1).combine(pose_A_flip, copy=True) pose_B_flip = Transform.scale(1, -1, -1).combine(poseB) pose_B_flip = self.matrix_transformation.combine(pose_B_flip, copy=True) poseB = Transform().scale(1, -1, -1).combine(pose_B_flip, copy=True) delta = delta_transform( poseA, poseB).to_parameters(isDegree=True).astype(np.float32) return delta, poseA, poseB def __len__(self): return len(self.raw_frames) - 1 def load_rgbd(self, index): pose = self._get_poses(index, index)[1] rgbd = self.raw_frames[index] rgbd = (rgbd[:, :, 2::-1].astype(np.uint8), rgbd[:, :, 3]) return rgbd, pose def _get_events(self, index): start_t = self.frame_ts[index] end_t = self.frame_ts[index + 1] delta = (end_t - start_t) end_t = start_t + delta events = self.raw_events[(self.raw_events.Timestamp >= start_t) & (self.raw_events.Timestamp < end_t)] events.rename(columns={'Timestamp': 'time'}, inplace=True) events.time -= start_t return events def load_events(self, index): pose = self._get_poses(index, index, transform=True) return self._get_events(index), pose