-
Notifications
You must be signed in to change notification settings - Fork 1
/
envs.py
1001 lines (828 loc) · 37.4 KB
/
envs.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
import math
import os
import pickle
import sys
import gym
from habitat.utils.geometry_utils import quaternion_rotate_vector
import matplotlib
import numpy as np
import quaternion
import skimage.morphology
import torch
from PIL import Image
from torch.nn import functional as F
from torchvision import transforms
import habitat
from habitat import logger
from utils.map_builder import MapBuilder
from utils.fmm_planner import FMMPlanner
import utils.pose as pu
import utils.visualizations as vu
from utils.supervision import HabitatMaps
from model import get_grid
if sys.platform == 'darwin':
matplotlib.use("tkagg")
else:
matplotlib.use('Agg')
import matplotlib.pyplot as plt
from habitat.core.vector_env import VectorEnv
from habitat.datasets.pointnav.pointnav_dataset import PointNavDatasetV1
from habitat.config.default import get_config as cfg_env
from habitat_baselines.config.default import get_config
from ppo_utils import batch_obs
def _preprocess_depth(depth):
depth = depth[:, :, 0]*1
mask2 = depth > 0.99
depth[mask2] = 0.
for i in range(depth.shape[1]):
depth[:,i][depth[:,i] == 0.] = depth[:,i].max()
mask1 = depth == 0
depth[mask1] = np.NaN
depth = depth*1000.
return depth
def make_vec_envs(args):
return construct_envs(args)
# Adapted from https://github.com/ikostrikov/pytorch-a2c-ppo-acktr-gail/blob/master/a2c_ppo_acktr/envs.py#L159
class VecPyTorch():
def __init__(self, venv, device):
self.venv = venv
self.num_envs = venv.num_envs
self.observation_space = venv.observation_spaces[0]
self.action_space = venv.action_spaces[0]
self.device = device
def reset_at(self, env_idx):
obs, info = self.venv.reset_at(env_idx)
obs = torch.from_numpy(obs).float().to(self.device)
return obs, info
def reset(self):
obs,info = self.venv.reset()
obs = batch_obs(obs)
for sensor in obs:
obs[sensor] = obs[sensor].to(self.device)
#obs = torch.from_numpy(obs).float().to(self.device)
return obs, info
def step_async(self, actions):
actions = actions.cpu().numpy()
self.venv.step_async(actions)
def step_wait(self):
obs, reward, done, info = self.venv.step_wait()
obs = torch.from_numpy(obs).float().to(self.device)
reward = torch.from_numpy(reward).float()
return obs, reward, done, info
def step(self, actions):
#actions = actions.cpu().numpy()
obs, reward, done, info = self.venv.step(actions)
obs = batch_obs(obs)
for sensor in obs:
obs[sensor] = obs[sensor].to(self.device)
#obs = torch.from_numpy(obs).float().to(self.device)
reward = torch.from_numpy(reward).float()
return obs, reward, done, info
def get_rewards(self, inputs):
reward = self.venv.get_rewards(inputs)
reward = torch.from_numpy(reward).float()
return reward
def get_short_term_goal(self, inputs):
stg = self.venv.get_short_term_goal(inputs)
stg = torch.from_numpy(stg).float()
return stg
def close(self):
return self.venv.close()
# This function will be subsequentlty used to create threaded environment
def make_env_fn(args, config_env, rank):
# Dataset
dataset = PointNavDatasetV1(config_env.DATASET)
env = Exploration_Env(args=args, rank=rank,
config_env=config_env, dataset=dataset
)
env.seed(rank)
return env
def construct_envs(args):
env_configs = []
args_list = []
basic_config = cfg_env(config_paths=
"habitat-lab/configs/tasks/pointnav.yaml")
basic_config.defrost()
basic_config.DATASET.SPLIT = args.split
basic_config.DATASET.DATA_PATH = (
"data/datasets/pointnav/gibson/v1/{split}/{split}.json.gz")
basic_config.DATASET.TYPE = "PointNavDataset-v1"
basic_config.freeze()
scenes = PointNavDatasetV1.get_scenes_to_load(basic_config.DATASET)
if len(scenes) > 0:
assert len(scenes) >= args.num_processes, (
"reduce the number of processes as there "
"aren't enough number of scenes"
)
scene_split_size = int(np.floor(len(scenes) / args.num_processes))
for i in range(args.num_processes):
config_env = cfg_env(config_paths=
"habitat-lab/configs/tasks/pointnav.yaml")
config_env.defrost()
if len(scenes) > 0:
config_env.DATASET.CONTENT_SCENES = scenes[
i * scene_split_size: (i + 1) * scene_split_size
]
if i < args.num_processes_on_first_gpu:
gpu_id = 0
else:
gpu_id = int((i - args.num_processes_on_first_gpu)
// args.num_processes_per_gpu) + args.sim_gpu_id
gpu_id = min(torch.cuda.device_count() - 1, gpu_id)
config_env.SIMULATOR.HABITAT_SIM_V0.GPU_DEVICE_ID = gpu_id
agent_sensors = []
agent_sensors.append("RGB_SENSOR")
agent_sensors.append("DEPTH_SENSOR")
config_env.DATASET.DATA_PATH = (
"data/datasets/pointnav/gibson/v1/{split}/{split}.json.gz"
)
config_env.SIMULATOR.AGENT_0.SENSORS = agent_sensors
config_env.ENVIRONMENT.MAX_EPISODE_STEPS = args.max_episode_length
config_env.ENVIRONMENT.ITERATOR_OPTIONS.SHUFFLE = False
config_env.SIMULATOR.RGB_SENSOR.WIDTH = args.env_frame_width
config_env.SIMULATOR.RGB_SENSOR.HEIGHT = args.env_frame_height
config_env.SIMULATOR.RGB_SENSOR.HFOV = args.hfov
config_env.SIMULATOR.RGB_SENSOR.POSITION = [0, args.camera_height, 0]
config_env.SIMULATOR.DEPTH_SENSOR.WIDTH = args.env_frame_width
config_env.SIMULATOR.DEPTH_SENSOR.HEIGHT = args.env_frame_height
config_env.SIMULATOR.DEPTH_SENSOR.HFOV = args.hfov
config_env.SIMULATOR.DEPTH_SENSOR.POSITION = [0, args.camera_height, 0]
config_env.SIMULATOR.TURN_ANGLE = 10
config_env.DATASET.SPLIT = args.split
config_env.freeze()
env_configs.append(config_env)
args_list.append(args)
# Create a vector environment for faster training and evaluation
envs = VectorEnv(
make_env_fn=make_env_fn,
env_fn_args=tuple(
tuple(
zip(args_list, env_configs,range(args.num_processes)
)
)
),
)
# Convert the data generated by the environment into pytorch tensors
envs = VecPyTorch(envs, args.device)
return envs
def _preprocess_depth(depth):
depth = depth[:, :, 0]*1
mask2 = depth > 0.99
depth[mask2] = 0.
for i in range(depth.shape[1]):
depth[:,i][depth[:,i] == 0.] = depth[:,i].max()
mask1 = depth == 0
depth[mask1] = np.NaN
depth = depth*1000.
return depth
class Exploration_Env(habitat.RLEnv):
def __init__(self, args, rank, config_env, dataset):
if args.visualize:
plt.ion()
if args.print_images or args.visualize:
self.figure, self.ax = plt.subplots(1,2, figsize=(6*16/9, 6),
facecolor="whitesmoke",
num="Thread {}".format(rank))
self.args = args
self.num_actions = 3
self.dt = 10
self.rank = rank
self.sensor_noise_fwd = \
pickle.load(open("noise_models/sensor_noise_fwd.pkl", 'rb'))
self.sensor_noise_right = \
pickle.load(open("noise_models/sensor_noise_right.pkl", 'rb'))
self.sensor_noise_left = \
pickle.load(open("noise_models/sensor_noise_left.pkl", 'rb'))
super().__init__(config_env, dataset)
self.mapper = self.build_mapper()
self.episode_no = 0
self.res = transforms.Compose([transforms.ToPILImage(),
transforms.Resize((args.frame_height, args.frame_width),
interpolation = Image.NEAREST)])
self.scene_name = None
self.maps_dict = {}
self._prev_measure = 0
def randomize_env(self):
self._env._episode_iterator._shuffle_iterator()
def save_trajectory_data(self):
if "replica" in self.scene_name:
folder = self.args.save_trajectory_data + "/" + \
self.scene_name.split("/")[-3]+"/"
else:
folder = self.args.save_trajectory_data + "/" + \
self.scene_name.split("/")[-1].split(".")[0]+"/"
if not os.path.exists(folder):
os.makedirs(folder)
filepath = folder+str(self.episode_no)+".txt"
with open(filepath, "w+") as f:
f.write(self.scene_name+"\n")
for state in self.trajectory_states:
f.write(str(state)+"\n")
f.flush()
def save_position(self):
self.agent_state = self._env.sim.get_agent_state()
self.trajectory_states.append([self.agent_state.position,
self.agent_state.rotation])
def reset(self):
args = self.args
self.timestep = 0
self._previous_action = None
self.trajectory_states = []
self.prm_planner = None
self.prm_planner_setup = None
# Get Ground Truth Map
self.explorable_map = None
while self.explorable_map is None:
obs = super().reset()
full_map_size = args.map_size_cm//args.map_resolution
self.explorable_map = self._get_gt_map(full_map_size)
self.prev_explored_area = 0.
self.episode_no += 1
# For prm path dataset generation
self.goal_reached =0
self.prm_star_path = {}
self.prm_star_path_idx = 0
# Preprocess observations
rgb = obs['rgb'].astype(np.uint8)
depth_ = obs['depth'].astype(np.uint8)
self.obs = rgb # For visualization
if self.args.frame_width != self.args.env_frame_width:
rgb = np.asarray(self.res(rgb))
depth_ = np.asarray(self.res(depth_))
depth_ = np.expand_dims(depth_, axis=0)
#state = rgb.transpose(2, 0, 1)
state = np.concatenate((rgb.transpose(2, 0, 1), depth_))
depth = _preprocess_depth(obs['depth'])
# To store as the dataset for Region proposal network
self.curr_rgb = rgb
self.curr_depth = obs['depth']
self.last_rgb = self.curr_rgb
self.last_depth = self.curr_depth
# Initialize map and pose
self.map_size_cm = args.map_size_cm
self.mapper.reset_map(self.map_size_cm)
self.curr_loc = [self.map_size_cm/100.0/2.0,
self.map_size_cm/100.0/2.0, 0.]
self.curr_loc_gt = self.curr_loc
self.last_loc_gt = self.curr_loc_gt
self.last_loc = self.curr_loc
self.last_sim_location = self.get_sim_location()
# Convert pose to cm and degrees for mapper
mapper_gt_pose = (self.curr_loc_gt[0]*100.0,
self.curr_loc_gt[1]*100.0,
np.deg2rad(self.curr_loc_gt[2]))
# Update ground_truth map and explored area
fp_proj, self.map, fp_explored, self.explored_map = \
self.mapper.update_map(depth, mapper_gt_pose)
# Initialize variables
#self.scene_name = self.habitat_env.sim.config.SCENE
self.visited = np.zeros(self.map.shape)
self.visited_vis = np.zeros(self.map.shape)
self.visited_gt = np.zeros(self.map.shape)
self.collison_map = np.zeros(self.map.shape)
self.col_width = 1
# Set info
self.info = {
'time': self.timestep,
'fp_proj': fp_proj,
'fp_explored': fp_explored,
'sensor_pose': [0., 0., 0.],
'pose_err': [0., 0., 0.],
'geodesic_distance':[0],
}
self.info['goal_location'] = obs['pointgoal_with_gps_compass']
self.info['distance_to_goal'] = self._env.get_metrics()["distance_to_goal"]
self.info['spl'] = self._env.get_metrics()["spl"]
self.info['success'] = self._env.get_metrics()["success"]
self.save_position()
#return state, self.info
return obs, self.info
def step(self, action):
args = self.args
self.timestep += 1
if (action == 0 ):
action = 1
if self.info['distance_to_goal'] < 0.2: # Stop
action = 0
self.last_loc = np.copy(self.curr_loc)
self.last_loc_gt = np.copy(self.curr_loc_gt)
self._previous_action = action
self.last_rgb = np.copy(self.curr_rgb)
self.last_depth = np.copy(self.curr_depth)
obs, rew, done, info = super().step(action)
# Preprocess observations
rgb = obs['rgb'].astype(np.uint8)
self.obs = rgb # For visualization
if self.args.frame_width != self.args.env_frame_width:
rgb = np.asarray(self.res(rgb))
depth_ = np.asarray(self.res(obs['depth']))
depth_ = np.expand_dims(depth_, axis=0)
state = np.concatenate((rgb.transpose(2, 0, 1), depth_))
depth = _preprocess_depth(obs['depth'])
# Get base sensor and ground-truth pose
dx_gt, dy_gt, do_gt = self.get_gt_pose_change()
dx_base, dy_base, do_base = self.get_base_pose_change(
action, (dx_gt, dy_gt, do_gt))
self.curr_loc = pu.get_new_pose(self.curr_loc,
(dx_base, dy_base, do_base))
self.curr_loc_gt = pu.get_new_pose(self.curr_loc_gt,
(dx_gt, dy_gt, do_gt))
self.curr_rgb = rgb
self.curr_depth = obs['depth']
if not args.noisy_odometry:
self.curr_loc = self.curr_loc_gt
dx_base, dy_base, do_base = dx_gt, dy_gt, do_gt
# Convert pose to cm and degrees for mapper
mapper_gt_pose = (self.curr_loc_gt[0]*100.0,
self.curr_loc_gt[1]*100.0,
np.deg2rad(self.curr_loc_gt[2]))
# Update ground_truth map and explored area
fp_proj, self.map, fp_explored, self.explored_map = \
self.mapper.update_map(depth, mapper_gt_pose)
# Update collision map
if action == 1:
x1, y1, t1 = self.last_loc
x2, y2, t2 = self.curr_loc
if abs(x1 - x2)< 0.05 and abs(y1 - y2) < 0.05:
self.col_width += 2
self.col_width = min(self.col_width, 9)
else:
self.col_width = 1
dist = pu.get_l2_distance(x1, x2, y1, y2)
if dist < args.collision_threshold: #Collision
length = 2
width = self.col_width
buf = 3
for i in range(length):
for j in range(width):
wx = x1 + 0.05*((i+buf) * np.cos(np.deg2rad(t1)) + \
(j-width//2) * np.sin(np.deg2rad(t1)))
wy = y1 + 0.05*((i+buf) * np.sin(np.deg2rad(t1)) - \
(j-width//2) * np.cos(np.deg2rad(t1)))
r, c = wy, wx
r, c = int(r*100/args.map_resolution), \
int(c*100/args.map_resolution)
[r, c] = pu.threshold_poses([r, c],
self.collison_map.shape)
self.collison_map[r,c] = 1
# Set info
self.info['time'] = self.timestep
self.info['fp_proj'] = fp_proj
self.info['fp_explored']= fp_explored
self.info['sensor_pose'] = [dx_base, dy_base, do_base]
self.info['pose_err'] = [dx_gt - dx_base,
dy_gt - dy_base,
do_gt - do_base]
self.info['goal_location'] = obs['pointgoal_with_gps_compass']
if self.timestep%args.num_local_steps==0:
area, ratio = self.get_global_reward()
self.info['exp_reward'] = area
self.info['exp_ratio'] = ratio
else:
self.info['exp_reward'] = None
self.info['exp_ratio'] = None
self.save_position()
if self.info['time'] >= args.max_episode_length or action == 0:
done = True
if self.args.save_trajectory_data != "0":
self.save_trajectory_data()
else:
done = False
self.info['distance_to_goal'] = self._env.get_metrics()["distance_to_goal"]
self.info['spl'] = self._env.get_metrics()["spl"]
self.info['success'] = self._env.get_metrics()["success"]
#return state, rew, done, self.info
return obs, rew, done, self.info
def get_goal_location(self, rel_goal_pos):
agent_x, agent_y, agent_o = self.get_sim_location()
#Polar coordinate relative to the agent position
r = rel_goal_pos[0]
if rel_goal_pos[1] < 0:
theta = (2*np.pi + rel_goal_pos[1])
else:
theta = rel_goal_pos[1]
theta = theta + agent_o + np.pi
# Converting into cartesian format
goal_x = r * np.cos(theta) - agent_x
goal_y = r * np.sin(theta) - agent_y
return [goal_x, goal_y]
def get_reward_range(self):
# This function is not used, Habitat-RLEnv requires this function
return (0., 1.0)
def get_reward(self, observations):
reward = 0
rel_goal_pos = observations['pointgoal_with_gps_compass']
episode_success_reward = self.get_episode_success_reward(rel_goal_pos)
agent_to_goal_dist_reward = self.get_agent_to_object_dist_reward(observations)
reward += (agent_to_goal_dist_reward + episode_success_reward)
return reward
def get_episode_success_reward(self, rel_goal_pos):
agent_x, agent_y, agent_o = self.get_sim_location()
goal_x, goal_y = self.get_goal_location(rel_goal_pos)
reward = 0
if (np.sqrt((goal_x - agent_x)**2 +(goal_y - agent_y)**2) < 0.2):
reward = 10
return reward
def get_agent_to_object_dist_reward(self, observations):
"""
Encourage the agent to move towards the goal.
"""
curr_metric = self._env.get_metrics()["distance_to_goal"]
prev_metric = self._prev_measure
dist_reward = prev_metric - curr_metric
self._prev_measure = curr_metric
return dist_reward
def get_global_reward(self):
curr_explored = self.explored_map*self.explorable_map
curr_explored_area = curr_explored.sum()
reward_scale = self.explorable_map.sum()
m_reward = (curr_explored_area - self.prev_explored_area)*1.
m_ratio = m_reward/reward_scale
m_reward = m_reward * 25./10000. # converting to m^2
self.prev_explored_area = curr_explored_area
m_reward *= 0.02 # Reward Scaling
return m_reward, m_ratio
def get_done(self, observations):
# This function is not used, Habitat-RLEnv requires this function
return False
def get_info(self, observations):
# This function is not used, Habitat-RLEnv requires this function
info = {}
return self.habitat_env.get_metrics()
def seed(self, seed):
self.rng = np.random.RandomState(seed)
def get_spaces(self):
return self.observation_space, self.action_space
def build_mapper(self):
params = {}
params['frame_width'] = self.args.env_frame_width
params['frame_height'] = self.args.env_frame_height
params['fov'] = self.args.hfov
params['resolution'] = self.args.map_resolution
params['map_size_cm'] = self.args.map_size_cm
params['agent_min_z'] = 25
params['agent_max_z'] = 150
params['agent_height'] = self.args.camera_height * 100
params['agent_view_angle'] = 0
params['du_scale'] = self.args.du_scale
params['vision_range'] = self.args.vision_range
params['visualize'] = self.args.visualize
params['obs_threshold'] = self.args.obs_threshold
self.selem = skimage.morphology.disk(self.args.obstacle_boundary /
self.args.map_resolution)
mapper = MapBuilder(params)
return mapper
def get_sim_location(self):
agent_state = super().habitat_env.sim.get_agent_state(0)
x = -agent_state.position[2]
y = -agent_state.position[0]
axis = quaternion.as_euler_angles(agent_state.rotation)[0]
if (axis%(2*np.pi)) < 0.1 or (axis%(2*np.pi)) > 2*np.pi - 0.1:
o = quaternion.as_euler_angles(agent_state.rotation)[1]
else:
o = 2*np.pi - quaternion.as_euler_angles(agent_state.rotation)[1]
if o > np.pi:
o -= 2 * np.pi
return x, y, o
def get_gt_pose_change(self):
curr_sim_pose = self.get_sim_location()
dx, dy, do = pu.get_rel_pose_change(curr_sim_pose, self.last_sim_location)
self.last_sim_location = curr_sim_pose
return dx, dy, do
def get_base_pose_change(self, action, gt_pose_change):
dx_gt, dy_gt, do_gt = gt_pose_change
if action == 1: ## Forward
x_err, y_err, o_err = self.sensor_noise_fwd.sample()[0][0]
elif action == 3: ## Right
x_err, y_err, o_err = self.sensor_noise_right.sample()[0][0]
elif action == 2: ## Left
x_err, y_err, o_err = self.sensor_noise_left.sample()[0][0]
else: ##Stop
x_err, y_err, o_err = 0., 0., 0.
x_err = x_err * self.args.noise_level
y_err = y_err * self.args.noise_level
o_err = o_err * self.args.noise_level
return dx_gt + x_err, dy_gt + y_err, do_gt + np.deg2rad(o_err)
def get_short_term_goal(self, inputs):
args = self.args
# Get Map prediction
map_pred = inputs['map_pred']
exp_pred = inputs['exp_pred']
grid = np.rint(map_pred)
explored = np.rint(exp_pred)
# Get pose prediction and global policy planning window
start_x, start_y, start_o, gx1, gx2, gy1, gy2 = inputs['pose_pred']
gx1, gx2, gy1, gy2 = int(gx1), int(gx2), int(gy1), int(gy2)
planning_window = [gx1, gx2, gy1, gy2]
# Get last loc
last_start_x, last_start_y = self.last_loc[0], self.last_loc[1]
r, c = last_start_y, last_start_x
last_start = [int(r * 100.0/args.map_resolution - gx1),
int(c * 100.0/args.map_resolution - gy1)]
last_start = pu.threshold_poses(last_start, grid.shape)
# Get curr loc
self.curr_loc = [start_x, start_y, start_o]
r, c = start_y, start_x
start = [int(r * 100.0/args.map_resolution - gx1),
int(c * 100.0/args.map_resolution - gy1)]
start = pu.threshold_poses(start, grid.shape)
#TODO: try reducing this
start_x - gy1*args.map_resolution/100.0
self.visited[gx1:gx2, gy1:gy2][start[0]-2:start[0]+3,
start[1]-2:start[1]+3] = 1
steps = 25
for i in range(steps):
x = int(last_start[0] + (start[0] - last_start[0]) * (i+1) / steps)
y = int(last_start[1] + (start[1] - last_start[1]) * (i+1) / steps)
self.visited_vis[gx1:gx2, gy1:gy2][x, y] = 1
# Get last loc ground truth pose
last_start_x, last_start_y = self.last_loc_gt[0], self.last_loc_gt[1]
r, c = last_start_y, last_start_x
last_start = [int(r * 100.0/args.map_resolution),
int(c * 100.0/args.map_resolution)]
last_start = pu.threshold_poses(last_start, self.visited_gt.shape)
# Get ground truth pose
start_x_gt, start_y_gt, start_o_gt = self.curr_loc_gt
r, c = start_y_gt, start_x_gt
start_gt = [int(r * 100.0/args.map_resolution),
int(c * 100.0/args.map_resolution)]
start_gt = pu.threshold_poses(start_gt, self.visited_gt.shape)
#self.visited_gt[start_gt[0], start_gt[1]] = 1
steps = 25
for i in range(steps):
x = int(last_start[0] + (start_gt[0] - last_start[0]) * (i+1) / steps)
y = int(last_start[1] + (start_gt[1] - last_start[1]) * (i+1) / steps)
self.visited_gt[x, y] = 1
# Get goal
goal = inputs['goal']
goal = pu.threshold_poses(goal, grid.shape)
# Get intrinsic reward for global policy
# Negative reward for exploring explored areas i.e.
# for choosing explored cell as long-term goal
self.extrinsic_rew = -pu.get_l2_distance(10, goal[0], 10, goal[1])
self.intrinsic_rew = -exp_pred[goal[0], goal[1]]
# Get short-term goal
stg = self._get_stg(grid, explored, start, np.copy(goal), planning_window)
# Find GT action
if self.args.eval or not self.args.train_local:
gt_action = 0
else:
gt_action = self._get_gt_action(1 - self.explorable_map, start,
[int(stg[0]), int(stg[1])],
planning_window, start_o)
(stg_x, stg_y) = stg
relative_dist = pu.get_l2_distance(stg_x, start[0], stg_y, start[1])
relative_dist = relative_dist*5./100.
angle_st_goal = math.degrees(math.atan2(stg_x - start[0],
stg_y - start[1]))
angle_agent = (start_o)%360.0
if angle_agent > 180:
angle_agent -= 360
relative_angle = (angle_agent - angle_st_goal)%360.0
if relative_angle > 180:
relative_angle -= 360
self.relative_angle = relative_angle
def discretize(dist):
dist_limits = [0.25, 3, 10]
dist_bin_size = [0.05, 0.25, 1.]
if dist < dist_limits[0]:
ddist = int(dist/dist_bin_size[0])
elif dist < dist_limits[1]:
ddist = int((dist - dist_limits[0])/dist_bin_size[1]) + \
int(dist_limits[0]/dist_bin_size[0])
elif dist < dist_limits[2]:
ddist = int((dist - dist_limits[1])/dist_bin_size[2]) + \
int(dist_limits[0]/dist_bin_size[0]) + \
int((dist_limits[1] - dist_limits[0])/dist_bin_size[1])
else:
ddist = int(dist_limits[0]/dist_bin_size[0]) + \
int((dist_limits[1] - dist_limits[0])/dist_bin_size[1]) + \
int((dist_limits[2] - dist_limits[1])/dist_bin_size[2])
return ddist
output = np.zeros((args.goals_size + 1 + 2))
# #prmstar path following for dataset generation
output[0] = int((relative_angle%360.)/5.)
output[1] = discretize(relative_dist)
output[2] = gt_action
output[3] = relative_dist
output[4] = -np.radians(relative_angle)
if args.visualize or args.print_images:
dump_dir = "{}/dump/{}/".format(args.dump_location,
args.exp_name)
ep_dir = '{}/episodes/{}/{}/'.format(
dump_dir, self.rank+1, self.episode_no)
if not os.path.exists(ep_dir):
os.makedirs(ep_dir)
if args.vis_type == 1: # Visualize predicted map and pose
vis_grid = vu.get_colored_map(np.rint(map_pred),
self.collison_map[gx1:gx2, gy1:gy2],
self.visited_vis[gx1:gx2, gy1:gy2],
self.visited_gt[gx1:gx2, gy1:gy2],
goal,stg,
self.explored_map[gx1:gx2, gy1:gy2],
self.explorable_map[gx1:gx2, gy1:gy2],
self.map[gx1:gx2, gy1:gy2] *
self.explored_map[gx1:gx2, gy1:gy2])
vis_grid = np.flipud(vis_grid)
vu.visualize(self.figure, self.ax, self.obs, vis_grid[:,:,::-1],
(start_x - gy1*args.map_resolution/100.0,
start_y - gx1*args.map_resolution/100.0,
start_o),
(start_x_gt - gy1*args.map_resolution/100.0,
start_y_gt - gx1*args.map_resolution/100.0,
start_o_gt),
dump_dir, self.rank, self.episode_no,
self.timestep, args.visualize,
args.print_images, args.vis_type)
else: # Visualize ground-truth map and pose
vis_grid = vu.get_colored_map(self.map,
self.collison_map,
self.visited_gt,
self.visited_gt,
(goal[0]+gx1, goal[1]+gy1),
self.explored_map,
self.explorable_map,
self.map*self.explored_map)
vis_grid = np.flipud(vis_grid)
vu.visualize(self.figure, self.ax, self.obs, vis_grid[:,:,::-1],
(start_x_gt, start_y_gt, start_o_gt),
(start_x_gt, start_y_gt, start_o_gt),
dump_dir, self.rank, self.episode_no,
self.timestep, args.visualize,
args.print_images, args.vis_type)
return output
def _get_gt_map(self, full_map_size):
#self.scene_name = self.habitat_env.sim.config.SCENE
#logger.error('Computing map for %s', self.scene_name)
# Get map in habitat simulator coordinates
self.map_obj = HabitatMaps(self.habitat_env)
if self.map_obj.size[0] < 1 or self.map_obj.size[1] < 1:
logger.error("Invalid map: {}/{}".format(
self.scene_name, self.episode_no))
return None
agent_y = self._env.sim.get_agent_state().position.tolist()[1]*100.
sim_map = self.map_obj.get_map(agent_y, -50., 50.0)
sim_map[sim_map > 0] = 1.
# Transform the map to align with the agent
min_x, min_y = self.map_obj.origin/100.0
x, y, o = self.get_sim_location()
x, y = -x - min_x, -y - min_y
range_x, range_y = self.map_obj.max/100. - self.map_obj.origin/100.
map_size = sim_map.shape
scale = 2.
grid_size = int(scale*max(map_size))
grid_map = np.zeros((grid_size, grid_size))
grid_map[(grid_size - map_size[0])//2:
(grid_size - map_size[0])//2 + map_size[0],
(grid_size - map_size[1])//2:
(grid_size - map_size[1])//2 + map_size[1]] = sim_map
if map_size[0] > map_size[1]:
st = torch.tensor([[
(x - range_x/2.) * 2. / (range_x * scale) \
* map_size[1] * 1. / map_size[0],
(y - range_y/2.) * 2. / (range_y * scale),
180.0 + np.rad2deg(o)
]])
else:
st = torch.tensor([[
(x - range_x/2.) * 2. / (range_x * scale),
(y - range_y/2.) * 2. / (range_y * scale) \
* map_size[0] * 1. / map_size[1],
180.0 + np.rad2deg(o)
]])
rot_mat, trans_mat = get_grid(st, (1, 1,
grid_size, grid_size), torch.device("cpu"))
grid_map = torch.from_numpy(grid_map).float()
grid_map = grid_map.unsqueeze(0).unsqueeze(0)
translated = F.grid_sample(grid_map, trans_mat)
rotated = F.grid_sample(translated, rot_mat)
episode_map = torch.zeros((full_map_size, full_map_size)).float()
if full_map_size > grid_size:
episode_map[(full_map_size - grid_size)//2:
(full_map_size - grid_size)//2 + grid_size,
(full_map_size - grid_size)//2:
(full_map_size - grid_size)//2 + grid_size] = \
rotated[0,0]
else:
episode_map = rotated[0,0,
(grid_size - full_map_size)//2:
(grid_size - full_map_size)//2 + full_map_size,
(grid_size - full_map_size)//2:
(grid_size - full_map_size)//2 + full_map_size]
episode_map = episode_map.numpy()
episode_map[episode_map > 0] = 1.
return episode_map
def _get_stg(self, grid, explored, start, goal, planning_window):
[gx1, gx2, gy1, gy2] = planning_window
x1 = min(start[0], goal[0])
x2 = max(start[0], goal[0])
y1 = min(start[1], goal[1])
y2 = max(start[1], goal[1])
dist = pu.get_l2_distance(goal[0], start[0], goal[1], start[1])
buf = max(20., dist)
x1 = max(1, int(x1 - buf))
x2 = min(grid.shape[0]-1, int(x2 + buf))
y1 = max(1, int(y1 - buf))
y2 = min(grid.shape[1]-1, int(y2 + buf))
rows = explored.sum(1)
rows[rows>0] = 1
ex1 = np.argmax(rows)
ex2 = len(rows) - np.argmax(np.flip(rows))
cols = explored.sum(0)
cols[cols>0] = 1
ey1 = np.argmax(cols)
ey2 = len(cols) - np.argmax(np.flip(cols))
ex1 = min(int(start[0]) - 2, ex1)
ex2 = max(int(start[0]) + 2, ex2)
ey1 = min(int(start[1]) - 2, ey1)
ey2 = max(int(start[1]) + 2, ey2)
x1 = max(x1, ex1)
x2 = min(x2, ex2)
y1 = max(y1, ey1)
y2 = min(y2, ey2)
traversible = skimage.morphology.binary_dilation(
grid[x1:x2, y1:y2],
self.selem) != True
traversible[self.collison_map[gx1:gx2, gy1:gy2][x1:x2, y1:y2] == 1] = 0
traversible[self.visited[gx1:gx2, gy1:gy2][x1:x2, y1:y2] == 1] = 1
traversible[int(start[0]-x1)-1:int(start[0]-x1)+2,
int(start[1]-y1)-1:int(start[1]-y1)+2] = 1
if goal[0]-2 > x1 and goal[0]+3 < x2\
and goal[1]-2 > y1 and goal[1]+3 < y2:
traversible[int(goal[0]-x1)-2:int(goal[0]-x1)+3,
int(goal[1]-y1)-2:int(goal[1]-y1)+3] = 1
else:
goal[0] = min(max(x1, goal[0]), x2)
goal[1] = min(max(y1, goal[1]), y2)
def add_boundary(mat):
h, w = mat.shape
new_mat = np.ones((h+2,w+2))
new_mat[1:h+1,1:w+1] = mat
return new_mat
traversible = add_boundary(traversible)
planner = FMMPlanner(traversible, 360//self.dt)
reachable = planner.set_goal([goal[1]-y1+1, goal[0]-x1+1])
stg_x, stg_y = start[0] - x1 + 1, start[1] - y1 + 1
for i in range(self.args.short_goal_dist):
stg_x, stg_y, replan = planner.get_short_term_goal([stg_x, stg_y])
if replan:
stg_x, stg_y = start[0], start[1]
else:
stg_x, stg_y = stg_x + x1 - 1, stg_y + y1 - 1
return (stg_x, stg_y)
def _get_gt_action(self, grid, start, goal, planning_window, start_o):
[gx1, gx2, gy1, gy2] = planning_window
x1 = min(start[0], goal[0])
x2 = max(start[0], goal[0])
y1 = min(start[1], goal[1])
y2 = max(start[1], goal[1])
dist = pu.get_l2_distance(goal[0], start[0], goal[1], start[1])
buf = max(5., dist)
x1 = max(0, int(x1 - buf))
x2 = min(grid.shape[0], int(x2 + buf))
y1 = max(0, int(y1 - buf))
y2 = min(grid.shape[1], int(y2 + buf))
path_found = False
goal_r = 0
while not path_found:
traversible = skimage.morphology.binary_dilation(
grid[gx1:gx2, gy1:gy2][x1:x2, y1:y2],
self.selem) != True
traversible[self.visited[gx1:gx2, gy1:gy2][x1:x2, y1:y2] == 1] = 1
traversible[int(start[0]-x1)-1:int(start[0]-x1)+2,
int(start[1]-y1)-1:int(start[1]-y1)+2] = 1
traversible[int(goal[0]-x1)-goal_r:int(goal[0]-x1)+goal_r+1,
int(goal[1]-y1)-goal_r:int(goal[1]-y1)+goal_r+1] = 1
scale = 1
planner = FMMPlanner(traversible, 360//self.dt, scale)
reachable = planner.set_goal([goal[1]-y1, goal[0]-x1])
stg_x_gt, stg_y_gt = start[0] - x1, start[1] - y1
for i in range(1):
stg_x_gt, stg_y_gt, replan = \
planner.get_short_term_goal([stg_x_gt, stg_y_gt])
if replan and buf < 100.:
buf = 2*buf
x1 = max(0, int(x1 - buf))
x2 = min(grid.shape[0], int(x2 + buf))
y1 = max(0, int(y1 - buf))
y2 = min(grid.shape[1], int(y2 + buf))
elif replan and goal_r < 50:
goal_r += 1
else:
path_found = True
stg_x_gt, stg_y_gt = stg_x_gt + x1, stg_y_gt + y1
angle_st_goal = math.degrees(math.atan2(stg_x_gt - start[0],
stg_y_gt - start[1]))
angle_agent = (start_o)%360.0
if angle_agent > 180:
angle_agent -= 360
relative_angle = (angle_agent - angle_st_goal)%360.0
if relative_angle > 180:
relative_angle -= 360
if relative_angle > 15.:
gt_action = 1
elif relative_angle < -15.:
gt_action = 0
else:
gt_action = 2