Skip to content

Commit

Permalink
Merge branch 'gl-dev' into main
Browse files Browse the repository at this point in the history
  • Loading branch information
Robin Chen committed Nov 18, 2021
2 parents eb93609 + e1c3011 commit f532c9e
Show file tree
Hide file tree
Showing 70 changed files with 200,007 additions and 127 deletions.
15 changes: 15 additions & 0 deletions CHANGELOG
Original file line number Diff line number Diff line change
@@ -1,3 +1,18 @@
## v0.2.1 (2021.11.18)
- Add NoCrash Carla099
- Add bev dataset
- Add Carla AD Challenge scenarios and routes
- Add LBC data collection and BeV training doc
- Add Latent RL BeV and RL training doc
- Add validation in LBC training
- Update Benchmark datasaver
- Update VAE model
- Update LBC Image policy learn mode
- Fix bug in benchmark collector
- Fix visualizer not closed after done
- Fix not alived sensor killed bug


## v0.2.0 (2021.11.1)
- Update DI-engine to version 0.2.0
- Reformat CIL to CILRS
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

<img src="./docs/figs/DI-drive.png" width="200" alt="icon"/>

Updated on 2021.11.01 DI-drive-v0.2.0 (beta)
Updated on 2021.11.18 DI-drive-v0.2.1 (beta)

DI-drive - Decision Intelligence Platform for Autonomous Driving simulation.

Expand Down
1 change: 1 addition & 0 deletions core/data/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,4 @@
from .cilrs_dataset import CILRSDataset
from .cict_dataset import CictDataset
from .lbc_dataset import LBCBirdViewDataset, LBCImageDataset
from .bev_vae_dataset import BeVVAEDataset
25 changes: 25 additions & 0 deletions core/data/benchmark/carla100/099/nocrash_Town01.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
79 227
105 21
129 88
19 105
231 212
252 192
222 120
202 226
11 17
79 247
3 177
191 114
235 240
4 54
17 207
223 212
154 66
187 123
129 56
114 6
40 192
176 123
121 187
238 225
219 154
25 changes: 25 additions & 0 deletions core/data/benchmark/carla100/099/nocrash_Town02.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
66 19
6 71
66 28
46 32
25 59
32 9
43 72
54 14
26 50
38 69
75 24
19 82
65 6
71 29
59 16
6 66
83 56
69 71
82 28
8 17
19 12
39 18
51 8
24 36
64 73
33 changes: 15 additions & 18 deletions core/data/benchmark_dataset_saver.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
import glob
import numpy as np
from pathlib import Path
from typing import Callable, List, Dict
from typing import Callable, List, Dict, Optional

from core.utils.data_utils.data_writter import write_json, write_episode_lmdb
from core.utils.others.image_helper import save_image, is_image
Expand All @@ -28,27 +28,26 @@ class BenchmarkDatasetSaver():
- save_dir (str): Dataset folder path.
- obs_cfg (Dict): Observation config dict in simulator.
- post_process_fn (Callable, optional): Post-process function defined by user. Defaults to None.
- lmdb_obs (List, optional): Observation types that saved as lmdb rather than image, default to ['lidar', 'bev']
:Interfaces: make_dataset_path, save_episodes_data, make_index
"""

def __init__(self, save_dir: str, obs_cfg: Dict, post_process_fn: Callable = None):
"""
[summary]
:Arguments:
- save_dir (str): [description]
- obs_cfg (Dict): [description]
- post_process_fn (Callable, optional): [description]. Defaults to None.
"""
def __init__(
self,
save_dir: str,
obs_cfg: Dict,
post_process_fn: Optional[Callable] = None,
lmdb_obs: Optional[List] = ['lidar', 'birdview'],
) -> None:
self._save_dir = save_dir
self._obs_cfg = obs_cfg
self._post_process_fn = post_process_fn
self._lmdb_obs_type = []
self._lmdb_obs_type = lmdb_obs
if self._post_process_fn is None:
self._post_process_fn = default_post_process_fn

def save_episodes_data(self, episodes_data: List, start_episode: int = 0):
def save_episodes_data(self, episodes_data: List, start_episode: int = 0) -> None:
"""
Save data from several episodes sampled from collector, with 'env_param' and 'data' key
saved in each episode.
Expand Down Expand Up @@ -93,7 +92,7 @@ def save_episodes_data(self, episodes_data: List, start_episode: int = 0):
data.append((measurements, sensor_data, others))
BenchmarkDatasetSaver._save_episode_data(episode_path, data, self._lmdb_obs_type)

