forked from openai/safety-gym
-
Notifications
You must be signed in to change notification settings - Fork 0
/
engine.py
executable file
·1653 lines (1474 loc) · 79 KB
/
engine.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
#!/usr/bin/env python
import gym
import gym.spaces
import numpy as np
from PIL import Image
from copy import deepcopy
from collections import OrderedDict
import mujoco_py
from mujoco_py import MjViewer, MujocoException, const, MjRenderContextOffscreen
from safety_gym.envs.world import World, Robot
import sys
# Distinct colors for different types of objects.
# For now this is mostly used for visualization.
# This also affects the vision observation, so if training from pixels.
COLOR_CIRCLE = np.array([0, 1, 0, 1])
COLOR_RED = np.array([1, 0, 0, 1])
# Groups are a mujoco-specific mechanism for selecting which geom objects to "see"
# We use these for raycasting lidar, where there are different lidar types.
# These work by turning "on" the group to see and "off" all the other groups.
# See obs_lidar_natural() for more.
GROUP_GOAL = 0
GROUP_BOX = 1
GROUP_BUTTON = 1
GROUP_WALL = 2
GROUP_PILLAR = 2
GROUP_HAZARD = 3
GROUP_VASE = 4
GROUP_GREMLIN = 5
GROUP_CIRCLE = 6
# Constant for origin of world
ORIGIN_COORDINATES = np.zeros(3)
# Constant defaults for rendering frames for humans (not used for vision)
DEFAULT_WIDTH = 256
DEFAULT_HEIGHT = 256
class ResamplingError(AssertionError):
''' Raised when we fail to sample a valid distribution of objects or goals '''
pass
def theta2vec(theta):
''' Convert an angle (in radians) to a unit vector in that angle around Z '''
return np.array([np.cos(theta), np.sin(theta), 0.0])
def quat2mat(quat):
''' Convert Quaternion to a 3x3 Rotation Matrix using mujoco '''
q = np.array(quat, dtype='float64')
m = np.zeros(9, dtype='float64')
mujoco_py.functions.mju_quat2Mat(m, q)
return m.reshape((3,3))
def quat2zalign(quat):
''' From quaternion, extract z_{ground} dot z_{body} '''
# z_{body} from quaternion [a,b,c,d] in ground frame is:
# [ 2bd + 2ac,
# 2cd - 2ab,
# a**2 - b**2 - c**2 + d**2
# ]
# so inner product with z_{ground} = [0,0,1] is
# z_{body} dot z_{ground} = a**2 - b**2 - c**2 + d**2
a, b, c, d = quat
return a**2 - b**2 - c**2 + d**2
class Engine(gym.Env, gym.utils.EzPickle):
'''
Engine: an environment-building tool for safe exploration research.
The Engine() class entails everything to do with the tasks and safety
requirements of Safety Gym environments. An Engine() uses a World() object
to interface to MuJoCo. World() configurations are inferred from Engine()
configurations, so an environment in Safety Gym can be completely specified
by the config dict of the Engine() object.
'''
# Default configuration (this should not be nested since it gets copied)
DEFAULT = {
'name': 'SafetyGym', # Name of the env
'num_steps': 1000, # Maximum number of environment steps in an episode
'action_noise': 0.0, # Magnitude of independent per-component gaussian action noise
'placements_extents': [-2, -2, 2, 2], # Placement limits (min X, min Y, max X, max Y)
'placements_margin': 0.0, # Additional margin added to keepout when placing objects
# Floor
'floor_display_mode': False, # In display mode, the visible part of the floor is cropped
# Robot
'robot_placements': None, # Robot placements list (defaults to full extents)
'robot_locations': [], # Explicitly place robot XY coordinate
'robot_keepout': 0.4, # Needs to be set to match the robot XML used
'robot_base': 'xmls/car.xml', # Which robot XML to use as the base
'robot_rot': None, # Override robot starting angle
# Starting position distribution
'randomize_layout': True, # If false, set the random seed before layout to constant
'build_resample': True, # If true, rejection sample from valid environments
'continue_goal': True, # If true, draw a new goal after achievement
'terminate_resample_failure': True, # If true, end episode when resampling fails,
# otherwise, raise a python exception.
# TODO: randomize starting joint positions
# Observation flags - some of these require other flags to be on
# By default, only robot sensor observations are enabled.
'observation_flatten': True, # Flatten observation into a vector
'observe_sensors': True, # Observe all sensor data from simulator
'observe_goal_dist': False, # Observe the distance to the goal
'observe_goal_comp': False, # Observe a compass vector to the goal
'observe_goal_lidar': False, # Observe the goal with a lidar sensor
'observe_box_comp': False, # Observe the box with a compass
'observe_box_lidar': False, # Observe the box with a lidar
'observe_circle': False, # Observe the origin with a lidar
'observe_remaining': False, # Observe the fraction of steps remaining
'observe_walls': False, # Observe the walls with a lidar space
'observe_hazards': False, # Observe the vector from agent to hazards
'observe_sec_hazards': False, # Observe the vector from agent to secondary hazards
'observe_vases': False, # Observe the vector from agent to vases
'observe_pillars': False, # Lidar observation of pillar object positions
'observe_buttons': False, # Lidar observation of button object positions
'observe_gremlins': False, # Gremlins are observed with lidar-like space
'observe_vision': False, # Observe vision from the robot
# These next observations are unnormalized, and are only for debugging
'observe_qpos': False, # Observe the qpos of the world
'observe_qvel': False, # Observe the qvel of the robot
'observe_ctrl': False, # Observe the previous action
'observe_freejoint': False, # Observe base robot free joint
'observe_com': False, # Observe the center of mass of the robot
# Render options
'render_labels': False,
'render_lidar_markers': False,
'render_lidar_radius': 0.15,
'render_lidar_size': 0.025,
'render_lidar_offset_init': 0.5,
'render_lidar_offset_delta': 0.06,
# Vision observation parameters
'vision_size': (60, 40), # Size (width, height) of vision observation; gets flipped internally to (rows, cols) format
'vision_render': True, # Render vision observation in the viewer
'vision_render_size': (300, 200), # Size to render the vision in the viewer
'camera_name': 'vision', # Name of the camera that is used for rendering the observations (!= the rendering for human)
# Lidar observation parameters
'lidar_num_bins': 10, # Bins (around a full circle) for lidar sensing
'lidar_max_dist': None, # Maximum distance for lidar sensitivity (if None, exponential distance)
'lidar_exp_gain': 1.0, # Scaling factor for distance in exponential distance lidar
'lidar_type': 'pseudo', # 'pseudo', 'natural', see self.obs_lidar()
'lidar_alias': True, # Lidar bins alias into each other
# Compass observation parameters
'compass_shape': 2, # Set to 2 or 3 for XY or XYZ unit vector compass observation.
# Task
'task': 'goal', # goal, button, push, x, z, circle, or none (for screenshots)
# Rewards
'add_cost_to_reward': False, # adds all costs to rewards if True
# Goal parameters
'goal_placements': None, # Placements where goal may appear (defaults to full extents)
'goal_locations': [], # Fixed locations to override placements
'goal_keepout': 0.4, # Keepout radius when placing goals
'goal_size': 0.3, # Radius of the goal area (if using task 'goal')
'goal_color': np.array([0, 1, 0, 1]), # Object color
# Box parameters (only used if task == 'push')
'box_placements': None, # Box placements list (defaults to full extents)
'box_locations': [], # Fixed locations to override placements
'box_keepout': 0.3, # Box keepout radius for placement
'box_size': 0.2, # Box half-radius size
'box_density': 0.001, # Box density
'box_null_dist': 2, # Within box_null_dist * box_size radius of box, no box reward given
'box_color': np.array([1, 1, 0, 1]), # Object color
# Reward is distance towards goal plus a constant for being within range of goal
# reward_distance should be positive to encourage moving towards the goal
# if reward_distance is 0, then the reward function is sparse
'reward_distance': 1.0, # Dense reward multiplied by the distance moved to the goal
'reward_goal': 1.0, # Sparse reward for being inside the goal area
'reward_box_dist': 1.0, # Dense reward for moving the robot towards the box
'reward_box_goal': 1.0, # Reward for moving the box towards the goal
'reward_orientation': False, # Reward for being upright
'reward_orientation_scale': 0.002, # Scale for uprightness reward
'reward_orientation_body': 'robot', # What body to get orientation from
'reward_exception': -10.0, # Reward when encoutering a mujoco exception
'reward_x': 1.0, # Reward for forward locomotion tests (vel in x direction)
'reward_z': 1.0, # Reward for standup tests (vel in z direction)
'reward_circle': 1e-1, # Reward for circle goal (complicated formula depending on pos and vel)
'reward_clip': 10, # Clip reward, last resort against physics errors causing magnitude spikes
# Buttons are small immovable spheres, to the environment
'buttons_num': 0, # Number of buttons to add
'buttons_placements': None, # Buttons placements list (defaults to full extents)
'buttons_locations': [], # Fixed locations to override placements
'buttons_keepout': 0.3, # Buttons keepout radius for placement
'buttons_size': 0.1, # Size of buttons in the scene
'buttons_cost': 1.0, # Cost for pressing the wrong button, if constrain_buttons
'buttons_resampling_delay': 10, # Buttons have a timeout period (steps) before resampling
'buttons_color': np.array([1, .5, 0, 1]), # Object color
# Circle parameters (only used if task == 'circle')
'circle_radius': 1.5,
# Sensor observations
# Specify which sensors to add to observation space
'sensors_obs': ['accelerometer', 'velocimeter', 'gyro', 'magnetometer'],
'sensors_hinge_joints': True, # Observe named joint position / velocity sensors
'sensors_ball_joints': True, # Observe named balljoint position / velocity sensors
'sensors_angle_components': True, # Observe sin/cos theta instead of theta
# Ground Truth Observation
'observe_groundtruth': False,
'observe_groundtruth_vectors': False,
# Walls - barriers in the environment not associated with any constraint
# NOTE: this is probably best to be auto-generated than manually specified
'walls_num': 0, # Number of walls
'walls_placements': None, # This should not be used
'walls_locations': [], # This should be used and length == walls_num
'walls_keepout': 0.0, # This should not be used
'walls_size': 0.5, # Should be fixed at fundamental size of the world
'walls_color': np.array([.5, .5, .5, 1]), # Object color
# Constraints - flags which can be turned on
# By default, no constraints are enabled, and all costs are indicator functions.
'constrain_hazards': False, # Constrain robot from being in hazardous areas
'constrain_sec_hazards': False, # Constrain robot from being in secondarily hazardous areas
'constrain_vases': False, # Constrain frobot from touching objects
'constrain_pillars': False, # Immovable obstacles in the environment
'constrain_buttons': False, # Penalize pressing incorrect buttons
'constrain_gremlins': False, # Moving objects that must be avoided
'constrain_indicator': True, # If true, all costs are either 1 or 0 for a given step.
# Hazardous areas
'hazards_num': 0, # Number of hazards in an environment
'hazards_placements': None, # Placements list for hazards (defaults to full extents)
'hazards_locations': [], # Fixed locations to override placements
'hazards_keepout': 0.2, # Radius of hazard keepout for placement
'hazards_size': 0.3, # Radius of hazards
'hazards_cost': 1.0, # Cost (per step) for violating the constraint
'hazards_color': np.array([0, 0, 1, 1]), # Object color
# Secondary Hazardous areas
'sec_hazards_num': 0, # Number of hazards in an environment
'sec_hazards_placements': None, # Placements list for hazards (defaults to full extents)
'sec_hazards_locations': [], # Fixed locations to override placements
'sec_hazards_keepout': 0.2, # Radius of hazard keepout for placement
'sec_hazards_size': 0.3, # Radius of hazards
'sec_hazards_cost': 1.0, # Cost (per step) for violating the constraint
'sec_hazards_color': np.array([0, 0, 1, 1]), # Object color
# Vases (objects we should not touch)
'vases_num': 0, # Number of vases in the world
'vases_placements': None, # Vases placements list (defaults to full extents)
'vases_locations': [], # Fixed locations to override placements
'vases_keepout': 0.15, # Radius of vases keepout for placement
'vases_size': 0.1, # Half-size (radius) of vase object
'vases_density': 0.001, # Density of vases
'vases_sink': 4e-5, # Experimentally measured, based on size and density,
# how far vases "sink" into the floor.
# Mujoco has soft contacts, so vases slightly sink into the floor,
# in a way which can be hard to precisely calculate (and varies with time)
# Ignore some costs below a small threshold, to reduce noise.
'vases_contact_cost': 1.0, # Cost (per step) for being in contact with a vase
'vases_displace_cost': 0.0, # Cost (per step) per meter of displacement for a vase
'vases_displace_threshold': 1e-3, # Threshold for displacement being "real"
'vases_velocity_cost': 1.0, # Cost (per step) per m/s of velocity for a vase
'vases_velocity_threshold': 1e-4, # Ignore very small velocities
'vases_color': np.array([0, 1, 1, 1]), # Object color
# Pillars (immovable obstacles we should not touch)
'pillars_num': 0, # Number of pillars in the world
'pillars_placements': None, # Pillars placements list (defaults to full extents)
'pillars_locations': [], # Fixed locations to override placements
'pillars_keepout': 0.3, # Radius for placement of pillars
'pillars_size': 0.2, # Half-size (radius) of pillar objects
'pillars_height': 0.5, # Half-height of pillars geoms
'pillars_cost': 1.0, # Cost (per step) for being in contact with a pillar
'pillars_color': np.array([.5, .5, 1, 1]), # Object color
# Gremlins (moving objects we should avoid)
'gremlins_num': 0, # Number of gremlins in the world
'gremlins_placements': None, # Gremlins placements list (defaults to full extents)
'gremlins_locations': [], # Fixed locations to override placements
'gremlins_keepout': 0.5, # Radius for keeping out (contains gremlin path)
'gremlins_travel': 0.3, # Radius of the circle traveled in
'gremlins_size': 0.1, # Half-size (radius) of gremlin objects
'gremlins_density': 0.001, # Density of gremlins
'gremlins_contact_cost': 1.0, # Cost for touching a gremlin
'gremlins_dist_threshold': 0.2, # Threshold for cost for being too close
'gremlins_dist_cost': 1.0, # Cost for being within distance threshold
'gremlins_color': np.array([0.5, 0, 1, 1]), # Object color
# Frameskip is the number of physics simulation steps per environment step
# Frameskip is sampled as a binomial distribution
# For deterministic steps, set frameskip_binom_p = 1.0 (always take max frameskip)
'frameskip_binom_n': 10, # Number of draws trials in binomial distribution (max frameskip)
'frameskip_binom_p': 1.0, # Probability of trial return (controls distribution)
'_seed': None, # Random state seed (avoid name conflict with self.seed)
}
def __init__(self, config={}):
# First, parse configuration. Important note: LOTS of stuff happens in
# parse, and many attributes of the class get set through setattr. If you
# are trying to track down where an attribute gets initially set, and
# can't find it anywhere else, it's probably set via the config dict
# and this parse function.
self.parse(config)
gym.utils.EzPickle.__init__(self, config=config)
# Load up a simulation of the robot, just to figure out observation space
self.robot = Robot(self.robot_base)
self.action_space = gym.spaces.Box(-1, 1, (self.robot.nu,), dtype=np.float32)
self.build_observation_space()
self.build_placements_dict()
self.viewer = None
self.world = None
self.clear()
self.seed(self._seed)
self.done = True
def parse(self, config):
''' Parse a config dict - see self.DEFAULT for description '''
self.config = deepcopy(self.DEFAULT)
self.config.update(deepcopy(config))
for key, value in self.config.items():
assert key in self.DEFAULT, f'Bad key {key}'
setattr(self, key, value)
@property
def sim(self):
''' Helper to get the world's simulation instance '''
return self.world.sim
@property
def model(self):
''' Helper to get the world's model instance '''
return self.sim.model
@property
def data(self):
''' Helper to get the world's simulation data instance '''
return self.sim.data
@property
def robot_pos(self):
''' Helper to get current robot position '''
return self.data.get_body_xpos('robot').copy()
@property
def goal_pos(self):
''' Helper to get goal position from layout '''
if self.task in ['goal', 'push']:
return self.data.get_body_xpos('goal').copy()
elif self.task == 'button':
return self.data.get_body_xpos(f'button{self.goal_button}').copy()
elif self.task == 'circle':
return ORIGIN_COORDINATES
elif self.task == 'none':
return np.zeros(2) # Only used for screenshots
else:
raise ValueError(f'Invalid task {self.task}')
@property
def box_pos(self):
''' Helper to get the box position '''
return self.data.get_body_xpos('box').copy()
@property
def buttons_pos(self):
''' Helper to get the list of button positions '''
return [self.data.get_body_xpos(f'button{i}').copy() for i in range(self.buttons_num)]
@property
def vases_pos(self):
''' Helper to get the list of vase positions '''
return [self.data.get_body_xpos(f'vase{p}').copy() for p in range(self.vases_num)]
@property
def vases_velp(self):
''' Helper to get the list of vase positions '''
return [self.data.get_body_xvelp(f'vase{p}').copy() for p in range(self.vases_num)]
@property
def gremlins_obj_pos(self):
''' Helper to get the current gremlin position '''
return [self.data.get_body_xpos(f'gremlin{i}obj').copy() for i in range(self.gremlins_num)]
@property
def gremlins_obj_velp(self):
''' Helper to get the current gremlin position '''
return [self.data.get_body_xvelp(f'gremlin{i}obj').copy() for i in range(self.gremlins_num)]
@property
def pillars_pos(self):
''' Helper to get list of pillar positions '''
return [self.data.get_body_xpos(f'pillar{i}').copy() for i in range(self.pillars_num)]
@property
def hazards_pos(self):
''' Helper to get the hazards positions from layout '''
return [self.data.get_body_xpos(f'hazard{i}').copy() for i in range(self.hazards_num)]
@property
def sec_hazards_pos(self):
''' Helper to get the secondary hazards positions from layout '''
return [self.data.get_body_xpos(f'sec_hazard{i}').copy() for i in range(self.sec_hazards_num)]
@property
def walls_pos(self):
''' Helper to get the hazards positions from layout '''
return [self.data.get_body_xpos(f'wall{i}').copy() for i in range(self.walls_num)]
def build_observation_space(self):
''' Construct observtion space. Happens only once at during __init__ '''
obs_space_dict = OrderedDict() # See self.obs()
if self.observe_freejoint:
obs_space_dict['freejoint'] = gym.spaces.Box(-np.inf, np.inf, (7,), dtype=np.float32)
if self.observe_com:
obs_space_dict['com'] = gym.spaces.Box(-np.inf, np.inf, (3,), dtype=np.float32)
if self.observe_sensors:
for sensor in self.sensors_obs: # Explicitly listed sensors
dim = self.robot.sensor_dim[sensor]
obs_space_dict[sensor] = gym.spaces.Box(-np.inf, np.inf, (dim,), dtype=np.float32)
# Velocities don't have wraparound effects that rotational positions do
# Wraparounds are not kind to neural networks
# Whereas the angle 2*pi is very close to 0, this isn't true in the network
# In theory the network could learn this, but in practice we simplify it
# when the sensors_angle_components switch is enabled.
for sensor in self.robot.hinge_vel_names:
obs_space_dict[sensor] = gym.spaces.Box(-np.inf, np.inf, (1,), dtype=np.float32)
for sensor in self.robot.ballangvel_names:
obs_space_dict[sensor] = gym.spaces.Box(-np.inf, np.inf, (3,), dtype=np.float32)
# Angular positions have wraparound effects, so output something more friendly
if self.sensors_angle_components:
# Single joints are turned into sin(x), cos(x) pairs
# These should be easier to learn for neural networks,
# Since for angles, small perturbations in angle give small differences in sin/cos
for sensor in self.robot.hinge_pos_names:
obs_space_dict[sensor] = gym.spaces.Box(-np.inf, np.inf, (2,), dtype=np.float32)
# Quaternions are turned into 3x3 rotation matrices
# Quaternions have a wraparound issue in how they are normalized,
# where the convention is to change the sign so the first element to be positive.
# If the first element is close to 0, this can mean small differences in rotation
# lead to large differences in value as the latter elements change sign.
# This also means that the first element of the quaternion is not expectation zero.
# The SO(3) rotation representation would be a good replacement here,
# since it smoothly varies between values in all directions (the property we want),
# but right now we have very little code to support SO(3) roatations.
# Instead we use a 3x3 rotation matrix, which if normalized, smoothly varies as well.
for sensor in self.robot.ballquat_names:
obs_space_dict[sensor] = gym.spaces.Box(-np.inf, np.inf, (3, 3), dtype=np.float32)
else:
# Otherwise include the sensor without any processing
# TODO: comparative study of the performance with and without this feature.
for sensor in self.robot.hinge_pos_names:
obs_space_dict[sensor] = gym.spaces.Box(-np.inf, np.inf, (1,), dtype=np.float32)
for sensor in self.robot.ballquat_names:
obs_space_dict[sensor] = gym.spaces.Box(-np.inf, np.inf, (4,), dtype=np.float32)
if self.task == 'push':
if self.observe_box_comp:
obs_space_dict['box_compass'] = gym.spaces.Box(-1.0, 1.0, (self.compass_shape,), dtype=np.float32)
if self.observe_box_lidar:
obs_space_dict['box_lidar'] = gym.spaces.Box(0.0, 1.0, (self.lidar_num_bins,), dtype=np.float32)
if self.observe_goal_dist:
obs_space_dict['goal_dist'] = gym.spaces.Box(0.0, 1.0, (1,), dtype=np.float32)
if self.observe_goal_comp:
obs_space_dict['goal_compass'] = gym.spaces.Box(-1.0, 1.0, (self.compass_shape,), dtype=np.float32)
if self.observe_goal_lidar:
obs_space_dict['goal_lidar'] = gym.spaces.Box(0.0, 1.0, (self.lidar_num_bins,), dtype=np.float32)
if self.task == 'circle' and self.observe_circle:
obs_space_dict['circle_lidar'] = gym.spaces.Box(0.0, 1.0, (self.lidar_num_bins,), dtype=np.float32)
if self.observe_remaining:
obs_space_dict['remaining'] = gym.spaces.Box(0.0, 1.0, (1,), dtype=np.float32)
if self.walls_num and self.observe_walls:
obs_space_dict['walls_lidar'] = gym.spaces.Box(0.0, 1.0, (self.lidar_num_bins,), dtype=np.float32)
if self.observe_hazards:
obs_space_dict['hazards_lidar'] = gym.spaces.Box(0.0, 1.0, (self.lidar_num_bins,), dtype=np.float32)
if self.observe_sec_hazards:
obs_space_dict['sec_hazards_lidar'] = gym.spaces.Box(0.0, 1.0, (self.lidar_num_bins,), dtype=np.float32)
if self.observe_vases:
obs_space_dict['vases_lidar'] = gym.spaces.Box(0.0, 1.0, (self.lidar_num_bins,), dtype=np.float32)
if self.gremlins_num and self.observe_gremlins:
obs_space_dict['gremlins_lidar'] = gym.spaces.Box(0.0, 1.0, (self.lidar_num_bins,), dtype=np.float32)
if self.pillars_num and self.observe_pillars:
obs_space_dict['pillars_lidar'] = gym.spaces.Box(0.0, 1.0, (self.lidar_num_bins,), dtype=np.float32)
if self.buttons_num and self.observe_buttons:
obs_space_dict['buttons_lidar'] = gym.spaces.Box(0.0, 1.0, (self.lidar_num_bins,), dtype=np.float32)
if self.observe_qpos:
obs_space_dict['qpos'] = gym.spaces.Box(-np.inf, np.inf, (self.robot.nq,), dtype=np.float32)
if self.observe_qvel:
obs_space_dict['qvel'] = gym.spaces.Box(-np.inf, np.inf, (self.robot.nv,), dtype=np.float32)
if self.observe_ctrl:
obs_space_dict['ctrl'] = gym.spaces.Box(-np.inf, np.inf, (self.robot.nu,), dtype=np.float32)
if self.observe_vision:
width, height = self.vision_size
rows, cols = height, width
self.vision_size = (rows, cols)
obs_space_dict['vision'] = gym.spaces.Box(0, 1.0, (3,) + self.vision_size, dtype=np.float32)
if self.observe_groundtruth:
obs_space_dict['robot_gt_pos'] = gym.spaces.Box(-np.inf, np.inf, (3,), dtype=np.float32)
obs_space_dict['goal_gt_pos'] = gym.spaces.Box(-np.inf, np.inf, (3,), dtype=np.float32)
if self.hazards_num > 0:
obs_space_dict['hazards_gt'] = gym.spaces.Box(-np.inf, np.inf, (self.hazards_num * 3,), dtype=np.float32)
if self.sec_hazards_num > 0:
obs_space_dict['sec_hazards_gt'] = gym.spaces.Box(-np.inf, np.inf, (self.sec_hazards_num * 3,), dtype=np.float32)
if self.vases_num > 0:
obs_space_dict['vases_gt'] = gym.spaces.Box(-np.inf, np.inf, (self.vases_num * (3 + 9),), dtype=np.float32)
if self.pillars_num > 0:
obs_space_dict['pillars_gt'] = gym.spaces.Box(-np.inf, np.inf, (self.pillars_num * 3,), dtype=np.float32)
if self.gremlins_num > 0:
obs_space_dict['gremlins_gt'] = gym.spaces.Box(-np.inf, np.inf, (self.gremlins_num * (3 + 9),), dtype=np.float32)
if self.buttons_num > 0:
obs_space_dict['buttons_gt'] = gym.spaces.Box(-np.inf, np.inf, (self.buttons_num * 3,), dtype=np.float32)
if self.observe_groundtruth_vectors:
num_objects = 6
obs_space_dict['vision'] = gym.spaces.Box(-np.inf, np.inf, (2 + self.hazards_num + self.sec_hazards_num + self.vases_num +
self.pillars_num, num_objects + 3), dtype=np.float32)
# Flatten it ourselves
self.obs_space_dict = obs_space_dict
if self.observation_flatten:
self.obs_flat_size = sum([np.prod(i.shape) for i in self.obs_space_dict.values()])
self.observation_space = gym.spaces.Box(-np.inf, np.inf, (self.obs_flat_size,), dtype=np.float32)
else:
self.observation_space = gym.spaces.Dict(obs_space_dict)
def toggle_observation_space(self):
self.observation_flatten = not(self.observation_flatten)
self.build_observation_space()
def placements_from_location(self, location, keepout):
''' Helper to get a placements list from a given location and keepout '''
x, y = location
return [(x - keepout, y - keepout, x + keepout, y + keepout)]
def placements_dict_from_object(self, object_name):
''' Get the placements dict subset just for a given object name '''
placements_dict = {}
if hasattr(self, object_name + 's_num'): # Objects with multiplicity
plural_name = object_name + 's'
object_fmt = object_name + '{i}'
object_num = getattr(self, plural_name + '_num', None)
object_locations = getattr(self, plural_name + '_locations', [])
object_placements = getattr(self, plural_name + '_placements', None)
object_keepout = getattr(self, plural_name + '_keepout')
else: # Unique objects
object_fmt = object_name
object_num = 1
object_locations = getattr(self, object_name + '_locations', [])
object_placements = getattr(self, object_name + '_placements', None)
object_keepout = getattr(self, object_name + '_keepout')
for i in range(object_num):
if i < len(object_locations):
x, y = object_locations[i]
k = object_keepout + 1e-9 # Epsilon to account for numerical issues
placements = [(x - k, y - k, x + k, y + k)]
else:
placements = object_placements
placements_dict[object_fmt.format(i=i)] = (placements, object_keepout)
return placements_dict
def build_placements_dict(self):
''' Build a dict of placements. Happens once during __init__. '''
# Dictionary is map from object name -> tuple of (placements list, keepout)
placements = {}
placements.update(self.placements_dict_from_object('robot'))
placements.update(self.placements_dict_from_object('wall'))
if self.task in ['goal', 'push']:
placements.update(self.placements_dict_from_object('goal'))
if self.task == 'push':
placements.update(self.placements_dict_from_object('box'))
if self.task == 'button' or self.buttons_num: #self.constrain_buttons:
placements.update(self.placements_dict_from_object('button'))
if self.hazards_num: #self.constrain_hazards:
placements.update(self.placements_dict_from_object('hazard'))
if self.sec_hazards_num: #self.constrain_hazards:
placements.update(self.placements_dict_from_object('sec_hazard'))
if self.vases_num: #self.constrain_vases:
placements.update(self.placements_dict_from_object('vase'))
if self.pillars_num: #self.constrain_pillars:
placements.update(self.placements_dict_from_object('pillar'))
if self.gremlins_num: #self.constrain_gremlins:
placements.update(self.placements_dict_from_object('gremlin'))
self.placements = placements
def seed(self, seed=None):
''' Set internal random state seeds '''
self._seed = np.random.randint(2**32) if seed is None else seed
self.rs = np.random.RandomState(self._seed)
def build_layout(self):
''' Rejection sample a placement of objects to find a layout. '''
if not self.randomize_layout:
self.rs = np.random.RandomState(0)
for _ in range(10000):
if self.sample_layout():
break
else:
raise ResamplingError('Failed to sample layout of objects')
def sample_layout(self):
''' Sample a single layout, returning True if successful, else False. '''
def placement_is_valid(xy, layout):
for other_name, other_xy in layout.items():
other_keepout = self.placements[other_name][1]
dist = np.sqrt(np.sum(np.square(xy - other_xy)))
if dist < other_keepout + self.placements_margin + keepout:
return False
return True
layout = {}
for name, (placements, keepout) in self.placements.items():
conflicted = True
for _ in range(100):
xy = self.draw_placement(placements, keepout)
if placement_is_valid(xy, layout):
conflicted = False
break
if conflicted:
return False
layout[name] = xy
self.layout = layout
return True
def constrain_placement(self, placement, keepout):
''' Helper function to constrain a single placement by the keepout radius '''
xmin, ymin, xmax, ymax = placement
return (xmin + keepout, ymin + keepout, xmax - keepout, ymax - keepout)
def draw_placement(self, placements, keepout):
'''
Sample an (x,y) location, based on potential placement areas.
Summary of behavior:
'placements' is a list of (xmin, xmax, ymin, ymax) tuples that specify
rectangles in the XY-plane where an object could be placed.
'keepout' describes how much space an object is required to have
around it, where that keepout space overlaps with the placement rectangle.
To sample an (x,y) pair, first randomly select which placement rectangle
to sample from, where the probability of a rectangle is weighted by its
area. If the rectangles are disjoint, there's an equal chance the (x,y)
location will wind up anywhere in the placement space. If they overlap, then
overlap areas are double-counted and will have higher density. This allows
the user some flexibility in building placement distributions. Finally,
randomly draw a uniform point within the selected rectangle.
'''
if placements is None:
choice = self.constrain_placement(self.placements_extents, keepout)
else:
# Draw from placements according to placeable area
constrained = []
for placement in placements:
xmin, ymin, xmax, ymax = self.constrain_placement(placement, keepout)
if xmin > xmax or ymin > ymax:
continue
constrained.append((xmin, ymin, xmax, ymax))
assert len(constrained), 'Failed to find any placements with satisfy keepout'
if len(constrained) == 1:
choice = constrained[0]
else:
areas = [(x2 - x1)*(y2 - y1) for x1, y1, x2, y2 in constrained]
probs = np.array(areas) / np.sum(areas)
choice = constrained[self.rs.choice(len(constrained), p=probs)]
xmin, ymin, xmax, ymax = choice
return np.array([self.rs.uniform(xmin, xmax), self.rs.uniform(ymin, ymax)])
def random_rot(self):
''' Use internal random state to get a random rotation in radians '''
return self.rs.uniform(0, 2 * np.pi)
def build_world_config(self):
''' Create a world_config from our own config '''
# TODO: parse into only the pieces we want/need
world_config = {}
world_config['robot_base'] = self.robot_base
world_config['robot_xy'] = self.layout['robot']
if self.robot_rot is None:
world_config['robot_rot'] = self.random_rot()
else:
world_config['robot_rot'] = float(self.robot_rot)
if self.floor_display_mode:
floor_size = max(self.placements_extents)
world_config['floor_size'] = [floor_size + .1, floor_size + .1, 1]
#if not self.observe_vision:
# world_config['render_context'] = -1 # Hijack this so we don't create context
world_config['observe_vision'] = self.observe_vision
# Extra objects to add to the scene
world_config['objects'] = {}
if self.vases_num:
for i in range(self.vases_num):
name = f'vase{i}'
object = {'name': name,
'size': np.ones(3) * self.vases_size,
'type': 'box',
'density': self.vases_density,
'pos': np.r_[self.layout[name], self.vases_size - self.vases_sink],
'rot': self.random_rot(),
'group': GROUP_VASE,
'rgba': self.vases_color}
world_config['objects'][name] = object
if self.gremlins_num:
self._gremlins_rots = dict()
for i in range(self.gremlins_num):
name = f'gremlin{i}obj'
self._gremlins_rots[i] = self.random_rot()
object = {'name': name,
'size': np.ones(3) * self.gremlins_size,
'type': 'box',
'density': self.gremlins_density,
'pos': np.r_[self.layout[name.replace('obj', '')], self.gremlins_size],
'rot': self._gremlins_rots[i],
'group': GROUP_GREMLIN,
'rgba': self.gremlins_color}
world_config['objects'][name] = object
if self.task == 'push':
object = {'name': 'box',
'type': 'box',
'size': np.ones(3) * self.box_size,
'pos': np.r_[self.layout['box'], self.box_size],
'rot': self.random_rot(),
'density': self.box_density,
'group': GROUP_BOX,
'rgba': self.box_color}
world_config['objects']['box'] = object
# Extra geoms (immovable objects) to add to the scene
world_config['geoms'] = {}
if self.task in ['goal', 'push']:
geom = {'name': 'goal',
'size': [self.goal_size, self.goal_size / 2],
'pos': np.r_[self.layout['goal'], self.goal_size / 2 + 1e-2],
'rot': self.random_rot(),
'type': 'cylinder',
'contype': 0,
'conaffinity': 0,
'group': GROUP_GOAL,
'rgba': self.goal_color}
world_config['geoms']['goal'] = geom
if self.hazards_num:
for i in range(self.hazards_num):
name = f'hazard{i}'
geom = {'name': name,
'size': [self.hazards_size, 1e-2],#self.hazards_size / 2],
'pos': np.r_[self.layout[name], 2e-2],#self.hazards_size / 2 + 1e-2],
'rot': self.random_rot(),
'type': 'cylinder',
'contype': 0,
'conaffinity': 0,
'group': GROUP_HAZARD,
'rgba': self.hazards_color}
world_config['geoms'][name] = geom
if self.sec_hazards_num:
for i in range(self.sec_hazards_num):
name = f'sec_hazard{i}'
geom = {'name': name,
'size': [self.sec_hazards_size, 1e-2],#self.sec_hazards_size / 2],
'pos': np.r_[self.layout[name], 2e-2],#self.sec_hazards_size / 2 + 1e-2],
'rot': self.random_rot(),
'type': 'cylinder',
'contype': 0,
'conaffinity': 0,
'group': GROUP_HAZARD,
'rgba': self.sec_hazards_color}
world_config['geoms'][name] = geom
if self.pillars_num:
for i in range(self.pillars_num):
name = f'pillar{i}'
geom = {'name': name,
'size': [self.pillars_size, self.pillars_height],
'pos': np.r_[self.layout[name], self.pillars_height],
'rot': self.random_rot(),
'type': 'cylinder',
'group': GROUP_PILLAR,
'rgba': self.pillars_color}
world_config['geoms'][name] = geom
if self.walls_num:
for i in range(self.walls_num):
name = f'wall{i}'
geom = {'name': name,
'size': np.ones(3) * self.walls_size,
'pos': np.r_[self.layout[name], self.walls_size],
'rot': 0,
'type': 'box',
'group': GROUP_WALL,
'rgba': self.walls_color}
world_config['geoms'][name] = geom
if self.buttons_num:
for i in range(self.buttons_num):
name = f'button{i}'
geom = {'name': name,
'size': np.ones(3) * self.buttons_size,
'pos': np.r_[self.layout[name], self.buttons_size],
'rot': self.random_rot(),
'type': 'sphere',
'group': GROUP_BUTTON,
'rgba': self.buttons_color}
world_config['geoms'][name] = geom
if self.task == 'circle':
geom = {'name': 'circle',
'size': np.array([self.circle_radius, 1e-2]),
'pos': np.array([0, 0, 2e-2]),
'rot': 0,
'type': 'cylinder',
'contype': 0,
'conaffinity': 0,
'group': GROUP_CIRCLE,
'rgba': COLOR_CIRCLE}
world_config['geoms']['circle'] = geom
# Extra mocap bodies used for control (equality to object of same name)
world_config['mocaps'] = {}
if self.gremlins_num:
for i in range(self.gremlins_num):
name = f'gremlin{i}mocap'
mocap = {'name': name,
'size': np.ones(3) * self.gremlins_size,
'type': 'box',
'pos': np.r_[self.layout[name.replace('mocap', '')], self.gremlins_size],
'rot': self._gremlins_rots[i],
'group': GROUP_GREMLIN,
'rgba': self.gremlins_color}
#'rgba': np.array([1, 1, 1, 0]) * COLOR_GREMLIN}
world_config['mocaps'][name] = mocap
return world_config
def clear(self):
''' Reset internal state for building '''
self.layout = None
def build_goal(self):
''' Build a new goal position, maybe with resampling due to hazards '''
if self.task == 'goal':
self.build_goal_position()
self.last_dist_goal = self.dist_goal()
elif self.task == 'push':
self.build_goal_position()
self.last_dist_goal = self.dist_goal()
self.last_dist_box = self.dist_box()
self.last_box_goal = self.dist_box_goal()
elif self.task == 'button':
assert self.buttons_num > 0, 'Must have at least one button'
self.build_goal_button()
self.last_dist_goal = self.dist_goal()
elif self.task in ['x', 'z']:
self.last_robot_com = self.world.robot_com()
elif self.task in ['circle', 'none']:
pass
else:
raise ValueError(f'Invalid task {self.task}')
def sample_goal_position(self):
''' Sample a new goal position and return True, else False if sample rejected '''
placements, keepout = self.placements['goal']
goal_xy = self.draw_placement(placements, keepout)
for other_name, other_xy in self.layout.items():
other_keepout = self.placements[other_name][1]
dist = np.sqrt(np.sum(np.square(goal_xy - other_xy)))
if dist < other_keepout + self.placements_margin + keepout:
return False
self.layout['goal'] = goal_xy
return True
def build_goal_position(self):
''' Build a new goal position, maybe with resampling due to hazards '''
# Resample until goal is compatible with layout
if 'goal' in self.layout:
del self.layout['goal']
for _ in range(10000): # Retries
if self.sample_goal_position():
break
else:
raise ResamplingError('Failed to generate goal')
# Move goal geom to new layout position
self.world_config_dict['geoms']['goal']['pos'][:2] = self.layout['goal']
#self.world.rebuild(deepcopy(self.world_config_dict))
#self.update_viewer_sim = True
goal_body_id = self.sim.model.body_name2id('goal')
self.sim.model.body_pos[goal_body_id][:2] = self.layout['goal']
self.sim.forward()
def build_goal_button(self):
''' Pick a new goal button, maybe with resampling due to hazards '''
self.goal_button = self.rs.choice(self.buttons_num)
def build(self):
''' Build a new physics simulation environment '''
# Sample object positions
self.build_layout()
# Build the underlying physics world
self.world_config_dict = self.build_world_config()
if self.world is None:
self.world = World(self.world_config_dict)
self.world.reset()
self.world.build()
else:
self.world.reset(build=False)
self.world.rebuild(self.world_config_dict, state=False)
# Redo a small amount of work, and setup initial goal state
self.build_goal()
# Save last action
self.last_action = np.zeros(self.action_space.shape)
# Save last subtree center of mass
self.last_subtreecom = self.world.get_sensor('subtreecom')
def reset(self):
''' Reset the physics simulation and return observation '''
# self._seed += 1 # Increment seed
# self.rs = np.random.RandomState(self._seed)
self.done = False
self.steps = 0 # Count of steps taken in this episode
# Set the button timer to zero (so button is immediately visible)
self.buttons_timer = 0
self.clear()
self.build()
# Save the layout at reset
self.reset_layout = deepcopy(self.layout)
cost = self.cost()
assert cost['cost'] == 0, f'World has starting cost! {cost}'
# Reset stateful parts of the environment
self.first_reset = False # Built our first world successfully
# Return an observation
return self.obs()
def dist_goal(self):
''' Return the distance from the robot to the goal XY position '''
return self.dist_xy(self.goal_pos)
def dist_box(self):
''' Return the distance from the robot to the box (in XY plane only) '''
assert self.task == 'push', f'invalid task {self.task}'
return np.sqrt(np.sum(np.square(self.box_pos - self.world.robot_pos())))
def dist_box_goal(self):
''' Return the distance from the box to the goal XY position '''
assert self.task == 'push', f'invalid task {self.task}'
return np.sqrt(np.sum(np.square(self.box_pos - self.goal_pos)))
def dist_xy(self, pos):
''' Return the distance from the robot to an XY position '''
pos = np.asarray(pos)
if pos.shape == (3,):
pos = pos[:2]
robot_pos = self.world.robot_pos()
return np.sqrt(np.sum(np.square(pos - robot_pos[:2])))
def world_xy(self, pos):
''' Return the world XY vector to a position from the robot '''
assert pos.shape == (2,)
return pos - self.world.robot_pos()[:2]
def ego_xy(self, pos):
''' Return the egocentric XY vector to a position from the robot '''
assert pos.shape == (2,), f'Bad pos {pos}'
robot_3vec = self.world.robot_pos()
robot_mat = self.world.robot_mat()
pos_3vec = np.concatenate([pos, [0]]) # Add a zero z-coordinate
world_3vec = pos_3vec - robot_3vec
return np.matmul(world_3vec, robot_mat)[:2] # only take XY coordinates