commit 3588a3ebea472623dce537a528801ac6b441fac2 Author: BorisIvanovic Date: Mon Jan 13 10:55:45 2020 -0800 Initial public release. diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000..019b8e4 --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "data/nuScenes/nuscenes-devkit"] + path = data/nuScenes/nuscenes-devkit + url = https://github.com/nutonomy/nuscenes-devkit diff --git a/README.md b/README.md new file mode 100644 index 0000000..3f44d4b --- /dev/null +++ b/README.md @@ -0,0 +1,56 @@ +# Trajectron++: Multi-Agent Generative Trajectory Forecasting With Heterogeneous Data for Control # + +This repository contains the code for [Trajectron++: Multi-Agent Generative Trajectory Forecasting With Heterogeneous Data for Control](https://arxiv.org/abs/2001.03093) by Tim Salzmann\*, Boris Ivanovic\*, Punarjay Chakravarty, and Marco Pavone (\* denotes equal contribution). + +Specifically, this branch is for the Trajectron++ applied to the nuScenes autonomous driving dataset. + +## Installation ## + +### Note about Submodules ### +When cloning this branch, make sure you clone the submodules as well, with the following command: +``` +git clone --recurse-submodules +``` +Alternatively, you can clone the repository as normal and then load submodules later with: +``` +git submodule init # Initializing our local configuration file +git submodule update # Fetching all of the data from the submodules at the specified commits +``` + +### Environment Setup ### + +First, we'll create a conda environment to hold the dependencies. +``` +conda create --name trajectron++ python=3.6 -y +source activate trajectron++ +pip install -r requirements.txt +``` + +Then, since this project uses IPython notebooks, we'll install this conda environment as a kernel. +``` +python -m ipykernel install --user --name trajectron++ --display-name "Python 3.6 (Trajectron++)" +``` + +Now, you can start a Jupyter session and view/run all the notebooks in `code/notebooks` with +``` +jupyter notebook +``` + +When you're done, don't forget to deactivate the conda environment with +``` +source deactivate +``` + +## Scripts ## + +Run any of these with a `-h` or `--help` flag to see all available command arguments. +* `code/train.py` - Trains a new Trajectron++ model. +* `code/notebooks/run_eval.bash` - Evaluates the performance of the Trajectron++. This script mainly collects evaluation data, which can then be visualized with `code/notebooks/NuScenes Quantitative.ipynb`. +* `data/nuScenes/process_nuScenes.py` - Processes the nuScenes dataset into a format that the Trajectron++ can directly work with, following our internal structures for handling data (see `code/data` for more information). +* `code/notebooks/NuScenes Qualitative.ipynb` - Visualizes the predictions that the Trajectron++ makes. + +## Datasets ## + +A sample of fully-processed scenes from the nuScenes dataset are available in this repository, in `data/processed`. + +If you want the *original* nuScenes dataset, you can find it here: [nuScenes Dataset](https://www.nuscenes.org/). diff --git a/code/config.json b/code/config.json new file mode 100644 index 0000000..758add6 --- /dev/null +++ b/code/config.json @@ -0,0 +1,108 @@ +{ + + "batch_size": 256, + "grad_clip": 1.0, + + "learning_rate_style": "exp", + "learning_rate": 0.002, + "min_learning_rate": 0.0005, + "learning_decay_rate": 0.9995, + + "prediction_horizon": 6, + "minimum_history_length": 1, + "maximum_history_length": 8, + + "map_context": 120, + "map_enc_num_layers": 4, + "map_enc_hidden_size": 512, + "map_enc_output_size": 512, + "map_enc_dropout": 0.5, + + "alpha": 1, + "k": 30, + "k_eval": 200, + "use_iwae": false, + "kl_exact": true, + + "kl_min": 0.07, + "kl_weight": 5.0, + "kl_weight_start": 0, + "kl_decay_rate": 0.99995, + "kl_crossover": 500, + "kl_sigmoid_divisor": 4, + + "inf_warmup": 1.0, + "inf_warmup_start": 1.0, + "inf_warmup_crossover": 1500, + "inf_warmup_sigmoid_divisor": 4, + + "rnn_kwargs": { + "dropout_keep_prob": 0.5 + }, + "MLP_dropout_keep_prob": 0.9, + "rnn_io_dropout_keep_prob": 1.0, + "enc_rnn_dim_multiple_inputs": 8, + "enc_rnn_dim_edge": 8, + "enc_rnn_dim_edge_influence": 8, + "enc_rnn_dim_history": 32, + "enc_rnn_dim_future": 32, + "dec_rnn_dim": 512, + "dec_GMM_proj_MLP_dims": null, + "sample_model_during_dec": true, + "dec_sample_model_prob_start": 1.00, + "dec_sample_model_prob_final": 1.00, + "dec_sample_model_prob_crossover": 200, + "dec_sample_model_prob_divisor": 4, + "q_z_xy_MLP_dims": null, + "p_z_x_MLP_dims": 32, + "fuzz_factor": 0.05, + "GMM_components": 12, + "log_sigma_min": -10, + "log_sigma_max": 10, + "log_p_yt_xz_max": 50, + "N": 2, + "K": 5, + "tau_init": 2.0, + "tau_final": 0.05, + "tau_decay_rate": 0.997, + "use_z_logit_clipping": true, + "z_logit_clip_start": 0.05, + "z_logit_clip_final": 5.0, + "z_logit_clip_crossover": 500, + "z_logit_clip_divisor": 5, + + "state": { + "PEDESTRIAN": { + "position": ["x", "y"], + "velocity": ["x", "y"], + "acceleration": ["x", "y"], + "heading": ["value"] + }, + "BICYCLE": { + "position": ["x", "y"], + "velocity": ["x", "y", "m"], + "acceleration": ["x", "y", "m"], + "heading": ["value"] + }, + "VEHICLE": { + "position": ["x", "y"], + "velocity": ["x", "y", "m"], + "acceleration": ["x", "y", "m"], + "heading": ["value"] + } + }, + + "pred_state": { + "PEDESTRIAN": { + "velocity": ["x", "y"] + }, + "BICYCLE": { + "velocity": ["x", "y"] + }, + "VEHICLE": { + "velocity": ["x", "y"] + } + }, + + "log_histograms": false +} \ No newline at end of file diff --git a/code/data/__init__.py b/code/data/__init__.py new file mode 100644 index 0000000..663be5b --- /dev/null +++ b/code/data/__init__.py @@ -0,0 +1,5 @@ +from .data_structures import Position, Velocity, Acceleration, Orientation, Map, ActuatorAngle, Scalar +from .scene import Scene +from .node import Node, BicycleNode +from .scene_graph import TemporalSceneGraph +from .environment import Environment diff --git a/code/data/data_structures.py b/code/data/data_structures.py new file mode 100644 index 0000000..d8a4b72 --- /dev/null +++ b/code/data/data_structures.py @@ -0,0 +1,163 @@ +import numpy as np +from scipy.ndimage.interpolation import rotate + + +class MotionEntity(object): + def __init__(self, x, y, z=None): + self.x = x + self.y = y + self.z = z + self.m = None + + @property + def l(self): + if self.z is not None: + return np.linalg.norm(np.vstack((self.x, self.y, self.z)), axis=0) + else: + return np.linalg.norm(np.vstack((self.x, self.y)), axis=0) + + +class Position(MotionEntity): + pass + + +class Velocity(MotionEntity): + @staticmethod + def from_position(position, dt=1): + dx = np.zeros_like(position.x) * np.nan + dx[~np.isnan(position.x)] = np.gradient(position.x[~np.isnan(position.x)], dt) + + dy = np.zeros_like(position.y) * np.nan + dy[~np.isnan(position.y)] = np.gradient(position.y[~np.isnan(position.y)], dt) + + if position.z is not None: + dz = np.zeros_like(position.z) * np.nan + dz[~np.isnan(position.z)] = np.gradient(position.z[~np.isnan(position.z)], dt) + else: + dz = None + + return Velocity(dx, dy, dz) + + +class Acceleration(MotionEntity): + @staticmethod + def from_velocity(velocity, dt=1): + ddx = np.zeros_like(velocity.x) * np.nan + ddx[~np.isnan(velocity.x)] = np.gradient(velocity.x[~np.isnan(velocity.x)], dt) + + ddy = np.zeros_like(velocity.y) * np.nan + ddy[~np.isnan(velocity.y)] = np.gradient(velocity.y[~np.isnan(velocity.y)], dt) + + if velocity.z is not None: + ddz = np.zeros_like(velocity.z) * np.nan + ddz[~np.isnan(velocity.z)] = np.gradient(velocity.z[~np.isnan(velocity.z)], dt) + else: + ddz = None + + return Acceleration(ddx, ddy, ddz) + + +class ActuatorAngle(object): + def __init__(self): + pass + + +class Scalar(object): + def __init__(self, value): + self.value = value + self.derivative = None + +# TODO Finish +class Orientation(object): + def __init__(self, x, y, z, w): + self.x = x + self.y = y + self.z = z + self.w = w + + +class Map(object): + def __init__(self, data=None, homography=None, description=None, data_file=""): + self.data = data + self.homography = homography + self.description = description + self.uint = False + self.data_file = data_file + self.rotated_maps_origin = None + self.rotated_maps = None + if self.data.dtype == np.uint8: + self.uint = True + + @property + def fdata(self): + if self.uint: + return self.data / 255. + else: + return self.data + + def to_map_points(self, world_pts): + org_shape = None + if len(world_pts.shape) > 2: + org_shape = world_pts.shape + world_pts = world_pts.reshape((-1, 2)) + N, dims = world_pts.shape + points_with_one = np.ones((dims + 1, N)) + points_with_one[:dims] = world_pts.T + map_points = (self.homography @ points_with_one).T[..., :dims] # TODO There was np.fliplr here for pedestrian dataset. WHY? + if org_shape is not None: + map_points = map_points.reshape(org_shape) + return map_points + + def to_rotated_map_points(self, world_pts, rotation_angle): + rotation_rad = -rotation_angle * np.pi / 180 + rot_mat = np.array([[np.cos(rotation_rad), np.sin(rotation_rad), 0.], + [-np.sin(rotation_rad), np.cos(rotation_rad), 0.], + [0., 0., 1.]]) + org_map_points = self.to_map_points(world_pts) + 1 + + org_shape = None + if len(org_map_points.shape) > 2: + org_shape = org_map_points.shape + org_map_points = org_map_points.reshape((-1, 2)) + N, dims = org_map_points.shape + points_with_one = np.ones((dims + 1, N)) + points_with_one[:dims] = org_map_points.T + org_map_pts_rot = (rot_mat @ points_with_one).T[..., :dims] + if org_shape is not None: + org_map_pts_rot = org_map_pts_rot.reshape(org_shape) + + map_pts_rot = self.rotated_maps_origin + org_map_pts_rot + return map_pts_rot + + def calculate_rotations(self): + org_shape = self.data.shape + l = (np.ceil(np.sqrt(org_shape[0]**2 + org_shape[1]**2)) * 2).astype(int) + 1 + rotated_maps = np.zeros((360, l, l, org_shape[2]), dtype=np.uint8) + o = np.array([l // 2, l // 2]) + rotated_maps[0, o[0]+1:o[0]+org_shape[0]+1, o[1]+1:o[1]+org_shape[1]+1] = self.data + for i in range(1, 360): + rotated_maps[i] = rotate(rotated_maps[0], reshape=False, angle=i, prefilter=False) + rotated_maps[0] = rotate(rotated_maps[0], reshape=False, angle=0, prefilter=False) + self.rotated_maps_origin = o + self.rotated_maps = rotated_maps + + # def __getstate__(self): + # with open(self.data_file, 'w') as f: + # np.save(f, self.rotated_maps) + # self.rotated_maps = None + # state = self.__dict__.copy() + # return state + # + # def __setstate__(self, state): + # self.__dict__.update(state) + # with open(self.data_file, 'r') as f: + # self.rotated_maps = np.load(f) + +if __name__ == "__main__": + img = np.zeros((103, 107, 3)) + img[57, 84] = 255. + homography = np.array([[1., 0., 0.], [0., 1., 0.], [0., 0., 1.]]) + m = Map(data=img, homography=homography) + m.calculate_rotations() + t = m.to_rotated_map_points(np.array([[57, 84]]), 0).astype(int) + print(m.rotated_maps[0, t[0, 0], t[0, 1]]) \ No newline at end of file diff --git a/code/data/environment.py b/code/data/environment.py new file mode 100644 index 0000000..9a3ef21 --- /dev/null +++ b/code/data/environment.py @@ -0,0 +1,74 @@ +import numpy as np +from enum import Enum +from itertools import product + + +class Environment(object): + def __init__(self, node_type_list, standardization, scenes=None, attention_radius=None): + self.scenes = scenes + self.node_type_list = node_type_list + self.attention_radius = attention_radius + self.NodeType = Enum('NodeType', node_type_list) + + self.standardization = standardization + + def get_edge_types(self): + return [e for e in product([node_type for node_type in self.NodeType], repeat=2)] + + def edge_type_str(self, edge_type): + return edge_type[0].name + '-' + edge_type[1].name + + def get_standardize_params(self, state, node_type): + standardize_mean_list = list() + standardize_std_list = list() + for entity, dims in state.items(): + for dim in dims: + standardize_mean_list.append(self.standardization[node_type.name][entity][dim]['mean']) + standardize_std_list.append(self.standardization[node_type.name][entity][dim]['std']) + standardize_mean = np.stack(standardize_mean_list) + standardize_std = np.stack(standardize_std_list) + + return standardize_mean, standardize_std + + def standardize(self, array, state, node_type, mean=None, std=None): + if mean is None and std is None: + mean, std = self.get_standardize_params(state, node_type) + elif mean is None and std is not None: + mean, _ = self.get_standardize_params(state, node_type) + elif mean is not None and std is None: + _, std = self.get_standardize_params(state, node_type) + return np.where(np.isnan(array), np.array(np.nan), (array - mean) / std) + + def unstandardize(self, array, state, node_type, mean=None, std=None): + if mean is None and std is None: + mean, std = self.get_standardize_params(state, node_type) + elif mean is None and std is not None: + mean, _ = self.get_standardize_params(state, node_type) + elif mean is not None and std is None: + _, std = self.get_standardize_params(state, node_type) + return array * std + mean + + # These two functions have to be implemented as pickle can not handle dynamic enums + def __getstate__(self): + for scene in self.scenes: + for node in scene.nodes: + node.type = node.type.name + attention_radius_no_enum = dict() + for key, value in self.attention_radius.items(): + attention_radius_no_enum[(key[0].name, key[1].name)] = value + self.attention_radius = attention_radius_no_enum + self.NodeType = None + state = self.__dict__.copy() + return state + + def __setstate__(self, state): + self.__dict__.update(state) + self.NodeType = Enum('NodeType', self.node_type_list) + for scene in self.scenes: + for node in scene.nodes: + node.type = getattr(self.NodeType, node.type) + attention_radius_enum = dict() + for key, value in self.attention_radius.items(): + attention_radius_enum[(getattr(self.NodeType, key[0]), getattr(self.NodeType, key[1]))] = value + self.attention_radius = attention_radius_enum + diff --git a/code/data/node.py b/code/data/node.py new file mode 100644 index 0000000..c1d8cff --- /dev/null +++ b/code/data/node.py @@ -0,0 +1,264 @@ +import numpy as np +from pyquaternion import Quaternion +from . import ActuatorAngle +from scipy.interpolate import splrep, splev, CubicSpline +from scipy.integrate import cumtrapz + + +class Node(object): + def __init__(self, type, position=None, velocity=None, acceleration=None, heading=None, orientation=None, + length=None, width=None, height=None, first_timestep=0, is_robot=False): + self.type = type + self.position = position + self.heading = heading + self.length = length + self.wdith = width + self.height = height + self.orientation = orientation + self.velocity = velocity + self.acceleration = acceleration + self.first_timestep = first_timestep + self.dimensions = ['x', 'y', 'z'] + self.is_robot = is_robot + self._last_timestep = None + self.description = "" + + def __repr__(self): + return self.type.name + + def scene_ts_to_node_ts(self, scene_ts): + """ + Transforms timestamp from scene into timeframe of node data. + :param scene_ts: Scene timesteps + :return: ts: Transformed timesteps, paddingl: Number of timesteps in scene range which are not available in + node data before data is available. paddingu: Number of timesteps in scene range which are not + available in node data after data is available. + """ + paddingl = (self.first_timestep - scene_ts[0]).clip(0) + paddingu = (scene_ts[1] - self.last_timestep).clip(0) + ts = np.array(scene_ts).clip(min=self.first_timestep, max=self.last_timestep) - self.first_timestep + return ts, paddingl, paddingu + + def history_points_at(self, ts): + """ + Number of history points in trajectory. Timestep is exclusive. + :param ts: Scene timestep where the number of history points are queried. + :return: Number of history timesteps. + """ + return ts - self.first_timestep + + def get_entity(self, ts_scene, entity, dims, padding=np.nan): + if ts_scene.size == 1: + ts_scene = np.array([ts_scene, ts_scene]) + length = ts_scene[1] - ts_scene[0] + 1 # ts is inclusive + entity_array = np.zeros((length, len(dims))) * padding + ts, paddingl, paddingu = self.scene_ts_to_node_ts(ts_scene) + entity_array[paddingl:length - paddingu] = np.array([getattr(getattr(self, entity), d)[ts[0]:ts[1]+1] for d in dims]).T + return entity_array + + def get(self, ts_scene, state, padding=np.nan): + return np.hstack([self.get_entity(ts_scene, entity, dims, padding) for entity, dims in state.items()]) + + + @property + def timesteps(self): + return self.position.x.size + + @property + def last_timestep(self): + if self._last_timestep is None: + self._last_timestep = self.first_timestep + self.timesteps - 1 + return self._last_timestep + + +class BicycleNode(Node): + def __init__(self, type, position=None, velocity=None, acceleration=None, heading=None, orientation=None, + length=None, width=None, height=None, first_timestep=0, actuator_angle=None): + super().__init__(type, position=position, velocity=velocity, acceleration=acceleration, heading=heading, + orientation=orientation, length=length, width=width, height=height, + first_timestep=first_timestep) + self.actuator_angle = actuator_angle + + # TODO Probably wrong. Differential of magnitude is not euqal to the the magnitude of the differentials + def calculate_steering_angle_old(self, vel_tresh=0.0): + vel = np.linalg.norm(np.hstack((np.expand_dims(self.velocity.x, 1), np.expand_dims(self.velocity.y, 1))), axis=1) + + beta = np.arctan2(self.velocity.y, self.velocity.x) - self.heading.value + beta[vel < vel_tresh] = 0. + steering_angle = np.arctan2(2 * np.sin(beta), np.cos(beta)) + steering_angle[np.abs(steering_angle) > np.pi / 2] = 0 # Velocity Outlier + + aa = ActuatorAngle() + aa.steering_angle = np.zeros_like(np.arctan2(2 * np.sin(beta), np.cos(beta))) + self.actuator_angle = aa + + def calculate_steering_angle(self, dt, steering_tresh=0.0, vel_tresh=0.0): + t = np.arange(0, self.timesteps * dt, dt) + s = 0.01 * len(t) + #c_pos_x_g_x_tck = CubicSpline(t, np.array(pos_x_filtert)) + #c_pos_y_g_x_tck = CubicSpline(t, np.array(pos_y_filtert)) + #c_pos_x_g_x_tck = splrep(t, self.position.x, s=s) + #c_pos_y_g_x_tck = splrep(t, self.position.y, s=s) + + #vel_x_g = c_pos_x_g_x_tck(t, 1) + #vel_y_g = c_pos_y_g_x_tck(t, 1) + #vel_x_g = splev(t, c_pos_x_g_x_tck, der=1) + #vel_y_g = splev(t, c_pos_y_g_x_tck, der=1) + + vel_x_g = self.velocity.x + vel_y_g = self.velocity.y + + v_x_ego = [] + h = [] + for t in range(self.timesteps): + dh_max = 1.2 / self.length * (np.linalg.norm(np.array([vel_x_g[t], vel_y_g[t]]))) + heading = np.arctan2(vel_y_g[t], vel_x_g[t]) + #if len(h) > 0 and np.abs(heading - h[-1]) > dh_max: + # heading = h[-1] + h.append(heading) + q = Quaternion(axis=(0.0, 0.0, 1.0), radians=heading) + v_x_ego_t = q.inverse.rotate(np.array([vel_x_g[t], vel_y_g[t], 1]))[0] + if v_x_ego_t < 0.0: + v_x_ego_t = 0. + v_x_ego.append(v_x_ego_t) + + v_x_ego = np.stack(v_x_ego, axis=0) + h = np.stack(h, axis=0) + + dh = np.gradient(h, dt) + + sa = np.arctan2(dh * self.length, v_x_ego) + sa[(dh == 0.) | (v_x_ego == 0.)] = 0. + sa = sa.clip(min=-steering_tresh, max=steering_tresh) + + a = np.gradient(v_x_ego, dt) + # int = self.integrate_bicycle_model(np.array([a]), + # sa, + # np.array([h[0]]), + # np.array([self.position.x[0], + # self.position.y[0]]), + # v_x_ego[0], + # self.length, 0.5) + # p = np.stack((self.position.x, self.position.y), axis=1) + # + # #assert ((int[0] - p) < 1.0).all() + + aa = ActuatorAngle() + aa.steering_angle = sa + self.acceleration.m = a + self.actuator_angle = aa + + def inverse_np_gradient(self, f, dx, F0=0.): + N = f.shape[0] + l = f.shape[-1] + l2 = np.ceil(l / 2).astype(int) + return (F0 + + ((2 * dx) * + np.c_['-1', + np.r_['-1', np.zeros((N, 1)), f[..., 1:-1:2].cumsum(axis=-1)], + f[..., ::2].cumsum(axis=-1) - f[..., [0]] / 2] + ).reshape((N, 2, l2)).reshape(N, 2 * l2, order='F')[:, :l] + ) + + def integrate_trajectory(self, v, x0, dt): + xd_ = self.inverse_np_gradient(v[..., 0], dx=dt, F0=x0[0]) + yd_ = self.inverse_np_gradient(v[..., 1], dx=dt, F0=x0[1]) + integrated = np.stack([xd_, yd_], axis=2) + return integrated + + def integrate_bicycle_model(self, a, sa, h0, x0, v0, l, dt): + v_m = self.inverse_np_gradient(a, dx=0.5, F0=v0) + + dh = (np.tan(sa) / l) * v_m[0] + h = self.inverse_np_gradient(np.array([dh]), dx=dt, F0=h0) + + vx = np.cos(h) * v_m + vy = np.sin(h) * v_m + + v = np.stack((vx, vy), axis=2) + return self.integrate_trajectory(v, x0, dt) + + def calculate_steering_angle_keep(self, dt, steering_tresh=0.0, vel_tresh=0.0): + + vel_approx = np.linalg.norm(np.stack((self.velocity.x, self.velocity.y), axis=0), axis=0) + mask = np.ones_like(vel_approx) + mask[vel_approx < vel_tresh] = 0 + + t = np.arange(0, self.timesteps * dt, dt) + pos_x_filtert = [] + pos_y_filtert = [] + s = None + for i in range(mask.size): + if mask[i] == 0 and s is None: + s = i + elif mask[i] != 0 and s is not None: + t_start = t[s-1] + pos_x_start = self.position.x[s-1] + pos_y_start = self.position.y[s-1] + t_mean = t[s:i].mean() + pos_x_mean = self.position.x[s:i].mean() + pos_y_mean = self.position.y[s:i].mean() + t_end = t[i] + pos_x_end = self.position.x[i] + pos_y_end = self.position.y[i] + for step in range(s, i+1): + if t[step] <= t_mean: + pos_x_filtert.append(pos_x_start + ((t[step] - t_start) / (t_mean - t_start)) * (pos_x_mean - pos_x_start)) + pos_y_filtert.append(pos_y_start + ((t[step] - t_start) / (t_mean - t_start)) * (pos_y_mean - pos_y_start)) + else: + pos_x_filtert.append(pos_x_mean + ((t[step] - t_end) / (t_end - t_mean)) * (pos_x_end - pos_x_mean)) + pos_y_filtert.append(pos_y_mean + ((t[step] - t_end) / (t_end - t_mean)) * (pos_y_end - pos_y_mean)) + s = None + elif mask[i] != 0 and s is None: + pos_x_filtert.append(self.position.x[i].mean()) + pos_y_filtert.append(self.position.y[i].mean()) + if s is not None: + t_start = t[s - 1] + pos_x_start = self.position.x[s - 1] + pos_y_start = self.position.y[s - 1] + t_mean = t[s:i].max() + pos_x_mean = self.position.x[s:i].mean() + pos_y_mean = self.position.y[s:i].mean() + for step in range(s, i+1): + pos_x_filtert.append( + pos_x_start + ((t[step] - t_start) / (t_mean - t_start)) * (pos_x_mean - pos_x_start)) + pos_y_filtert.append( + pos_y_start + ((t[step] - t_start) / (t_mean - t_start)) * (pos_y_mean - pos_y_start)) + + s = 0.001 * len(t) + #c_pos_x_g_x_tck = CubicSpline(t, np.array(pos_x_filtert)) + #c_pos_y_g_x_tck = CubicSpline(t, np.array(pos_y_filtert)) + c_pos_x_g_x_tck = splrep(t, np.array(pos_x_filtert), s=s) + c_pos_y_g_x_tck = splrep(t, np.array(pos_y_filtert), s=s) + + #vel_x_g = c_pos_x_g_x_tck(t, 1) + #vel_y_g = c_pos_y_g_x_tck(t, 1) + vel_x_g = splev(t, c_pos_x_g_x_tck, der=1) + vel_y_g = splev(t, c_pos_y_g_x_tck, der=1) + + v_x_ego = [] + h = [] + for t in range(self.timesteps): + dh_max = 1.19 / self.length * (np.linalg.norm(np.array([vel_x_g[t], vel_y_g[t]]))) + heading = np.arctan2(vel_y_g[t], vel_x_g[t]) + if len(h) > 0 and np.abs(heading - h[-1]) > dh_max: + heading = h[-1] + h.append(heading) + q = Quaternion(axis=(0.0, 0.0, 1.0), radians=heading) + v_x_ego_t = q.inverse.rotate(np.array([vel_x_g[t], vel_y_g[t], 1]))[0] + if v_x_ego_t < 0.0: + v_x_ego_t = 0. + v_x_ego.append(v_x_ego_t) + + v_x_ego = np.stack(v_x_ego, axis=0) + h = np.stack(h, axis=0) + + dh = np.gradient(h, dt) + + sa = np.arctan2(dh * self.length, v_x_ego) + sa[dh == 0.] = 0. + + aa = ActuatorAngle() + aa.steering_angle = sa + self.actuator_angle = aa + diff --git a/code/data/scene.py b/code/data/scene.py new file mode 100644 index 0000000..db4d4b9 --- /dev/null +++ b/code/data/scene.py @@ -0,0 +1,102 @@ +import numpy as np +from .scene_graph import TemporalSceneGraph + + +class Scene(object): + def __init__(self, map=None, timesteps=0, dt=1, name=""): + self.map = map + self.timesteps = timesteps + self.dt = dt + self.name = name + + self.nodes = [] + + self.robot = None + + self.temporal_scene_graph = None + + self.description = "" + + def get_scene_graph(self, timestep, attention_radius=None, edge_addition_filter=None, edge_removal_filter=None): + if self.temporal_scene_graph is None: + timestep_range = np.array([timestep - len(edge_addition_filter), timestep + len(edge_removal_filter)]) + node_pos_dict = dict() + present_nodes = self.present_nodes(np.array([timestep])) + + for node in present_nodes[timestep]: + node_pos_dict[node] = np.squeeze(node.get(timestep_range, {'position': ['x', 'y']})) + tsg = TemporalSceneGraph.create_from_temp_scene_dict(node_pos_dict, + attention_radius, + duration=(len(edge_addition_filter) + + len(edge_removal_filter) + 1), + edge_addition_filter=edge_addition_filter, + edge_removal_filter=edge_removal_filter + ) + + return tsg.to_scene_graph(t=len(edge_addition_filter), + t_hist=len(edge_addition_filter), + t_fut=len(edge_removal_filter)) + else: + return self.temporal_scene_graph.to_scene_graph(timestep, + len(edge_addition_filter), + len(edge_removal_filter)) + + def calculate_scene_graph(self, attention_radius, state, edge_addition_filter=None, edge_removal_filter=None): + timestep_range = np.array([0, self.timesteps-1]) + node_pos_dict = dict() + + for node in self.nodes: + node_pos_dict[node] = np.squeeze(node.get(timestep_range, {'position': ['x', 'y']})) + + self.temporal_scene_graph = TemporalSceneGraph.create_from_temp_scene_dict(node_pos_dict, + attention_radius, + duration=self.timesteps, + edge_addition_filter=edge_addition_filter, + edge_removal_filter=edge_removal_filter) + + def length(self): + return self.timesteps * self.dt + + def present_nodes(self, timesteps, type=None, min_history_timesteps=0, min_future_timesteps=0, include_robot=True, max_nodes=None, curve=False): # TODO REMOVE + present_nodes = {} + + picked_nodes = 0 + + rand_idx = np.random.choice(len(self.nodes), len(self.nodes), replace=False) + + for i in rand_idx: + node = self.nodes[i] + if node.is_robot and not include_robot: + continue + if type is None or node.type == type: + if curve and node.type.name == 'VEHICLE': + if 'curve' not in node.description and np.random.rand() > 0.1: + continue + lower_bound = timesteps - min_history_timesteps + upper_bound = timesteps + min_future_timesteps + mask = (node.first_timestep <= lower_bound) & (upper_bound <= node.last_timestep) + if mask.any(): + timestep_indices_present = np.nonzero(mask)[0] + for timestep_index_present in timestep_indices_present: + if timesteps[timestep_index_present] in present_nodes.keys(): + present_nodes[timesteps[timestep_index_present]].append(node) + else: + present_nodes[timesteps[timestep_index_present]] = [node] + picked_nodes += 1 + if max_nodes is not None and picked_nodes >= max_nodes: + break + + if max_nodes is not None and picked_nodes >= max_nodes: + break + + return present_nodes + + def sample_timesteps(self, batch_size, min_future_timesteps=0): + if batch_size > self.timesteps: + batch_size = self.timesteps + return np.random.choice(np.arange(0, self.timesteps-min_future_timesteps), size=batch_size, replace=False) + + def __repr__(self): + return f"Scene: Duration: {self.length()}s," \ + f" Nodes: {len(self.nodes)}," \ + f" Map: {'Yes' if self.map is not None else 'No'}." diff --git a/code/data/scene_graph.py b/code/data/scene_graph.py new file mode 100644 index 0000000..fef1ba6 --- /dev/null +++ b/code/data/scene_graph.py @@ -0,0 +1,173 @@ +import numpy as np +from scipy.spatial.distance import pdist, squareform +import scipy.signal as ss +from collections import defaultdict +import warnings + + +class TemporalSceneGraph(object): + def __init__(self, + edge_radius, + nodes=None, + adj_cube=np.zeros((1, 0, 0)), + weight_cube=np.zeros((1, 0, 0)), + node_type_mat=np.zeros((0, 0)), + edge_scaling=None): + self.edge_radius = edge_radius + self.nodes = nodes + if nodes is None: + self.nodes = np.array([]) + self.adj_cube = adj_cube + self.weight_cube = weight_cube + self.node_type_mat = node_type_mat + self.adj_mat = np.max(self.adj_cube, axis=0).clip(max=1.0) + self.edge_scaling = edge_scaling + self.node_index_lookup = None + self.calculate_node_index_lookup() + + def calculate_node_index_lookup(self): + node_index_lookup = dict() + for i, node in enumerate(self.nodes): + node_index_lookup[node] = i + + self.node_index_lookup = node_index_lookup + + def get_num_edges(self, t=0): + return np.sum(self.adj_cube[t]) // 2 + + def get_index(self, node): + return self.node_index_lookup[node] + + @staticmethod + def get_edge_type(n1, n2): + return '-'.join(sorted([str(n1), str(n2)])) + + @classmethod + def create_from_temp_scene_dict(cls, + scene_temp_dict, + attention_radius, + duration=1, + edge_addition_filter=None, + edge_removal_filter=None): + """ + Construct a spatiotemporal graph from agent positions in a dataset. + + returns: sg: An aggregate SceneGraph of the dataset. + """ + nodes = scene_temp_dict.keys() + N = len(nodes) + total_timesteps = duration + + position_cube = np.zeros((total_timesteps, N, 2)) + + adj_cube = np.zeros((total_timesteps, N, N), dtype=np.int8) + dist_cube = np.zeros((total_timesteps, N, N), dtype=np.float) + + node_type_mat = np.zeros((N, N), dtype=np.int8) + node_attention_mat = np.zeros((N, N), dtype=np.float) + + for node_idx, node in enumerate(nodes): + position_cube[:, node_idx] = scene_temp_dict[node] + node_type_mat[:, node_idx] = node.type.value + for node_idx_from, node_from in enumerate(nodes): + node_attention_mat[node_idx_from, node_idx] = attention_radius[(node_from.type, node.type)] + + np.fill_diagonal(node_type_mat, 0) + agg_adj_matrix = np.zeros((N, N), dtype=np.int8) + + for timestep in range(position_cube.shape[0]): + dists = squareform(pdist(position_cube[timestep], metric='euclidean')) + + # Put a 1 for all agent pairs which are closer than the edge_radius. + # Can produce a warning as dists can be nan if no data for node is available. + # This is accepted as nan <= x evaluates to False + with warnings.catch_warnings(): + warnings.simplefilter("ignore") + adj_matrix = (dists <= node_attention_mat).astype(np.int8) * node_type_mat + + # Remove self-loops. + np.fill_diagonal(adj_matrix, 0) + + agg_adj_matrix |= adj_matrix + + adj_cube[timestep] = adj_matrix + dist_cube[timestep] = dists + + dist_cube[np.isnan(dist_cube)] = 0. + weight_cube = np.divide(1., + dist_cube, + out=np.zeros_like(dist_cube), + where=(dist_cube > 0.)) + edge_scaling = None + if edge_addition_filter is not None and edge_removal_filter is not None: + edge_scaling = cls.calculate_edge_scaling(adj_cube, edge_addition_filter, edge_removal_filter) + sg = cls(attention_radius, np.array(list(nodes)), adj_cube, weight_cube, node_type_mat, edge_scaling=edge_scaling) + return sg + + @staticmethod + def calculate_edge_scaling(adj_cube, edge_addition_filter, edge_removal_filter): + new_edges = np.minimum( + ss.convolve(adj_cube, np.reshape(edge_addition_filter, (-1, 1, 1)), 'same'), 1. + ) + + old_edges = np.minimum( + ss.convolve(adj_cube, np.reshape(edge_removal_filter, (-1, 1, 1)), 'same'), 1. + ) + + return np.minimum(new_edges + old_edges, 1.) + + def to_scene_graph(self, t, t_hist=0, t_fut=0): + lower_t = np.clip(t-t_hist, a_min=0, a_max=None) + higher_t = np.clip(t + t_fut + 1, a_min=None, a_max=self.adj_cube.shape[0] + 1) + adj_mat = np.max(self.adj_cube[lower_t:higher_t], axis=0) + weight_mat = np.max(self.weight_cube[lower_t:higher_t], axis=0) + return SceneGraph(self.edge_radius, + self.nodes, + adj_mat, + weight_mat, + self.node_type_mat, + self.node_index_lookup, + edge_scaling=self.edge_scaling[t]) + + +class SceneGraph(object): + def __init__(self, + edge_radius, + nodes=None, + adj_mat=np.zeros((0, 0)), + weight_mat=np.zeros((0, 0)), + node_type_mat=np.zeros((0, 0)), + node_index_lookup=None, + edge_scaling=None): + self.edge_radius = edge_radius + self.nodes = nodes + if nodes is None: + self.nodes = np.array([]) + self.node_type_mat = node_type_mat + self.adj_mat = adj_mat + self.weight_mat = weight_mat + self.edge_scaling = edge_scaling + self.node_index_lookup = node_index_lookup + + def get_index(self, node): + return self.node_index_lookup[node] + + def get_neighbors(self, node, type): + node_index = self.get_index(node) + connection_mask = self.adj_mat[node_index].astype(bool) + mask = ((self.node_type_mat[node_index] == type.value) * connection_mask) + return self.nodes[mask] + + def get_edge_scaling(self, node=None): + if node is None: + return self.edge_scaling + else: + node_index = self.get_index(node) + return self.edge_scaling[node_index, self.adj_mat[node_index] > 0.] + + def get_edge_weight(self, node=None): + if node is None: + return self.weight_mat + else: + node_index = self.get_index(node) + return self.weight_mat[node_index, self.adj_mat[node_index] > 0.] \ No newline at end of file diff --git a/code/evaluation/__init__.py b/code/evaluation/__init__.py new file mode 100644 index 0000000..808fd76 --- /dev/null +++ b/code/evaluation/__init__.py @@ -0,0 +1 @@ +from .evaluation import compute_batch_statistics, log_batch_errors \ No newline at end of file diff --git a/code/evaluation/evaluation.py b/code/evaluation/evaluation.py new file mode 100644 index 0000000..9780080 --- /dev/null +++ b/code/evaluation/evaluation.py @@ -0,0 +1,106 @@ +import numpy as np +from scipy.interpolate import RectBivariateSpline +from scipy.ndimage import binary_dilation +from scipy.stats import gaussian_kde +from utils import prediction_output_to_trajectories +import visualization +from matplotlib import pyplot as plt + + +def compute_ade(predicted_trajs, gt_traj): + error = np.linalg.norm(predicted_trajs - gt_traj, axis=-1) + ade = np.mean(error, axis=-1) + return ade + + +def compute_fde(predicted_trajs, gt_traj): + final_error = np.linalg.norm(predicted_trajs[:, -1] - gt_traj[-1], axis=-1) + return final_error + + +def compute_kde_nll(predicted_trajs, gt_traj): + kde_ll = 0. + log_pdf_lower_bound = -20 + num_timesteps = gt_traj.shape[0] + + for timestep in range(num_timesteps): # TODO First timestep + kde = gaussian_kde(predicted_trajs[:, timestep].T) + pdf = np.clip(kde.logpdf(gt_traj[timestep].T), a_min=log_pdf_lower_bound, a_max=None)[0] + kde_ll += pdf / num_timesteps + + return -kde_ll + + +def compute_obs_violations(predicted_trajs, map): + obs_map = 1 - map.fdata[..., 0] + + interp_obs_map = RectBivariateSpline(range(obs_map.shape[0]), + range(obs_map.shape[1]), + obs_map, + kx=1, ky=1) + + old_shape = predicted_trajs.shape + pred_trajs_map = map.to_map_points(predicted_trajs.reshape((-1, 2))) + + traj_obs_values = interp_obs_map(pred_trajs_map[:, 0], pred_trajs_map[:, 1], grid=False) + traj_obs_values = traj_obs_values.reshape((old_shape[0], old_shape[1])) + num_viol_trajs = np.sum(traj_obs_values.max(axis=1) > 0, dtype=float) + + return num_viol_trajs + + +def compute_batch_statistics(prediction_output_dict, dt, max_hl, ph, node_type_enum, kde=True, obs=False, map=None): + + (prediction_dict, + _, + futures_dict) = prediction_output_to_trajectories(prediction_output_dict, dt, max_hl, ph) + + batch_error_dict = dict() + for node_type in node_type_enum: + batch_error_dict[node_type] = {'ade': list(), 'fde': list(), 'kde': list(), 'obs_viols': list()} + + for t in prediction_dict.keys(): + for node in prediction_dict[t].keys(): + ade_errors = compute_ade(prediction_dict[t][node], futures_dict[t][node]) + fde_errors = compute_fde(prediction_dict[t][node], futures_dict[t][node]) + if kde: + kde_ll = compute_kde_nll(prediction_dict[t][node], futures_dict[t][node]) + else: + kde_ll = 0 + if obs: + obs_viols = compute_obs_violations(prediction_dict[t][node], map) + else: + obs_viols = 0 + batch_error_dict[node.type]['ade'].extend(list(ade_errors)) + batch_error_dict[node.type]['fde'].extend(list(fde_errors)) + batch_error_dict[node.type]['kde'].extend([kde_ll]) + batch_error_dict[node.type]['obs_viols'].extend([obs_viols]) + + return batch_error_dict + + +def log_batch_errors(batch_errors_list, log_writer, namespace, curr_iter, bar_plot=[], box_plot=[]): + for node_type in batch_errors_list[0].keys(): + for metric in batch_errors_list[0][node_type].keys(): + metric_batch_error = [] + for batch_errors in batch_errors_list: + metric_batch_error.extend(batch_errors[node_type][metric]) + + if len(metric_batch_error) > 0: + log_writer.add_histogram(f"{node_type.name}/{namespace}/{metric}", metric_batch_error, curr_iter) + log_writer.add_scalar(f"{node_type.name}/{namespace}/{metric}_mean", np.mean(metric_batch_error), curr_iter) + log_writer.add_scalar(f"{node_type.name}/{namespace}/{metric}_median", np.median(metric_batch_error), curr_iter) + + if metric in bar_plot: + pd = {'dataset': [namespace] * len(metric_batch_error), + metric: metric_batch_error} + kde_barplot_fig, ax = plt.subplots(figsize=(5, 5)) + visualization.visualization_utils.plot_barplots(ax, pd, 'dataset', metric) + log_writer.add_figure(f"{node_type.name}/{namespace}/{metric}_bar_plot", kde_barplot_fig, curr_iter) + + if metric in box_plot: + mse_fde_pd = {'dataset': [namespace] * len(metric_batch_error), + metric: metric_batch_error} + fig, ax = plt.subplots(figsize=(5, 5)) + visualization.visualization_utils.plot_boxplots(ax, mse_fde_pd, 'dataset', metric) + log_writer.add_figure(f"{node_type.name}/{namespace}/{metric}_box_plot", fig, curr_iter) diff --git a/code/model/__init__.py b/code/model/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/code/model/components/__init__.py b/code/model/components/__init__.py new file mode 100644 index 0000000..116a37c --- /dev/null +++ b/code/model/components/__init__.py @@ -0,0 +1,4 @@ +from .discrete_latent import DiscreteLatent +from .gmm2d import GMM2D +from .map_encoder import CNNMapEncoder +from .additive_attention import AdditiveAttention, TemporallyBatchedAdditiveAttention diff --git a/code/model/components/additive_attention.py b/code/model/components/additive_attention.py new file mode 100644 index 0000000..9362324 --- /dev/null +++ b/code/model/components/additive_attention.py @@ -0,0 +1,67 @@ +import torch +import torch.nn as nn +import torch.nn.functional as F + + +class AdditiveAttention(nn.Module): + # Implementing the attention module of Bahdanau et al. 2015 where + # score(h_j, s_(i-1)) = v . tanh(W_1 h_j + W_2 s_(i-1)) + def __init__(self, encoder_hidden_state_dim, decoder_hidden_state_dim, internal_dim=None): + super(AdditiveAttention, self).__init__() + + if internal_dim is None: + internal_dim = int((encoder_hidden_state_dim + decoder_hidden_state_dim) / 2) + + self.w1 = nn.Linear(encoder_hidden_state_dim, internal_dim, bias=False) + self.w2 = nn.Linear(decoder_hidden_state_dim, internal_dim, bias=False) + self.v = nn.Linear(internal_dim, 1, bias=False) + + def score(self, encoder_state, decoder_state): + # encoder_state is of shape (batch, enc_dim) + # decoder_state is of shape (batch, dec_dim) + # return value should be of shape (batch, 1) + return self.v(torch.tanh(self.w1(encoder_state) + self.w2(decoder_state))) + + def forward(self, encoder_states, decoder_state): + # encoder_states is of shape (batch, num_enc_states, enc_dim) + # decoder_state is of shape (batch, dec_dim) + score_vec = torch.cat([self.score(encoder_states[:, i], decoder_state) for i in range(encoder_states.shape[1])], + dim=1) + # score_vec is of shape (batch, num_enc_states) + + attention_probs = torch.unsqueeze(F.softmax(score_vec, dim=1), dim=2) + # attention_probs is of shape (batch, num_enc_states, 1) + + final_context_vec = torch.sum(attention_probs * encoder_states, dim=1) + # final_context_vec is of shape (batch, enc_dim) + + return final_context_vec, attention_probs + + +class TemporallyBatchedAdditiveAttention(AdditiveAttention): + # Implementing the attention module of Bahdanau et al. 2015 where + # score(h_j, s_(i-1)) = v . tanh(W_1 h_j + W_2 s_(i-1)) + def __init__(self, encoder_hidden_state_dim, decoder_hidden_state_dim, internal_dim=None): + super(TemporallyBatchedAdditiveAttention, self).__init__(encoder_hidden_state_dim, + decoder_hidden_state_dim, + internal_dim) + + def score(self, encoder_state, decoder_state): + # encoder_state is of shape (batch, num_enc_states, max_time, enc_dim) + # decoder_state is of shape (batch, max_time, dec_dim) + # return value should be of shape (batch, num_enc_states, max_time, 1) + return self.v(torch.tanh(self.w1(encoder_state) + torch.unsqueeze(self.w2(decoder_state), dim=1))) + + def forward(self, encoder_states, decoder_state): + # encoder_states is of shape (batch, num_enc_states, max_time, enc_dim) + # decoder_state is of shape (batch, max_time, dec_dim) + score_vec = self.score(encoder_states, decoder_state) + # score_vec is of shape (batch, num_enc_states, max_time, 1) + + attention_probs = F.softmax(score_vec, dim=1) + # attention_probs is of shape (batch, num_enc_states, max_time, 1) + + final_context_vec = torch.sum(attention_probs * encoder_states, dim=1) + # final_context_vec is of shape (batch, max_time, enc_dim) + + return final_context_vec, torch.squeeze(torch.transpose(attention_probs, 1, 2), dim=3) diff --git a/code/model/components/discrete_latent.py b/code/model/components/discrete_latent.py new file mode 100644 index 0000000..f0fcee5 --- /dev/null +++ b/code/model/components/discrete_latent.py @@ -0,0 +1,107 @@ +import torch +import torch.distributions as td +import numpy as np +from model.model_utils import ModeKeys, tile + + +class DiscreteLatent(object): + def __init__(self, hyperparams, device): + self.hyperparams = hyperparams + self.z_dim = hyperparams['N'] * hyperparams['K'] + self.N = hyperparams['N'] + self.K = hyperparams['K'] + self.kl_min = hyperparams['kl_min'] + self.device = device + self.temp = None # filled in by MultimodalGenerativeCVAE.set_annealing_params + self.z_logit_clip = None # filled in by MultimodalGenerativeCVAE.set_annealing_params + self.p_dist = None # filled in by MultimodalGenerativeCVAE.encoder + self.q_dist = None # filled in by MultimodalGenerativeCVAE.encoder + + def dist_from_h(self, h, mode): + logits_separated = torch.reshape(h, (-1, self.N, self.K)) + logits_separated_mean_zero = logits_separated - torch.mean(logits_separated, dim=-1, keepdim=True) + if self.z_logit_clip is not None and mode == ModeKeys.TRAIN: + c = self.z_logit_clip + logits = torch.clamp(logits_separated_mean_zero, min=-c, max=c) + else: + logits = logits_separated_mean_zero + + return td.OneHotCategorical(logits=logits) + + def sample_q(self, k, mode): + if mode == ModeKeys.TRAIN: + z_dist = td.RelaxedOneHotCategorical(self.temp, logits=self.q_dist.logits) + z_NK = z_dist.rsample((k,)) + elif mode == ModeKeys.EVAL: + z_NK = self.q_dist.sample((k,)) + return torch.reshape(z_NK, (k, -1, self.z_dim)) + + def sample_p(self, num_samples_z, mode, num_samples_gmm=1, most_likely=False, all_z=False): + if all_z: + bs = self.p_dist.probs.size()[0] + z_NK = torch.from_numpy(self.all_one_hot_combinations(self.N, self.K)).float().to(self.device).repeat(1, bs) + num_samples_z = self.K ** self.N + + elif most_likely: + # Sampling the most likely z from p(z|x). + eye_mat = torch.eye(self.p_dist.event_shape[-1], device=self.device) + argmax_idxs = torch.argmax(self.p_dist.probs, dim=2) + z_NK = torch.unsqueeze(eye_mat[argmax_idxs], dim=0).expand(num_samples_z, -1, -1, -1) + + else: + z_NK = self.p_dist.sample((num_samples_z,)) + + z_NK = tile(z_NK, 0, num_samples_gmm, device=self.device) + k = num_samples_z * num_samples_gmm + + if mode == ModeKeys.PREDICT: + return torch.reshape(z_NK, (k, -1, self.N * self.K)), num_samples_z + else: + return torch.reshape(z_NK, (k, -1, self.N * self.K)) + + def kl_q_p(self, log_writer=None, prefix=None, curr_iter=None): + kl_separated = td.kl_divergence(self.q_dist, self.p_dist) + if len(kl_separated.size()) < 2: + kl_separated = torch.unsqueeze(kl_separated, dim=0) + + kl_minibatch = torch.mean(kl_separated, dim=0, keepdim=True) + + if log_writer is not None: + log_writer.add_scalar(prefix + '/true_kl', torch.sum(kl_minibatch), curr_iter) + + if self.kl_min > 0: + kl_lower_bounded = torch.clamp(kl_minibatch, min=self.kl_min) + kl = torch.sum(kl_lower_bounded) + else: + kl = torch.sum(kl_minibatch) + + return kl + + def q_log_prob(self, z): + k = z.size()[0] + z_NK = torch.reshape(z, [k, -1, self.N, self.K]) + return torch.sum(self.q_dist.log_prob(z_NK), dim=2) + + def p_log_prob(self, z): + k = z.size()[0] + z_NK = torch.reshape(z, [k, -1, self.N, self.K]) + return torch.sum(self.p_dist.log_prob(z_NK), dim=2) + + def get_p_dist_probs(self): + return self.p_dist.probs + + @staticmethod + def all_one_hot_combinations(N, K): + return np.eye(K).take(np.reshape(np.indices([K] * N), [N, -1]).T, axis=0).reshape(-1, N * K) # [K**N, N*K] + + def summarize_for_tensorboard(self, log_writer, prefix, curr_iter): + log_writer.add_histogram(prefix + "/latent/p_z_x", self.p_dist.probs, curr_iter) + log_writer.add_histogram(prefix + "/latent/q_z_xy", self.q_dist.probs, curr_iter) + log_writer.add_histogram(prefix + "/latent/p_z_x_logits", self.p_dist.logits, curr_iter) + log_writer.add_histogram(prefix + "/latent/q_z_xy_logits", self.q_dist.logits, curr_iter) + if self.z_dim <= 9: + for i in range(self.N): + for j in range(self.K): + log_writer.add_histogram(prefix + "/latent/q_z_xy_logit{0}{1}".format(i, j), + self.q_dist.logits[:, i, j], + curr_iter) diff --git a/code/model/components/gmm2d.py b/code/model/components/gmm2d.py new file mode 100644 index 0000000..1bc5b8a --- /dev/null +++ b/code/model/components/gmm2d.py @@ -0,0 +1,61 @@ +import torch +import torch.distributions as td +import numpy as np +from model.model_utils import to_one_hot + + +class GMM2D(object): + def __init__(self, log_pis, mus, log_sigmas, corrs, pred_state_length, device, + clip_lo=-10, clip_hi=10): + self.device = device + self.pred_state_length = pred_state_length + + # input shapes + # pis: [..., GMM_c] + # mus: [..., GMM_c*2] + # sigmas: [..., GMM_c*2] + # corrs: [..., GMM_c] + GMM_c = log_pis.shape[-1] + + # Sigma = [s1^2 p*s1*s2 L = [s1 0 + # p*s1*s2 s2^2 ] p*s2 sqrt(1-p^2)*s2] + log_pis = log_pis - torch.logsumexp(log_pis, dim=-1, keepdim=True) + mus = self.reshape_to_components(mus, GMM_c) # [..., GMM_c, 2] + log_sigmas = self.reshape_to_components(torch.clamp(log_sigmas, min=clip_lo, max=clip_hi), GMM_c) + sigmas = torch.exp(log_sigmas) # [..., GMM_c, 2] + one_minus_rho2 = 1 - corrs**2 # [..., GMM_c] + + self.L1 = sigmas*torch.stack([torch.ones_like(corrs, device=self.device), corrs], dim=-1) + self.L2 = sigmas*torch.stack([torch.zeros_like(corrs, device=self.device), torch.sqrt(one_minus_rho2)], dim=-1) + + self.batch_shape = log_pis.shape[:-1] + self.GMM_c = GMM_c + self.log_pis = log_pis # [..., GMM_c] + self.mus = mus # [..., GMM_c, 2] + self.log_sigmas = log_sigmas # [..., GMM_c, 2] + self.sigmas = sigmas # [..., GMM_c, 2] + self.corrs = corrs # [..., GMM_c] + self.one_minus_rho2 = one_minus_rho2 # [..., GMM_c] + self.cat = td.Categorical(logits=log_pis) + + def sample(self): + MVN_samples = (self.mus + + self.L1*torch.unsqueeze(torch.randn_like(self.corrs, device=self.device), dim=-1) # [..., GMM_c, 2] + + self.L2*torch.unsqueeze(torch.randn_like(self.corrs, device=self.device), dim=-1)) # (manual 2x2 matmul) + cat_samples = self.cat.sample() # [...] + selector = torch.unsqueeze(to_one_hot(cat_samples, self.GMM_c, self.device), dim=-1) + return torch.sum(MVN_samples*selector, dim=-2) + + def log_prob(self, x): + # x: [..., 2] + x = torch.unsqueeze(x, dim=-2) # [..., 1, 2] + dx = x - self.mus # [..., GMM_c, 2] + z = (torch.sum((dx/self.sigmas)**2, dim=-1) - + 2*self.corrs*torch.prod(dx, dim=-1)/torch.prod(self.sigmas, dim=-1)) # [..., GMM_c] + component_log_p = -(torch.log(self.one_minus_rho2) + 2*torch.sum(self.log_sigmas, dim=-1) + + z/self.one_minus_rho2 + + 2*np.log(2*np.pi))/2 + return torch.logsumexp(self.log_pis + component_log_p, dim=-1) + + def reshape_to_components(self, tensor, GMM_c): + return torch.reshape(tensor, list(tensor.shape[:-1]) + [GMM_c, self.pred_state_length]) \ No newline at end of file diff --git a/code/model/components/map_encoder.py b/code/model/components/map_encoder.py new file mode 100644 index 0000000..6562d83 --- /dev/null +++ b/code/model/components/map_encoder.py @@ -0,0 +1,20 @@ +import torch +import torch.nn as nn +import torch.nn.functional as F + + +class CNNMapEncoder(nn.Module): + def __init__(self, input_size, hidden_size, output_size): + super(CNNMapEncoder, self).__init__() + self.conv1 = nn.Conv2d(3, 128, 5, stride=2) + self.conv2 = nn.Conv2d(128, 256, 5, stride=3) + self.conv3 = nn.Conv2d(256, 64, 5, stride=2) + self.fc = nn.Linear(7 * 7 * 64, 512) + + def forward(self, x): + x = F.relu(self.conv1(x)) + x = F.relu(self.conv2(x)) + x = F.relu(self.conv3(x)) + x = x.view(-1, 7 * 7 * 64) + x = F.relu(self.fc(x)) + return x diff --git a/code/model/dyn_stg.py b/code/model/dyn_stg.py new file mode 100644 index 0000000..d9b3358 --- /dev/null +++ b/code/model/dyn_stg.py @@ -0,0 +1,454 @@ +import numpy as np +import torch +from model.node_model import MultimodalGenerativeCVAE + + +class SpatioTemporalGraphCVAEModel(object): + def __init__(self, model_registrar, + hyperparams, log_writer, + device): + super(SpatioTemporalGraphCVAEModel, self).__init__() + self.hyperparams = hyperparams + self.log_writer = log_writer + self.device = device + self.curr_iter = 0 + + self.model_registrar = model_registrar + self.node_models_dict = dict() + self.nodes = set() + + self.env = None + + self.min_hl = self.hyperparams['minimum_history_length'] + self.max_hl = self.hyperparams['maximum_history_length'] + self.ph = self.hyperparams['prediction_horizon'] + self.state = self.hyperparams['state'] + self.state_length = dict() + for type in self.state.keys(): + self.state_length[type] = int(np.sum([len(entity_dims) for entity_dims in self.state[type].values()])) + self.pred_state = self.hyperparams['pred_state'] + + def set_scene_graph(self, env): + self.env = env + + self.node_models_dict.clear() + + edge_types = env.get_edge_types() + + for node_type in env.NodeType: + self.node_models_dict[node_type] = MultimodalGenerativeCVAE(env, + node_type, + self.model_registrar, + self.hyperparams, + self.device, + edge_types, + log_writer=self.log_writer) + + def set_curr_iter(self, curr_iter): + self.curr_iter = curr_iter + for node_str, model in self.node_models_dict.items(): + model.set_curr_iter(curr_iter) + + def set_annealing_params(self): + for node_str, model in self.node_models_dict.items(): + model.set_annealing_params() + + def step_annealers(self): + for node in self.node_models_dict: + self.node_models_dict[node].step_annealers() + + def get_input(self, scene, timesteps, node_type, min_future_timesteps, max_nodes=None, curve=False): # Curve is there to resample during training + inputs = list() + labels = list() + first_history_indices = list() + nodes = list() + node_scene_graph_batched = list() + timesteps_in_scene = list() + nodes_per_ts = scene.present_nodes(timesteps, + type=node_type, + min_history_timesteps=self.min_hl, + min_future_timesteps=min_future_timesteps, + include_robot=not self.hyperparams['incl_robot_node'], + max_nodes=max_nodes, + curve=curve) + + # Get Inputs for each node present in Scene + for timestep in timesteps: + if timestep in nodes_per_ts.keys(): + present_nodes = nodes_per_ts[timestep] + timestep_range = np.array([timestep - self.max_hl, timestep + min_future_timesteps]) + scene_graph_t = scene.get_scene_graph(timestep, + self.env.attention_radius, + self.hyperparams['edge_addition_filter'], + self.hyperparams['edge_removal_filter']) + + for node in present_nodes: + timesteps_in_scene.append(timestep) + input = node.get(timestep_range, self.state[node.type.name]) + label = node.get(timestep_range, self.pred_state[node.type.name]) + first_history_index = (self.max_hl - node.history_points_at(timestep)).clip(0) + inputs.append(input) + labels.append(label) + first_history_indices.append(first_history_index) + nodes.append(node) + + node_scene_graph_batched.append((node, scene_graph_t)) + + return inputs, labels, first_history_indices, timesteps_in_scene, node_scene_graph_batched, nodes + + def train_loss(self, scene, timesteps, max_nodes=None): + losses = dict() + for node_type in self.env.NodeType: + losses[node_type] = [] + + for node_type in self.env.NodeType: + # Get Input data for node type and given timesteps + (inputs, + labels, + first_history_indices, + timesteps_in_scene, + node_scene_graph_batched, _) = self.get_input(scene, + timesteps, + node_type, + self.ph, + max_nodes=max_nodes, + curve=True) # Curve is there to resample during training + + # There are no nodes of type present for timestep + if len(inputs) == 0: + continue + + uniform_t = self.max_hl + + inputs = np.array(inputs) + labels = np.array(labels) + + # Vehicles are rotated such that the x axis is lateral + if node_type == self.env.NodeType.VEHICLE: + # transform x y to ego. + pos = inputs[..., 0:2] + pos_org = pos.copy() + vel = inputs[..., 2:4] + acc = inputs[..., 5:7] + heading = inputs[:, uniform_t, -1] + rot_mat = np.zeros((pos.shape[0], pos.shape[1], 3, 3)) + rot_mat[:, :, 0, 0] = np.cos(heading)[:, np.newaxis] + rot_mat[:, :, 0, 1] = np.sin(heading)[:, np.newaxis] + rot_mat[:, :, 1, 0] = -np.sin(heading)[:, np.newaxis] + rot_mat[:, :, 1, 1] = np.cos(heading)[:, np.newaxis] + rot_mat[:, :, 2, 2] = 1. + + pos = pos - pos[:, uniform_t, np.newaxis, :] + + pos_with_one = np.ones((pos.shape[0], pos.shape[1], 3, 1)) + pos_with_one[:, :, :2] = pos[..., np.newaxis] + pos_rot = np.squeeze(rot_mat @ pos_with_one, axis=-1)[..., :2] + + vel_with_one = np.ones((vel.shape[0], vel.shape[1], 3, 1)) + vel_with_one[:, :, :2] = vel[..., np.newaxis] + vel_rot = np.squeeze(rot_mat @ vel_with_one, axis=-1)[..., :2] + + acc_with_one = np.ones((acc.shape[0], acc.shape[1], 3, 1)) + acc_with_one[:, :, :2] = acc[..., np.newaxis] + acc_rot = np.squeeze(rot_mat @ acc_with_one, axis=-1)[..., :2] + + inputs[..., 0:2] = pos_rot + inputs[..., 2:4] = vel_rot + inputs[..., 5:7] = acc_rot + + l_vel_with_one = np.ones((labels.shape[0], labels.shape[1], 3, 1)) + l_vel_with_one[:, :, :2] = labels[..., np.newaxis] + labels = np.squeeze(rot_mat @ l_vel_with_one, axis=-1)[..., :2] + + # Standardize, Position is standardized relative to current pos and attention_radius for node_type-node_type + _, std = self.env.get_standardize_params(self.state[node_type.name], node_type=node_type) + # std[0:2] = self.env.attention_radius[(node_type, node_type)] + rel_state = np.array(inputs)[:, uniform_t] + rel_state = np.hstack((rel_state, np.zeros_like(rel_state))) + rel_state = np.expand_dims(rel_state, 1) + std = np.tile(std, 2) + inputs = np.tile(inputs, 2) + inputs[..., self.state_length[node_type.name]:self.state_length[node_type.name]+2] = 0. + inputs_st = self.env.standardize(inputs, + self.state[node_type.name], + mean=rel_state, + std=std, + node_type=node_type) + labels_st = self.env.standardize(labels, self.pred_state[node_type.name], node_type=node_type) + + if node_type == self.env.NodeType.VEHICLE: + inputs[..., 0:2] = pos_org + + # Convert to torch tensors + inputs = torch.tensor(inputs).float().to(self.device) + inputs_st = torch.tensor(inputs_st).float().to(self.device) + first_history_indices = torch.tensor(first_history_indices).float().to(self.device).long() + labels = torch.tensor(labels).float().to(self.device) + labels_st = torch.tensor(labels_st).float().to(self.device) + + # Run forward pass + model = self.node_models_dict[node_type] + loss = model.train_loss(inputs, + inputs_st, + first_history_indices, + labels, + labels_st, + scene, + node_scene_graph_batched, + timestep=uniform_t, + timesteps_in_scene=timesteps_in_scene, + prediction_horizon=self.ph) + + losses[node_type].append(loss) + + for node_type in self.env.NodeType: + losses[node_type] = torch.mean(torch.stack(losses[node_type])) if len(losses[node_type]) > 0 else None + return losses + + def eval_loss(self, scene, timesteps, max_nodes=None): + losses = dict() + for node_type in self.env.NodeType: + losses[node_type] = {'nll_q_is': list(), 'nll_p': list(), 'nll_exact': list(), 'nll_sampled': list()} + for node_type in self.env.NodeType: + # Get Input data for node type and given timesteps + (inputs, + labels, + first_history_indices, + timesteps_in_scene, + node_scene_graph_batched, _) = self.get_input(scene, timesteps, node_type, self.ph, max_nodes=max_nodes) + + # There are no nodes of type present for timestep + if len(inputs) == 0: + continue + + uniform_t = self.max_hl + + inputs = np.array(inputs) + labels = np.array(labels) + + # Vehicles are rotated such that the x axis is lateral + if node_type == self.env.NodeType.VEHICLE: + # transform x y to ego. + pos = inputs[..., 0:2] + pos_org = pos.copy() + vel = inputs[..., 2:4] + acc = inputs[..., 5:7] + heading = inputs[:, uniform_t, -1] + rot_mat = np.zeros((pos.shape[0], pos.shape[1], 3, 3)) + rot_mat[:, :, 0, 0] = np.cos(heading)[:, np.newaxis] + rot_mat[:, :, 0, 1] = np.sin(heading)[:, np.newaxis] + rot_mat[:, :, 1, 0] = -np.sin(heading)[:, np.newaxis] + rot_mat[:, :, 1, 1] = np.cos(heading)[:, np.newaxis] + rot_mat[:, :, 2, 2] = 1. + + pos = pos - pos[:, uniform_t, np.newaxis, :] + + pos_with_one = np.ones((pos.shape[0], pos.shape[1], 3, 1)) + pos_with_one[:, :, :2] = pos[..., np.newaxis] + pos_rot = np.squeeze(rot_mat @ pos_with_one, axis=-1)[..., :2] + + vel_with_one = np.ones((vel.shape[0], vel.shape[1], 3, 1)) + vel_with_one[:, :, :2] = vel[..., np.newaxis] + vel_rot = np.squeeze(rot_mat @ vel_with_one, axis=-1)[..., :2] + + acc_with_one = np.ones((acc.shape[0], acc.shape[1], 3, 1)) + acc_with_one[:, :, :2] = acc[..., np.newaxis] + acc_rot = np.squeeze(rot_mat @ acc_with_one, axis=-1)[..., :2] + + inputs[..., 0:2] = pos_rot + inputs[..., 2:4] = vel_rot + inputs[..., 5:7] = acc_rot + + l_vel_with_one = np.ones((labels.shape[0], labels.shape[1], 3, 1)) + l_vel_with_one[:, :, :2] = labels[..., np.newaxis] + labels = np.squeeze(rot_mat @ l_vel_with_one, axis=-1)[..., :2] + + # Standardize, Position is standardized relative to current pos and attention_radius for node_type-node_type + _, std = self.env.get_standardize_params(self.state[node_type.name], node_type=node_type) + rel_state = np.array(inputs)[:, uniform_t] + rel_state = np.hstack((rel_state, np.zeros_like(rel_state))) + rel_state = np.expand_dims(rel_state, 1) + std = np.tile(std, 2) + inputs = np.tile(inputs, 2) + inputs[..., self.state_length[node_type.name]:self.state_length[node_type.name]+2] = 0. + inputs_st = self.env.standardize(inputs, + self.state[node_type.name], + mean=rel_state, + std=std, + node_type=node_type) + labels_st = self.env.standardize(labels, self.pred_state[node_type.name], node_type=node_type) + + if node_type == self.env.NodeType.VEHICLE: + inputs[..., 0:2] = pos_org + + # Convert to torch tensors + inputs = torch.tensor(inputs).float().to(self.device) + inputs_st = torch.tensor(inputs_st).float().to(self.device) + first_history_indices = torch.tensor(first_history_indices).float().to(self.device).long() + labels = torch.tensor(labels).float().to(self.device) + labels_st = torch.tensor(labels_st).float().to(self.device) + + # Run forward pass + model = self.node_models_dict[node_type] + (nll_q_is, nll_p, nll_exact, nll_sampled) = model.eval_loss(inputs, + inputs_st, + first_history_indices, + labels, + labels_st, + scene, + node_scene_graph_batched, + timestep=uniform_t, + timesteps_in_scene=timesteps_in_scene, + prediction_horizon=self.ph) + + if nll_q_is is not None: + losses[node_type]['nll_q_is'].append(nll_q_is.cpu().numpy()) + losses[node_type]['nll_p'].append(nll_p.cpu().numpy()) + losses[node_type]['nll_exact'].append(nll_exact.cpu().numpy()) + losses[node_type]['nll_sampled'].append(nll_sampled.cpu().numpy()) + + return losses + + def predict(self, + scene, + timesteps, + ph, + num_samples_z=1, + num_samples_gmm=1, + min_future_timesteps=0, + most_likely_z=False, + most_likely_gmm=False, + all_z=False, + max_nodes=None): + + predictions_dict = {} + for node_type in self.env.NodeType: + # Get Input data for node type and given timesteps + (inputs, + labels, + first_history_indices, + timesteps_in_scene, + node_scene_graph_batched, + nodes) = self.get_input(scene, timesteps, node_type, min_future_timesteps, max_nodes=max_nodes) + + # There are no nodes of type present for timestep + if len(inputs) == 0: + continue + + uniform_t = self.max_hl + + inputs = np.array(inputs) + labels = np.array(labels) + + # Vehicles are rotated such that the x axis is lateral + if node_type == self.env.NodeType.VEHICLE: + # transform x y to ego. + pos = inputs[..., 0:2] + pos_org = pos.copy() + vel = inputs[..., 2:4] + acc = inputs[..., 5:7] + heading = inputs[:, uniform_t, -1] + rot_mat = np.zeros((pos.shape[0], pos.shape[1], 3, 3)) + rot_mat[:, :, 0, 0] = np.cos(heading)[:, np.newaxis] + rot_mat[:, :, 0, 1] = np.sin(heading)[:, np.newaxis] + rot_mat[:, :, 1, 0] = -np.sin(heading)[:, np.newaxis] + rot_mat[:, :, 1, 1] = np.cos(heading)[:, np.newaxis] + rot_mat[:, :, 2, 2] = 1. + + pos = pos - pos[:, uniform_t, np.newaxis, :] + + pos_with_one = np.ones((pos.shape[0], pos.shape[1], 3, 1)) + pos_with_one[:, :, :2] = pos[..., np.newaxis] + pos_rot = np.squeeze(rot_mat @ pos_with_one, axis=-1)[..., :2] + + vel_with_one = np.ones((vel.shape[0], vel.shape[1], 3, 1)) + vel_with_one[:, :, :2] = vel[..., np.newaxis] + vel_rot = np.squeeze(rot_mat @ vel_with_one, axis=-1)[..., :2] + + acc_with_one = np.ones((acc.shape[0], acc.shape[1], 3, 1)) + acc_with_one[:, :, :2] = acc[..., np.newaxis] + acc_rot = np.squeeze(rot_mat @ acc_with_one, axis=-1)[..., :2] + + inputs[..., 0:2] = pos_rot + inputs[..., 2:4] = vel_rot + inputs[..., 5:7] = acc_rot + + l_vel_with_one = np.ones((labels.shape[0], labels.shape[1], 3, 1)) + l_vel_with_one[:, :, :2] = labels[..., np.newaxis] + labels = np.squeeze(rot_mat @ l_vel_with_one, axis=-1)[..., :2] + + # Standardize, Position is standardized relative to current pos and attention_radius for node_type-node_type + _, std = self.env.get_standardize_params(self.state[node_type.name], node_type=node_type) + rel_state = np.array(inputs)[:, uniform_t] + rel_state = np.hstack((rel_state, np.zeros_like(rel_state))) + rel_state = np.expand_dims(rel_state, 1) + std = np.tile(std, 2) + inputs = np.tile(inputs, 2) + inputs[..., self.state_length[node_type.name]:self.state_length[node_type.name]+2] = 0. + inputs_st = self.env.standardize(inputs, + self.state[node_type.name], + mean=rel_state, + std=std, + node_type=node_type) + labels_st = self.env.standardize(labels, self.pred_state[node_type.name], node_type=node_type) + + if node_type == self.env.NodeType.VEHICLE: + inputs[..., 0:2] = pos_org + + # Convert to torch tensors + inputs = torch.tensor(inputs).float().to(self.device) + inputs_st = torch.tensor(inputs_st).float().to(self.device) + first_history_indices = torch.tensor(first_history_indices).float().to(self.device).long() + labels = torch.tensor(labels).float().to(self.device) + labels_st = torch.tensor(labels_st).float().to(self.device) + + # Run forward pass + model = self.node_models_dict[node_type] + predictions = model.predict(inputs, + inputs_st, + labels, + labels_st, + first_history_indices, + scene, + node_scene_graph_batched, + timestep=uniform_t, + timesteps_in_scene=timesteps_in_scene, + prediction_horizon=ph, + num_samples_z=num_samples_z, + num_samples_gmm=num_samples_gmm, + most_likely_z=most_likely_z, + most_likely_gmm=most_likely_gmm, + all_z=all_z) + + predictions_uns = self.env.unstandardize(predictions.cpu().detach().numpy(), + self.pred_state[node_type.name], + node_type) + + # Vehicles are rotated such that the x axis is lateral. For output rotation has to be reversed + if node_type == self.env.NodeType.VEHICLE: + heading = inputs.cpu().detach().numpy()[:, uniform_t, -1] + rot_mat = np.zeros((predictions_uns.shape[0], + predictions_uns.shape[1], + predictions_uns.shape[2], + predictions_uns.shape[3], 3, 3)) + rot_mat[:, :, :, :, 0, 0] = np.cos(-heading)[:, np.newaxis] + rot_mat[:, :, :, :, 0, 1] = np.sin(-heading)[:, np.newaxis] + rot_mat[:, :, :, :, 1, 0] = -np.sin(-heading)[:, np.newaxis] + rot_mat[:, :, :, :, 1, 1] = np.cos(-heading)[:, np.newaxis] + rot_mat[:, :, :, :, 2, 2] = 1. + + p_vel_with_one = np.ones((predictions_uns.shape[0], + predictions_uns.shape[1], + predictions_uns.shape[2], + predictions_uns.shape[3], 3, 1)) + p_vel_with_one[:, :, :, :, :2] = predictions_uns[..., np.newaxis] + predictions_uns = np.squeeze(rot_mat @ p_vel_with_one, axis=-1)[..., :2] + + # Assign predictions to node + for i, ts in enumerate(timesteps_in_scene): + if not ts in predictions_dict.keys(): + predictions_dict[ts] = dict() + predictions_dict[ts][nodes[i]] = predictions_uns[:, :, i] + + return predictions_dict + diff --git a/code/model/model_registrar.py b/code/model/model_registrar.py new file mode 100644 index 0000000..8bfc302 --- /dev/null +++ b/code/model/model_registrar.py @@ -0,0 +1,70 @@ +import os +import torch +import torch.nn as nn + + +def get_model_device(model): + return next(model.parameters()).device + + +class ModelRegistrar(nn.Module): + def __init__(self, model_dir, device): + super(ModelRegistrar, self).__init__() + self.model_dict = nn.ModuleDict() + self.model_dir = model_dir + self.device = device + + + def forward(self): + raise NotImplementedError('Although ModelRegistrar is a nn.Module, it is only to store parameters.') + + + def get_model(self, name, model_if_absent=None): + # 4 cases: name in self.model_dict and model_if_absent is None (OK) + # name in self.model_dict and model_if_absent is not None (OK) + # name not in self.model_dict and model_if_absent is not None (OK) + # name not in self.model_dict and model_if_absent is None (NOT OK) + + if name in self.model_dict: + return self.model_dict[name] + + elif model_if_absent is not None: + self.model_dict[name] = model_if_absent.to(self.device) + return self.model_dict[name] + + else: + raise ValueError(f'{name} was never initialized in this Registrar!') + + + def print_model_names(self): + print(self.model_dict.keys()) + + + def save_models(self, curr_iter): + # Create the model directiory if it's not present. + save_path = os.path.join(self.model_dir, + 'model_registrar-%d.pt' % curr_iter) + print('') + print('Saving to ' + save_path) + torch.save(self.model_dict, save_path) + print('Saved!') + print('') + + + def load_models(self, iter_num): + self.model_dict.clear() + + save_path = os.path.join(self.model_dir, + 'model_registrar-%d.pt' % iter_num) + + print('') + print('Loading from ' + save_path) + self.model_dict = torch.load(save_path, map_location=self.device) + print('Loaded!') + print('') + + + def to(self, device): + for name, model in self.model_dict.items(): + if get_model_device(model) != device: + model.to(device) diff --git a/code/model/model_utils.py b/code/model/model_utils.py new file mode 100644 index 0000000..82d8b86 --- /dev/null +++ b/code/model/model_utils.py @@ -0,0 +1,169 @@ +import torch +import torch.nn.utils.rnn as rnn +from enum import Enum +import functools +import numpy as np +import math +from scipy.ndimage import interpolation + + +class ModeKeys(Enum): + TRAIN = 1 + EVAL = 2 + PREDICT = 3 + +def cyclical_lr(stepsize, min_lr=3e-4, max_lr=3e-3, decay=1.): + + # Lambda function to calculate the LR + lr_lambda = lambda it: min_lr + (max_lr - min_lr) * relative(it, stepsize) * decay**it + + # Additional function to see where on the cycle we are + def relative(it, stepsize): + cycle = math.floor(1 + it / (2 * stepsize)) + x = abs(it / stepsize - 2 * cycle + 1) + return max(0, (1 - x)) + + return lr_lambda + + +def tile(a, dim, n_tile, device='cpu'): + init_dim = a.size(dim) + repeat_idx = [1] * a.dim() + repeat_idx[dim] = n_tile + a = a.repeat(*(repeat_idx)) + order_index = torch.LongTensor(np.concatenate([init_dim * np.arange(n_tile) + i for i in range(init_dim)])).to(device) + return torch.index_select(a, dim, order_index) + + +def to_one_hot(labels, n_labels, device): + return torch.eye(n_labels, device=device)[labels] + + +def exp_anneal(anneal_kws): + device = anneal_kws['device'] + start = torch.tensor(anneal_kws['start'], device=device) + finish = torch.tensor(anneal_kws['finish'], device=device) + rate = torch.tensor(anneal_kws['rate'], device=device) + return lambda step: finish - (finish - start)*torch.pow(rate, torch.tensor(step, dtype=torch.float, device=device)) + + +def sigmoid_anneal(anneal_kws): + device = anneal_kws['device'] + start = torch.tensor(anneal_kws['start'], device=device) + finish = torch.tensor(anneal_kws['finish'], device=device) + center_step = torch.tensor(anneal_kws['center_step'], device=device, dtype=torch.float) + steps_lo_to_hi = torch.tensor(anneal_kws['steps_lo_to_hi'], device=device, dtype=torch.float) + return lambda step: start + (finish - start)*torch.sigmoid((torch.tensor(float(step), device=device) - center_step) * (1./steps_lo_to_hi)) + + +class CustomLR(torch.optim.lr_scheduler.LambdaLR): + def __init__(self, optimizer, lr_lambda, last_epoch=-1): + super(CustomLR, self).__init__(optimizer, lr_lambda, last_epoch) + + def get_lr(self): + return [lmbda(self.last_epoch) + for lmbda, base_lr in zip(self.lr_lambdas, self.base_lrs)] + + +def run_lstm_on_variable_length_seqs(lstm_module, original_seqs, break_indices, lower_indices, total_length): + # This is done so that we can just pass in self.prediction_timesteps + # (which we want to INCLUDE, so this will exclude the next timestep). + inclusive_break_indices = break_indices + 1 + + pad_list = list() + for i, seq_len in enumerate(inclusive_break_indices): + pad_list.append(original_seqs[i, lower_indices[i]:seq_len]) + + packed_seqs = rnn.pack_sequence(pad_list, enforce_sorted=False) + packed_output, (h_n, c_n) = lstm_module(packed_seqs) + output, _ = rnn.pad_packed_sequence(packed_output, + batch_first=True, + total_length=total_length) + + return output, (h_n, c_n) + + +def extract_subtensor_per_batch_element(tensor, indices): + batch_idxs = torch.arange(start=0, end=len(indices)) + + batch_idxs = batch_idxs[~torch.isnan(indices)] + indices = indices[~torch.isnan(indices)] + if indices.size == 0: + return None + else: + indices = indices.long() + if tensor.is_cuda: + batch_idxs = batch_idxs.to(tensor.get_device()) + indices = indices.to(tensor.get_device()) + return tensor[batch_idxs, indices] + + +def unpack_RNN_state(state_tuple): + # PyTorch returned LSTM states have 3 dims: + # (num_layers * num_directions, batch, hidden_size) + + state = torch.cat(state_tuple, dim=0).permute(1, 0, 2) + # Now state is (batch, 2 * num_layers * num_directions, hidden_size) + + state_size = state.size() + return torch.reshape(state, (-1, state_size[1] * state_size[2])) + + +def rsetattr(obj, attr, val): + pre, _, post = attr.rpartition('.') + return setattr(rgetattr(obj, pre) if pre else obj, post, val) + + +# using wonder's beautiful simplification: +# https://stackoverflow.com/questions/31174295/getattr-and-setattr-on-nested-objects/31174427?noredirect=1#comment86638618_31174427 +def rgetattr(obj, attr, *args): + def _getattr(obj, attr): + return getattr(obj, attr, *args) + return functools.reduce(_getattr, [obj] + attr.split('.')) + + +def get_cropped_maps(world_pts, map, context_size=50): + """world_pts: N x 2 array of positions relative to the world.""" + expanded_obs_img = np.full((map.data.shape[0] + context_size, map.data.shape[1] + context_size, map.data.shape[2]), False, dtype=np.float32) + expanded_obs_img[context_size//2:-context_size//2, context_size//2:-context_size//2] = map.fdata.astype(np.float32) + img_pts = context_size//2 + np.round(map.to_map_points(world_pts)).astype(int) + return np.stack([expanded_obs_img[img_pts[i, 0] - context_size//2 : img_pts[i, 0] + context_size//2, + img_pts[i, 1] - context_size//2 : img_pts[i, 1] + context_size//2] + for i in range(world_pts.shape[0])], axis=0) + +def get_cropped_maps_heading(world_pts, map, context_size=50, heading=None): + """world_pts: N x 2 array of positions relative to the world.""" + rotations = np.round((heading) / (np.pi / 2)).astype(int) + + expanded_obs_img = np.full((map.data.shape[0] + context_size, map.data.shape[1] + context_size, map.data.shape[2]), + False, dtype=np.float32) + expanded_obs_img[context_size // 2:-context_size // 2, context_size // 2:-context_size // 2] = map.fdata.astype( + np.float32) + img_pts = context_size // 2 + np.round(map.to_map_points(world_pts)).astype(int) + map_h = np.stack([expanded_obs_img[img_pts[i, 0] - context_size // 2: img_pts[i, 0] + context_size // 2, + img_pts[i, 1] - context_size // 2: img_pts[i, 1] + context_size // 2] + for i in range(world_pts.shape[0])], axis=0) + + map_h[rotations == 1] = np.rot90(map_h[rotations == 1], -1, axes=(1, 2)) + map_h[rotations == 2] = np.rot90(map_h[rotations == 2], 2, axes=(1, 2)) + map_h[rotations == -1] = np.rot90(map_h[rotations == -1], 1, axes=(1, 2)) + map_h[rotations == -2] = np.rot90(map_h[rotations == -2], 2, axes=(1, 2)) + return map_h + +def get_cropped_maps_heading_exact(world_pts, map, context_size=50, heading=None): + """world_pts: N x 2 array of positions relative to the world.""" + angles = -heading * 180 / np.pi + + expanded_obs_img = np.full((map.data.shape[0] + context_size, map.data.shape[1] + context_size, map.data.shape[2]), + False, dtype=np.float32) + expanded_obs_img[context_size // 2:-context_size // 2, context_size // 2:-context_size // 2] = map.fdata.astype( + np.float32) + img_pts = context_size // 2 + np.round(map.to_map_points(world_pts)).astype(int) + map_h = np.stack([expanded_obs_img[img_pts[i, 0] - context_size // 2: img_pts[i, 0] + context_size // 2, + img_pts[i, 1] - context_size // 2: img_pts[i, 1] + context_size // 2] + for i in range(world_pts.shape[0])], axis=0) + + for i in range(angles.shape[0]): + map_h[i] = interpolation.rotate(map_h[i], reshape=False, angle=angles[i], prefilter=False) + + return map_h \ No newline at end of file diff --git a/code/model/node_model.py b/code/model/node_model.py new file mode 100644 index 0000000..69b3591 --- /dev/null +++ b/code/model/node_model.py @@ -0,0 +1,1200 @@ +import warnings +import torch.distributions as td +import torch.nn as nn +import torch.nn.functional as F +import torch.optim as optim +from model.components import * +from model.model_utils import * + + +class MultimodalGenerativeCVAE(object): + def __init__(self, + env, + node_type, + model_registrar, + hyperparams, + device, + edge_types, + log_writer=None): + self.env = env + self.node_type = node_type.name + self.model_registrar = model_registrar + self.log_writer = log_writer + self.device = device + self.edge_types = [edge_type for edge_type in edge_types if edge_type[0] is node_type] + self.curr_iter = 0 + + self.node_modules = dict() + self.hyperparams = hyperparams + + self.min_hl = self.hyperparams['minimum_history_length'] + self.max_hl = self.hyperparams['maximum_history_length'] + self.ph = self.hyperparams['prediction_horizon'] + self.state = self.hyperparams['state'] + self.pred_state = self.hyperparams['pred_state'][node_type.name] + self.state_length = int(np.sum([len(entity_dims) for entity_dims in self.state[node_type.name].values()])) * 2 # We have the relative and absolute state + self.robot_state_length = int(np.sum([len(entity_dims) for entity_dims in self.state['VEHICLE'].values()])) # TODO VEHICLE is hard coded for now + self.pred_state_length = int(np.sum([len(entity_dims) for entity_dims in self.pred_state.values()])) + + edge_types_str = [env.edge_type_str(edge_type) for edge_type in self.edge_types] + + self.create_graphical_model(edge_types_str) + + def set_curr_iter(self, curr_iter): + self.curr_iter = curr_iter + + def add_submodule(self, name, model_if_absent): + self.node_modules[name] = self.model_registrar.get_model(name, model_if_absent) + + def clear_submodules(self): + self.node_modules.clear() + + def create_graphical_model(self, edge_types): + self.clear_submodules() + + ############################ + # Node History Encoder # + ############################ + self.add_submodule(self.node_type + '/node_history_encoder', + model_if_absent=nn.LSTM(input_size=self.state_length, + hidden_size=self.hyperparams['enc_rnn_dim_history'], + batch_first=True)) + + ########################### + # Node Future Encoder # + ########################### + # We'll create this here, but then later check if in training mode. + # Based on that, we'll factor this into the computation graph (or not). + self.add_submodule(self.node_type + '/node_future_encoder', + model_if_absent=nn.LSTM(input_size=self.pred_state_length, + hidden_size=self.hyperparams['enc_rnn_dim_future'], + bidirectional=True, + batch_first=True)) + # These are related to how you initialize states for the node future encoder. + self.add_submodule(self.node_type + '/node_future_encoder/initial_h', + model_if_absent=nn.Linear(self.state_length, + self.hyperparams['enc_rnn_dim_future'])) + self.add_submodule(self.node_type + '/node_future_encoder/initial_c', + model_if_absent=nn.Linear(self.state_length, + self.hyperparams['enc_rnn_dim_future'])) + + ############################ + # Robot Future Encoder # + ############################ + # We'll create this here, but then later check if we're next to the robot. + # Based on that, we'll factor this into the computation graph (or not). + if self.hyperparams['incl_robot_node']: + self.add_submodule('robot_future_encoder', + model_if_absent=nn.LSTM(input_size=self.robot_state_length , + hidden_size=self.hyperparams['enc_rnn_dim_future'], + bidirectional=True, + batch_first=True)) + # These are related to how you initialize states for the robot future encoder. + self.add_submodule('robot_future_encoder/initial_h', + model_if_absent=nn.Linear(self.robot_state_length, + self.hyperparams['enc_rnn_dim_future'])) + self.add_submodule('robot_future_encoder/initial_c', + model_if_absent=nn.Linear(self.robot_state_length, + self.hyperparams['enc_rnn_dim_future'])) + + ##################### + # Edge Encoders # + ##################### + # print('create_graphical_model', self.node) + # print('create_graphical_model', self.neighbors_via_edge_type) + for edge_type in edge_types: + neighbor_state_length = int(np.sum([len(entity_dims) for entity_dims in self.state[edge_type.split('-')[1]].values()])) + if self.hyperparams['edge_state_combine_method'] == 'pointnet': + self.add_submodule(edge_type + '/pointnet_encoder', + model_if_absent=nn.Sequential( + nn.Linear(self.state_length, 2 * self.state_length), + nn.ReLU(), + nn.Linear(2 * self.state_length, 2 * self.state_length), + nn.ReLU())) + + edge_encoder_input_size = 2 * self.state_length + self.state_length + + elif self.hyperparams['edge_state_combine_method'] == 'attention': + self.add_submodule(self.node_type + '/edge_attention_combine', + model_if_absent=TemporallyBatchedAdditiveAttention( + encoder_hidden_state_dim=self.state_length, + decoder_hidden_state_dim=self.state_length)) + edge_encoder_input_size = self.state_length + neighbor_state_length + + else: + edge_encoder_input_size = self.state_length + neighbor_state_length + + self.add_submodule(edge_type + '/edge_encoder', + model_if_absent=nn.LSTM(input_size=edge_encoder_input_size, + hidden_size=self.hyperparams['enc_rnn_dim_edge'], + batch_first=True)) + + ############################## + # Edge Influence Encoder # + ############################## + # NOTE: The edge influence encoding happens during calls + # to forward or incremental_forward, so we don't create + # a model for it here for the max and sum variants. + if self.hyperparams['edge_influence_combine_method'] == 'bi-rnn': + self.add_submodule(self.node_type + '/edge_influence_encoder', + model_if_absent=nn.LSTM(input_size=self.hyperparams['enc_rnn_dim_edge'], + hidden_size=self.hyperparams['enc_rnn_dim_edge_influence'], + bidirectional=True, + batch_first=True)) + + # Four times because we're trying to mimic a bi-directional + # LSTM's output (which, here, is c and h from both ends). + self.eie_output_dims = 4 * self.hyperparams['enc_rnn_dim_edge_influence'] + + elif self.hyperparams['edge_influence_combine_method'] == 'attention': + # Chose additive attention because of https://arxiv.org/pdf/1703.03906.pdf + # We calculate an attention context vector using the encoded edges as the "encoder" (that we attend _over_) + # and the node history encoder representation as the "decoder state" (that we attend _on_). + self.add_submodule(self.node_type + '/edge_influence_encoder', + model_if_absent=AdditiveAttention( + encoder_hidden_state_dim=self.hyperparams['enc_rnn_dim_edge_influence'], + decoder_hidden_state_dim=self.hyperparams['enc_rnn_dim_history'])) + + self.eie_output_dims = self.hyperparams['enc_rnn_dim_edge_influence'] + + ################### + # Map Encoder # + ################### + if self.hyperparams['use_map_encoding']: + self.add_submodule(self.node_type + '/map_encoder', + model_if_absent=CNNMapEncoder(input_size=self.hyperparams['map_context'], + hidden_size=self.hyperparams['map_enc_hidden_size'], + output_size=self.hyperparams['map_enc_output_size'])) + + ################################ + # Discrete Latent Variable # + ################################ + self.latent = DiscreteLatent(self.hyperparams, self.device) + + ###################################################################### + # Various Fully-Connected Layers from Encoder to Latent Variable # + ###################################################################### + # Edge Influence Encoder Node History Encoder + x_size = self.eie_output_dims + self.hyperparams['enc_rnn_dim_history'] + if self.hyperparams['incl_robot_node']: + # Future Conditional Encoder + x_size += 4 * self.hyperparams['enc_rnn_dim_future'] + + if self.hyperparams['use_map_encoding']: + # Map Encoder + x_size += self.hyperparams['map_enc_output_size'] + + z_size = self.hyperparams['N'] * self.hyperparams['K'] + + if self.hyperparams['p_z_x_MLP_dims'] is not None: + self.add_submodule(self.node_type + '/p_z_x', + model_if_absent=nn.Linear(x_size, self.hyperparams['p_z_x_MLP_dims'])) + hx_size = self.hyperparams['p_z_x_MLP_dims'] + else: + hx_size = x_size + + self.add_submodule(self.node_type + '/hx_to_z', + model_if_absent=nn.Linear(hx_size, self.latent.z_dim)) + + if self.hyperparams['q_z_xy_MLP_dims'] is not None: + self.add_submodule(self.node_type + '/q_z_xy', + # Node Future Encoder + model_if_absent=nn.Linear(x_size + 4 * self.hyperparams['enc_rnn_dim_future'], + self.hyperparams['q_z_xy_MLP_dims'])) + hxy_size = self.hyperparams['q_z_xy_MLP_dims'] + else: + # Node Future Encoder + hxy_size = x_size + 4 * self.hyperparams['enc_rnn_dim_future'] + + self.add_submodule(self.node_type + '/hxy_to_z', + model_if_absent=nn.Linear(hxy_size, self.latent.z_dim)) + + #################### + # Decoder LSTM # + #################### + if self.hyperparams['incl_robot_node']: + decoder_input_dims = self.pred_state_length + self.robot_state_length + z_size + x_size + else: + decoder_input_dims = self.pred_state_length + z_size + x_size + + self.add_submodule(self.node_type + '/decoder/lstm_cell', + model_if_absent=nn.GRUCell(decoder_input_dims, self.hyperparams['dec_rnn_dim'])) + self.add_submodule(self.node_type + '/decoder/initial_h', + model_if_absent=nn.Linear(z_size + x_size, self.hyperparams['dec_rnn_dim'])) + self.add_submodule(self.node_type + '/decoder/initial_c', + model_if_absent=nn.Linear(z_size + x_size, self.hyperparams['dec_rnn_dim'])) + + + ################### + # Decoder GMM # + ################### + self.add_submodule(self.node_type + '/decoder/proj_to_GMM_log_pis', + model_if_absent=nn.Linear(self.hyperparams['dec_rnn_dim'], + self.hyperparams['GMM_components'])) + self.add_submodule(self.node_type + '/decoder/proj_to_GMM_mus', + model_if_absent=nn.Linear(self.hyperparams['dec_rnn_dim'], + self.hyperparams['GMM_components'] * self.pred_state_length)) + self.add_submodule(self.node_type + '/decoder/proj_to_GMM_log_sigmas', + model_if_absent=nn.Linear(self.hyperparams['dec_rnn_dim'], + self.hyperparams['GMM_components'] * self.pred_state_length)) + self.add_submodule(self.node_type + '/decoder/proj_to_GMM_corrs', + model_if_absent=nn.Linear(self.hyperparams['dec_rnn_dim'], + self.hyperparams['GMM_components'])) + + for name, module in self.node_modules.items(): + module.to(self.device) + + def create_new_scheduler(self, name, annealer, annealer_kws, creation_condition=True): + value_scheduler = None + rsetattr(self, name + '_scheduler', value_scheduler) + if creation_condition: + annealer_kws['device'] = self.device + value_annealer = annealer(annealer_kws) + rsetattr(self, name + '_annealer', value_annealer) + + # This is the value that we'll update on each call of + # step_annealers(). + with warnings.catch_warnings(): + warnings.simplefilter("ignore") + rsetattr(self, name, torch.tensor(value_annealer(0), device=self.device)) + dummy_optimizer = optim.Optimizer([rgetattr(self, name)], + {'lr': torch.tensor(value_annealer(0), device=self.device)}) + rsetattr(self, name + '_optimizer', dummy_optimizer) + + value_scheduler = CustomLR(dummy_optimizer, + value_annealer) + rsetattr(self, name + '_scheduler', value_scheduler) + + self.schedulers.append(value_scheduler) + self.annealed_vars.append(name) + + def set_annealing_params(self): + self.schedulers = list() + self.annealed_vars = list() + + self.create_new_scheduler(name='kl_weight', + annealer=sigmoid_anneal, + annealer_kws={ + 'start': self.hyperparams['kl_weight_start'], + 'finish': self.hyperparams['kl_weight'], + 'center_step': self.hyperparams['kl_crossover'], + 'steps_lo_to_hi': self.hyperparams['kl_crossover'] / self.hyperparams[ + 'kl_sigmoid_divisor'] + }, + creation_condition=((np.abs(self.hyperparams['alpha'] - 1.0) < 1e-3) + and (not self.hyperparams['use_iwae']))) + + self.create_new_scheduler(name='dec_sample_model_prob', + annealer=sigmoid_anneal, + annealer_kws={ + 'start': self.hyperparams['dec_sample_model_prob_start'], + 'finish': self.hyperparams['dec_sample_model_prob_final'], + 'center_step': self.hyperparams['dec_sample_model_prob_crossover'], + 'steps_lo_to_hi': self.hyperparams['dec_sample_model_prob_crossover'] / + self.hyperparams['dec_sample_model_prob_divisor'] + }, + creation_condition=self.hyperparams['sample_model_during_dec']) + + self.create_new_scheduler(name='latent.temp', + annealer=exp_anneal, + annealer_kws={ + 'start': self.hyperparams['tau_init'], + 'finish': self.hyperparams['tau_final'], + 'rate': self.hyperparams['tau_decay_rate'] + }) + + self.create_new_scheduler(name='latent.z_logit_clip', + annealer=sigmoid_anneal, + annealer_kws={ + 'start': self.hyperparams['z_logit_clip_start'], + 'finish': self.hyperparams['z_logit_clip_final'], + 'center_step': self.hyperparams['z_logit_clip_crossover'], + 'steps_lo_to_hi': self.hyperparams['z_logit_clip_crossover'] / self.hyperparams[ + 'z_logit_clip_divisor'] + }, + creation_condition=self.hyperparams['use_z_logit_clipping']) + + self.create_new_scheduler(name='warmup_dropout_keep', + annealer=sigmoid_anneal, + annealer_kws={ + 'start': self.hyperparams['inf_warmup_start'], + 'finish': self.hyperparams['inf_warmup'], + 'center_step': self.hyperparams['inf_warmup_crossover'], + 'steps_lo_to_hi': self.hyperparams['inf_warmup_crossover'] / self.hyperparams[ + 'inf_warmup_sigmoid_divisor'] + }) + + def step_annealers(self): + # This should manage all of the step-wise changed + # parameters automatically. + for idx, annealed_var in enumerate(self.annealed_vars): + if rgetattr(self, annealed_var + '_scheduler') is not None: + # First we step the scheduler. + rgetattr(self, annealed_var + '_scheduler').step() + + # Then we set the annealed vars' value. + rsetattr(self, annealed_var, rgetattr(self, annealed_var + '_optimizer').param_groups[0]['lr']) + + self.summarize_annealers() + + def summarize_annealers(self): + if self.log_writer is not None: + for annealed_var in self.annealed_vars: + if rgetattr(self, annealed_var) is not None: + self.log_writer.add_scalar('%s/%s' % (str(self.node_type), annealed_var.replace('.', '/')), + rgetattr(self, annealed_var), self.curr_iter) + + def obtain_encoded_tensor_dict(self, + mode, + timestep, + timesteps_in_scene, + inputs, + inputs_st, + labels, + labels_st, + first_history_indices, + scene, + node_scene_graph_batched): + + tensor_dict = dict() # tensor_dict + batch_size = inputs.shape[0] + + ######################################### + # Provide basic information to encoders # + ######################################### + node_traj = inputs + node_history = inputs[:, :timestep + 1] + node_present_state = inputs[:, timestep] + node_pos = inputs[:, timestep, 0:2] + node_vel = inputs[:, timestep, 2:4] + + node_traj_st = inputs_st + node_history_st = inputs_st[:, :timestep + 1] + node_present_state_st = inputs_st[:, timestep] + node_pos_st = inputs_st[:, timestep, 0:2] + node_vel_st = inputs_st[:, timestep, 2:4] + + if self.hyperparams['incl_robot_node'] and scene.robot is not None: + robot_traj_list = [] + for timestep_s in timesteps_in_scene: + timestep_range = np.array([timestep_s - self.max_hl, timestep_s + node_traj.shape[1] - self.max_hl - 1]) + robot_traj_list.append(scene.robot.get(timestep_range, self.state[scene.robot.type.name])) + robot_traj_np = np.array(robot_traj_list) + + # Make Robot State relative to node + _, std = self.env.get_standardize_params(self.state[scene.robot.type.name], node_type=scene.robot.type) + std[0:2] = 40 + rel_state = np.zeros_like(robot_traj_np) + rel_state[..., :6] = node_traj[..., :6].cpu() + robot_traj_np_st = self.env.standardize(robot_traj_np, + self.state[scene.robot.type.name], + node_type=scene.robot.type, + mean=rel_state, + std=std) + robot_traj_st = torch.tensor(robot_traj_np_st).float().to(self.device) + robot_present_state_st = robot_traj_st[:, timestep] + robot_future_st = robot_traj_st[:, timestep+1:] + + tensor_dict['robot_present'] = robot_present_state_st + tensor_dict['robot_future'] = robot_future_st + + ################## + # Encode History # + ################## + tensor_dict['node_history_encoded'] = self.encode_node_history(mode, + node_history_st, + first_history_indices, + timestep) + + ################## + # Encode Present # + ################## + tensor_dict['node_present'] = node_present_state_st # [bs, state_dim] + + ################## + # Encode Future # + ################## + if mode != ModeKeys.PREDICT: + tensor_dict['node_future'] = labels_st[:, timestep + 1:timestep + self.ph + 1] # [bs, ph, state_dim] + + ####################################### + # Encode Joint Present (Robot + Node) # + ####################################### + if self.warmup_dropout_keep < 0.5: + if self.hyperparams['incl_robot_node'] and scene.robot is not None: + tensor_dict['joint_present'] = torch.zeros_like(torch.cat([robot_present_state_st, + labels_st[:, timestep]], dim=1)) + else: + tensor_dict['joint_present'] = torch.zeros_like(labels_st[:, timestep]) + else: + if self.hyperparams['incl_robot_node'] and scene.robot is not None: + tensor_dict['joint_present'] = torch.cat([robot_present_state_st, labels_st[:, timestep]], dim=1) + else: + tensor_dict['joint_present'] = labels_st[:, timestep] + + ############################## + # Encode Node Edges per Type # + ############################## + tensor_dict["node_edges_encoded"] = list() + for edge_type in self.edge_types: + connected_nodes_batched = list() + edge_masks_batched = list() + for i, (node, scene_graph) in enumerate(node_scene_graph_batched): + # We get all nodes which are connected to the current node for the current timestep + + connected_nodes_batched.append(scene_graph.get_neighbors(node, edge_type[1])) + + if self.hyperparams['dynamic_edges'] == 'yes': + # We get the edge masks for the current node at the current timestep + edge_masks_for_node = scene_graph.get_edge_scaling(node) + edge_masks_batched.append(torch.tensor(edge_masks_for_node).float().to(self.device)) + + # Encode edges for given edge type + encoded_edges_type = self.encode_edge(mode, + node_history, + node_history_st, + edge_type, + connected_nodes_batched, + edge_masks_batched, + first_history_indices, + timestep, + timesteps_in_scene, + scene) + tensor_dict["node_edges_encoded"].append(encoded_edges_type) # List of [bs/nbs, enc_rnn_dim] + ##################### + # Encode Node Edges # + ##################### + tensor_dict["total_edge_influence"] = self.encode_total_edge_influence(mode, + tensor_dict["node_edges_encoded"], + tensor_dict["node_history_encoded"], + batch_size) # [bs/nbs, 4*enc_rnn_dim] + #print(time.time() - t) + ############## + # Encode Map # + ############## + if mode == ModeKeys.TRAIN: + rand_heading = (2 * np.random.rand(node_present_state.shape[0]) - 1) * 5 * np.pi / 180 # outside if because seeding + else: + rand_heading = 0. + if self.hyperparams['use_map_encoding']: + heading = node_present_state.cpu().numpy()[:, -1] + rand_heading + node_pos_cpu = node_pos.cpu().numpy() + if self.node_type == 'VEHICLE': + node_pos_cpu = node_pos_cpu + 20 * np.array([np.cos(heading), np.sin(heading)]).T + cropped_maps_np = get_cropped_maps_heading_exact(world_pts=node_pos_cpu, + map=scene.map[self.node_type], + context_size=self.hyperparams['map_context'], + heading=heading) + cropped_maps_np = np.swapaxes(cropped_maps_np, -1, 1) + cropped_maps = torch.from_numpy(cropped_maps_np).to(self.device) + del cropped_maps_np + encoded_map = self.node_modules[self.node_type + '/map_encoder'](cropped_maps) + + encoded_map = F.dropout(encoded_map, 0.5, training=(mode == ModeKeys.TRAIN)) + + tensor_dict["encoded_maps"] = encoded_map + + if self.log_writer is not None and mode != ModeKeys.PREDICT: + context_size = self.hyperparams['map_context'] + #cropped_maps = cropped_maps.clone() + #cropped_maps[:, :, context_size // 2 - 3:context_size // 2 + 3, context_size // 2 - 3:context_size // 2 + 3] = 1. + self.log_writer.add_images('%s/cropped_maps' % str(self.node_type), + cropped_maps, + self.curr_iter) + + img_pts = scene.map[self.node_type].to_map_points(node_pos_cpu) + + box_arr = np.empty((img_pts.shape[0], 4)) + box_arr[:, 0] = img_pts[:, 0] - context_size // 2 + box_arr[:, 1] = img_pts[:, 1] - context_size // 2 + box_arr[:, 2] = img_pts[:, 0] + context_size // 2 + box_arr[:, 3] = img_pts[:, 1] + context_size // 2 + + self.log_writer.add_image_with_boxes('%s/cropped_locs' % str(self.node_type), + np.swapaxes(scene.map[self.node_type].fdata, -1, 0).astype(float), + box_arr, + self.curr_iter) + + ###################################### + # Concatenate Encoder Outputs into x # + ###################################### + concat_list = list() + if self.hyperparams['use_map_encoding']: + concat_list.append(tensor_dict["encoded_maps"]) # [bs/nbs, map_enc_output_size] + + # Every node has an edge-influence encoder (which could just be zero). + if self.warmup_dropout_keep < 0.5: + concat_list.append(torch.zeros_like(tensor_dict["total_edge_influence"])) + else: + concat_list.append(tensor_dict["total_edge_influence"]) # [bs/nbs, 4*enc_rnn_dim] + + # Every node has a history encoder. + if self.warmup_dropout_keep < 0.5: + concat_list.append(torch.zeros_like(tensor_dict["node_history_encoded"])) + else: + concat_list.append(tensor_dict["node_history_encoded"]) # [bs/nbs, enc_rnn_dim_history] + + if self.hyperparams['incl_robot_node'] and scene.robot is not None: + tensor_dict[scene.robot.type.name + "_robot_future_encoder"] = self.encode_robot_future( + tensor_dict['robot_present'], + tensor_dict['robot_future'], + mode, + scene.robot.type.name + '_robot') + # [bs/nbs, 4*enc_rnn_dim_future] + concat_list.append(tensor_dict[scene.robot.type.name + "_robot_future_encoder"]) + + elif self.hyperparams['incl_robot_node']: + # Four times because we're trying to mimic a bi-directional RNN's output (which is c and h from both ends). + concat_list.append( + torch.zeros([batch_size, 4 * self.hyperparams['enc_rnn_dim_future']], device=self.device)) + + tensor_dict["x"] = torch.cat(concat_list, dim=1) + + if mode == ModeKeys.TRAIN or mode == ModeKeys.EVAL: + tensor_dict[self.node_type + "_future_encoder"] = self.encode_node_future(tensor_dict['node_present'], + tensor_dict['node_future'], + mode, + self.node_type) + + return tensor_dict + + def encode_node_history(self, mode, node_traj, first_history_indices, timestep): + outputs, _ = run_lstm_on_variable_length_seqs(self.node_modules[self.node_type + '/node_history_encoder'], + node_traj, + torch.ones_like(first_history_indices) * timestep, + first_history_indices, + self.hyperparams[ + 'maximum_history_length'] + 1) # history + current + + outputs = F.dropout(outputs, + p=1. - self.hyperparams['rnn_kwargs']['dropout_keep_prob'], + training=(mode == ModeKeys.TRAIN)) # [bs, max_time, enc_rnn_dim] + + last_index_per_sequence = timestep - first_history_indices + + return outputs[torch.arange(first_history_indices.shape[0]), last_index_per_sequence] + + def encode_edge(self, + mode, + node_history, + node_history_st, + edge_type, + connected_nodes, + edge_masks, + first_history_indices, + timestep, + timesteps_in_scene, + scene): + + max_hl = self.hyperparams['maximum_history_length'] + + edge_states_list = list() # list of [#of neighbors, max_hl, state_dim] + for i, timestep_in_scene in enumerate(timesteps_in_scene): # Get neighbors for timestep in batch + neighbor_states = list() + for node in connected_nodes[i]: + neighbor_state_np = node.get(np.array([timestep_in_scene - max_hl, timestep_in_scene]), + self.state[node.type.name], + padding=0.0) + + # Make State relative to node + _, std = self.env.get_standardize_params(self.state[node.type.name], node_type=node.type) + std[0:2] = self.env.attention_radius[edge_type] + rel_state = np.zeros_like(neighbor_state_np) + rel_state[:, :6] = node_history[i, -1, :6].cpu() + neighbor_state_np_st = self.env.standardize(neighbor_state_np, + self.state[node.type.name], + node_type=node.type, + mean=rel_state, + std=std) + + neighbor_state = torch.tensor(neighbor_state_np_st).float().to(self.device) + neighbor_states.append(neighbor_state) + if len(neighbor_states) == 0: # There are no neighbors for edge type # TODO necessary? + neighbor_state_length = int(np.sum([len(entity_dims) for entity_dims in self.state[edge_type[1].name].values()])) + edge_states_list.append(torch.zeros((1, max_hl + 1, neighbor_state_length), device=self.device)) + else: + edge_states_list.append(torch.stack(neighbor_states, dim=0)) + + if self.hyperparams['edge_state_combine_method'] == 'sum': + # Used in Structural-RNN to combine edges as well. + op_applied_edge_states_list = list() + for neighbors_state in edge_states_list: + op_applied_edge_states_list.append(torch.sum(neighbors_state, dim=0)) + combined_neighbors = torch.stack(op_applied_edge_states_list, dim=0) + if self.hyperparams['dynamic_edges'] == 'yes': + # Should now be (bs, time, 1) + op_applied_edge_mask_list = list() + for edge_mask in edge_masks: + op_applied_edge_mask_list.append(torch.clamp(torch.sum(edge_mask, dim=0, keepdim=True), max=1.)) + combined_edge_masks = torch.stack(op_applied_edge_mask_list, dim=0) + + elif self.hyperparams['edge_state_combine_method'] == 'max': + # Used in NLP, e.g. max over word embeddings in a sentence. + op_applied_edge_states_list = list() + for neighbors_state in edge_states_list: + op_applied_edge_states_list.append(torch.max(neighbors_state, dim=0)) + combined_neighbors = torch.stack(op_applied_edge_states_list, dim=0) + if self.hyperparams['dynamic_edges'] == 'yes': + # Should now be (bs, time, 1) + op_applied_edge_mask_list = list() + for edge_mask in edge_masks: + op_applied_edge_mask_list.append(torch.clamp(torch.max(edge_mask, dim=0, keepdim=True), max=1.)) + combined_edge_masks = torch.stack(op_applied_edge_mask_list, dim=0) + + elif self.hyperparams['edge_state_combine_method'] == 'mean': + # Used in NLP, e.g. mean over word embeddings in a sentence. + op_applied_edge_states_list = list() + for neighbors_state in edge_states_list: + op_applied_edge_states_list.append(torch.mean(neighbors_state, dim=0)) + combined_neighbors = torch.stack(op_applied_edge_states_list, dim=0) + if self.hyperparams['dynamic_edges'] == 'yes': + # Should now be (bs, time, 1) + op_applied_edge_mask_list = list() + for edge_mask in edge_masks: + op_applied_edge_mask_list.append(torch.clamp(torch.mean(edge_mask, dim=0, keepdim=True), max=1.)) + combined_edge_masks = torch.stack(op_applied_edge_mask_list, dim=0) + + joint_history = torch.cat([combined_neighbors, node_history_st], dim=-1) + + outputs, _ = run_lstm_on_variable_length_seqs(self.node_modules[self.env.edge_type_str(edge_type) + '/edge_encoder'], + joint_history, + torch.ones_like(first_history_indices) * timestep, + first_history_indices, + self.hyperparams[ + 'maximum_history_length'] + 1) # Add prediction timestep + + outputs = F.dropout(outputs, + p=1. - self.hyperparams['rnn_kwargs']['dropout_keep_prob'], + training=(mode == ModeKeys.TRAIN)) # [bs, max_time, enc_rnn_dim] + + last_index_per_sequence = timestep - first_history_indices + ret = outputs[torch.arange(last_index_per_sequence.shape[0]), last_index_per_sequence] + if self.hyperparams['dynamic_edges'] == 'yes': + return ret * combined_edge_masks + else: + return ret + + def encode_total_edge_influence(self, mode, encoded_edges, node_history_encoder, batch_size): + if self.hyperparams['edge_influence_combine_method'] == 'sum': + stacked_encoded_edges = torch.stack(encoded_edges, dim=0) + combined_edges = torch.sum(stacked_encoded_edges, dim=0) + + elif self.hyperparams['edge_influence_combine_method'] == 'mean': + stacked_encoded_edges = torch.stack(encoded_edges, dim=0) + combined_edges = torch.mean(stacked_encoded_edges, dim=0) + + elif self.hyperparams['edge_influence_combine_method'] == 'max': + stacked_encoded_edges = torch.stack(encoded_edges, dim=0) + combined_edges = torch.max(stacked_encoded_edges, dim=0) + + elif self.hyperparams['edge_influence_combine_method'] == 'bi-rnn': + if len(encoded_edges) == 0: + combined_edges = torch.zeros((batch_size, self.eie_output_dims), device=self.device) + + else: + # axis=1 because then we get size [batch_size, max_time, depth] + encoded_edges = torch.stack(encoded_edges, dim=1) + + _, state = self.node_modules[self.node_type + '/edge_influence_encoder'](encoded_edges) + combined_edges = unpack_RNN_state(state) + combined_edges = F.dropout(combined_edges, + p=1. - self.hyperparams['rnn_kwargs']['dropout_keep_prob'], + training=(mode == ModeKeys.TRAIN)) + + elif self.hyperparams['edge_influence_combine_method'] == 'attention': + # Used in Social Attention (https://arxiv.org/abs/1710.04689) + if len(encoded_edges) == 0: + combined_edges = torch.zeros((batch_size, self.eie_output_dims), device=self.device) + + else: + # axis=1 because then we get size [batch_size, max_time, depth] + encoded_edges = torch.stack(encoded_edges, dim=1) + combined_edges, _ = self.node_modules[self.node_type + '/edge_influence_encoder'](encoded_edges, + node_history_encoder) + combined_edges = F.dropout(combined_edges, + p=1. - self.hyperparams['rnn_kwargs']['dropout_keep_prob'], + training=(mode == ModeKeys.TRAIN)) + + return combined_edges + + def encode_node_future(self, node_present, node_future, mode, scope): + initial_h_model = self.node_modules[self.node_type + '/node_future_encoder/initial_h'] + initial_c_model = self.node_modules[self.node_type + '/node_future_encoder/initial_c'] + + # Here we're initializing the forward hidden states, + # but zeroing the backward ones. + initial_h = initial_h_model(node_present) + initial_h = torch.stack([initial_h, torch.zeros_like(initial_h, device=self.device)], dim=0) + + initial_c = initial_c_model(node_present) + initial_c = torch.stack([initial_c, torch.zeros_like(initial_c, device=self.device)], dim=0) + + initial_state = (initial_h, initial_c) + + _, state = self.node_modules[self.node_type + '/node_future_encoder'](node_future, initial_state) + state = unpack_RNN_state(state) + state = F.dropout(state, + p=1. - self.hyperparams['rnn_kwargs']['dropout_keep_prob'], + training=(mode == ModeKeys.TRAIN)) + + return state + + def encode_robot_future(self, robot_present, robot_future, mode, scope): + initial_h_model = self.node_modules['robot_future_encoder/initial_h'] + initial_c_model = self.node_modules['robot_future_encoder/initial_c'] + + # Here we're initializing the forward hidden states, + # but zeroing the backward ones. + initial_h = initial_h_model(robot_present) + initial_h = torch.stack([initial_h, torch.zeros_like(initial_h, device=self.device)], dim=0) + + initial_c = initial_c_model(robot_present) + initial_c = torch.stack([initial_c, torch.zeros_like(initial_c, device=self.device)], dim=0) + + initial_state = (initial_h, initial_c) + + _, state = self.node_modules['robot_future_encoder'](robot_future, initial_state) + state = unpack_RNN_state(state) + state = F.dropout(state, + p=1. - self.hyperparams['rnn_kwargs']['dropout_keep_prob'], + training=(mode == ModeKeys.TRAIN)) + + return state + + def q_z_xy(self, x, y, mode): + xy = torch.cat([x, y], dim=1) + + if self.hyperparams['q_z_xy_MLP_dims'] is not None: + dense = self.node_modules[self.node_type + '/q_z_xy'] + h = F.dropout(F.relu(dense(xy)), + p=1. - self.hyperparams['MLP_dropout_keep_prob'], + training=(mode == ModeKeys.TRAIN)) + + else: + h = xy + + to_latent = self.node_modules[self.node_type + '/hxy_to_z'] + return self.latent.dist_from_h(to_latent(h), mode) + + def p_z_x(self, x, mode): + if self.hyperparams['p_z_x_MLP_dims'] is not None: + dense = self.node_modules[self.node_type + '/p_z_x'] + h = F.dropout(F.relu(dense(x)), + p=1. - self.hyperparams['MLP_dropout_keep_prob'], + training=(mode == ModeKeys.TRAIN)) + + else: + h = x + + to_latent = self.node_modules[self.node_type + '/hx_to_z'] + return self.latent.dist_from_h(to_latent(h), mode) + + def project_to_GMM_params(self, tensor): + log_pis = self.node_modules[self.node_type + '/decoder/proj_to_GMM_log_pis'](tensor) + mus = self.node_modules[self.node_type + '/decoder/proj_to_GMM_mus'](tensor) + log_sigmas = self.node_modules[self.node_type + '/decoder/proj_to_GMM_log_sigmas'](tensor) + corrs = torch.tanh(self.node_modules[self.node_type + '/decoder/proj_to_GMM_corrs'](tensor)) + return log_pis, mus, log_sigmas, corrs + + def p_y_xz(self, x, z_stacked, tensor_dict, mode, + num_predicted_timesteps, num_samples_z, num_samples_gmm=1, most_likely_gmm=False): + ph = num_predicted_timesteps + + our_future = "node_future" + robot_future = "robot_future" + + k = num_samples_z * num_samples_gmm + GMM_c, pred_dim = self.hyperparams['GMM_components'], self.pred_state_length + + z = torch.reshape(z_stacked, (-1, self.latent.z_dim)) + zx = torch.cat([z, x.repeat(k, 1)], dim=1) + + cell = self.node_modules[self.node_type + '/decoder/lstm_cell'] + initial_h_model = self.node_modules[self.node_type + '/decoder/initial_h'] + + initial_state = initial_h_model(zx) + + log_pis, mus, log_sigmas, corrs = [], [], [], [] + if mode in [ModeKeys.TRAIN, ModeKeys.EVAL]: + state = initial_state + if self.hyperparams['sample_model_during_dec'] and mode == ModeKeys.TRAIN: + input_ = torch.cat([zx, tensor_dict['joint_present'].repeat(k, 1)], dim=1) + for j in range(ph): + h_state = cell(input_, state) + log_pi_t, mu_t, log_sigma_t, corr_t = self.project_to_GMM_params(h_state) + y_t = GMM2D(log_pi_t, mu_t, log_sigma_t, corr_t, self.pred_state_length, self.device, + self.hyperparams['log_sigma_min'], + self.hyperparams['log_sigma_max']).sample() # [k;bs, pred_dim] + + # This is where we pick our output y_t or the true output + # our_future to pass into the next cell (we do this with + # probability self.dec_sample_model_prob and is only done + # during training). + mask = td.Bernoulli(probs=self.dec_sample_model_prob).sample((y_t.size()[0], 1)) + y_t = mask * y_t + (1 - mask) * (tensor_dict[our_future][:, j, :].repeat(k, 1)) + + log_pis.append(log_pi_t) + mus.append(mu_t) + log_sigmas.append(log_sigma_t) + corrs.append(corr_t) + + if self.hyperparams['incl_robot_node']: + dec_inputs = torch.cat([tensor_dict[robot_future][:, j, :].repeat(k, 1), y_t], dim=1) + else: + dec_inputs = y_t + + input_ = torch.cat([zx, dec_inputs], dim=1) + state = h_state + + log_pis = torch.stack(log_pis, dim=1) + mus = torch.stack(mus, dim=1) + log_sigmas = torch.stack(log_sigmas, dim=1) + corrs = torch.stack(corrs, dim=1) + + else: + zx_with_time_dim = zx.unsqueeze(dim=1) # [k;bs/nbs, 1, N*K + 2*enc_rnn_dim] + zx_time_tiled = zx_with_time_dim.repeat(1, ph, 1) + if self.hyperparams['incl_robot_node']: + dec_inputs = torch.cat([ + tensor_dict["joint_present"].unsqueeze(dim=1), + torch.cat([tensor_dict[robot_future][:, :ph - 1, :], tensor_dict[our_future][:, :ph - 1, :]], + dim=2) + ], dim=1) + else: + dec_inputs = torch.cat([ + tensor_dict["joint_present"].unsqueeze(dim=1), + tensor_dict[our_future][:, :ph - 1, :] + ], dim=1) + + outputs = list() + for j in range(ph): + inputs = torch.cat([zx_time_tiled, dec_inputs.repeat(k, 1, 1)], + dim=2) + h_state = cell(inputs[:, j, :], state) + outputs.append(h_state) + state = h_state + + outputs = torch.stack(outputs, dim=1) + log_pis, mus, log_sigmas, corrs = self.project_to_GMM_params(outputs) + + if self.hyperparams['log_histograms'] and self.log_writer is not None: + self.log_writer.add_histogram('%s/%s' % (str(self.node_type), 'GMM_log_pis'), log_pis, self.curr_iter) + self.log_writer.add_histogram('%s/%s' % (str(self.node_type), 'GMM_mus'), mus, self.curr_iter) + self.log_writer.add_histogram('%s/%s' % (str(self.node_type), 'GMM_log_sigmas'), log_sigmas, + self.curr_iter) + self.log_writer.add_histogram('%s/%s' % (str(self.node_type), 'GMM_corrs'), corrs, self.curr_iter) + + elif mode == ModeKeys.PREDICT: + input_ = torch.cat([zx, tensor_dict["joint_present"].repeat(k, 1)], dim=1) + state = initial_state + + log_pis, mus, log_sigmas, corrs, y = [], [], [], [], [] + for j in range(ph): + h_state = cell(input_, state) + log_pi_t, mu_t, log_sigma_t, corr_t = self.project_to_GMM_params(h_state) + + gmm = GMM2D(log_pi_t, mu_t, log_sigma_t, corr_t, self.pred_state_length, self.device, + self.hyperparams['log_sigma_min'], + self.hyperparams['log_sigma_max']) # [k;bs, pred_dim] + + if most_likely_gmm: + y_t_list = [] + for i in range(gmm.mus.shape[0]): + gmm_i = GMM2D(log_pi_t[i], mu_t[i], log_sigma_t[i], corr_t[i], self.pred_state_length, + self.device, + self.hyperparams['log_sigma_min'], + self.hyperparams['log_sigma_max']) # [k;bs, pred_dim] + x_min = gmm.mus[i, ..., 0].min() + x_max = gmm.mus[i, ..., 0].max() + y_min = gmm.mus[i, ..., 1].min() + y_max = gmm.mus[i, ..., 1].max() + x_min = x_min - 0.5 * torch.abs(x_min) + x_max = x_max + 0.5 * torch.abs(x_max) + y_min = y_min - 0.5 * torch.abs(y_min) + y_max = y_max + 0.5 * torch.abs(y_max) + search_grid = torch.stack(torch.meshgrid([torch.arange(x_min, x_max, 0.01), + torch.arange(y_min, y_max, 0.01)]), dim=2 + ).view(1, -1, 2).float().to( + self.device) + + ll_score = gmm_i.log_prob(search_grid).squeeze() + y_t_list.append(search_grid[0, torch.argmax(ll_score, dim=0)]) + + y_t = torch.stack(y_t_list, dim=0) + else: + y_t = gmm.sample() + + log_pis.append(log_pi_t) + mus.append(mu_t) + log_sigmas.append(log_sigma_t) + corrs.append(corr_t) + y.append(y_t) + + if self.hyperparams['incl_robot_node']: + dec_inputs = torch.cat([tensor_dict[robot_future][:, j, :].repeat(k, 1), y_t], dim=1) + else: + dec_inputs = y_t + + input_ = torch.cat([zx, dec_inputs],dim=1) + state = h_state + + log_pis = torch.stack(log_pis, dim=1) + mus = torch.stack(mus, dim=1) + log_sigmas = torch.stack(log_sigmas, dim=1) + corrs = torch.stack(corrs, dim=1) + sampled_future = torch.reshape(torch.stack(y, dim=1), (num_samples_z, num_samples_gmm, -1, ph, pred_dim)) + + y_dist = GMM2D(torch.reshape(log_pis, [k, -1, ph, GMM_c]), + torch.reshape(mus, [k, -1, ph, GMM_c * pred_dim]), + torch.reshape(log_sigmas, [k, -1, ph, GMM_c * pred_dim]), + torch.reshape(corrs, [k, -1, ph, GMM_c]), + self.pred_state_length, self.device, + self.hyperparams['log_sigma_min'], self.hyperparams['log_sigma_max']) + + if mode == ModeKeys.PREDICT: + return y_dist, sampled_future + else: + return y_dist + + def encoder(self, x, y, mode, num_samples=None): + if mode == ModeKeys.TRAIN: + sample_ct = self.hyperparams['k'] + elif mode == ModeKeys.EVAL: + sample_ct = self.hyperparams['k_eval'] + elif mode == ModeKeys.PREDICT: + sample_ct = num_samples + if num_samples is None: + raise ValueError("num_samples cannot be None with mode == PREDICT.") + + self.latent.q_dist = self.q_z_xy(x, y, mode) + self.latent.p_dist = self.p_z_x(x, mode) + + z = self.latent.sample_q(sample_ct, mode) + + if mode == ModeKeys.TRAIN and self.hyperparams['kl_exact']: + kl_obj = self.latent.kl_q_p(self.log_writer, '%s' % str(self.node_type), self.curr_iter) + if self.log_writer is not None: + self.log_writer.add_scalar('%s/%s' % (str(self.node_type), 'kl'), kl_obj, self.curr_iter) + else: + kl_obj = None + + return z, kl_obj + + def decoder(self, x, y, z, tensor_dict, mode, num_predicted_timesteps, num_samples): + y_dist = self.p_y_xz(x, z, tensor_dict, mode, num_predicted_timesteps, num_samples) + log_p_yt_xz = torch.clamp(y_dist.log_prob(y), max=self.hyperparams['log_p_yt_xz_max']) + if self.hyperparams['log_histograms'] and self.log_writer is not None: + self.log_writer.add_histogram('%s/%s' % (str(self.node_type), 'log_p_yt_xz'), log_p_yt_xz, self.curr_iter) + + log_p_y_xz = torch.sum(log_p_yt_xz, dim=2) + return log_p_y_xz + + def mutual_inf_mc(self, x_dist): + dist = x_dist.__class__ + H_y = dist(probs=x_dist.probs.mean(dim=0)).entropy() + return (H_y - x_dist.entropy().mean(dim=0)).sum() + + def train_loss(self, + inputs, + inputs_st, + first_history_indices, + labels, + labels_st, + scene, + node_scene_graph_batched, + timestep, + timesteps_in_scene, + prediction_horizon): + + mode = ModeKeys.TRAIN + + tensor_dict = self.obtain_encoded_tensor_dict(mode, + timestep, + timesteps_in_scene, + inputs, + inputs_st, + labels, + labels_st, + first_history_indices, + scene, + node_scene_graph_batched) + + z, kl = self.encoder(tensor_dict["x"], tensor_dict[self.node_type + "_future_encoder"], mode) + log_p_y_xz = self.decoder(tensor_dict["x"], tensor_dict["node_future"], z, tensor_dict, mode, + prediction_horizon, + self.hyperparams['k']) + + if np.abs(self.hyperparams['alpha'] - 1.0) < 1e-3 and not self.hyperparams['use_iwae']: + log_p_y_xz_mean = torch.mean(log_p_y_xz, dim=0) # [nbs] + log_likelihood = torch.mean(log_p_y_xz_mean) + + mutual_inf_q = self.mutual_inf_mc(self.latent.q_dist) + mutual_inf_p = self.mutual_inf_mc(self.latent.p_dist) + + ELBO = log_likelihood - self.kl_weight * kl + 1. * mutual_inf_p + loss = -ELBO + + if self.hyperparams['log_histograms'] and self.log_writer is not None: + self.log_writer.add_histogram('%s/%s' % (str(self.node_type), 'log_p_y_xz'), + log_p_y_xz_mean, + self.curr_iter) + + else: + log_q_z_xy = self.latent.q_log_prob(z) # [k, nbs] + log_p_z_x = self.latent.p_log_prob(z) # [k, nbs] + a = self.hyperparams['alpha'] + log_pp_over_q = log_p_y_xz + log_p_z_x - log_q_z_xy + log_likelihood = (torch.mean(torch.logsumexp(log_pp_over_q * (1. - a), dim=0)) + - torch.log(self.hyperparams['k'])) / (1. - a) + loss = -log_likelihood + + if self.log_writer is not None: + self.log_writer.add_scalar('%s/%s' % (str(self.node_type), 'mutual_information_q'), + mutual_inf_q, + self.curr_iter) + self.log_writer.add_scalar('%s/%s' % (str(self.node_type), 'mutual_information_p'), + mutual_inf_p, + self.curr_iter) + self.log_writer.add_scalar('%s/%s' % (str(self.node_type), 'log_likelihood'), + log_likelihood, + self.curr_iter) + self.log_writer.add_scalar('%s/%s' % (str(self.node_type), 'loss'), + loss, + self.curr_iter) + if self.hyperparams['log_histograms']: + self.latent.summarize_for_tensorboard(self.log_writer, str(self.node_type), self.curr_iter) + + return loss + + def eval_loss(self, + inputs, + inputs_st, + first_history_indices, + labels, + labels_st, + scene, + node_scene_graph_batched, + timestep, + timesteps_in_scene, + prediction_horizon, + compute_naive=True, + compute_exact=True, + compute_sample=True): + mode = ModeKeys.EVAL + + tensor_dict = self.obtain_encoded_tensor_dict(mode, + timestep, + timesteps_in_scene, + inputs, + inputs_st, + labels, + labels_st, + first_history_indices, + scene, + node_scene_graph_batched) + + ### Importance sampled NLL estimate + z, _ = self.encoder(tensor_dict["x"], tensor_dict[self.node_type + "_future_encoder"], + mode) # [k_eval, nbs, N*K] + log_p_y_xz = self.decoder(tensor_dict["x"], tensor_dict['node_future'], z, tensor_dict, mode, + prediction_horizon, + self.hyperparams['k_eval']) # [k_eval, nbs] + log_q_z_xy = self.latent.q_log_prob(z) # [k_eval, nbs] + log_p_z_x = self.latent.p_log_prob(z) # [k_eval, nbs] + log_likelihood = torch.mean(torch.logsumexp(log_p_y_xz + log_p_z_x - log_q_z_xy, dim=0)) - \ + torch.log(torch.tensor(self.hyperparams['k_eval'], dtype=torch.float, device=self.device)) + nll_q_is = -log_likelihood + + ### Naive sampled NLL estimate + nll_p = torch.tensor(np.nan) + if compute_naive: + z = self.latent.sample_p(self.hyperparams['k_eval'], mode) + log_p_y_xz = self.decoder(tensor_dict["x"], tensor_dict['node_future'], z, tensor_dict, mode, + prediction_horizon, + self.hyperparams['k_eval']) + log_likelihood_p = torch.mean(torch.logsumexp(log_p_y_xz, dim=0)) - \ + torch.log( + torch.tensor(self.hyperparams['k_eval'], dtype=torch.float, device=self.device)) + nll_p = -log_likelihood_p + + ### Exact NLL + nll_exact = torch.tensor(np.nan) + if compute_exact: + K, N = self.hyperparams['K'], self.hyperparams['N'] + if K ** N < 50: + nbs = tensor_dict["x"].size()[0] + z_raw = torch.from_numpy( + DiscreteLatent.all_one_hot_combinations(N, K).astype(np.float32) + ).to(self.device).repeat(1, nbs) # [K**N, nbs*N*K] + + z = torch.reshape(z_raw, (K ** N, -1, N * K)) # [K**N, nbs, N*K] + log_p_y_xz = self.decoder(tensor_dict["x"], tensor_dict['node_future'], z, tensor_dict, mode, + prediction_horizon, + K ** N) # [K**N, nbs] + log_p_z_x = self.latent.p_log_prob(z) # [K**N, nbs] + exact_log_likelihood = torch.mean(torch.logsumexp(log_p_y_xz + log_p_z_x, dim=0)) + + nll_exact = -exact_log_likelihood + + nll_sampled = torch.tensor(np.nan) + if compute_sample: + z = self.latent.sample_p(self.hyperparams['k_eval'], mode) + y_dist, _ = self.p_y_xz(tensor_dict["x"], z, tensor_dict, ModeKeys.PREDICT, prediction_horizon, + self.hyperparams['k_eval']) + log_p_yt_xz = torch.clamp(y_dist.log_prob(tensor_dict['node_future']), + max=self.hyperparams['log_p_yt_xz_max']) + log_p_y_xz = torch.sum(log_p_yt_xz, dim=2) + log_p_y_xz_mean = torch.mean(log_p_y_xz, dim=0) # [nbs] + log_likelihood = torch.mean(log_p_y_xz_mean) + nll_sampled = -log_likelihood + + if self.log_writer is not None: + self.log_writer.add_scalar('%s/%s' % (str(self.node_type), 'log_likelihood_eval'), + log_likelihood, + self.curr_iter) + + return nll_q_is, nll_p, nll_exact, nll_sampled + + def predict(self, + inputs, + inputs_st, + labels, + labels_st, + first_history_indices, + scene, + node_scene_graph_batched, + timestep, + timesteps_in_scene, + prediction_horizon, + num_samples_z, + num_samples_gmm, + most_likely_z=False, + most_likely_gmm=False, + all_z=False): + mode = ModeKeys.PREDICT + + tensor_dict = self.obtain_encoded_tensor_dict(mode, + timestep, + timesteps_in_scene, + inputs, + inputs_st, + labels, + labels_st, + first_history_indices, + scene, + node_scene_graph_batched) + + self.latent.p_dist = self.p_z_x(tensor_dict["x"], mode) + z, num_samples_z = self.latent.sample_p(num_samples_z, + mode, + num_samples_gmm=num_samples_gmm, + most_likely=most_likely_z, + all_z=all_z) + + y_dist, our_sampled_future = self.p_y_xz(tensor_dict["x"], z, tensor_dict, mode, + prediction_horizon, + num_samples_z, + num_samples_gmm, + most_likely_gmm) # y_dist.mean is [k, bs, ph*state_dim] + + return our_sampled_future diff --git a/code/notebooks/Car TOP_VIEW 375397.png b/code/notebooks/Car TOP_VIEW 375397.png new file mode 100644 index 0000000..6c39526 Binary files /dev/null and b/code/notebooks/Car TOP_VIEW 375397.png differ diff --git a/code/notebooks/Car TOP_VIEW 80CBE5.png b/code/notebooks/Car TOP_VIEW 80CBE5.png new file mode 100644 index 0000000..a52a6f6 Binary files /dev/null and b/code/notebooks/Car TOP_VIEW 80CBE5.png differ diff --git a/code/notebooks/Car TOP_VIEW ABCB51.png b/code/notebooks/Car TOP_VIEW ABCB51.png new file mode 100644 index 0000000..8e2e369 Binary files /dev/null and b/code/notebooks/Car TOP_VIEW ABCB51.png differ diff --git a/code/notebooks/Car TOP_VIEW C8B0B0.png b/code/notebooks/Car TOP_VIEW C8B0B0.png new file mode 100644 index 0000000..d515038 Binary files /dev/null and b/code/notebooks/Car TOP_VIEW C8B0B0.png differ diff --git a/code/notebooks/Car TOP_VIEW F05F78.png b/code/notebooks/Car TOP_VIEW F05F78.png new file mode 100644 index 0000000..e721425 Binary files /dev/null and b/code/notebooks/Car TOP_VIEW F05F78.png differ diff --git a/code/notebooks/Car TOP_VIEW ROBOT.png b/code/notebooks/Car TOP_VIEW ROBOT.png new file mode 100644 index 0000000..6487cc9 Binary files /dev/null and b/code/notebooks/Car TOP_VIEW ROBOT.png differ diff --git a/code/notebooks/NuScenes Qualitative.ipynb b/code/notebooks/NuScenes Qualitative.ipynb new file mode 100644 index 0000000..a0c0b6f --- /dev/null +++ b/code/notebooks/NuScenes Qualitative.ipynb @@ -0,0 +1,675 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "%matplotlib inline\n", + "import sys\n", + "sys.path.append('../../code')\n", + "import os\n", + "import numpy as np\n", + "import torch\n", + "import pickle\n", + "import json\n", + "import matplotlib.pyplot as plt\n", + "import matplotlib.ticker as ticker\n", + "import matplotlib.patheffects as pe\n", + "from helper import *\n", + "from data import *" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Load nuScenes SDK and data" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "nuScenes_data_path = # Data Path to nuScenes data set \n", + "nuScenes_devkit_path = '../../data/nuScenes/nuscenes-devkit/python-sdk/'\n", + "sys.path.append(nuScenes_devkit_path)\n", + "from nuscenes.map_expansion.map_api import NuScenesMap\n", + "nusc_map = NuScenesMap(dataroot=nuScenes_data_path, map_name='singapore-queenstown')" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [], + "source": [ + "line_colors = ['#375397','#80CBE5','#ABCB51','#F05F78', '#C8B0B0']" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Map Encoding Demo" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [], + "source": [ + "with open('../../data/processed/nuScenes_samples.pkl', 'rb') as f:\n", + " eval_env = pickle.load(f, encoding='latin1')\n", + "eval_scenes = eval_env.scenes" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Loading from ../../data/nuScenes/models/me_demo/model_registrar-1.pt\n", + "Loaded!\n", + "\n" + ] + } + ], + "source": [ + "ph = 6\n", + "log_dir = '../../data/nuScenes/models'\n", + "model_dir = os.path.join(log_dir, 'me_demo') \n", + "eval_stg, hyp = load_model(model_dir, eval_env, ts=1)" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [], + "source": [ + "# Load Scene\n", + "for s_scene in eval_scenes:\n", + " if s_scene.name == \"1002\":\n", + " scene = s_scene" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [], + "source": [ + "# Define ROI in nuScenes Map\n", + "x_min = 262.0\n", + "x_max = 560.0\n", + "y_min = 1864.0\n", + "y_max = 2071.0" + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [], + "source": [ + "layers = ['drivable_area',\n", + " 'road_segment',\n", + " 'lane',\n", + " 'ped_crossing',\n", + " 'walkway',\n", + " 'stop_line',\n", + " 'road_divider',\n", + " 'lane_divider']" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Prediction including Map Encoding" + ] + }, + { + "cell_type": "code", + "execution_count": 10, + "metadata": {}, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Clipping input data to the valid range for imshow with RGB data ([0..1] for floats or [0..255] for integers).\n", + "Clipping input data to the valid range for imshow with RGB data ([0..1] for floats or [0..255] for integers).\n", + "Clipping input data to the valid range for imshow with RGB data ([0..1] for floats or [0..255] for integers).\n", + "Clipping input data to the valid range for imshow with RGB data ([0..1] for floats or [0..255] for integers).\n", + "Clipping input data to the valid range for imshow with RGB data ([0..1] for floats or [0..255] for integers).\n" + ] + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "ph = 7\n", + "with torch.no_grad():\n", + " timestep = np.array([32])\n", + " predictions = eval_stg.predict(scene,\n", + " timestep,\n", + " ph,\n", + " num_samples_z=500,\n", + " most_likely_z=False,\n", + " all_z=False,\n", + " most_likely_gmm=False)\n", + "\n", + " predictions_mm = eval_stg.predict(scene,\n", + " timestep,\n", + " ph,\n", + " num_samples_z=1,\n", + " most_likely_z=True,\n", + " all_z=False,\n", + " most_likely_gmm=True)\n", + "\n", + " # Plot predicted timestep for random scene in map\n", + " my_patch = (x_min, y_min, x_max, y_max)\n", + " fig, ax = nusc_map.render_map_patch(my_patch, layers, figsize=(10, 22.4), alpha=0.1, render_egoposes_range=False)\n", + "\n", + " ax.plot([], [], 'ko-',\n", + " zorder=620,\n", + " markersize=4,\n", + " linewidth=2, alpha=0.7, label='Ours (MM)')\n", + "\n", + " ax.plot([],\n", + " [],\n", + " 'w--o', label='Ground Truth',\n", + " linewidth=3,\n", + " path_effects=[pe.Stroke(linewidth=4, foreground='k'), pe.Normal()])\n", + "\n", + " plot_vehicle_nice(ax,\n", + " predictions,\n", + " scene.dt,\n", + " max_hl=10,\n", + " ph=ph,\n", + " map=None, x_min=x_min, y_min=y_min)\n", + "\n", + " plot_vehicle_mm(ax,\n", + " predictions_mm,\n", + " scene.dt,\n", + " max_hl=10,\n", + " ph=ph,\n", + " map=None, x_min=x_min, y_min=y_min)\n", + "\n", + " ax.set_ylim((1965, 2020))\n", + " ax.set_xlim((370, 405))\n", + " leg = ax.legend(loc='center left', fontsize=28, frameon=True)\n", + " ax.axis('off')\n", + " for lh in leg.legendHandles:\n", + " lh.set_alpha(.5)\n", + " fig.show()\n", + " # fig.savefig('plots/qual_nuScenes_map.pdf', dpi=300, bbox_inches='tight')" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Prediction without Map Encoding" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Loading from ../../data/nuScenes/models/baseline/model_registrar-1.pt\n", + "Loaded!\n", + "\n" + ] + } + ], + "source": [ + "model_dir = os.path.join(log_dir, 'baseline') \n", + "eval_stg_nm, hyp = load_model(model_dir, eval_env, ts=1)" + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": {}, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Clipping input data to the valid range for imshow with RGB data ([0..1] for floats or [0..255] for integers).\n", + "Clipping input data to the valid range for imshow with RGB data ([0..1] for floats or [0..255] for integers).\n", + "Clipping input data to the valid range for imshow with RGB data ([0..1] for floats or [0..255] for integers).\n", + "Clipping input data to the valid range for imshow with RGB data ([0..1] for floats or [0..255] for integers).\n", + "Clipping input data to the valid range for imshow with RGB data ([0..1] for floats or [0..255] for integers).\n" + ] + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "with torch.no_grad():\n", + " timestep = np.array([32])\n", + " predictions = eval_stg_nm.predict(scene,\n", + " timestep,\n", + " ph,\n", + " num_samples_z=500,\n", + " most_likely_z=False,\n", + " all_z=False,\n", + " most_likely_gmm=False)\n", + "\n", + " predictions_mm = eval_stg_nm.predict(scene,\n", + " timestep,\n", + " ph,\n", + " num_samples_z=1,\n", + " most_likely_z=True,\n", + " all_z=False,\n", + " most_likely_gmm=True)\n", + "\n", + " # Plot predicted timestep for random scene in map\n", + " my_patch = (x_min, y_min, x_max, y_max)\n", + " fig, ax = nusc_map.render_map_patch(my_patch, nusc_map.non_geometric_layers[:-1], figsize=(10, 22.4), alpha=0.1,\n", + " render_egoposes_range=False)\n", + "\n", + " ax.plot([], [], 'ko-',\n", + " zorder=620,\n", + " markersize=4,\n", + " linewidth=2, alpha=0.7, label='Ours (MM)')\n", + "\n", + " ax.plot([],\n", + " [],\n", + " 'w--',\n", + " linewidth=4,\n", + " zorder=650,\n", + " path_effects=[pe.Stroke(linewidth=2, foreground='k'), pe.Normal()], label=\"Ground Truth\")\n", + "\n", + " plot_vehicle_nice(ax,\n", + " predictions,\n", + " scene.dt,\n", + " max_hl=10,\n", + " ph=ph,\n", + " map=None, x_min=x_min, y_min=y_min)\n", + " plot_vehicle_mm(ax,\n", + " predictions_mm,\n", + " scene.dt,\n", + " max_hl=10,\n", + " ph=ph,\n", + " map=None, x_min=x_min, y_min=y_min)\n", + "\n", + " ax.set_ylim((1965, 2020))\n", + " ax.set_xlim((370, 405))\n", + " ax.axis('off')\n", + " ax.get_legend().remove()\n", + " fig.show()\n", + " # fig.savefig('plots/qual_nuScenes_no_map.pdf', dpi=300, bbox_inches='tight')" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Robot Future Influence Demo" + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "metadata": {}, + "outputs": [], + "source": [ + "with open('../../data/processed/nuScenes_samples.pkl', 'rb') as f:\n", + " eval_env = pickle.load(f, encoding='latin1')\n", + "eval_scenes = eval_env.scenes" + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Loading from ../../data/nuScenes/models/robot_demo/model_registrar-1.pt\n", + "Loaded!\n", + "\n" + ] + } + ], + "source": [ + "ph = 6\n", + "model_dir = os.path.join(log_dir, 'robot_demo') \n", + "eval_stg_nm, hyp = load_model(model_dir, eval_env, ts=1)" + ] + }, + { + "cell_type": "code", + "execution_count": 15, + "metadata": {}, + "outputs": [], + "source": [ + "# Define ROI in nuScenes map\n", + "x_min = 277\n", + "x_max = 523\n", + "y_min = 1515\n", + "y_max = 1783" + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": {}, + "outputs": [], + "source": [ + "nusc_map = NuScenesMap(dataroot=nuScenes_data_path, map_name='boston-seaport')" + ] + }, + { + "cell_type": "code", + "execution_count": 17, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Found\n" + ] + } + ], + "source": [ + "for s_scene in eval_scenes:\n", + " if s_scene.name == \"234\":\n", + " scene = s_scene\n", + " print('Found')" + ] + }, + { + "cell_type": "code", + "execution_count": 18, + "metadata": {}, + "outputs": [], + "source": [ + "keep_nodes = []\n", + "for i in range(len(scene.nodes)):\n", + " if scene.nodes[i].position.x[0] > 140 and scene.nodes[i].position.x[0] < 160:\n", + " if scene.nodes[i].position.y[0] > 104 and scene.nodes[i].position.y[0] < 120:\n", + " keep_nodes.append(scene.nodes[i])\n", + "scene.nodes = keep_nodes" + ] + }, + { + "cell_type": "code", + "execution_count": 19, + "metadata": {}, + "outputs": [], + "source": [ + "layers = ['drivable_area',\n", + " 'lane',\n", + " 'ped_crossing',\n", + " 'walkway',\n", + " 'road_divider',\n", + " 'lane_divider']" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Robot normal acceleration" + ] + }, + { + "cell_type": "code", + "execution_count": 22, + "metadata": {}, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Clipping input data to the valid range for imshow with RGB data ([0..1] for floats or [0..255] for integers).\n", + "Clipping input data to the valid range for imshow with RGB data ([0..1] for floats or [0..255] for integers).\n" + ] + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "with torch.no_grad():\n", + " timestep = np.array([9])\n", + " predictions = eval_stg_nm.predict(scene,\n", + " timestep,\n", + " ph,\n", + " num_samples_z=100,\n", + " most_likely_z=False,\n", + " all_z=False,\n", + " min_future_timesteps=ph,\n", + " most_likely_gmm=False)\n", + "\n", + " my_patch = (x_min, y_min, x_max, y_max)\n", + " fig, ax = nusc_map.render_map_patch(my_patch, layers, figsize=(10.8, 9), alpha=0.1, render_egoposes_range=False,\n", + " render_legend=False)\n", + " hand, labl = ax.get_legend_handles_labels()\n", + " handout = []\n", + " lablout = []\n", + " ax.legend(handout, lablout)\n", + " fig.legend(handout, lablout)\n", + " ax.plot([],\n", + " [],\n", + " '--o',\n", + " c='#F05F78',\n", + " linewidth=4,\n", + " markersize=3,\n", + " zorder=650,\n", + " path_effects=[pe.Stroke(linewidth=2, foreground='k'), pe.Normal()], label=\"Ego Plan\")\n", + "\n", + " plot_vehicle_nice_mv(ax,\n", + " predictions,\n", + " scene.dt,\n", + " max_hl=10,\n", + " ph=ph,\n", + " map=None, x_min=x_min, y_min=y_min)\n", + "\n", + " test = {'u': 2}\n", + " p_robot = dict()\n", + " p_robot[timestep[0]] = {scene.robot: np.zeros((1, 1, ph, 2))}\n", + "\n", + " plot_vehicle_nice_mv_robot(ax,\n", + " p_robot,\n", + " scene.dt,\n", + " max_hl=10,\n", + " ph=ph,\n", + " map=None, x_min=x_min, y_min=y_min)\n", + "\n", + " ax.set_ylim((1615, 1630))\n", + " ax.set_xlim((418, 435))\n", + " ax.axis('off')\n", + " leg = ax.legend(loc='lower left', fontsize=31, frameon=True)\n", + " ax.axis('off')\n", + " for lh in leg.legendHandles:\n", + " lh.set_alpha(.5)\n", + " # leg.remove()\n", + " fig.show()\n", + " #fig.savefig('plots/qual_nuScenes_robot_vel.pdf', dpi=300, bbox_inches='tight')" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Robot decrease acceleration" + ] + }, + { + "cell_type": "code", + "execution_count": 23, + "metadata": {}, + "outputs": [], + "source": [ + "breaking_at_t = 10\n", + "breaking_sequence = np.arange(1, scene.timesteps - breaking_at_t + 1)\n", + "scene.robot.velocity.x[breaking_at_t:] = 0.25 * scene.robot.velocity.x[breaking_at_t:]\n", + "scene.robot.velocity.y[breaking_at_t:] = 0.25 * scene.robot.velocity.y[breaking_at_t:]\n", + "scene.robot.position.x[breaking_at_t:] = np.squeeze(integrate(scene.robot.velocity.x[np.newaxis, breaking_at_t:], 0.5, scene.robot.position.x[breaking_at_t]))\n", + "scene.robot.position.y[breaking_at_t:] = np.squeeze(integrate(scene.robot.velocity.y[np.newaxis, breaking_at_t:], 0.5, scene.robot.position.y[breaking_at_t]))\n", + "scene.robot.acceleration.x = np.gradient(scene.robot.velocity.x[breaking_at_t:], 0.5)\n", + "scene.robot.acceleration.y = np.gradient(scene.robot.velocity.y[breaking_at_t:], 0.5)" + ] + }, + { + "cell_type": "code", + "execution_count": 24, + "metadata": {}, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Clipping input data to the valid range for imshow with RGB data ([0..1] for floats or [0..255] for integers).\n", + "Clipping input data to the valid range for imshow with RGB data ([0..1] for floats or [0..255] for integers).\n" + ] + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "with torch.no_grad():\n", + " timestep = np.array([9])\n", + " predictions = eval_stg_nm.predict(scene,\n", + " timestep,\n", + " ph,\n", + " num_samples_z=100,\n", + " most_likely_z=False,\n", + " all_z=False,\n", + " min_future_timesteps=ph,\n", + " most_likely_gmm=False)\n", + "\n", + " my_patch = (x_min, y_min, x_max, y_max)\n", + " fig, ax = nusc_map.render_map_patch(my_patch, layers, figsize=(10.8, 9), alpha=0.1, render_egoposes_range=False,\n", + " render_legend=False)\n", + " hand, labl = ax.get_legend_handles_labels()\n", + " handout = []\n", + " lablout = []\n", + " ax.legend(handout, lablout)\n", + " fig.legend(handout, lablout)\n", + " ax.plot([],\n", + " [],\n", + " '--o',\n", + " c='#F05F78',\n", + " linewidth=4,\n", + " markersize=3,\n", + " zorder=650,\n", + " path_effects=[pe.Stroke(linewidth=2, foreground='k'), pe.Normal()], label=\"Ego Plan\")\n", + "\n", + " plot_vehicle_nice_mv(ax,\n", + " predictions,\n", + " scene.dt,\n", + " max_hl=10,\n", + " ph=ph,\n", + " map=None, x_min=x_min, y_min=y_min)\n", + "\n", + " test = {'u': 2}\n", + " p_robot = dict()\n", + " p_robot[timestep[0]] = {scene.robot: np.zeros((1, 1, ph, 2))}\n", + "\n", + " plot_vehicle_nice_mv_robot(ax,\n", + " p_robot,\n", + " scene.dt,\n", + " max_hl=10,\n", + " ph=ph,\n", + " map=None, x_min=x_min, y_min=y_min)\n", + "\n", + " ax.set_ylim((1615, 1630))\n", + " ax.set_xlim((418, 435))\n", + " ax.axis('off')\n", + " leg = ax.legend(loc='lower left', fontsize=31, frameon=True)\n", + " ax.axis('off')\n", + " for lh in leg.legendHandles:\n", + " lh.set_alpha(.5)\n", + " # leg.remove()\n", + " fig.show()\n", + " #fig.savefig('plots/qual_nuScenes_robot_no_vel.pdf', dpi=300, bbox_inches='tight')" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python [conda env:trajectron] *", + "language": "python", + "name": "conda-env-trajectron-py" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.6.9" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/code/notebooks/NuScenes Quantitative.ipynb b/code/notebooks/NuScenes Quantitative.ipynb new file mode 100644 index 0000000..c5d87c2 --- /dev/null +++ b/code/notebooks/NuScenes Quantitative.ipynb @@ -0,0 +1,357 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 18, + "metadata": {}, + "outputs": [], + "source": [ + "import pandas as pd\n", + "import numpy as np\n", + "import glob\n", + "import matplotlib.pyplot as plt\n", + "import matplotlib.ticker as ticker" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Vehicles" + ] + }, + { + "cell_type": "code", + "execution_count": 22, + "metadata": { + "scrolled": false + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "FDE Results for: full\n", + "-----------------PH: 2 -------------------\n", + "FDE Mean @1.0s: 0.20380615197870672\n", + "RB Viols @1.0s: 0.009331367081367082\n", + "FDE @1.0s: 0.159987192509441\n", + "----------------------------------------------\n", + "-----------------PH: 4 -------------------\n", + "FDE Mean @2.0s: 0.7089245446368799\n", + "RB Viols @2.0s: 0.01796110396110396\n", + "FDE @2.0s: 0.5775874097014032\n", + "----------------------------------------------\n", + "-----------------PH: 6 -------------------\n", + "FDE Mean @3.0s: 1.4580818527562975\n", + "RB Viols @3.0s: 0.03552634777634778\n", + "FDE @3.0s: 1.2355597794019821\n", + "----------------------------------------------\n", + "-----------------PH: 8 -------------------\n", + "FDE Mean @4.0s: 2.4471793265269386\n", + "RB Viols @4.0s: 0.060967467467467465\n", + "FDE @4.0s: 2.1380248632492256\n", + "----------------------------------------------\n", + "\n", + "FDE Results for: me\n", + "-----------------PH: 2 -------------------\n", + "FDE Mean @1.0s: 0.18777519200515588\n", + "RB Viols @1.0s: 0.009766516516516516\n", + "FDE @1.0s: 0.1417875049716435\n", + "----------------------------------------------\n", + "-----------------PH: 4 -------------------\n", + "FDE Mean @2.0s: 0.7073491425264654\n", + "RB Viols @2.0s: 0.020398362648362648\n", + "FDE @2.0s: 0.5714762070457313\n", + "----------------------------------------------\n", + "-----------------PH: 6 -------------------\n", + "FDE Mean @3.0s: 1.4959927599549832\n", + "RB Viols @3.0s: 0.04249910624910625\n", + "FDE @3.0s: 1.246918581584546\n", + "----------------------------------------------\n", + "-----------------PH: 8 -------------------\n", + "FDE Mean @4.0s: 2.5390342440589615\n", + "RB Viols @4.0s: 0.0770950235950236\n", + "FDE @4.0s: 2.179967698272057\n", + "----------------------------------------------\n", + "\n", + "FDE Results for: edge\n", + "-----------------PH: 2 -------------------\n", + "FDE Mean @1.0s: 0.15595462204927724\n", + "RB Viols @1.0s: 0.010491312741312741\n", + "FDE @1.0s: 0.1078299341842368\n", + "----------------------------------------------\n", + "-----------------PH: 4 -------------------\n", + "FDE Mean @2.0s: 0.7240192573370534\n", + "RB Viols @2.0s: 0.02703835978835979\n", + "FDE @2.0s: 0.5440453973645435\n", + "----------------------------------------------\n", + "-----------------PH: 6 -------------------\n", + "FDE Mean @3.0s: 1.6096807601302014\n", + "RB Viols @3.0s: 0.05722472472472472\n", + "FDE @3.0s: 1.2470658003652806\n", + "----------------------------------------------\n", + "-----------------PH: 8 -------------------\n", + "FDE Mean @4.0s: 2.8022766895142093\n", + "RB Viols @4.0s: 0.09920749320749321\n", + "FDE @4.0s: 2.2312648038365013\n", + "----------------------------------------------\n", + "\n", + "FDE Results for: baseline\n", + "-----------------PH: 2 -------------------\n", + "FDE Mean @1.0s: 0.1570008548474456\n", + "RB Viols @1.0s: 0.010126090376090377\n", + "FDE @1.0s: 0.1244030330443721\n", + "----------------------------------------------\n", + "-----------------PH: 4 -------------------\n", + "FDE Mean @2.0s: 0.7250004386936006\n", + "RB Viols @2.0s: 0.028963248963248964\n", + "FDE @2.0s: 0.55775542534863\n", + "----------------------------------------------\n", + "-----------------PH: 6 -------------------\n", + "FDE Mean @3.0s: 1.6166743345433776\n", + "RB Viols @3.0s: 0.060814421564421565\n", + "FDE @3.0s: 1.2488000332764773\n", + "----------------------------------------------\n", + "-----------------PH: 8 -------------------\n", + "FDE Mean @4.0s: 2.8218295359569936\n", + "RB Viols @4.0s: 0.1029012584012584\n", + "FDE @4.0s: 2.2299034558777775\n", + "----------------------------------------------\n", + "\n" + ] + } + ], + "source": [ + "for model in ['full', 'me', 'edge', 'baseline']:\n", + " print(f\"FDE Results for: {model}\")\n", + " for ph in [2, 4, 6, 8]:\n", + " print(f\"-----------------PH: {ph} -------------------\")\n", + " perf_df = pd.DataFrame()\n", + " for f in glob.glob(f\"csv/{model}_veh_fde_full*{ph}ph.csv\"):\n", + " dataset_df = pd.read_csv(f)\n", + " dataset_df['model'] = model\n", + " perf_df = perf_df.append(dataset_df, ignore_index=True)\n", + " del perf_df['Unnamed: 0']\n", + " \n", + " print(f\"FDE Mean @{ph*0.5}s: {perf_df['error_value'][perf_df['error_type'] == 'fde'].mean()}\")\n", + " del perf_df \n", + " \n", + " perf_df = pd.DataFrame()\n", + " for f in glob.glob(f\"csv/{model}_veh_obs_full*{ph}ph.csv\"):\n", + " dataset_df = pd.read_csv(f)\n", + " dataset_df['model'] = model\n", + " perf_df = perf_df.append(dataset_df, ignore_index=True)\n", + " del perf_df['Unnamed: 0']\n", + " print(f\"RB Viols @{ph*0.5}s: {perf_df['error_value'][perf_df['error_type'] == 'obs'].sum() / (len(perf_df['error_value'][perf_df['error_type'] == 'obs'].index)*2000)}\")\n", + " del perf_df\n", + "\n", + " perf_df = pd.DataFrame()\n", + " for f in glob.glob(f\"csv/{model}_veh_fde_mm*{ph}ph.csv\"):\n", + " dataset_df = pd.read_csv(f)\n", + " dataset_df['model'] = model\n", + " perf_df = perf_df.append(dataset_df, ignore_index=True)\n", + " del perf_df['Unnamed: 0']\n", + " print(f\"FDE @{ph*0.5}s: {perf_df['error_value'][perf_df['error_type'] == 'fde'].mean()}\") \n", + " print(\"----------------------------------------------\")\n", + " del perf_df\n", + " print(\"\")" + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": {}, + "outputs": [], + "source": [ + "line_colors = ['#375397','#80CBE5','#ABCB51','#F05F78', '#C8B0B0']" + ] + }, + { + "cell_type": "code", + "execution_count": 17, + "metadata": {}, + "outputs": [], + "source": [ + "t = [0, 1, 3]\n", + "t_ours = [0, 1, 2, 3, 4]\n", + "SLSTM_l2 = np.array([0.24, 0.71, 1.85])\n", + "CSP_l2 = np.array([0.24, 0.70, 1.74])\n", + "CARNET_l2 = np.array([0.23, 0.61, 1.58])\n", + "SPAGNN_l2 = np.array([0.22, 0.58, 1.45])\n", + "OURS_l2 = np.array([0., 0.159987192509441, 0.5775874097014032, 1.2355597794019826, 2.138024863249226])\n", + "LINEAR_l2 = np.array([0., 0.32, 0.89, 1.7, 2.73])" + ] + }, + { + "cell_type": "code", + "execution_count": 21, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "fig, ax = plt.subplots(figsize=(4, 2), dpi=300)\n", + "ax.plot(t_ours[1:], LINEAR_l2[1:], '--o', linewidth=2, markersize=6 , label='Const. Velocity', c='#E79675', zorder=-10, markeredgecolor='#545454')\n", + "ax.scatter(t[1:], SPAGNN_l2[1:], 50, marker='s', label='SpAGNN', c=line_colors[2], edgecolor='#545454', zorder=2)\n", + "ax.scatter(t[1:], CSP_l2[1:], 50, marker='o' , label='CSP', c=line_colors[4], edgecolor='#545454')\n", + "ax.scatter(t[1:], CARNET_l2[1:], 50, marker='D' , label='CAR-Net', c=line_colors[1], edgecolor='#545454', zorder=1)\n", + "ax.scatter(t[1:], SLSTM_l2[1:], 50, marker='*', label='S-LSTM', c=line_colors[0], edgecolor='#545454')\n", + "ax.plot(t_ours[1:], OURS_l2[1:], '-X', linewidth=3 , label='Ours (MM)', markersize=8, c=line_colors[3], markeredgecolor='#545454')\n", + "\n", + "ax.legend(loc='lower right')\n", + "ax.set_xlabel('Time (s)')\n", + "ax.set_ylabel('Final Displacement Error (m)', fontsize=8)\n", + "\n", + "ax.set_ylim((0, 2.8))\n", + "ax.xaxis.grid(False)\n", + "ax.xaxis.set_major_locator(ticker.MultipleLocator(1.0))\n", + "\n", + "leg = ax.legend(loc='best', fontsize=7, frameon=True)\n", + "\n", + "fig.savefig('plots/nuscenes_fde_time.pdf', dpi=300, bbox_inches='tight')" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Pedestrians" + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "FDE Results for: full\n", + "-----------------PH: 2 -------------------\n", + "FDE Mean @1.0s: 0.05230925689054953\n", + "ADE Mean @1.0s: 0.04856795664591188\n", + "KDE Mean @1.0s: -0.3251187847736798\n", + "FDE @1.0s: 0.04016995675203458\n", + "ADE @1.0s: 0.041850598781567855\n", + "----------------------------------------------\n", + "-----------------PH: 4 -------------------\n", + "FDE Mean @2.0s: 0.22040387111879736\n", + "ADE Mean @2.0s: 0.11191537726981232\n", + "KDE Mean @2.0s: -1.0563039331643547\n", + "FDE @2.0s: 0.17426690322281393\n", + "ADE @2.0s: 0.08985219625873946\n", + "----------------------------------------------\n", + "-----------------PH: 6 -------------------\n", + "FDE Mean @3.0s: 0.4262051877411372\n", + "ADE Mean @3.0s: 0.19877290465482894\n", + "KDE Mean @3.0s: -0.736257085075441\n", + "FDE @3.0s: 0.34659922052319353\n", + "ADE @3.0s: 0.16031131517313374\n", + "----------------------------------------------\n", + "-----------------PH: 8 -------------------\n", + "FDE Mean @4.0s: 0.6871485975784108\n", + "ADE Mean @4.0s: 0.30302359859532546\n", + "KDE Mean @4.0s: -0.1948802425435838\n", + "FDE @4.0s: 0.5796212036776903\n", + "ADE @4.0s: 0.24894417052873324\n", + "----------------------------------------------\n", + "\n" + ] + } + ], + "source": [ + "for model in ['full']:\n", + " print(f\"FDE Results for: {model}\")\n", + " for ph in [2, 4, 6, 8]:\n", + " print(f\"-----------------PH: {ph} -------------------\")\n", + " perf_df = pd.DataFrame()\n", + " for f in glob.glob(f\"csv/{model}_ped_fde_full*{ph}ph.csv\"):\n", + " dataset_df = pd.read_csv(f)\n", + " dataset_df['model'] = model\n", + " perf_df = perf_df.append(dataset_df, ignore_index=True)\n", + " del perf_df['Unnamed: 0']\n", + " print(f\"FDE Mean @{ph*0.5}s: {perf_df['error_value'][perf_df['error_type'] == 'fde'].mean()}\")\n", + " del perf_df \n", + " \n", + " perf_df = pd.DataFrame()\n", + " for f in glob.glob(f\"csv/{model}_ped_ade_full*{ph}ph.csv\"):\n", + " dataset_df = pd.read_csv(f)\n", + " dataset_df['model'] = model\n", + " perf_df = perf_df.append(dataset_df, ignore_index=True)\n", + " del perf_df['Unnamed: 0']\n", + " print(f\"ADE Mean @{ph*0.5}s: {perf_df['error_value'][perf_df['error_type'] == 'ade'].mean()}\")\n", + " del perf_df\n", + " \n", + " perf_df = pd.DataFrame()\n", + " for f in glob.glob(f\"csv/{model}_ped_kde_full*{ph}ph.csv\"):\n", + " dataset_df = pd.read_csv(f)\n", + " dataset_df['model'] = model\n", + " perf_df = perf_df.append(dataset_df, ignore_index=True)\n", + " del perf_df['Unnamed: 0']\n", + " print(f\"KDE Mean @{ph*0.5}s: {perf_df['error_value'][perf_df['error_type'] == 'kde'].mean()}\")\n", + " del perf_df \n", + "\n", + " perf_df = pd.DataFrame()\n", + " for f in glob.glob(f\"csv/{model}_ped_fde_mm*{ph}ph.csv\"):\n", + " dataset_df = pd.read_csv(f)\n", + " dataset_df['model'] = model\n", + " perf_df = perf_df.append(dataset_df, ignore_index=True)\n", + " del perf_df['Unnamed: 0']\n", + " print(f\"FDE @{ph*0.5}s: {perf_df['error_value'][perf_df['error_type'] == 'fde'].mean()}\") \n", + " del perf_df\n", + " \n", + " perf_df = pd.DataFrame()\n", + " for f in glob.glob(f\"csv/{model}_ped_ade_mm*{ph}ph.csv\"):\n", + " dataset_df = pd.read_csv(f)\n", + " dataset_df['model'] = model\n", + " perf_df = perf_df.append(dataset_df, ignore_index=True)\n", + " del perf_df['Unnamed: 0']\n", + " print(f\"ADE @{ph*0.5}s: {perf_df['error_value'][perf_df['error_type'] == 'ade'].mean()}\") \n", + " del perf_df\n", + " print(\"----------------------------------------------\")\n", + " print(\"\")" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python [conda env:trajectron] *", + "language": "python", + "name": "conda-env-trajectron-py" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.6.9" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/code/notebooks/helper.py b/code/notebooks/helper.py new file mode 100644 index 0000000..1909007 --- /dev/null +++ b/code/notebooks/helper.py @@ -0,0 +1,288 @@ +import os +import json +import numpy as np +import matplotlib.pyplot as plt +from matplotlib.offsetbox import OffsetImage, AnnotationBbox +import matplotlib.patheffects as pe +from scipy.ndimage import rotate +import seaborn as sns + +from model.model_registrar import ModelRegistrar +from model.dyn_stg import SpatioTemporalGraphCVAEModel +from utils import prediction_output_to_trajectories + +from scipy.integrate import cumtrapz + +line_colors = ['#80CBE5', '#375397', '#F05F78', '#ABCB51', '#C8B0B0'] + +cars = [plt.imread('Car TOP_VIEW 80CBE5.png'), + plt.imread('Car TOP_VIEW 375397.png'), + plt.imread('Car TOP_VIEW F05F78.png'), + plt.imread('Car TOP_VIEW ABCB51.png'), + plt.imread('Car TOP_VIEW C8B0B0.png')] + +robot = plt.imread('Car TOP_VIEW ROBOT.png') + + +def load_model(model_dir, env, ts=3999): + model_registrar = ModelRegistrar(model_dir, 'cpu') + model_registrar.load_models(ts) + with open(os.path.join(model_dir, 'config.json'), 'r') as config_json: + hyperparams = json.load(config_json) + + hyperparams['map_enc_dropout'] = 0.0 + if 'incl_robot_node' not in hyperparams: + hyperparams['incl_robot_node'] = False + + stg = SpatioTemporalGraphCVAEModel(model_registrar, + hyperparams, + None, 'cpu') + + stg.set_scene_graph(env) + + stg.set_annealing_params() + + return stg, hyperparams + + +def plot_vehicle_nice(ax, predictions, dt, max_hl=10, ph=6, map=None, x_min=0, y_min=0): + prediction_dict, histories_dict, futures_dict = prediction_output_to_trajectories(predictions, + dt, + max_hl, + ph, + map=map) + assert (len(prediction_dict.keys()) <= 1) + if len(prediction_dict.keys()) == 0: + return + ts_key = list(prediction_dict.keys())[0] + + prediction_dict = prediction_dict[ts_key] + histories_dict = histories_dict[ts_key] + futures_dict = futures_dict[ts_key] + + if map is not None: + ax.imshow(map.fdata, origin='lower', alpha=0.5) + + cmap = ['k', 'b', 'y', 'g', 'r'] + line_alpha = 0.7 + line_width = 0.2 + edge_width = 2 + circle_edge_width = 0.5 + node_circle_size = 0.3 + a = [] + i = 0 + node_list = sorted(histories_dict.keys(), key=lambda x: x.length) + for node in node_list: + history = histories_dict[node] + np.array([x_min, y_min]) + future = futures_dict[node] + np.array([x_min, y_min]) + predictions = prediction_dict[node] + np.array([x_min, y_min]) + if node.type.name == 'VEHICLE': + # ax.plot(history[:, 0], history[:, 1], 'ko-', linewidth=1) + + ax.plot(future[:, 0], + future[:, 1], + 'w--o', + linewidth=4, + markersize=3, + zorder=650, + path_effects=[pe.Stroke(linewidth=5, foreground='k'), pe.Normal()]) + + for t in range(predictions.shape[1]): + sns.kdeplot(predictions[:, t, 0], predictions[:, t, 1], + ax=ax, shade=True, shade_lowest=False, + color=line_colors[i % len(line_colors)], zorder=600, alpha=0.8) + + vel = node.get(ts_key, {'velocity': ['x', 'y']}) + h = np.arctan2(vel[0, 1], vel[0, 0]) + r_img = rotate(cars[i % len(cars)], node.get(ts_key, {'heading': ['value']})[0, 0] * 180 / np.pi, + reshape=True) + oi = OffsetImage(r_img, zoom=0.035, zorder=700) + veh_box = AnnotationBbox(oi, (history[-1, 0], history[-1, 1]), frameon=False) + veh_box.zorder = 700 + ax.add_artist(veh_box) + i += 1 + else: + # ax.plot(history[:, 0], history[:, 1], 'k--') + + for t in range(predictions.shape[1]): + sns.kdeplot(predictions[:, t, 0], predictions[:, t, 1], + ax=ax, shade=True, shade_lowest=False, + color='b', zorder=600, alpha=0.8) + + ax.plot(future[:, 0], + future[:, 1], + 'w--', + zorder=650, + path_effects=[pe.Stroke(linewidth=edge_width, foreground='k'), pe.Normal()]) + # Current Node Position + circle = plt.Circle((history[-1, 0], + history[-1, 1]), + node_circle_size, + facecolor='g', + edgecolor='k', + lw=circle_edge_width, + zorder=3) + ax.add_artist(circle) + + +def plot_vehicle_mm(ax, predictions, dt, max_hl=10, ph=6, map=None, x_min=0, y_min=0): + prediction_dict, histories_dict, futures_dict = prediction_output_to_trajectories(predictions, + dt, + max_hl, + ph, + map=map) + assert (len(prediction_dict.keys()) <= 1) + if len(prediction_dict.keys()) == 0: + return + ts_key = list(prediction_dict.keys())[0] + + prediction_dict = prediction_dict[ts_key] + histories_dict = histories_dict[ts_key] + futures_dict = futures_dict[ts_key] + + if map is not None: + ax.imshow(map.fdata, origin='lower', alpha=0.5) + + cmap = ['k', 'b', 'y', 'g', 'r'] + line_alpha = 0.7 + line_width = 0.2 + edge_width = 2 + circle_edge_width = 0.5 + node_circle_size = 0.5 + a = [] + i = 0 + node_list = sorted(histories_dict.keys(), key=lambda x: x.length) + for node in node_list: + history = histories_dict[node] + np.array([x_min, y_min]) + future = futures_dict[node] + np.array([x_min, y_min]) + + predictions = prediction_dict[node] + np.array([x_min, y_min]) + if node.type.name == 'VEHICLE': + for sample_num in range(prediction_dict[node].shape[0]): + ax.plot(predictions[sample_num, :, 0], predictions[sample_num, :, 1], 'ko-', + zorder=620, + markersize=5, + linewidth=3, alpha=0.7) + else: + for sample_num in range(prediction_dict[node].shape[0]): + ax.plot(predictions[sample_num, :, 0], predictions[sample_num, :, 1], 'ko-', + zorder=620, + markersize=2, + linewidth=1, alpha=0.7) + + +def plot_vehicle_nice_mv(ax, predictions, dt, max_hl=10, ph=6, map=None, x_min=0, y_min=0): + prediction_dict, histories_dict, futures_dict = prediction_output_to_trajectories(predictions, + dt, + max_hl, + ph, + map=map) + assert (len(prediction_dict.keys()) <= 1) + if len(prediction_dict.keys()) == 0: + return + ts_key = list(prediction_dict.keys())[0] + + prediction_dict = prediction_dict[ts_key] + histories_dict = histories_dict[ts_key] + futures_dict = futures_dict[ts_key] + + if map is not None: + ax.imshow(map.fdata, origin='lower', alpha=0.5) + + cmap = ['k', 'b', 'y', 'g', 'r'] + line_alpha = 0.7 + line_width = 0.2 + edge_width = 2 + circle_edge_width = 0.5 + node_circle_size = 0.3 + a = [] + i = 0 + node_list = sorted(histories_dict.keys(), key=lambda x: x.length) + for node in node_list: + h = node.get(ts_key, {'heading': ['value']})[0, 0] + history_org = histories_dict[node] + np.array([x_min, y_min]) + history = histories_dict[node] + np.array([x_min, y_min]) + node.length * np.array([np.cos(h), np.sin(h)]) + future = futures_dict[node] + np.array([x_min, y_min]) + node.length * np.array([np.cos(h), np.sin(h)]) + predictions = prediction_dict[node] + np.array([x_min, y_min]) + node.length * np.array([np.cos(h), np.sin(h)]) + if node.type.name == 'VEHICLE': + for t in range(predictions.shape[1]): + sns.kdeplot(predictions[:, t, 0], predictions[:, t, 1], + ax=ax, shade=True, shade_lowest=False, + color=line_colors[i % len(line_colors)], zorder=600, alpha=1.0) + + r_img = rotate(cars[i % len(cars)], node.get(ts_key, {'heading': ['value']})[0, 0] * 180 / np.pi, + reshape=True) + oi = OffsetImage(r_img, zoom=0.08, zorder=700) + veh_box = AnnotationBbox(oi, (history_org[-1, 0], history_org[-1, 1]), frameon=False) + veh_box.zorder = 700 + ax.add_artist(veh_box) + i += 1 + else: + + for t in range(predictions.shape[1]): + sns.kdeplot(predictions[:, t, 0], predictions[:, t, 1], + ax=ax, shade=True, shade_lowest=False, + color='b', zorder=600, alpha=0.8) + + # Current Node Position + circle = plt.Circle((history[-1, 0], + history[-1, 1]), + node_circle_size, + facecolor='g', + edgecolor='k', + lw=circle_edge_width, + zorder=3) + ax.add_artist(circle) + + +def plot_vehicle_nice_mv_robot(ax, predictions, dt, max_hl=10, ph=6, map=None, x_min=0, y_min=0): + prediction_dict, histories_dict, futures_dict = prediction_output_to_trajectories(predictions, + dt, + max_hl, + ph, + map=map) + assert (len(prediction_dict.keys()) <= 1) + if len(prediction_dict.keys()) == 0: + return + ts_key = list(prediction_dict.keys())[0] + + prediction_dict = prediction_dict[ts_key] + histories_dict = histories_dict[ts_key] + futures_dict = futures_dict[ts_key] + + if map is not None: + ax.imshow(map.fdata, origin='lower', alpha=0.5) + + cmap = ['k', 'b', 'y', 'g', 'r'] + line_alpha = 0.7 + line_width = 0.2 + edge_width = 2 + circle_edge_width = 0.5 + node_circle_size = 0.3 + + node_list = sorted(histories_dict.keys(), key=lambda x: x.length) + for node in node_list: + h = node.get(ts_key, {'heading': ['value']})[0, 0] + history_org = histories_dict[node] + np.array([x_min, y_min]) + node.length / 2 * np.array( + [np.cos(h), np.sin(h)]) + future = futures_dict[node] + np.array([x_min, y_min]) + node.length * np.array([np.cos(h), np.sin(h)]) + + ax.plot(future[:, 0], + future[:, 1], + '--o', + c='#F05F78', + linewidth=4, + markersize=3, + zorder=650, + path_effects=[pe.Stroke(linewidth=5, foreground='k'), pe.Normal()]) + + r_img = rotate(robot, node.get(ts_key, {'heading': ['value']})[0, 0] * 180 / np.pi, reshape=True) + oi = OffsetImage(r_img, zoom=0.08, zorder=700) + veh_box = AnnotationBbox(oi, (history_org[-1, 0], history_org[-1, 1]), frameon=False) + veh_box.zorder = 700 + ax.add_artist(veh_box) + + +def integrate(f, dx, F0=0.): + N = f.shape[0] + return F0 + np.hstack((np.zeros((N, 1)), cumtrapz(f, axis=1, dx=dx))) diff --git a/code/notebooks/model_to_metric_nuScenes.py b/code/notebooks/model_to_metric_nuScenes.py new file mode 100644 index 0000000..7693010 --- /dev/null +++ b/code/notebooks/model_to_metric_nuScenes.py @@ -0,0 +1,182 @@ +import sys +sys.path.append('../../code') +import os +import pickle +import json +import argparse +import torch +import numpy as np +import pandas as pd +from tqdm import tqdm +from model.model_registrar import ModelRegistrar +from model.dyn_stg import SpatioTemporalGraphCVAEModel +import evaluation +from utils import prediction_output_to_trajectories +from scipy.interpolate import RectBivariateSpline + +parser = argparse.ArgumentParser() +parser.add_argument("--model", help="model full path", type=str) +parser.add_argument("--checkpoint", help="model checkpoint to evaluate", type=int) +parser.add_argument("--data", help="full path to data file", type=str) +parser.add_argument("--output", help="full path to output csv file", type=str) +parser.add_argument("--node_type", help="Node Type to evaluate", type=str) +parser.add_argument("--prediction_horizon", nargs='+', help="prediction horizon", type=int, default=None) +args = parser.parse_args() + + +def compute_obs_violations(predicted_trajs, map): + obs_map = 1 - map.fdata[..., 0] + + interp_obs_map = RectBivariateSpline(range(obs_map.shape[0]), + range(obs_map.shape[1]), + obs_map, + kx=1, ky=1) + + old_shape = predicted_trajs.shape + pred_trajs_map = map.to_map_points(predicted_trajs.reshape((-1, 2))) + + traj_obs_values = interp_obs_map(pred_trajs_map[:, 0], pred_trajs_map[:, 1], grid=False) + traj_obs_values = traj_obs_values.reshape((old_shape[0], old_shape[1])) + num_viol_trajs = np.sum(traj_obs_values.max(axis=1) > 0, dtype=float) + + return num_viol_trajs + +def compute_heading_error(prediction_output_dict, dt, max_hl, ph, node_type_enum, kde=True, obs=False, map=None): + + heading_error = list() + + for t in prediction_output_dict.keys(): + for node in prediction_output_dict[t].keys(): + if node.type.name == 'VEHICLE': + gt_vel = node.get(t + ph - 1, {'velocity': ['x', 'y']})[0] + gt_heading = np.arctan2(gt_vel[1], gt_vel[0]) + our_heading = np.arctan2(prediction_output_dict[t][node][..., -2, 1], prediction_output_dict[t][node][..., -2, 0]) + he = np.mean(np.abs(gt_heading - our_heading)) % (2 * np.pi) + heading_error.append(he) + + return heading_error + + +def load_model(model_dir, env, ts=99): + model_registrar = ModelRegistrar(model_dir, 'cpu') + model_registrar.load_models(ts) + with open(os.path.join(model_dir, 'config.json'), 'r') as config_json: + hyperparams = json.load(config_json) + + stg = SpatioTemporalGraphCVAEModel(model_registrar, + hyperparams, + None, 'cuda:0') + hyperparams['incl_robot_node'] = False + + stg.set_scene_graph(env) + stg.set_annealing_params() + return stg, hyperparams + + +if __name__ == "__main__": + with open(args.data, 'rb') as f: + env = pickle.load(f, encoding='latin1') + scenes = env.scenes + + eval_stg, hyperparams = load_model(args.model, env, ts=args.checkpoint) + + print("-- Preparing Node Graph") + for scene in tqdm(scenes): + scene.calculate_scene_graph(hyperparams['edge_radius'], + hyperparams['state'], + hyperparams['edge_addition_filter'], + hyperparams['edge_removal_filter']) + + if args.prediction_horizon is None: + args.prediction_horizon = [hyperparams['prediction_horizon']] + + for ph in args.prediction_horizon: + print(f"Prediction Horizon: {ph}") + max_hl = hyperparams['maximum_history_length'] + node_type = env.NodeType[args.node_type] + print(f"Node Type: {node_type.name}") + print(f"Edge Radius: {hyperparams['edge_radius']}") + + with torch.no_grad(): + eval_ade_batch_errors = np.array([]) + eval_fde_batch_errors = np.array([]) + eval_kde_nll = np.array([]) + eval_obs_viols = np.array([]) + print("-- Evaluating Full") + for i, scene in enumerate(tqdm(scenes)): + for timestep in range(scene.timesteps): + predictions = eval_stg.predict(scene, + np.array([timestep]), + ph, + num_samples_z=2000, + most_likely_z=False, + min_future_timesteps=8) + + if not predictions: + continue + + eval_error_dict = evaluation.compute_batch_statistics(predictions, + scene.dt, + node_type_enum=env.NodeType, + max_hl=max_hl, + ph=ph, + map=scene.map[node_type.name], + obs=True) + + eval_ade_batch_errors = np.hstack((eval_ade_batch_errors, eval_error_dict[node_type]['ade'])) + eval_fde_batch_errors = np.hstack((eval_fde_batch_errors, eval_error_dict[node_type]['fde'])) + eval_kde_nll = np.hstack((eval_kde_nll, eval_error_dict[node_type]['kde'])) + eval_obs_viols = np.hstack((eval_obs_viols, eval_error_dict[node_type]['obs_viols'])) + + del predictions + del eval_error_dict + + print(f"Final Mean Displacement Error @{ph * scene.dt}s: {np.mean(eval_fde_batch_errors)}") + print(f"Road Violations @{ph * scene.dt}s: {100 * np.sum(eval_obs_viols) / (eval_obs_viols.shape[0] * 2000)}%") + pd.DataFrame({'error_value': eval_ade_batch_errors, 'error_type': 'ade', 'type': 'full', 'ph': ph}).to_csv(args.output + '_ade_full_' + str(ph)+'ph' + '.csv') + pd.DataFrame({'error_value': eval_fde_batch_errors, 'error_type': 'fde', 'type': 'full', 'ph': ph}).to_csv(args.output + '_fde_full' + str(ph)+'ph' + '.csv') + pd.DataFrame({'error_value': eval_kde_nll, 'error_type': 'kde', 'type': 'full', 'ph': ph}).to_csv(args.output + '_kde_full' + str(ph)+'ph' + '.csv') + pd.DataFrame({'error_value': eval_obs_viols, 'error_type': 'obs', 'type': 'full', 'ph': ph}).to_csv(args.output + '_obs_full' + str(ph)+'ph' + '.csv') + + eval_ade_batch_errors = np.array([]) + eval_fde_batch_errors = np.array([]) + eval_heading_err = np.array([]) + eval_obs_viols = np.array([]) + print("-- Evaluating most likely Z and GMM") + for i, scene in enumerate(scenes): + print(f"---- Evaluating Scene {i+1}/{len(scenes)}") + for t in np.arange(0, scene.timesteps, 20): + timesteps = np.arange(t, t+20) + + predictions = eval_stg.predict(scene, + timesteps, + ph, + num_samples_z=1, + most_likely_z=True, + most_likely_gmm=True, + min_future_timesteps=8) + + eval_error_dict = evaluation.compute_batch_statistics(predictions, + scene.dt, + node_type_enum=env.NodeType, + max_hl=max_hl, + ph=ph, + map=1 - scene.map[node_type.name].fdata[..., 0], + kde=False) + eval_ade_batch_errors = np.hstack((eval_ade_batch_errors, eval_error_dict[node_type]['ade'])) + eval_fde_batch_errors = np.hstack((eval_fde_batch_errors, eval_error_dict[node_type]['fde'])) + eval_obs_viols = np.hstack((eval_obs_viols, eval_error_dict[node_type]['obs_viols'])) + + heading_error = compute_heading_error(predictions, + scene.dt, + node_type_enum=env.NodeType, + max_hl=max_hl, + ph=ph, + map=1 - scene.map[node_type.name].fdata[..., 0], + kde=False) + eval_heading_err = np.hstack((eval_heading_err, heading_error)) + + print(f"Final Displacement Error @{ph * scene.dt}s: {np.mean(eval_fde_batch_errors)}") + pd.DataFrame({'error_value': eval_ade_batch_errors, 'error_type': 'ade', 'type': 'mm', 'ph': ph}).to_csv(args.output + '_ade_mm' + str(ph)+'ph' + '.csv') + pd.DataFrame({'error_value': eval_fde_batch_errors, 'error_type': 'fde', 'type': 'mm', 'ph': ph}).to_csv(args.output + '_fde_mm' + str(ph)+'ph' + '.csv') + pd.DataFrame({'error_value': eval_obs_viols, 'error_type': 'obs', 'type': 'mm', 'ph': ph}).to_csv( args.output + '_obs_mm' + str(ph)+'ph' + '.csv') diff --git a/code/notebooks/run_eval.bash b/code/notebooks/run_eval.bash new file mode 100644 index 0000000..64d300f --- /dev/null +++ b/code/notebooks/run_eval.bash @@ -0,0 +1,6 @@ +#!/bin/bash +python model_to_metric_nuScenes.py --model "../../data/nuScenes/models/full" --checkpoint 1 --data "../../data/processed/nuScenes_test.pkl" --output "./csv/full_veh" --node_type "VEHICLE" --prediction_horizon 2 4 6 8 > full_out.txt +python model_to_metric_nuScenes.py --model "../../data/nuScenes/models/me_demo" --checkpoint 1 --data "../../data/processed/nuScenes_test.pkl" --output "./csv/me_veh" --node_type "VEHICLE" --prediction_horizon 2 4 6 8 > me_out.txt +python model_to_metric_nuScenes.py --model "../../data/nuScenes/models/edge" --checkpoint 1 --data "../../data/processed/nuScenes_test.pkl" --output "./csv/edge_veh" --node_type "VEHICLE" --prediction_horizon 2 4 6 8 > edge_out.txt +python model_to_metric_nuScenes.py --model "../../data/nuScenes/models/baseline" --checkpoint 1 --data "../../data/processed/nuScenes_test.pkl" --output "./csv/baseline_veh" --node_type "VEHICLE" --prediction_horizon 2 4 6 8 > baseline_out.txt +python model_to_metric_nuScenes.py --model "../../data/nuScenes/models/full" --checkpoint 1 --data "../../data/processed/nuScenes_test.pkl" --output "./csv/full_ped" --node_type "PEDESTRIAN" --prediction_horizon 2 4 6 8 > full_out_ped.txt \ No newline at end of file diff --git a/code/train.py b/code/train.py new file mode 100644 index 0000000..4f85def --- /dev/null +++ b/code/train.py @@ -0,0 +1,476 @@ +import torch +from torch import nn, optim +import numpy as np +import os +import time +import psutil +import pickle +import json +import random +import argparse +import pathlib +import visualization +import evaluation +import matplotlib.pyplot as plt +from model.dyn_stg import SpatioTemporalGraphCVAEModel +from model.model_registrar import ModelRegistrar +from model.model_utils import cyclical_lr +from tensorboardX import SummaryWriter +#torch.autograd.set_detect_anomaly(True) # TODO Remove for speed + + +parser = argparse.ArgumentParser() +parser.add_argument("--conf", help="path to json config file for hyperparameters", + type=str, default='config.json') +parser.add_argument("--offline_scene_graph", help="whether to precompute the scene graphs offline, options are 'no' and 'yes'", + type=str, default='yes') +parser.add_argument("--dynamic_edges", help="whether to use dynamic edges or not, options are 'no' and 'yes'", + type=str, default='yes') +parser.add_argument("--edge_radius", help="the radius (in meters) within which two nodes will be connected by an edge", + type=float, default=3.0) +parser.add_argument("--edge_state_combine_method", help="the method to use for combining edges of the same type", + type=str, default='sum') +parser.add_argument("--edge_influence_combine_method", help="the method to use for combining edge influences", + type=str, default='attention') +parser.add_argument('--edge_addition_filter', nargs='+', help="what scaling to use for edges as they're created", + type=float, default=[0.25, 0.5, 0.75, 1.0]) # We automatically pad left with 0.0 +parser.add_argument('--edge_removal_filter', nargs='+', help="what scaling to use for edges as they're removed", + type=float, default=[1.0, 0.0]) # We automatically pad right with 0.0 +parser.add_argument('--incl_robot_node', help="whether to include a robot node in the graph or simply model all agents", + action='store_true') +parser.add_argument('--use_map_encoding', help="Whether to use map encoding or not", + action='store_true') + +parser.add_argument("--data_dir", help="what dir to look in for data", + type=str, default='../data/processed') +parser.add_argument("--train_data_dict", help="what file to load for training data", + type=str, default='nuScenes_train.pkl') +parser.add_argument("--eval_data_dict", help="what file to load for evaluation data", + type=str, default='nuScenes_val.pkl') +parser.add_argument("--log_dir", help="what dir to save training information (i.e., saved models, logs, etc)", + type=str, default='../data/nuScenes/logs') +parser.add_argument("--log_tag", help="tag for the log folder", + type=str, default='') + +parser.add_argument('--device', help='what device to perform training on', + type=str, default='cuda:1') +parser.add_argument("--eval_device", help="what device to use during evaluation", + type=str, default=None) + +parser.add_argument("--num_iters", help="number of iterations to train for", + type=int, default=2000) +parser.add_argument('--batch_multiplier', help='how many minibatches to run per iteration of training', + type=int, default=1) +parser.add_argument('--batch_size', help='training batch size', + type=int, default=256) +parser.add_argument('--eval_batch_size', help='evaluation batch size', + type=int, default=256) +parser.add_argument('--k_eval', help='how many samples to take during evaluation', + type=int, default=50) + +parser.add_argument('--seed', help='manual seed to use, default is 123', + type=int, default=123) +parser.add_argument('--eval_every', help='how often to evaluate during training, never if None', + type=int, default=50) +parser.add_argument('--vis_every', help='how often to visualize during training, never if None', + type=int, default=50) +parser.add_argument('--save_every', help='how often to save during training, never if None', + type=int, default=100) +args = parser.parse_args() + +if not torch.cuda.is_available() or args.device == 'cpu': + args.device = torch.device('cpu') +else: + if torch.cuda.device_count() == 1: + # If you have CUDA_VISIBLE_DEVICES set, which you should, + # then this will prevent leftover flag arguments from + # messing with the device allocation. + args.device = 'cuda:0' + + args.device = torch.device(args.device) + +if args.eval_device is None: + args.eval_device = 'cpu' + +if args.seed is not None: + random.seed(args.seed) + np.random.seed(args.seed) + torch.manual_seed(args.seed) + if torch.cuda.is_available(): + torch.cuda.manual_seed_all(args.seed) + +def main(): + # Load hyperparameters from json + if not os.path.exists(args.conf): + print('Config json not found!') + with open(args.conf, 'r') as conf_json: + hyperparams = json.load(conf_json) + + # Add hyperparams from arguments + hyperparams['dynamic_edges'] = args.dynamic_edges + hyperparams['edge_state_combine_method'] = args.edge_state_combine_method + hyperparams['edge_influence_combine_method'] = args.edge_influence_combine_method + hyperparams['edge_radius'] = args.edge_radius + hyperparams['use_map_encoding'] = args.use_map_encoding + hyperparams['edge_addition_filter'] = args.edge_addition_filter + hyperparams['edge_removal_filter'] = args.edge_removal_filter + hyperparams['batch_size'] = args.batch_size + hyperparams['k_eval'] = args.k_eval + hyperparams['offline_scene_graph'] = args.offline_scene_graph + hyperparams['incl_robot_node'] = args.incl_robot_node + + print('-----------------------') + print('| TRAINING PARAMETERS |') + print('-----------------------') + print('| iterations: %d' % args.num_iters) + print('| batch_size: %d' % args.batch_size) + print('| batch_multiplier: %d' % args.batch_multiplier) + print('| effective batch size: %d (= %d * %d)' % (args.batch_size * args.batch_multiplier, args.batch_size, args.batch_multiplier)) + print('| device: %s' % args.device) + print('| eval_device: %s' % args.eval_device) + print('| Offline Scene Graph Calculation: %s' % args.offline_scene_graph) + print('| edge_radius: %s' % args.edge_radius) + print('| EE state_combine_method: %s' % args.edge_state_combine_method) + print('| EIE scheme: %s' % args.edge_influence_combine_method) + print('| dynamic_edges: %s' % args.dynamic_edges) + print('| robot node: %s' % args.incl_robot_node) + print('| map encoding: %s' % args.use_map_encoding) + print('| edge_addition_filter: %s' % args.edge_addition_filter) + print('| edge_removal_filter: %s' % args.edge_removal_filter) + print('| MHL: %s' % hyperparams['minimum_history_length']) + print('| PH: %s' % hyperparams['prediction_horizon']) + print('-----------------------') + + # Create the log and model directiory if they're not present. + model_dir = os.path.join(args.log_dir, 'models_' + time.strftime('%d_%b_%Y_%H_%M_%S', time.localtime()) + args.log_tag) + pathlib.Path(model_dir).mkdir(parents=True, exist_ok=True) + + # Save config to model directory + with open(os.path.join(model_dir, 'config.json'), 'w') as conf_json: + json.dump(hyperparams, conf_json) + + log_writer = SummaryWriter(log_dir=model_dir) + + train_scenes = [] + train_data_path = os.path.join(args.data_dir, args.train_data_dict) + with open(train_data_path, 'rb') as f: + train_env = pickle.load(f, encoding='latin1') + train_scenes = train_env.scenes + print('Loaded training data from %s' % (train_data_path,)) + + eval_scenes = [] + if args.eval_every is not None: + eval_data_path = os.path.join(args.data_dir, args.eval_data_dict) + with open(eval_data_path, 'rb') as f: + eval_env = pickle.load(f, encoding='latin1') + eval_scenes = eval_env.scenes + print('Loaded evaluation data from %s' % (eval_data_path, )) + + # Calculate Scene Graph + if hyperparams['offline_scene_graph'] == 'yes': + print(f"Offline calculating scene graphs") + for i, scene in enumerate(train_scenes): + scene.calculate_scene_graph(train_env.attention_radius, + hyperparams['state'], + hyperparams['edge_addition_filter'], + hyperparams['edge_removal_filter']) + print(f"Created Scene Graph for Scene {i}") + + for i, scene in enumerate(eval_scenes): + scene.calculate_scene_graph(eval_env.attention_radius, + hyperparams['state'], + hyperparams['edge_addition_filter'], + hyperparams['edge_removal_filter']) + print(f"Created Scene Graph for Scene {i}") + + model_registrar = ModelRegistrar(model_dir, args.device) + + # We use pre trained weights for the map CNN + if args.use_map_encoding: + inf_encoder_registrar = os.path.join(args.log_dir, 'weight_trans/model_registrar-1499.pt') + model_dict = torch.load(inf_encoder_registrar, map_location=args.device) + + for key in model_dict.keys(): + if 'map_encoder' in key: + model_registrar.model_dict[key] = model_dict[key] + assert model_registrar.get_model(key) is model_dict[key] + + stg = SpatioTemporalGraphCVAEModel(model_registrar, + hyperparams, + log_writer, args.device) + stg.set_scene_graph(train_env) + stg.set_annealing_params() + print('Created training STG model.') + + eval_stg = None + if args.eval_every is not None or args.vis_ervery is not None: + eval_stg = SpatioTemporalGraphCVAEModel(model_registrar, + hyperparams, + log_writer, args.device) + eval_stg.set_scene_graph(eval_env) + eval_stg.set_annealing_params() # TODO Check if necessary + if hyperparams['learning_rate_style'] == 'const': + optimizer = optim.Adam(model_registrar.parameters(), lr=hyperparams['learning_rate']) + lr_scheduler = optim.lr_scheduler.ExponentialLR(optimizer, gamma=1.0) + elif hyperparams['learning_rate_style'] == 'exp': + optimizer = optim.Adam(model_registrar.parameters(), lr=hyperparams['learning_rate']) + lr_scheduler = optim.lr_scheduler.ExponentialLR(optimizer, gamma=hyperparams['learning_decay_rate']) + elif hyperparams['learning_rate_style'] == 'triangle': + optimizer = optim.Adam(model_registrar.parameters(), lr=1.0) + clr = cyclical_lr(100, min_lr=hyperparams['min_learning_rate'], max_lr=hyperparams['learning_rate'], decay=hyperparams['learning_decay_rate']) + lr_scheduler = optim.lr_scheduler.LambdaLR(optimizer, [clr]) + + print_training_header(newline_start=True) + for curr_iter in range(args.num_iters): + # Necessary because we flip the weights contained between GPU and CPU sometimes. + model_registrar.to(args.device) + + # Setting the current iterator value for internal logging. + stg.set_curr_iter(curr_iter) + if args.vis_every is not None: + eval_stg.set_curr_iter(curr_iter) + + # Stepping forward the learning rate scheduler and annealers. + lr_scheduler.step() + log_writer.add_scalar('train/learning_rate', + lr_scheduler.get_lr()[0], + curr_iter) + stg.step_annealers() + + # Zeroing gradients for the upcoming iteration. + optimizer.zero_grad() + train_losses = dict() + for node_type in train_env.NodeType: + train_losses[node_type] = [] + for scene in np.random.choice(train_scenes, 10): + for mb_num in range(args.batch_multiplier): + # Obtaining the batch's training loss. + timesteps = scene.sample_timesteps(hyperparams['batch_size']) + + # Compute the training loss. + train_loss_by_type = stg.train_loss(scene, timesteps, max_nodes=hyperparams['batch_size']) + for node_type, train_loss in train_loss_by_type.items(): + if train_loss is not None: + train_loss = train_loss / (args.batch_multiplier * 10) + train_losses[node_type].append(train_loss.item()) + + # Calculating gradients. + train_loss.backward() + + # Print training information. Also, no newline here. It's added in at a later line. + print('{:9} | '.format(curr_iter), end='', flush=True) + for node_type in train_env.NodeType: + print('{}:{:10} | '.format(node_type.name[0], '%.2f' % sum(train_losses[node_type])), end='', flush=True) + + for node_type in train_env.NodeType: + if len(train_losses[node_type]) > 0: + log_writer.add_histogram(f"{node_type.name}/train/minibatch_losses", np.asarray(train_losses[node_type]), curr_iter) + log_writer.add_scalar(f"{node_type.name}/train/loss", sum(train_losses[node_type]), curr_iter) + + # Clipping gradients. + if hyperparams['grad_clip'] is not None: + nn.utils.clip_grad_value_(model_registrar.parameters(), hyperparams['grad_clip']) + + # Performing a gradient step. + optimizer.step() + + del train_loss # TODO Necessary? + + if args.vis_every is not None and (curr_iter + 1) % args.vis_every == 0: + max_hl = hyperparams['maximum_history_length'] + ph = hyperparams['prediction_horizon'] + with torch.no_grad(): + # Predict random timestep to plot for train data set + scene = np.random.choice(train_scenes) + timestep = scene.sample_timesteps(1, min_future_timesteps=ph) + predictions = stg.predict(scene, + timestep, + ph, + num_samples_z=100, + most_likely_z=False, + all_z=False) + + # Plot predicted timestep for random scene + fig, ax = plt.subplots(figsize=(5, 5)) + visualization.visualize_prediction(ax, + predictions, + scene.dt, + max_hl=max_hl, + ph=ph) + ax.set_title(f"{scene.name}-t: {timestep}") + log_writer.add_figure('train/prediction', fig, curr_iter) + + # Predict random timestep to plot for eval data set + scene = np.random.choice(eval_scenes) + timestep = scene.sample_timesteps(1, min_future_timesteps=ph) + predictions = eval_stg.predict(scene, + timestep, + ph, + num_samples_z=100, + most_likely_z=False, + all_z=False, + max_nodes=4 * args.eval_batch_size) + + # Plot predicted timestep for random scene + fig, ax = plt.subplots(figsize=(5, 5)) + visualization.visualize_prediction(ax, + predictions, + scene.dt, + max_hl=max_hl, + ph=ph) + ax.set_title(f"{scene.name}-t: {timestep}") + log_writer.add_figure('eval/prediction', fig, curr_iter) + + # Plot predicted timestep for random scene in map + fig, ax = plt.subplots(figsize=(15, 15)) + visualization.visualize_prediction(ax, + predictions, + scene.dt, + max_hl=max_hl, + ph=ph, + map=scene.map['PLOT']) + ax.set_title(f"{scene.name}-t: {timestep}") + log_writer.add_figure('eval/prediction_map', fig, curr_iter) + + # Predict random timestep to plot for eval data set + predictions = eval_stg.predict(scene, + timestep, + ph, + num_samples_gmm=50, + most_likely_z=False, + all_z=True, + max_nodes=4 * args.eval_batch_size) + + # Plot predicted timestep for random scene + fig, ax = plt.subplots(figsize=(5, 5)) + visualization.visualize_prediction(ax, + predictions, + scene.dt, + max_hl=max_hl, + ph=ph) + ax.set_title(f"{scene.name}-t: {timestep}") + log_writer.add_figure('eval/prediction_all_z', fig, curr_iter) + + if args.eval_every is not None and (curr_iter + 1) % args.eval_every == 0: + max_hl = hyperparams['maximum_history_length'] + ph = hyperparams['prediction_horizon'] + with torch.no_grad(): + # Predict batch timesteps for training dataset evaluation + train_batch_errors = [] + max_scenes = np.min([len(train_scenes), 5]) + for scene in np.random.choice(train_scenes, max_scenes): + timesteps = scene.sample_timesteps(args.eval_batch_size) + predictions = stg.predict(scene, + timesteps, + ph, + num_samples_z=100, + min_future_timesteps=ph, + max_nodes=4*args.eval_batch_size) + + train_batch_errors.append(evaluation.compute_batch_statistics(predictions, + scene.dt, + max_hl=max_hl, + ph=ph, + node_type_enum=train_env.NodeType, + map=scene.map)) + + evaluation.log_batch_errors(train_batch_errors, + log_writer, + 'train', + curr_iter, + bar_plot=['kde'], + box_plot=['ade', 'fde']) + + # Predict batch timesteps for evaluation dataset evaluation + eval_batch_errors = [] + for scene in eval_scenes: + timesteps = scene.sample_timesteps(args.eval_batch_size) + + predictions = eval_stg.predict(scene, + timesteps, + ph, + num_samples_z=100, + min_future_timesteps=ph, + max_nodes=4 * args.eval_batch_size) + + eval_batch_errors.append(evaluation.compute_batch_statistics(predictions, + scene.dt, + max_hl=max_hl, + ph=ph, + node_type_enum=eval_env.NodeType, + map=scene.map)) + + evaluation.log_batch_errors(eval_batch_errors, + log_writer, + 'eval', + curr_iter, + bar_plot=['kde'], + box_plot=['ade', 'fde']) + + + # Predict maximum likelihood batch timesteps for evaluation dataset evaluation + eval_batch_errors_ml = [] + for scene in eval_scenes: + timesteps = scene.sample_timesteps(scene.timesteps) + + predictions = eval_stg.predict(scene, + timesteps, + ph, + num_samples_z=1, + min_future_timesteps=ph, + most_likely_z=True, + most_likely_gmm=True) + + eval_batch_errors_ml.append(evaluation.compute_batch_statistics(predictions, + scene.dt, + max_hl=max_hl, + ph=ph, + map=scene.map, + node_type_enum=eval_env.NodeType, + kde=False)) + + evaluation.log_batch_errors(eval_batch_errors_ml, + log_writer, + 'eval/ml', + curr_iter) + + eval_loss = [] + max_scenes = np.min([len(eval_scenes), 25]) + for scene in np.random.choice(eval_scenes, max_scenes): + eval_loss.append(eval_stg.eval_loss(scene, timesteps)) + + evaluation.log_batch_errors(eval_loss, + log_writer, + 'eval/loss', + curr_iter) + + + else: + print('{:15} | {:10} | {:14}'.format('', '', ''), + end='', flush=True) + + # Here's the newline that ends the current training information printing. + print('') + + if args.save_every is not None and (curr_iter + 1) % args.save_every == 0: + model_registrar.save_models(curr_iter) + print_training_header() + + +def print_training_header(newline_start=False): + if newline_start: + print('') + + print('Iteration | Train Loss | Eval NLL Q (IS) | Eval NLL P | Eval NLL Exact') + print('----------------------------------------------------------------------') + + +def memInUse(): + pid = os.getpid() + py = psutil.Process(pid) + memoryUse = py.memory_info()[0] / 2. ** 30 # memory use in GB...I think + print('memory GB:', memoryUse) + + +if __name__ == '__main__': + main() diff --git a/code/utils/__init__.py b/code/utils/__init__.py new file mode 100644 index 0000000..a24ea74 --- /dev/null +++ b/code/utils/__init__.py @@ -0,0 +1 @@ +from .trajectory_utils import integrate_trajectory, prediction_output_to_trajectories diff --git a/code/utils/trajectory_utils.py b/code/utils/trajectory_utils.py new file mode 100644 index 0000000..822e8b9 --- /dev/null +++ b/code/utils/trajectory_utils.py @@ -0,0 +1,72 @@ +import numpy as np +from scipy.integrate import cumtrapz + + +def integrate(f, dx, F0=0.): + N = f.shape[0] + return F0 + np.hstack((np.zeros((N, 1)), cumtrapz(f, axis=1, dx=dx))) + + +def integrate_trajectory(v, x0, dt): + xd_ = integrate(v[..., 0], dx=dt, F0=x0[0]) + yd_ = integrate(v[..., 1], dx=dt, F0=x0[1]) + integrated = np.stack([xd_, yd_], axis=2) + return integrated + + +def prediction_output_to_trajectories(prediction_output_dict, + dt, + max_h, + ph, + map=None, + gmm_agg='mean', + prune_ph_to_future=False): + + prediction_timesteps = prediction_output_dict.keys() + + output_dict = dict() + histories_dict = dict() + futures_dict = dict() + + for t in prediction_timesteps: + histories_dict[t] = dict() + output_dict[t] = dict() + futures_dict[t] = dict() + prediction_nodes = prediction_output_dict[t].keys() + for node in prediction_nodes: + predictions_output = prediction_output_dict[t][node] + position_state = {'position': ['x', 'y']} + velocity_state = {'velocity': ['x', 'y']} + acceleration_state = {'acceleration': ['m']} + history = node.get(np.array([t - max_h, t]), position_state) # History includes current pos + history = history[~np.isnan(history.sum(axis=1))] + + future = node.get(np.array([t + 1, t + ph]), position_state) + future = future[~np.isnan(future.sum(axis=1))] + + current_pos = node.get(t, position_state)[0] # List with single item + current_vel = node.get(t, velocity_state)[0] # List with single item + + predictions_output = getattr(predictions_output, gmm_agg)(axis=1) + + if prune_ph_to_future: + predictions_output = predictions_output[:, :future.shape[0]] + if predictions_output.shape[1] == 0: + continue + + vel_broad = np.expand_dims(np.broadcast_to(current_vel, + (predictions_output.shape[0], + current_vel.shape[-1])), axis=-2) + vel = np.concatenate((vel_broad, predictions_output), axis=1) + trajectory = integrate_trajectory(vel, current_pos, dt=dt)[:, 1:] + + if map is None: + histories_dict[t][node] = history + output_dict[t][node] = trajectory + futures_dict[t][node] = future + else: + histories_dict[t][node] = map.to_map_points(history) + output_dict[t][node] = map.to_map_points(trajectory) + futures_dict[t][node] = map.to_map_points(future) + + return output_dict, histories_dict, futures_dict diff --git a/code/visualization/__init__.py b/code/visualization/__init__.py new file mode 100644 index 0000000..e9af42c --- /dev/null +++ b/code/visualization/__init__.py @@ -0,0 +1,2 @@ +from .visualization import visualize_prediction +from .visualization_utils import plot_boxplots \ No newline at end of file diff --git a/code/visualization/visualization.py b/code/visualization/visualization.py new file mode 100644 index 0000000..118a432 --- /dev/null +++ b/code/visualization/visualization.py @@ -0,0 +1,101 @@ +from utils import prediction_output_to_trajectories +import matplotlib.pyplot as plt +import matplotlib.patheffects as pe + + +def plot_trajectories(ax, + prediction_dict, + histories_dict, + futures_dict, + line_alpha=0.7, + line_width=0.2, + edge_width=2, + circle_edge_width=0.5, + node_circle_size=0.3): + + cmap = ['k', 'b', 'y', 'g', 'r'] + + for node in histories_dict: + history = histories_dict[node] + future = futures_dict[node] + predictions = prediction_dict[node] + + ax.plot(history[:, 1], history[:, 0], 'k--') + + for sample_num in range(prediction_dict[node].shape[0]): + ax.plot(predictions[sample_num, :, 1], predictions[sample_num, :, 0], + color=cmap[node.type.value], + linewidth=line_width, alpha=line_alpha) + + ax.plot(future[:, 1], + future[:, 0], + 'w--', + path_effects=[pe.Stroke(linewidth=edge_width, foreground='k'), pe.Normal()]) + + # Current Node Position + circle = plt.Circle((history[-1, 1], + history[-1, 0]), + node_circle_size, + facecolor='g', + edgecolor='k', + lw=circle_edge_width, + zorder=3) + ax.add_artist(circle) + + # Robot Node # TODO Robot Node + # if robot_node is not None: + # prefix_earliest_idx = max(0, t_predict - predict_horizon) + # robot_prefix = inputs[robot_node][0, prefix_earliest_idx : t_predict + 1, 0:2].cpu().numpy() + # robot_future = inputs[robot_node][0, t_predict + 1 : min(t_predict + predict_horizon + 1, traj_length), 0:2].cpu().numpy() + # + # prefix_all_zeros = not np.any(robot_prefix) + # future_all_zeros = not np.any(robot_future) + # if not (prefix_all_zeros and future_all_zeros): + # ax.plot(robot_prefix[:, 0], robot_prefix[:, 1], 'k--') + # ax.plot(robot_future[:, 0], robot_future[:, 1], 'w--', + # path_effects=[pe.Stroke(linewidth=edge_width, foreground='k'), pe.Normal()]) + # + # circle = plt.Circle((robot_prefix[-1, 0], + # robot_prefix[-1, 1]), + # node_circle_size, + # facecolor='g', + # edgecolor='k', + # lw=circle_edge_width, + # zorder=3) + # ax.add_artist(circle) + # + # # Radius of influence + # if robot_circle: + # circle = plt.Circle((robot_prefix[-1, 0], robot_prefix[-1, 1]), test_stg.hyperparams['edge_radius'], + # fill=False, color='r', linestyle='--', zorder=3) + # ax.plot([], [], 'r--', label='Edge Radius') + # ax.add_artist(circle) + + +def visualize_prediction(ax, + prediction_output_dict, + dt, + max_hl, + ph, + robot_node=None, + map=None, + **kwargs): + + prediction_dict, histories_dict, futures_dict = prediction_output_to_trajectories(prediction_output_dict, + dt, + max_hl, + ph, + map=map) + + assert(len(prediction_dict.keys()) <= 1) + if len(prediction_dict.keys()) == 0: + return + ts_key = list(prediction_dict.keys())[0] + + prediction_dict = prediction_dict[ts_key] + histories_dict = histories_dict[ts_key] + futures_dict = futures_dict[ts_key] + + if map is not None: + ax.imshow(map.fdata, origin='lower', alpha=0.5) + plot_trajectories(ax, prediction_dict, histories_dict, futures_dict, *kwargs) \ No newline at end of file diff --git a/code/visualization/visualization_utils.py b/code/visualization/visualization_utils.py new file mode 100644 index 0000000..8ad700e --- /dev/null +++ b/code/visualization/visualization_utils.py @@ -0,0 +1,20 @@ +import numpy as np +import pandas as pd +import seaborn as sns + + +def plot_boxplots(ax, perf_dict_for_pd, x_label, y_label): + perf_df = pd.DataFrame.from_dict(perf_dict_for_pd) + our_mean_color = sns.color_palette("muted")[9] + marker_size = 7 + mean_markers = 'X' + with sns.color_palette("muted"): + sns.boxplot(x=x_label, y=y_label, data=perf_df, ax=ax, showfliers=False) + ax.plot([0], [np.mean(perf_df[y_label])], color=our_mean_color, marker=mean_markers, + markeredgecolor='#545454', markersize=marker_size, zorder=10) + + +def plot_barplots(ax, perf_dict_for_pd, x_label, y_label): + perf_df = pd.DataFrame.from_dict(perf_dict_for_pd) + with sns.color_palette("muted"): + sns.barplot(x=x_label, y=y_label, ax=ax, data=perf_df) \ No newline at end of file diff --git a/data/nuScenes/download_file.py b/data/nuScenes/download_file.py new file mode 100644 index 0000000..e386434 --- /dev/null +++ b/data/nuScenes/download_file.py @@ -0,0 +1,11 @@ +#!/usr/bin/python + +import sys +import urllib.request + +def main(): + # print command line arguments + urllib.request.urlretrieve(sys.argv[1], sys.argv[2]) + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/data/nuScenes/kalman_filter.py b/data/nuScenes/kalman_filter.py new file mode 100644 index 0000000..fb39533 --- /dev/null +++ b/data/nuScenes/kalman_filter.py @@ -0,0 +1,191 @@ +import numpy as np + + +class LinearPointMass: + """Linear Kalman Filter for an autonomous point mass system, assuming constant velocity""" + + def __init__(self, dt, sPos=None, sVel=None, sMeasurement=None): + """ + input matrices must be numpy arrays + :param A: state transition matrix + :param B: state control matrix + :param C: measurement matrix + :param Q: covariance of the Gaussian error in state transition + :param R: covariance of the Gaussain error in measurement + """ + self.dt = dt + + # matrices of state transition and measurement + self.A = np.array([[1, dt, 0, 0], [0, 1, 0, 0], [0, 0, 1, dt], [0, 0, 0, 1]]) + self.B = np.array([[0, 0], [dt, 0], [0, 0], [0, dt]]) + self.C = np.array([[1, 0, 0, 0], [0, 0, 1, 0]]) + + # default noise covariance + if (sPos is None) and (sVel is None) and (sMeasurement is None): + # sPos = 0.5 * 5 * dt ** 2 # assume 5m/s2 as maximum acceleration + # sVel = 5.0 * dt # assume 8.8m/s2 as maximum acceleration + sPos = 1.3*self.dt # assume 5m/s2 as maximum acceleration + sVel = 4*self.dt # assume 8.8m/s2 as maximum acceleration + sMeasurement = 0.2 # 68% of the measurement is within [-sMeasurement, sMeasurement] + + # state transition noise + self.Q = np.diag([sPos ** 2, sVel ** 2, sPos ** 2, sVel ** 2]) + # measurement noise + self.R = np.diag([sMeasurement ** 2, sMeasurement ** 2]) + + def predict_and_update(self, x_vec_est, u_vec, P_matrix, z_new): + """ + for background please refer to wikipedia: https://en.wikipedia.org/wiki/Kalman_filter + :param x_vec_est: + :param u_vec: + :param P_matrix: + :param z_new: + :return: + """ + + ## Prediction Step + # predicted state estimate + x_pred = self.A.dot(x_vec_est) + self.B.dot(u_vec) + # predicted error covariance + P_pred = self.A.dot(P_matrix.dot(self.A.transpose())) + self.Q + + ## Update Step + # innovation or measurement pre-fit residual + y_telda = z_new - self.C.dot(x_pred) + # innovation covariance + S = self.C.dot(P_pred.dot(self.C.transpose())) + self.R + # optimal Kalman gain + K = P_pred.dot(self.C.transpose().dot(np.linalg.inv(S))) + # updated (a posteriori) state estimate + x_vec_est_new = x_pred + K.dot(y_telda) + # updated (a posteriori) estimate covariance + P_matrix_new = np.dot((np.identity(4) - K.dot(self.C)), P_pred) + + return x_vec_est_new, P_matrix_new + + +class NonlinearKinematicBicycle: + """ + Nonlinear Kalman Filter for a kinematic bicycle model, assuming constant longitudinal speed + and constant heading angle + """ + + def __init__(self, lf, lr, dt, sPos=None, sHeading=None, sVel=None, sMeasurement=None): + self.dt = dt + + # params for state transition + self.lf = lf + self.lr = lr + # measurement matrix + self.C = np.array([[1, 0, 0, 0], [0, 1, 0, 0], [0, 0, 1, 0], [0, 0, 0, 1]]) + + # default noise covariance + if (sPos is None) and (sHeading is None) and (sVel is None) and (sMeasurement is None): + # TODO need to further check + # sPos = 0.5 * 8.8 * dt ** 2 # assume 8.8m/s2 as maximum acceleration + # sHeading = 0.5 * dt # assume 0.5rad/s as maximum turn rate + # sVel = 8.8 * dt # assume 8.8m/s2 as maximum acceleration + # sMeasurement = 1.0 + sPos = 16 * self.dt # assume 8.8m/s2 as maximum acceleration + sHeading = np.pi/2 * self.dt # assume 0.5rad/s as maximum turn rate + sVel = 8 * self.dt # assume 8.8m/s2 as maximum acceleration + sMeasurement = 0.8 + # state transition noise + self.Q = np.diag([sPos ** 2, sPos ** 2, sHeading ** 2, sVel ** 2]) + # measurement noise + self.R = np.diag([sMeasurement ** 2, sMeasurement ** 2, sMeasurement ** 2, sMeasurement ** 2]) + + def predict_and_update(self, x_vec_est, u_vec, P_matrix, z_new): + """ + for background please refer to wikipedia: https://en.wikipedia.org/wiki/Extended_Kalman_filter + :param x_vec_est: + :param u_vec: + :param P_matrix: + :param z_new: + :return: + """ + + ## Prediction Step + # predicted state estimate + x_pred = self._kinematic_bicycle_model_rearCG(x_vec_est, u_vec) + # Compute Jacobian to obtain the state transition matrix + A = self._cal_state_Jacobian(x_vec_est, u_vec) + # predicted error covariance + P_pred = A.dot(P_matrix.dot(A.transpose())) + self.Q + + ## Update Step + # innovation or measurement pre-fit residual + y_telda = z_new - self.C.dot(x_pred) + # innovation covariance + S = self.C.dot(P_pred.dot(self.C.transpose())) + self.R + # near-optimal Kalman gain + K = P_pred.dot(self.C.transpose().dot(np.linalg.inv(S))) + # updated (a posteriori) state estimate + x_vec_est_new = x_pred + K.dot(y_telda) + # updated (a posteriori) estimate covariance + P_matrix_new = np.dot((np.identity(4) - K.dot(self.C)), P_pred) + + return x_vec_est_new, P_matrix_new + + def _kinematic_bicycle_model_rearCG(self, x_old, u): + """ + :param x: vehicle state vector = [x position, y position, heading, velocity] + :param u: control vector = [acceleration, steering angle] + :param dt: + :return: + """ + + acc = u[0] + delta = u[1] + + x = x_old[0] + y = x_old[1] + psi = x_old[2] + vel = x_old[3] + + x_new = np.array([[0.], [0.], [0.], [0.]]) + + beta = np.arctan(self.lr * np.tan(delta) / (self.lf + self.lr)) + + x_new[0] = x + self.dt * vel * np.cos(psi + beta) + x_new[1] = y + self.dt * vel * np.sin(psi + beta) + x_new[2] = psi + self.dt * vel * np.cos(beta) / (self.lf + self.lr) * np.tan(delta) + #x_new[2] = _heading_angle_correction(x_new[2]) + x_new[3] = vel + self.dt * acc + + return x_new + + def _cal_state_Jacobian(self, x_vec, u_vec): + acc = u_vec[0] + delta = u_vec[1] + + x = x_vec[0] + y = x_vec[1] + psi = x_vec[2] + vel = x_vec[3] + + beta = np.arctan(self.lr * np.tan(delta) / (self.lf + self.lr)) + + a13 = -self.dt * vel * np.sin(psi + beta) + a14 = self.dt * np.cos(psi + beta) + a23 = self.dt * vel * np.cos(psi + beta) + a24 = self.dt * np.sin(psi + beta) + a34 = self.dt * np.cos(beta) / (self.lf + self.lr) * np.tan(delta) + + JA = np.array([[1.0, 0.0, a13[0], a14[0]], + [0.0, 1.0, a23[0], a24[0]], + [0.0, 0.0, 1.0, a34[0]], + [0.0, 0.0, 0.0, 1.0]]) + + return JA + + +def _heading_angle_correction(theta): + """ + correct heading angle so that it always remains in [-pi, pi] + :param theta: + :return: + """ + theta_corrected = (theta + np.pi) % (2.0 * np.pi) - np.pi + return theta_corrected + diff --git a/data/nuScenes/models/baseline/config.json b/data/nuScenes/models/baseline/config.json new file mode 100644 index 0000000..f708c39 --- /dev/null +++ b/data/nuScenes/models/baseline/config.json @@ -0,0 +1 @@ +{"batch_size": 256, "grad_clip": 1.0, "learning_rate_style": "exp", "learning_rate": 0.003, "min_learning_rate": 0.0005, "learning_decay_rate": 0.9995, "prediction_horizon": 6, "minimum_history_length": 1, "maximum_history_length": 8, "map_context": 120, "map_enc_num_layers": 4, "map_enc_hidden_size": 512, "map_enc_output_size": 512, "map_enc_dropout": 0.3, "alpha": 1, "k": 30, "k_eval": 50, "use_iwae": false, "kl_exact": true, "kl_min": 0.07, "kl_weight": 5.0, "kl_weight_start": 0, "kl_decay_rate": 0.99995, "kl_crossover": 500, "kl_sigmoid_divisor": 4, "inf_warmup": 1.0, "inf_warmup_start": 1.0, "inf_warmup_crossover": 1500, "inf_warmup_sigmoid_divisor": 4, "rnn_kwargs": {"dropout_keep_prob": 0.7}, "MLP_dropout_keep_prob": 0.9, "rnn_io_dropout_keep_prob": 1.0, "enc_rnn_dim_multiple_inputs": 8, "enc_rnn_dim_edge": 8, "enc_rnn_dim_edge_influence": 8, "enc_rnn_dim_history": 32, "enc_rnn_dim_future": 32, "dec_rnn_dim": 512, "dec_GMM_proj_MLP_dims": null, "sample_model_during_dec": true, "dec_sample_model_prob_start": 1.0, "dec_sample_model_prob_final": 1.0, "dec_sample_model_prob_crossover": 200, "dec_sample_model_prob_divisor": 4, "q_z_xy_MLP_dims": null, "p_z_x_MLP_dims": 32, "fuzz_factor": 0.05, "GMM_components": 12, "log_sigma_min": -10, "log_sigma_max": 10, "log_p_yt_xz_max": 50, "N": 2, "K": 5, "tau_init": 2.0, "tau_final": 0.05, "tau_decay_rate": 0.997, "use_z_logit_clipping": true, "z_logit_clip_start": 0.05, "z_logit_clip_final": 5.0, "z_logit_clip_crossover": 500, "z_logit_clip_divisor": 5, "state": {"PEDESTRIAN": {"position": ["x", "y"], "velocity": ["x", "y"], "acceleration": ["x", "y"], "heading": ["value"]}, "BICYCLE": {"position": ["x", "y"], "velocity": ["x", "y", "m"], "acceleration": ["x", "y", "m"], "heading": ["value"]}, "VEHICLE": {"position": ["x", "y"], "velocity": ["x", "y", "m"], "acceleration": ["x", "y", "m"], "heading": ["value"]}}, "pred_state": {"PEDESTRIAN": {"velocity": ["x", "y"]}, "BICYCLE": {"velocity": ["x", "y"]}, "VEHICLE": {"velocity": ["x", "y"]}}, "log_histograms": false, "dynamic_edges": "yes", "edge_state_combine_method": "sum", "edge_influence_combine_method": "attention", "edge_radius": 0.0, "use_map_encoding": false, "edge_addition_filter": [0.25, 0.5, 0.75, 1.0], "edge_removal_filter": [1.0, 0.0], "offline_scene_graph": "yes"} \ No newline at end of file diff --git a/data/nuScenes/models/baseline/model_registrar-1.pt b/data/nuScenes/models/baseline/model_registrar-1.pt new file mode 100644 index 0000000..8ced20e Binary files /dev/null and b/data/nuScenes/models/baseline/model_registrar-1.pt differ diff --git a/data/nuScenes/models/edge/config.json b/data/nuScenes/models/edge/config.json new file mode 100644 index 0000000..ef403f3 --- /dev/null +++ b/data/nuScenes/models/edge/config.json @@ -0,0 +1 @@ +{"batch_size": 256, "grad_clip": 1.0, "learning_rate_style": "exp", "learning_rate": 0.003, "min_learning_rate": 0.0005, "learning_decay_rate": 0.9995, "prediction_horizon": 6, "minimum_history_length": 1, "maximum_history_length": 8, "map_context": 120, "map_enc_num_layers": 4, "map_enc_hidden_size": 512, "map_enc_output_size": 512, "map_enc_dropout": 0.15, "alpha": 1, "k": 30, "k_eval": 50, "use_iwae": false, "kl_exact": true, "kl_min": 0.07, "kl_weight": 5.0, "kl_weight_start": 0, "kl_decay_rate": 0.99995, "kl_crossover": 500, "kl_sigmoid_divisor": 4, "inf_warmup": 1.0, "inf_warmup_start": 1.0, "inf_warmup_crossover": 1500, "inf_warmup_sigmoid_divisor": 4, "rnn_kwargs": {"dropout_keep_prob": 0.7}, "MLP_dropout_keep_prob": 0.9, "rnn_io_dropout_keep_prob": 1.0, "enc_rnn_dim_multiple_inputs": 8, "enc_rnn_dim_edge": 8, "enc_rnn_dim_edge_influence": 8, "enc_rnn_dim_history": 32, "enc_rnn_dim_future": 32, "dec_rnn_dim": 512, "dec_GMM_proj_MLP_dims": null, "sample_model_during_dec": true, "dec_sample_model_prob_start": 1.0, "dec_sample_model_prob_final": 1.0, "dec_sample_model_prob_crossover": 200, "dec_sample_model_prob_divisor": 4, "q_z_xy_MLP_dims": null, "p_z_x_MLP_dims": 32, "fuzz_factor": 0.05, "GMM_components": 12, "log_sigma_min": -10, "log_sigma_max": 10, "log_p_yt_xz_max": 50, "N": 2, "K": 5, "tau_init": 2.0, "tau_final": 0.05, "tau_decay_rate": 0.997, "use_z_logit_clipping": true, "z_logit_clip_start": 0.05, "z_logit_clip_final": 5.0, "z_logit_clip_crossover": 500, "z_logit_clip_divisor": 5, "state": {"PEDESTRIAN": {"position": ["x", "y"], "velocity": ["x", "y"], "acceleration": ["x", "y"], "heading": ["value"]}, "BICYCLE": {"position": ["x", "y"], "velocity": ["x", "y", "m"], "acceleration": ["x", "y", "m"], "heading": ["value"]}, "VEHICLE": {"position": ["x", "y"], "velocity": ["x", "y", "m"], "acceleration": ["x", "y", "m"], "heading": ["value"]}}, "pred_state": {"PEDESTRIAN": {"velocity": ["x", "y"]}, "BICYCLE": {"velocity": ["x", "y"]}, "VEHICLE": {"velocity": ["x", "y"]}}, "log_histograms": false, "dynamic_edges": "yes", "edge_state_combine_method": "sum", "edge_influence_combine_method": "attention", "edge_radius": 20.0, "use_map_encoding": false, "edge_addition_filter": [0.25, 0.5, 0.75, 1.0], "edge_removal_filter": [1.0, 0.0], "offline_scene_graph": "yes"} \ No newline at end of file diff --git a/data/nuScenes/models/edge/model_registrar-1.pt b/data/nuScenes/models/edge/model_registrar-1.pt new file mode 100644 index 0000000..5e2d713 Binary files /dev/null and b/data/nuScenes/models/edge/model_registrar-1.pt differ diff --git a/data/nuScenes/models/full/config.json b/data/nuScenes/models/full/config.json new file mode 100644 index 0000000..eef2c13 --- /dev/null +++ b/data/nuScenes/models/full/config.json @@ -0,0 +1 @@ +{"batch_size": 256, "grad_clip": 1.0, "learning_rate_style": "const", "learning_rate": 0.002, "min_learning_rate": 0.0005, "learning_decay_rate": 0.9995, "prediction_horizon": 6, "minimum_history_length": 1, "maximum_history_length": 8, "map_context": 120, "map_enc_num_layers": 4, "map_enc_hidden_size": 512, "map_enc_output_size": 512, "map_enc_dropout": 0.5, "alpha": 1, "k": 30, "k_eval": 50, "use_iwae": false, "kl_exact": true, "kl_min": 0.07, "kl_weight": 5.0, "kl_weight_start": 0, "kl_decay_rate": 0.99995, "kl_crossover": 500, "kl_sigmoid_divisor": 4, "inf_warmup": 1.0, "inf_warmup_start": 1.0, "inf_warmup_crossover": 1500, "inf_warmup_sigmoid_divisor": 4, "rnn_kwargs": {"dropout_keep_prob": 0.5}, "MLP_dropout_keep_prob": 0.9, "rnn_io_dropout_keep_prob": 1.0, "enc_rnn_dim_multiple_inputs": 8, "enc_rnn_dim_edge": 8, "enc_rnn_dim_edge_influence": 8, "enc_rnn_dim_history": 32, "enc_rnn_dim_future": 32, "dec_rnn_dim": 512, "dec_GMM_proj_MLP_dims": null, "sample_model_during_dec": true, "dec_sample_model_prob_start": 1.0, "dec_sample_model_prob_final": 1.0, "dec_sample_model_prob_crossover": 200, "dec_sample_model_prob_divisor": 4, "q_z_xy_MLP_dims": null, "p_z_x_MLP_dims": 32, "fuzz_factor": 0.05, "GMM_components": 12, "log_sigma_min": -10, "log_sigma_max": 10, "log_p_yt_xz_max": 50, "N": 2, "K": 5, "tau_init": 2.0, "tau_final": 0.05, "tau_decay_rate": 0.997, "use_z_logit_clipping": true, "z_logit_clip_start": 0.05, "z_logit_clip_final": 5.0, "z_logit_clip_crossover": 500, "z_logit_clip_divisor": 5, "state": {"PEDESTRIAN": {"position": ["x", "y"], "velocity": ["x", "y"], "acceleration": ["x", "y"], "heading": ["value"]}, "BICYCLE": {"position": ["x", "y"], "velocity": ["x", "y", "m"], "acceleration": ["x", "y", "m"], "heading": ["value"]}, "VEHICLE": {"position": ["x", "y"], "velocity": ["x", "y", "m"], "acceleration": ["x", "y", "m"], "heading": ["value"]}}, "pred_state": {"PEDESTRIAN": {"velocity": ["x", "y"]}, "BICYCLE": {"velocity": ["x", "y"]}, "VEHICLE": {"velocity": ["x", "y"]}}, "log_histograms": false, "dynamic_edges": "yes", "edge_state_combine_method": "sum", "edge_influence_combine_method": "attention", "edge_radius": 20.0, "use_map_encoding": true, "edge_addition_filter": [0.25, 0.5, 0.75, 1.0], "edge_removal_filter": [1.0, 0.0], "offline_scene_graph": "yes", "incl_robot_node": false} \ No newline at end of file diff --git a/data/nuScenes/models/full/model_registrar-1.pt b/data/nuScenes/models/full/model_registrar-1.pt new file mode 100644 index 0000000..1183cea Binary files /dev/null and b/data/nuScenes/models/full/model_registrar-1.pt differ diff --git a/data/nuScenes/models/me_demo/config.json b/data/nuScenes/models/me_demo/config.json new file mode 100644 index 0000000..beea3c7 --- /dev/null +++ b/data/nuScenes/models/me_demo/config.json @@ -0,0 +1 @@ +{"batch_size": 256, "grad_clip": 1.0, "learning_rate_style": "exp", "learning_rate": 0.002, "min_learning_rate": 0.0005, "learning_decay_rate": 0.9995, "prediction_horizon": 6, "minimum_history_length": 1, "maximum_history_length": 8, "map_context": 120, "map_enc_num_layers": 4, "map_enc_hidden_size": 512, "map_enc_output_size": 512, "map_enc_dropout": 0.5, "alpha": 1, "k": 30, "k_eval": 50, "use_iwae": false, "kl_exact": true, "kl_min": 0.07, "kl_weight": 5.0, "kl_weight_start": 0, "kl_decay_rate": 0.99995, "kl_crossover": 500, "kl_sigmoid_divisor": 4, "inf_warmup": 1.0, "inf_warmup_start": 1.0, "inf_warmup_crossover": 1500, "inf_warmup_sigmoid_divisor": 4, "rnn_kwargs": {"dropout_keep_prob": 0.5}, "MLP_dropout_keep_prob": 0.9, "rnn_io_dropout_keep_prob": 1.0, "enc_rnn_dim_multiple_inputs": 8, "enc_rnn_dim_edge": 8, "enc_rnn_dim_edge_influence": 8, "enc_rnn_dim_history": 32, "enc_rnn_dim_future": 32, "dec_rnn_dim": 512, "dec_GMM_proj_MLP_dims": null, "sample_model_during_dec": true, "dec_sample_model_prob_start": 1.0, "dec_sample_model_prob_final": 1.0, "dec_sample_model_prob_crossover": 200, "dec_sample_model_prob_divisor": 4, "q_z_xy_MLP_dims": null, "p_z_x_MLP_dims": 32, "fuzz_factor": 0.05, "GMM_components": 12, "log_sigma_min": -10, "log_sigma_max": 10, "log_p_yt_xz_max": 50, "N": 2, "K": 5, "tau_init": 2.0, "tau_final": 0.05, "tau_decay_rate": 0.997, "use_z_logit_clipping": true, "z_logit_clip_start": 0.05, "z_logit_clip_final": 5.0, "z_logit_clip_crossover": 500, "z_logit_clip_divisor": 5, "state": {"PEDESTRIAN": {"position": ["x", "y"], "velocity": ["x", "y"], "acceleration": ["x", "y"], "heading": ["value"]}, "BICYCLE": {"position": ["x", "y"], "velocity": ["x", "y", "m"], "acceleration": ["x", "y", "m"], "heading": ["value"]}, "VEHICLE": {"position": ["x", "y"], "velocity": ["x", "y", "m"], "acceleration": ["x", "y", "m"], "heading": ["value"]}}, "pred_state": {"PEDESTRIAN": {"velocity": ["x", "y"]}, "BICYCLE": {"velocity": ["x", "y"]}, "VEHICLE": {"velocity": ["x", "y"]}}, "log_histograms": false, "dynamic_edges": "yes", "edge_state_combine_method": "sum", "edge_influence_combine_method": "attention", "edge_radius": 0.0, "use_map_encoding": true, "edge_addition_filter": [0.25, 0.5, 0.75, 1.0], "edge_removal_filter": [1.0, 0.0], "offline_scene_graph": "yes"} \ No newline at end of file diff --git a/data/nuScenes/models/me_demo/model_registrar-1.pt b/data/nuScenes/models/me_demo/model_registrar-1.pt new file mode 100644 index 0000000..4cf73d5 Binary files /dev/null and b/data/nuScenes/models/me_demo/model_registrar-1.pt differ diff --git a/data/nuScenes/models/robot_demo/config.json b/data/nuScenes/models/robot_demo/config.json new file mode 100644 index 0000000..17f22af --- /dev/null +++ b/data/nuScenes/models/robot_demo/config.json @@ -0,0 +1 @@ +{"batch_size": 256, "grad_clip": 1.0, "learning_rate_style": "exp", "learning_rate": 0.003, "min_learning_rate": 0.0005, "learning_decay_rate": 0.9995, "prediction_horizon": 6, "minimum_history_length": 1, "maximum_history_length": 8, "map_context": 120, "map_enc_num_layers": 4, "map_enc_hidden_size": 512, "map_enc_output_size": 512, "map_enc_dropout": 0.5, "alpha": 1, "k": 30, "k_eval": 50, "use_iwae": false, "kl_exact": true, "kl_min": 0.07, "kl_weight": 5.0, "kl_weight_start": 0, "kl_decay_rate": 0.99995, "kl_crossover": 500, "kl_sigmoid_divisor": 4, "inf_warmup": 1.0, "inf_warmup_start": 1.0, "inf_warmup_crossover": 1500, "inf_warmup_sigmoid_divisor": 4, "rnn_kwargs": {"dropout_keep_prob": 0.5}, "MLP_dropout_keep_prob": 0.9, "rnn_io_dropout_keep_prob": 1.0, "enc_rnn_dim_multiple_inputs": 8, "enc_rnn_dim_edge": 8, "enc_rnn_dim_edge_influence": 8, "enc_rnn_dim_history": 32, "enc_rnn_dim_future": 32, "dec_rnn_dim": 512, "dec_GMM_proj_MLP_dims": null, "sample_model_during_dec": true, "dec_sample_model_prob_start": 1.0, "dec_sample_model_prob_final": 1.0, "dec_sample_model_prob_crossover": 200, "dec_sample_model_prob_divisor": 4, "q_z_xy_MLP_dims": null, "p_z_x_MLP_dims": 32, "fuzz_factor": 0.05, "GMM_components": 12, "log_sigma_min": -10, "log_sigma_max": 10, "log_p_yt_xz_max": 50, "N": 2, "K": 5, "tau_init": 2.0, "tau_final": 0.05, "tau_decay_rate": 0.997, "use_z_logit_clipping": true, "z_logit_clip_start": 0.05, "z_logit_clip_final": 5.0, "z_logit_clip_crossover": 500, "z_logit_clip_divisor": 5, "state": {"PEDESTRIAN": {"position": ["x", "y"], "velocity": ["x", "y"], "acceleration": ["x", "y"], "heading": ["value"]}, "BICYCLE": {"position": ["x", "y"], "velocity": ["x", "y", "m"], "acceleration": ["x", "y", "m"], "heading": ["value"]}, "VEHICLE": {"position": ["x", "y"], "velocity": ["x", "y", "m"], "acceleration": ["x", "y", "m"], "heading": ["value"]}}, "pred_state": {"PEDESTRIAN": {"velocity": ["x", "y"]}, "BICYCLE": {"velocity": ["x", "y"]}, "VEHICLE": {"velocity": ["x", "y"]}}, "log_histograms": false, "dynamic_edges": "yes", "edge_state_combine_method": "sum", "edge_influence_combine_method": "attention", "edge_radius": 20.0, "use_map_encoding": false, "edge_addition_filter": [0.25, 0.5, 0.75, 1.0], "edge_removal_filter": [1.0, 0.0], "offline_scene_graph": "yes", "incl_robot_node": true} \ No newline at end of file diff --git a/data/nuScenes/models/robot_demo/model_registrar-1.pt b/data/nuScenes/models/robot_demo/model_registrar-1.pt new file mode 100644 index 0000000..40f3703 Binary files /dev/null and b/data/nuScenes/models/robot_demo/model_registrar-1.pt differ diff --git a/data/nuScenes/nuscenes-devkit b/data/nuScenes/nuscenes-devkit new file mode 160000 index 0000000..f3594b9 --- /dev/null +++ b/data/nuScenes/nuscenes-devkit @@ -0,0 +1 @@ +Subproject commit f3594b967cbf42396da5c6cb08bd714437b53111 diff --git a/data/nuScenes/process_nuScenes.py b/data/nuScenes/process_nuScenes.py new file mode 100644 index 0000000..dceb052 --- /dev/null +++ b/data/nuScenes/process_nuScenes.py @@ -0,0 +1,491 @@ +import sys +import os +import numpy as np +import pandas as pd +import pickle +import json +from tqdm import tqdm +from pyquaternion import Quaternion +from kalman_filter import LinearPointMass, NonlinearKinematicBicycle +from scipy.integrate import cumtrapz +from scipy.ndimage.morphology import binary_dilation, generate_binary_structure + +nu_path = './nuscenes-devkit/python-sdk/' +#op_path = './pytorch-openpose/python/' +sys.path.append(nu_path) +sys.path.append("../../code") +#sys.path.append(op_path) +from nuscenes.nuscenes import NuScenes +from nuscenes.map_expansion.map_api import NuScenesMap +from data import Environment, Scene, Node, BicycleNode, Position, Velocity, Acceleration, ActuatorAngle, Map, Scalar + +scene_blacklist = [3, 12, 18, 19, 33, 35, 36, 41, 45, 50, 54, 55, 61, 120, 121, 123, 126, 132, 133, 134, 149, + 154, 159, 196, 268, 278, 351, 365, 367, 368, 369, 372, 376, 377, 382, 385, 499, 515, 517, + 945, 947, 952, 955, 962, 963, 968] + [969] + + +types = ['PEDESTRIAN', + 'BICYCLE', + 'VEHICLE'] + +standardization = { + 'PEDESTRIAN': { + 'position': { + 'x': {'mean': 0, 'std': 25}, + 'y': {'mean': 0, 'std': 25} + }, + 'velocity': { + 'x': {'mean': 0, 'std': 2}, + 'y': {'mean': 0, 'std': 2} + }, + 'acceleration': { + 'x': {'mean': 0, 'std': 1}, + 'y': {'mean': 0, 'std': 1} + }, + 'heading': { + 'value': {'mean': 0, 'std': np.pi}, + 'derivative': {'mean': 0, 'std': np.pi / 4} + } + }, + 'BICYCLE': { + 'position': { + 'x': {'mean': 0, 'std': 50}, + 'y': {'mean': 0, 'std': 50} + }, + 'velocity': { + 'x': {'mean': 0, 'std': 6}, + 'y': {'mean': 0, 'std': 6}, + 'm': {'mean': 0, 'std': 6} + }, + 'acceleration': { + 'x': {'mean': 0, 'std': 4}, + 'y': {'mean': 0, 'std': 4}, + 'm': {'mean': 0, 'std': 4} + }, + 'actuator_angle': { + 'steering_angle': {'mean': 0, 'std': np.pi/2} + }, + 'heading': { + 'value': {'mean': 0, 'std': np.pi}, + 'derivative': {'mean': 0, 'std': np.pi / 4} + } + }, + 'VEHICLE': { + 'position': { + 'x': {'mean': 0, 'std': 100}, + 'y': {'mean': 0, 'std': 100} + }, + 'velocity': { + 'x': {'mean': 0, 'std': 20}, + 'y': {'mean': 0, 'std': 20}, + 'm': {'mean': 0, 'std': 20} + }, + 'acceleration': { + 'x': {'mean': 0, 'std': 4}, + 'y': {'mean': 0, 'std': 4}, + 'm': {'mean': 0, 'std': 4} + }, + 'actuator_angle': { + 'steering_angle': {'mean': 0, 'std': np.pi/2} + }, + 'heading': { + 'value': {'mean': 0, 'std': np.pi}, + 'derivative': {'mean': 0, 'std': np.pi / 4} + } + } +} + +def inverse_np_gradient(f, dx, F0=0.): + N = f.shape[0] + return F0 + np.hstack((np.zeros((N, 1)), cumtrapz(f, axis=1, dx=dx))) + +def integrate_trajectory(v, x0, dt): + xd_ = inverse_np_gradient(v[..., 0], dx=dt, F0=x0[0]) + yd_ = inverse_np_gradient(v[..., 1], dx=dt, F0=x0[1]) + integrated = np.stack([xd_, yd_], axis=2) + return integrated + +def integrate_heading_model(a, dh, h0, x0, v0, dt): + h = inverse_np_gradient(dh, dx=dt, F0=h0) + v_m = inverse_np_gradient(a, dx=dt, F0=v0) + + vx = np.cos(h) * v_m + vy = np.sin(h) * v_m + + v = np.stack((vx, vy), axis=2) + return integrate_trajectory(v, x0, dt) + +if __name__ == "__main__": + num_global_straight = 0 + num_global_curve = 0 + + test = False + if sys.argv[1] == 'mini': + data_path = './raw_data/mini' + nusc = NuScenes(version='v1.0-mini', dataroot=data_path, verbose=True) + add = "_mini" + train_scenes = nusc.scene[0:7] + val_scenes = nusc.scene[7:] + test_scenes = [] + elif sys.argv[1] == 'test': + test = True + data_path = './raw_data' + nusc = NuScenes(version='v1.0-test', dataroot=data_path, verbose=True) + train_scenes = [] + val_scenes = [] + test_scenes = nusc.scene + with open(os.path.join('./raw_data/results_test_megvii.json'), 'r') as test_json: + test_annotations = json.load(test_json) + else: + data_path = '/home/timsal/Documents/code/GenTrajectron_nuScenes_ssh/data/nuScenes/raw_data' + nusc = NuScenes(version='v1.0-trainval', dataroot=data_path, verbose=True) + add = "" + train_scenes = nusc.scene[0:] + val_scenes = nusc.scene[700:] + test_scenes = [] + + for data_class, nuscenes in [('train', train_scenes), ('val', val_scenes), ('test', test_scenes)]: + print(f"Processing data class {data_class}") + data_dict_path = os.path.join('../processed', '_'.join(['nuScenes', data_class])+ 'samp.pkl') + env = Environment(node_type_list=types, standardization=standardization) + attention_radius = dict() + attention_radius[(env.NodeType.PEDESTRIAN, env.NodeType.PEDESTRIAN)] = 3.0 + attention_radius[(env.NodeType.PEDESTRIAN, env.NodeType.VEHICLE)] = 20.0 + attention_radius[(env.NodeType.PEDESTRIAN, env.NodeType.BICYCLE)] = 10.0 + attention_radius[(env.NodeType.VEHICLE, env.NodeType.PEDESTRIAN)] = 20.0 + attention_radius[(env.NodeType.VEHICLE, env.NodeType.VEHICLE)] = 20.0 + attention_radius[(env.NodeType.VEHICLE, env.NodeType.BICYCLE)] = 20.0 + attention_radius[(env.NodeType.BICYCLE, env.NodeType.PEDESTRIAN)] = 10.0 + attention_radius[(env.NodeType.BICYCLE, env.NodeType.VEHICLE)] = 20.0 + attention_radius[(env.NodeType.BICYCLE, env.NodeType.BICYCLE)] = 10.0 + env.attention_radius = attention_radius + scenes = [] + pbar = tqdm(nuscenes, ncols=100) + for nuscene in pbar: + scene_id = int(nuscene['name'].replace('scene-', '')) + if scene_id in scene_blacklist: # Some scenes have bad localization + continue + + if not (scene_id == 1002 or scene_id == 234): + continue + + data = pd.DataFrame(columns=['frame_id', + 'type', + 'node_id', + 'robot', + 'x', 'y', 'z', + 'length', + 'width', + 'height', + 'heading', + 'orientation']) + + sample_token = nuscene['first_sample_token'] + sample = nusc.get('sample', sample_token) + frame_id = 0 + while sample['next']: + if not test: + annotation_tokens = sample['anns'] + else: + annotation_tokens = test_annotations['results'][sample['token']] + for annotation_token in annotation_tokens: + if not test: + annotation = nusc.get('sample_annotation', annotation_token) + category = annotation['category_name'] + if len(annotation['attribute_tokens']): + attribute = nusc.get('attribute', annotation['attribute_tokens'][0])['name'] + + if 'pedestrian' in category and not 'stroller' in category and not 'wheelchair' in category: + our_category = env.NodeType.PEDESTRIAN + elif ('vehicle.bicycle' in category) and 'with_rider' in attribute: + continue + our_category = env.NodeType.BICYCLE + elif 'vehicle' in category and 'bicycle' not in category and 'motorcycle' not in category and 'parked' not in attribute: + our_category = env.NodeType.VEHICLE + # elif ('vehicle.motorcycle' in category) and 'with_rider' in attribute: + # our_category = env.NodeType.VEHICLE + else: + continue + else: + annotation = annotation_token + category = annotation['tracking_name'] + attribute = ""#annotation['attribute_name'] + + if 'pedestrian' in category : + our_category = env.NodeType.PEDESTRIAN + elif (('car' in category or 'bus' in category or 'construction_vehicle' in category) and 'parked' not in attribute): + our_category = env.NodeType.VEHICLE + # elif ('vehicle.motorcycle' in category) and 'with_rider' in attribute: + # our_category = env.NodeType.VEHICLE + else: + continue + + + data_point = pd.Series({'frame_id': frame_id, + 'type': our_category, + 'node_id': annotation['instance_token'] if not test else annotation['tracking_id'], + 'robot': False, + 'x': annotation['translation'][0], + 'y': annotation['translation'][1], + 'z': annotation['translation'][2], + 'length': annotation['size'][0], + 'width': annotation['size'][1], + 'height': annotation['size'][2], + 'heading': Quaternion(annotation['rotation']).yaw_pitch_roll[0], + 'orientation': None}) + data = data.append(data_point, ignore_index=True) + + # Ego Vehicle + our_category = env.NodeType.VEHICLE + sample_data = nusc.get('sample_data', sample['data']['CAM_FRONT']) + annotation = nusc.get('ego_pose', sample_data['ego_pose_token']) + data_point = pd.Series({'frame_id': frame_id, + 'type': our_category, + 'node_id': 'ego', + 'robot': True, + 'x': annotation['translation'][0], + 'y': annotation['translation'][1], + 'z': annotation['translation'][2], + 'length': 4, + 'width': 1.7, + 'height': 1.5, + 'heading': Quaternion(annotation['rotation']).yaw_pitch_roll[0], + 'orientation': None}) + data = data.append(data_point, ignore_index=True) + + sample = nusc.get('sample', sample['next']) + frame_id += 1 + + if len(data.index) == 0: + continue + + data.sort_values('frame_id', inplace=True) + max_timesteps = data['frame_id'].max() + + x_min = np.round(data['x'].min() - 50) + x_max = np.round(data['x'].max() + 50) + y_min = np.round(data['y'].min() - 50) + y_max = np.round(data['y'].max() + 50) + + data['x'] = data['x'] - x_min + data['y'] = data['y'] - y_min + + scene = Scene(timesteps=max_timesteps + 1, dt=0.5, name=str(scene_id)) + + # Generate Maps + map_name = nusc.get('log', nuscene['log_token'])['location'] + nusc_map = NuScenesMap(dataroot=data_path, map_name=map_name) + + type_map = dict() + x_size = x_max - x_min + y_size = y_max - y_min + patch_box = (x_min + 0.5 * (x_max - x_min), y_min + 0.5 * (y_max - y_min), y_size, x_size) + patch_angle = 0 # Default orientation where North is up + canvas_size = (np.round(3 * y_size).astype(int), np.round(3 * x_size).astype(int)) + homography = np.array([[3., 0., 0.], [0., 3., 0.], [0., 0., 3.]]) + layer_names = ['lane', 'road_segment', 'drivable_area', 'road_divider', 'lane_divider', 'stop_line', + 'ped_crossing', 'stop_line', 'ped_crossing', 'walkway'] + map_mask = (nusc_map.get_map_mask(patch_box, patch_angle, layer_names, canvas_size) * 255.0).astype( + np.uint8) + map_mask = np.swapaxes(map_mask, 1, 2) # x axis comes first + # PEDESTRIANS + map_mask_pedestrian = np.stack((map_mask[9], map_mask[8], np.max(map_mask[:3], axis=0)), axis=2) + type_map['PEDESTRIAN'] = Map(data=map_mask_pedestrian, homography=homography, + description=', '.join(layer_names)) + # Bicycles + map_mask_bicycles = np.stack((map_mask[9], map_mask[8], np.max(map_mask[:3], axis=0)), axis=2) + type_map['BICYCLE'] = Map(data=map_mask_bicycles, homography=homography, description=', '.join(layer_names)) + # VEHICLES + map_mask_vehicle = np.stack((np.max(map_mask[:3], axis=0), map_mask[3], map_mask[4]), axis=2) + type_map['VEHICLE'] = Map(data=map_mask_vehicle, homography=homography, description=', '.join(layer_names)) + + map_mask_plot = np.stack(((np.max(map_mask[:3], axis=0) - (map_mask[3] + 0.5 * map_mask[4]).clip( + max=255)).clip(min=0).astype(np.uint8), map_mask[8], map_mask[9]), axis=2) + type_map['PLOT'] = Map(data=map_mask_plot, homography=homography, description=', '.join(layer_names)) + + scene.map = type_map + del map_mask + del map_mask_pedestrian + del map_mask_vehicle + del map_mask_bicycles + del map_mask_plot + + for node_id in pd.unique(data['node_id']): + node_df = data[data['node_id'] == node_id] + + if node_df['x'].shape[0] < 2: + continue + + if not np.all(np.diff(node_df['frame_id']) == 1): + #print('Occlusion') + continue # TODO Make better + + node_values = node_df['x'].values + if node_df.iloc[0]['type'] == env.NodeType.PEDESTRIAN: + node = Node(type=node_df.iloc[0]['type']) + else: + node = BicycleNode(type=node_df.iloc[0]['type']) + node.first_timestep = node_df['frame_id'].iloc[0] + node.position = Position(node_df['x'].values, node_df['y'].values) + node.velocity = Velocity.from_position(node.position, scene.dt) + node.velocity.m = np.linalg.norm(np.vstack((node.velocity.x, node.velocity.y)), axis=0) + node.acceleration = Acceleration.from_velocity(node.velocity, scene.dt) + node.heading = Scalar(node_df['heading'].values) + heading_t = node_df['heading'].values.copy() + shifted_heading = np.zeros_like(node.heading.value) + shifted_heading[0] = node.heading.value[0] + for i in range(1, len(node.heading.value)): + if not (np.sign(node.heading.value[i]) == np.sign(node.heading.value[i - 1])) and np.abs( + node.heading.value[i]) > np.pi / 2: + shifted_heading[i] = shifted_heading[i - 1] + ( + node.heading.value[i] - node.heading.value[i - 1]) - np.sign( + (node.heading.value[i] - node.heading.value[i - 1])) * 2 * np.pi + else: + shifted_heading[i] = shifted_heading[i - 1] + ( + node.heading.value[i] - node.heading.value[i - 1]) + node.heading.value = shifted_heading + node.length = node_df.iloc[0]['length'] + node.width = node_df.iloc[0]['width'] + + if node_df.iloc[0]['robot'] == True: + node.is_robot = True + + if node_df.iloc[0]['type'] == env.NodeType.PEDESTRIAN: + filter_ped = LinearPointMass(dt=scene.dt) + for i in range(len(node.position.x)): + if i == 0: # initalize KF + P_matrix = np.identity(4) + elif i < len(node.position.x): + # assign new est values + node.position.x[i] = x_vec_est_new[0][0] + node.velocity.x[i] = x_vec_est_new[1][0] + node.position.y[i] = x_vec_est_new[2][0] + node.velocity.y[i] = x_vec_est_new[3][0] + + if i < len(node.position.x) - 1: # no action on last data + # filtering + x_vec_est = np.array([[node.position.x[i]], + [node.velocity.x[i]], + [node.position.y[i]], + [node.velocity.y[i]]]) + z_new = np.array([[node.position.x[i+1]], + [node.position.y[i+1]]]) + x_vec_est_new, P_matrix_new = filter_ped.predict_and_update( + x_vec_est=x_vec_est, + u_vec=np.array([[0.], [0.]]), + P_matrix=P_matrix, + z_new=z_new + ) + P_matrix = P_matrix_new + else: + filter_veh = NonlinearKinematicBicycle(lf=node.length*0.6, lr=node.length*0.4, dt=scene.dt) + for i in range(len(node.position.x)): + if i == 0: # initalize KF + # initial P_matrix + P_matrix = np.identity(4) + elif i < len(node.position.x): + # assign new est values + node.position.x[i] = x_vec_est_new[0][0] + node.position.y[i] = x_vec_est_new[1][0] + node.heading.value[i] = x_vec_est_new[2][0] + node.velocity.m[i] = x_vec_est_new[3][0] + + if i < len(node.position.x) - 1: # no action on last data + # filtering + x_vec_est = np.array([[node.position.x[i]], + [node.position.y[i]], + [node.heading.value[i]], + [node.velocity.m[i]]]) + z_new = np.array([[node.position.x[i+1]], + [node.position.y[i+1]], + [node.heading.value[i+1]], + [node.velocity.m[i+1]]]) + x_vec_est_new, P_matrix_new = filter_veh.predict_and_update( + x_vec_est=x_vec_est, + u_vec=np.array([[0.], [0.]]), + P_matrix=P_matrix, + z_new=z_new + ) + P_matrix = P_matrix_new + + v_tmp = node.velocity.m + node.velocity = Velocity.from_position(node.position, scene.dt) + node.velocity.m = v_tmp + #if (np.abs(np.linalg.norm(np.vstack((node.velocity.x, node.velocity.y)), axis=0) - v_tmp) > 0.4).any(): + # print(np.abs(np.linalg.norm(np.vstack((node.velocity.x, node.velocity.y)), axis=0) - v_tmp)) + + node.acceleration = Acceleration.from_velocity(node.velocity, scene.dt) + node.acceleration.m = np.gradient(v_tmp, scene.dt) + node.heading.derivative = np.gradient(node.heading.value, scene.dt) + node.heading.value = (node.heading.value + np.pi) % (2.0 * np.pi) - np.pi + + if node_df.iloc[0]['type'] == env.NodeType.VEHICLE: + node_pos = np.stack((node.position.x, node.position.y), axis=1) + node_pos_map = scene.map[env.NodeType.VEHICLE.name].to_map_points(node_pos) + node_pos_int = np.round(node_pos_map).astype(int) + dilated_map = binary_dilation(scene.map[env.NodeType.VEHICLE.name].data[..., 0], generate_binary_structure(2, 2)) + if np.sum((dilated_map[node_pos_int[:, 0], node_pos_int[:, 1]] == 0))/node_pos_int.shape[0] > 0.1: + del node + continue # Out of map + + + + if not node_df.iloc[0]['type'] == env.NodeType.PEDESTRIAN: + # Re Integrate: + i_pos = integrate_heading_model(np.array([node.acceleration.m[1:]]), + np.array([node.heading.derivative[1:]]), + node.heading.value[0], + np.vstack((node.position.x[0], node.position.y[0])), + node.velocity.m[0], 0.5) + + + #if (np.abs(node.heading.derivative) > np.pi/8).any(): + # print(np.abs(node.heading.derivative).max()) + scene.nodes.append(node) + if node.is_robot is True: + scene.robot = node + + robot = False + num_heading_changed = 0 + num_moving_vehicles = 0 + for node in scene.nodes: + node.description = "straight" + num_global_straight += 1 + if node.type == env.NodeType.VEHICLE: + if np.linalg.norm((node.position.x[0] - node.position.x[-1], node.position.y[0] - node.position.y[-1])) > 10: + num_moving_vehicles += 1 + if np.abs(node.heading.value[0] - node.heading.value[-1]) > np.pi / 6: + if not np.sign(node.heading.value[0]) == np.sign(node.heading.value[-1]) and np.abs(node.heading.value[0] > 1/2 * np.pi): + if (node.heading.value[0] - node.heading.value[-1]) - np.sign((node.heading.value[0] - node.heading.value[-1])) * 2 * np.pi > np.pi / 6: + node.description = "curve" + num_global_curve += 1 + num_global_straight -= 1 + num_heading_changed += 1 + else: + node.description = "curve" + num_global_curve += 1 + num_global_straight -= 1 + num_heading_changed += 1 + + if node.is_robot: + robot = True + + if num_moving_vehicles > 0 and num_heading_changed / num_moving_vehicles > 0.4: + scene.description = "curvy" + else: + scene.description = "straight" + + if robot: # If we dont have a ego vehicle there was bad localization + pbar.set_description(str(scene)) + scenes.append(scene) + + del data + + env.scenes = scenes + + if len(scenes) > 0: + with open(data_dict_path, 'wb') as f: + pickle.dump(env, f, protocol=pickle.HIGHEST_PROTOCOL) + + print(num_global_straight) + print(num_global_curve) \ No newline at end of file diff --git a/data/processed/nuScenes_samples.pkl b/data/processed/nuScenes_samples.pkl new file mode 100644 index 0000000..9e398d4 Binary files /dev/null and b/data/processed/nuScenes_samples.pkl differ diff --git a/requirements.txt b/requirements.txt new file mode 100644 index 0000000..ae748ae --- /dev/null +++ b/requirements.txt @@ -0,0 +1,13 @@ +matplotlib +numpy==1.16.4 +pandas==0.25.1 +psutil==5.6.3 +scipy==1.3.1 +seaborn==0.9.0 +tensorboard==1.14.0 +tensorboardX==1.8 +tensorflow==1.14.0 +tensorflow-estimator==1.14.0 +torch==1.2.0 +Pillow==6.1.0 +pyquaternion==0.9.5