def make_dataset_path(self, dataset_metainfo: Dict = dict()):
def make_dataset_path(self, dataset_metainfo: Dict = dict()) -> None:
"""
Make dataset folder and write dataset meta infomation into a json file.
Expand All @@ -111,20 +110,18 @@ def make_dataset_path(self, dataset_metainfo: Dict = dict()):
obs_item = obs_item.copy()
obs_item.pop('name')
obs_metainfo.update({obs_name: obs_item})
if obs_item['type'] in ['lidar', 'bev']:
self._lmdb_obs_type.append(obs_name)

dataset_metainfo.update({'obs': obs_metainfo})

write_json(os.path.join(self._save_dir, 'metainfo.json'), dataset_metainfo)

@staticmethod
def _make_episode_path(episode_path, env_params):
def _make_episode_path(episode_path, env_params) -> None:
os.makedirs(episode_path, exist_ok=True)
write_json(os.path.join(episode_path, 'episode_metainfo.json'), env_params)

@staticmethod
def _save_episode_data(episode_path, data, lmdb_obs_type=None):
def _save_episode_data(episode_path, data, lmdb_obs_type=None) -> None:
write_episode_lmdb(episode_path, data, lmdb_obs_type)
for i, x in enumerate(data):
sensor_data = x[1]
Expand All @@ -134,7 +131,7 @@ def _save_episode_data(episode_path, data, lmdb_obs_type=None):
else:
save_image(os.path.join(episode_path, "%s_%05d.png" % (k, i)), v)

def make_index(self, command_index: int = 11):
def make_index(self, command_index: int = 11) -> None:
"""
Make an index txt file to save all the command of each frame in dataset.
Expand Down
79 changes: 79 additions & 0 deletions core/data/bev_vae_dataset.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
import os
import lmdb
import cv2
import numpy as np
from typing import Any, Dict
import torch
from torchvision import transforms
from torch.utils.data import Dataset

PIXEL_OFFSET = 10


class BeVVAEDataset(Dataset):

def __init__(
self,
root_dir,
img_size=320,
crop_size=192,
crop_x_jitter=5,
crop_y_jitter=5,
angle_jitter=5,
down_ratio=4,
max_frames=None
) -> None:
self._root_dir = root_dir
self._img_size = img_size
self._crop_size = crop_size
self._crop_x_jitter = crop_x_jitter
self._crop_y_jitter = crop_y_jitter
self._angle_jitter = angle_jitter
self._down_ratio = down_ratio
self._max_frames = max_frames
self.bird_view_transform = transforms.ToTensor()

epi_folder = [x for x in os.listdir(root_dir) if x.startswith('epi')]

self._lmdb_list = []
self._idx_list = []

for item in epi_folder:
lmdb_file = lmdb.open(os.path.join(root_dir, item, 'measurements.lmdb')).begin(write=False)
max_len = int(lmdb_file.get('len'.encode()))
for i in range(max_len):
self._lmdb_list.append(lmdb_file)
self._idx_list.append(i)

def __len__(self):
return len(self._lmdb_list)

def __getitem__(self, index) -> Any:
lmdb_txn = self._lmdb_list[index]
episode_index = self._idx_list[index]

birdview = np.frombuffer(lmdb_txn.get(('birdview_%05d' % episode_index).encode()),
np.uint8).reshape(320, 320, 7) * 255

delta_angle = np.random.randint(-self._angle_jitter, self._angle_jitter + 1)
dx = np.random.randint(-self._crop_x_jitter, self._crop_x_jitter + 1)
dy = np.random.randint(0, self._crop_y_jitter + 1) - PIXEL_OFFSET

pixel_ox = 160
pixel_oy = 260

birdview = cv2.warpAffine(
birdview,
cv2.getRotationMatrix2D((pixel_ox, pixel_oy), delta_angle, 1.0),
birdview.shape[1::-1],
flags=cv2.INTER_LINEAR
)

# random cropping
center_x, center_y = 160, 260 - self._crop_size // 2
birdview = birdview[dy + center_y - self._crop_size // 2:dy + center_y + self._crop_size // 2,
dx + center_x - self._crop_size // 2:dx + center_x + self._crop_size // 2]

birdview = self.bird_view_transform(birdview)

return {'birdview': birdview}
5 changes: 3 additions & 2 deletions core/data/carla_benchmark_collector.py
Original file line number Diff line number Diff line change
Expand Up @@ -257,8 +257,9 @@ def collect(
reset_param_index = self._collect_suite_index_dict[next_suite]
reset_param = self._collect_suite_reset_params[next_suite][reset_param_index]
self._collect_suite_index_dict[next_suite] += 1
if reset_param_index >= len(self._collect_suite_reset_params[next_suite]):
self._collect_suite_index_dict[next_suite] = 0
self._collect_suite_index_dict[next_suite] %= len(
self._collect_suite_reset_params[next_suite]
)
running_env_params[env_id] = reset_param
self._env_manager.reset({env_id: reset_param})
self._traj_cache[env_id].clear()
Expand Down
2 changes: 1 addition & 1 deletion core/data/casezoo/configs/route01.json
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
}
}
],
"scenario_type": "FollowLeadingVehicle"
"scenario_type": "FollowLeadingVehicleNew"
},
{
"available_event_configurations": [
Expand Down
4 changes: 2 additions & 2 deletions core/data/casezoo/configs/route02.json
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
}
}
],
"scenario_type": "ControlLoss"
"scenario_type": "ControlLossNew"
},
{
"available_event_configurations": [
Expand All @@ -28,7 +28,7 @@
}
}
],
"scenario_type": "FollowLeadingVehicle"
"scenario_type": "FollowLeadingVehicleNew"
}
]
}
Expand Down
2 changes: 1 addition & 1 deletion core/data/casezoo/configs/route03.json
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@
}
}
],
"scenario_type": "FollowLeadingVehicle"
"scenario_type": "FollowLeadingVehicleNew"
},
{
"available_event_configurations": [
Expand Down
4 changes: 2 additions & 2 deletions core/data/casezoo/configs/route04.json
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
}
}
],
"scenario_type": "FollowLeadingVehicle"
"scenario_type": "FollowLeadingVehicleNew"
},
{
"available_event_configurations": [
Expand All @@ -53,7 +53,7 @@
}
}
],
"scenario_type": "ControlLoss"
"scenario_type": "ControlLossNew"
},
{
"available_event_configurations": [
Expand Down
6 changes: 3 additions & 3 deletions core/data/casezoo/configs/route06.json
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
}
}
],
"scenario_type": "FollowLeadingVehicle"
"scenario_type": "FollowLeadingVehicleNew"
},
{
"available_event_configurations": [
Expand Down Expand Up @@ -85,7 +85,7 @@
}
}
],
"scenario_type": "FollowLeadingVehicle"
"scenario_type": "FollowLeadingVehicleNew"
},
{
"available_event_configurations": [
Expand All @@ -99,7 +99,7 @@
}
}
],
"scenario_type": "ControlLoss"
"scenario_type": "ControlLossNew"
}
]
}
Expand Down
4 changes: 2 additions & 2 deletions core/data/casezoo/configs/route07.json
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@
}
}
],
"scenario_type": "FollowLeadingVehicle"
"scenario_type": "FollowLeadingVehicleNew"
},
{
"available_event_configurations": [
Expand All @@ -78,7 +78,7 @@
}
}
],
"scenario_type": "ControlLoss"
"scenario_type": "ControlLossNew"
}
]
}
Expand Down
4 changes: 2 additions & 2 deletions core/data/casezoo/configs/route09.json
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@
}
}
],
"scenario_type": "FollowLeadingVehicle"
"scenario_type": "FollowLeadingVehicleNew"
},
{
"available_event_configurations": [
Expand All @@ -107,7 +107,7 @@
}
}
],
"scenario_type": "ControlLoss"
"scenario_type": "ControlLossNew"
}
]
}
Expand Down
2 changes: 1 addition & 1 deletion core/data/casezoo/configs/town03_1.json
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@
}
}
],
"scenario_type": "FollowLeadingVehicle"
"scenario_type": "FollowLeadingVehicleNew"
},
{
"available_event_configurations": [
Expand Down
2 changes: 1 addition & 1 deletion core/data/casezoo/configs/town04_1.json
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@
}
}
],
"scenario_type": "FollowLeadingVehicle"
"scenario_type": "FollowLeadingVehicleNew"
},
{
"available_event_configurations": [
Expand Down
Loading

0 comments on commit f532c9e

Please sign in to comment.