-
Notifications
You must be signed in to change notification settings - Fork 44
/
Copy pathlegged_robot.py
executable file
·1590 lines (1361 loc) · 84.3 KB
/
legged_robot.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
# License: see [LICENSE, LICENSES/legged_gym/LICENSE]
import os
from typing import Dict
from isaacgym import gymtorch, gymapi, gymutil
from isaacgym.torch_utils import *
assert gymtorch
import torch
from mini_gym import MINI_GYM_ROOT_DIR
from mini_gym.envs.base.base_task import BaseTask
from mini_gym.utils.math_utils import quat_apply_yaw, wrap_to_pi, get_scale_shift
from mini_gym.utils.terrain import Terrain
from .legged_robot_config import Cfg
class LeggedRobot(BaseTask):
def __init__(self, cfg: Cfg, sim_params, physics_engine, sim_device, headless, eval_cfg=None,
initial_dynamics_dict=None):
""" Parses the provided config file,
calls create_sim() (which creates, simulation, terrain and environments),
initilizes pytorch buffers used during training
Args:
cfg (Dict): Environment config file
sim_params (gymapi.SimParams): simulation parameters
physics_engine (gymapi.SimType): gymapi.SIM_PHYSX (must be PhysX)
device_type (string): 'cuda' or 'cpu'
device_id (int): 0, 1, ...
headless (bool): Run without rendering if True
"""
self.cfg = cfg
self.eval_cfg = eval_cfg
self.sim_params = sim_params
self.height_samples = None
self.debug_viz = False
self.init_done = False
self.initial_dynamics_dict = initial_dynamics_dict
if eval_cfg is not None: self._parse_cfg(eval_cfg)
self._parse_cfg(self.cfg)
super().__init__(self.cfg, sim_params, physics_engine, sim_device, headless, self.eval_cfg)
self._init_command_distribution(torch.arange(self.num_envs, device=self.device))
# self.rand_buffers_eval = self._init_custom_buffers__(self.num_eval_envs)
if not self.headless:
self.set_camera(self.cfg.viewer.pos, self.cfg.viewer.lookat)
self._init_buffers()
self._prepare_reward_function()
self.init_done = True
self.record_now = False
self.record_eval_now = False
self.collecting_evaluation = False
self.num_still_evaluating = 0
def load_cfg(self, cfg: Cfg, headless, eval_cfg=None, deploy=False, prone=False, num_envs=None):
self.cfg = cfg
self.eval_cfg = eval_cfg
if num_envs is not None:
self.cfg.env.num_envs = num_envs
if prone:
self.cfg.init_state.rot = [0.0, 1.0, 0.0, 0.0]
self.cfg.init_state.pos = [0.0, 0.0, 0.15]
self.cfg.asset.fix_base_link = True
if deploy: # turn off randomization, fix terrain
self.cfg.env.num_envs = 1
terrain_level = 1
self.cfg.terrain.num_rows = 3
self.cfg.terrain.num_cols = 3
self.cfg.terrain.curriculum = False
self.cfg.noise.add_noise = False
self.cfg.domain_rand.push_robots = False
self.cfg.domain_rand.randomize_friction = False
self.cfg.env.episode_length_s = 100
self.cfg.commands.lin_vel_x = [0, 0]
self.cfg.commands.lin_vel_y = [0, 0]
self.cfg.commands.ang_vel_yaw = [0, 0]
self.cfg.commands.heading = [0, 0]
self.cfg.commands.heading_command = False
if self.headless == False:
self.gym.destroy_viewer(self.viewer)
self.gym.destroy_sim(self.sim)
self.headless = headless
if eval_cfg is not None: self._parse_cfg(eval_cfg)
self._parse_cfg(cfg)
super().__init__(self.cfg, self.sim_params, self.physics_engine, self.sim_device, self.headless, self.eval_cfg)
if not self.headless:
self.set_camera(self.cfg.viewer.pos, self.cfg.viewer.lookat)
self._init_buffers()
self._prepare_reward_function()
self.init_done = True
self.record_now = False
def step(self, actions):
""" Apply actions, simulate, call self.post_physics_step()
Args:
actions (torch.Tensor): Tensor of shape (num_envs, num_actions_per_env)
"""
clip_actions = self.cfg.normalization.clip_actions
self.actions = torch.clip(actions, -clip_actions, clip_actions).to(self.device)
# step physics and render each frame
self.render_gui()
for _ in range(self.cfg.control.decimation):
self.torques = self._compute_torques(self.actions).view(self.torques.shape)
self.gym.set_dof_actuation_force_tensor(self.sim, gymtorch.unwrap_tensor(self.torques))
self.gym.simulate(self.sim)
# if self.device == 'cpu':
self.gym.fetch_results(self.sim, True)
self.gym.refresh_dof_state_tensor(self.sim)
self.post_physics_step()
# return clipped obs, clipped states (None), rewards, dones and infos
clip_obs = self.cfg.normalization.clip_observations
self.obs_buf = torch.clip(self.obs_buf, -clip_obs, clip_obs)
if self.privileged_obs_buf is not None:
self.privileged_obs_buf = torch.clip(self.privileged_obs_buf, -clip_obs, clip_obs)
return self.obs_buf, self.privileged_obs_buf, self.rew_buf, self.reset_buf, self.extras
def post_physics_step(self):
""" check terminations, compute observations and rewards
calls self._post_physics_step_callback() for common computations
calls self._draw_debug_vis() if needed
"""
self.gym.refresh_actor_root_state_tensor(self.sim)
self.gym.refresh_net_contact_force_tensor(self.sim)
self.gym.refresh_rigid_body_state_tensor(self.sim)
if self.record_now:
self.gym.step_graphics(self.sim)
self.gym.render_all_camera_sensors(self.sim)
self.episode_length_buf += 1
self.common_step_counter += 1
# prepare quantities
self.base_quat[:] = self.root_states[:, 3:7]
self.base_lin_vel[:] = quat_rotate_inverse(self.base_quat, self.root_states[:, 7:10])
self.base_ang_vel[:] = quat_rotate_inverse(self.base_quat, self.root_states[:, 10:13])
self.projected_gravity[:] = quat_rotate_inverse(self.base_quat, self.gravity_vec)
self.foot_velocities = self.rigid_body_state.view(self.num_envs, self.num_bodies, 13
)[:, self.feet_indices, 7:10]
self._post_physics_step_callback()
# compute observations, rewards, resets, ...
self.check_termination()
self.compute_reward()
env_ids = self.reset_buf.nonzero(as_tuple=False).flatten()
self.reset_idx(env_ids)
self.compute_observations()
self.last_actions[:] = self.actions[:]
self.last_dof_vel[:] = self.dof_vel[:]
self.last_root_vel[:] = self.root_states[:, 7:13]
if self.viewer and self.enable_viewer_sync and self.debug_viz:
self._draw_debug_vis()
self._render_headless()
def check_termination(self):
""" Check if environments need to be reset
"""
self.reset_buf = torch.any(torch.norm(self.contact_forces[:, self.termination_contact_indices, :], dim=-1) > 1.,
dim=1)
self.time_out_buf = self.episode_length_buf > self.cfg.env.max_episode_length # no terminal reward for time-outs
self.reset_buf |= self.time_out_buf
if self.cfg.rewards.use_terminal_body_height:
self.body_height_buf = torch.mean(self.root_states[:, 2].unsqueeze(1) - self.measured_heights, dim=1) \
< self.cfg.rewards.terminal_body_height
self.reset_buf = torch.logical_or(self.body_height_buf, self.reset_buf)
def reset_evaluation_envs(self):
if self.eval_cfg is None: return
env_ids_eval = torch.arange(self.num_train_envs, self.num_envs, device=self.device)
# return info about the previous evaluation batch
for key in self.episode_sums_eval.keys():
# maybe some episodes didn't terminate -- that's ok, record their final reward.
unset_eval_envs = env_ids_eval[self.episode_sums_eval[key][env_ids_eval] == -1]
self.episode_sums_eval[key][unset_eval_envs] = self.episode_sums[key][unset_eval_envs]
# log the mean reward across evaluation envs for every metric
ep_sums_key = self.episode_sums_eval[key]
self.extras["eval/episode"]['rew_' + key] = torch.mean(ep_sums_key[ep_sums_key != -1])
# update command curriculum
self.update_command_curriculum(env_ids_eval, self.eval_cfg, self.episode_sums_eval)
print("RESET AND LOGGED ALL EVAL ENVIRONMENTS")
# do the reset
self.reset_idx(env_ids_eval)
for key in self.episode_sums_eval.keys():
self.episode_sums_eval[key] = -1 * torch.ones(self.num_envs, dtype=torch.float, device=self.device,
requires_grad=False)
def reset_idx(self, env_ids):
""" Reset some environments.
Calls self._reset_dofs(env_ids), self._reset_root_states(env_ids), and self._resample_commands(env_ids)
[Optional] calls self._update_terrain_curriculum(env_ids), self.update_command_curriculum(env_ids) and
Logs episode info
Resets some buffers
Args:
env_ids (list[int]): List of environment ids which must be reset
"""
if len(env_ids) == 0:
return
# update curriculum
self._call_train_eval(self._update_terrain_curriculum, env_ids)
self._call_train_eval(self.update_command_curriculum, env_ids)
# reset robot states
self._resample_commands(env_ids)
self._call_train_eval(self._randomize_dof_props, env_ids)
# self._call_train_eval(self._randomize_rigid_body_props, env_ids)
self._call_train_eval(self._reset_dofs, env_ids)
self._call_train_eval(self._reset_root_states, env_ids)
# reset buffersew
self.last_actions[env_ids] = 0.
self.last_dof_vel[env_ids] = 0.
self.feet_air_time[env_ids] = 0.
self.episode_length_buf[env_ids] = 0
self.reset_buf[env_ids] = 1
# fill extras
train_env_ids = env_ids[env_ids < self.num_train_envs]
if len(train_env_ids) > 0:
self.extras["train/episode"] = {}
for key in self.episode_sums.keys():
self.extras["train/episode"]['rew_' + key] = torch.mean(
self.episode_sums[key][train_env_ids]) # / self.cfg.env.episode_length_s
self.episode_sums[key][train_env_ids] = 0.
eval_env_ids = env_ids[env_ids >= self.num_train_envs]
if len(eval_env_ids) > 0:
self.extras["eval/episode"] = {}
for key in self.episode_sums.keys():
# save the evaluation rollout result if not already saved
unset_eval_envs = eval_env_ids[self.episode_sums_eval[key][eval_env_ids] == -1]
self.episode_sums_eval[key][unset_eval_envs] = self.episode_sums[key][unset_eval_envs]
self.episode_sums[key][eval_env_ids] = 0.
# log additional curriculum info
if self.cfg.terrain.curriculum:
self.extras["train/episode"]["terrain_level"] = torch.mean(
self.terrain_levels[:self.num_train_envs].float())
if self.cfg.commands.command_curriculum:
self.extras["env_bins"] = torch.Tensor(self.env_command_bins)[:self.num_train_envs]
self.extras["train/episode"]["command_area"] = np.sum(self.curriculum.weights) / self.curriculum.weights.shape[0]
if self.cfg.commands.yaw_command_curriculum:
self.extras["train/episode"]["max_command_yaw"] = self.cfg.command_ranges["ang_vel_yaw"][1]
if self.eval_cfg is not None:
self.extras["eval/episode"]["max_command_yaw"] = self.eval_cfg.command_ranges["ang_vel_yaw"][1]
# send timeout info to the algorithm
if self.cfg.env.send_timeouts:
self.extras["time_outs"] = self.time_out_buf[:self.num_train_envs]
def set_idx_pose(self, env_ids, dof_pos, base_state):
if len(env_ids) == 0:
return
env_ids_int32 = env_ids.to(dtype=torch.int32).to(self.device)
# joints
if dof_pos is not None:
self.dof_pos[env_ids] = dof_pos
self.dof_vel[env_ids] = 0.
self.gym.set_dof_state_tensor_indexed(self.sim,
gymtorch.unwrap_tensor(self.dof_state),
gymtorch.unwrap_tensor(env_ids_int32), len(env_ids_int32))
# base position
self.root_states[env_ids] = base_state.to(self.device)
self.gym.set_actor_root_state_tensor_indexed(self.sim,
gymtorch.unwrap_tensor(self.root_states),
gymtorch.unwrap_tensor(env_ids_int32), len(env_ids_int32))
def compute_reward(self):
""" Compute rewards
Calls each reward function which had a non-zero scale (processed in self._prepare_reward_function())
adds each terms to the episode sums and to the total reward
"""
self.rew_buf[:] = 0.
for i in range(len(self.reward_functions)):
name = self.reward_names[i]
rew = self.reward_functions[i]() * self.reward_scales[name]
self.rew_buf += rew
self.episode_sums[name] += rew
self.command_sums[name] += rew
if self.cfg.rewards.only_positive_rewards:
self.rew_buf[:] = torch.clip(self.rew_buf[:], min=0.)
self.episode_sums["total"] += self.rew_buf
# add termination reward after clipping
if "termination" in self.reward_scales:
rew = self._reward_termination() * self.reward_scales["termination"]
self.rew_buf += rew
self.episode_sums["termination"] += rew
self.command_sums["termination"] += rew
self.command_sums["lin_vel_raw"] += self.base_lin_vel[:, 0]
self.command_sums["ang_vel_raw"] += self.base_ang_vel[:, 2]
self.command_sums["lin_vel_residual"] += (self.base_lin_vel[:, 0] - self.commands[:, 0]) ** 2
self.command_sums["ang_vel_residual"] += (self.base_ang_vel[:, 2] - self.commands[:, 2]) ** 2
self.command_sums["ep_timesteps"] += 1
def compute_observations(self):
""" Computes observations
"""
self.obs_buf = torch.cat((self.projected_gravity,
(self.dof_pos - self.default_dof_pos) * self.obs_scales.dof_pos,
self.dof_vel * self.obs_scales.dof_vel,
self.actions
), dim=-1)
if self.cfg.env.observe_command:
self.obs_buf = torch.cat((self.projected_gravity,
self.commands[:, :3] * self.commands_scale,
(self.dof_pos - self.default_dof_pos) * self.obs_scales.dof_pos,
self.dof_vel * self.obs_scales.dof_vel,
self.actions
), dim=-1)
if self.cfg.env.observe_vel:
if self.cfg.commands.global_reference:
self.obs_buf = torch.cat((self.root_states[:, 7:10] * self.obs_scales.lin_vel,
self.base_ang_vel * self.obs_scales.ang_vel,
self.obs_buf), dim=-1)
else:
self.obs_buf = torch.cat((self.base_lin_vel * self.obs_scales.lin_vel,
self.base_ang_vel * self.obs_scales.ang_vel,
self.obs_buf), dim=-1)
if self.cfg.env.observe_only_ang_vel:
self.obs_buf = torch.cat((self.base_ang_vel * self.obs_scales.ang_vel,
self.obs_buf), dim=-1)
if self.cfg.env.observe_only_lin_vel:
self.obs_buf = torch.cat((self.base_lin_vel * self.obs_scales.lin_vel,
self.obs_buf), dim=-1)
if self.cfg.env.observe_yaw:
forward = quat_apply(self.base_quat, self.forward_vec)
heading = torch.atan2(forward[:, 1], forward[:, 0])
heading_error = torch.clip(0.5 * wrap_to_pi(heading), -1., 1.).unsqueeze(1)
self.obs_buf = torch.cat((self.obs_buf,
heading_error), dim=-1)
# add perceptive inputs if not blind
if self.cfg.terrain.measure_heights:
heights = torch.clip(self.root_states[:, 2].unsqueeze(1) - 0.5 - self.measured_heights, -1,
1.) * self.obs_scales.height_measurements
self.obs_buf = torch.cat((self.obs_buf, heights), dim=-1)
# add noise if needed
if self.add_noise:
self.obs_buf += (2 * torch.rand_like(self.obs_buf) - 1) * self.noise_scale_vec
# build privileged obs
# in RLvRL: Friction, Restitution, Payload, CoM displacement, Motor Strength
# scale all the randomization from -1 to 1
friction_coeffs_scale, friction_coeffs_shift = get_scale_shift(self.cfg.normalization.friction_range)
restitutions_scale, restitutions_shift = get_scale_shift(self.cfg.normalization.restitution_range)
payloads_scale, payloads_shift = get_scale_shift(self.cfg.normalization.added_mass_range)
com_displacements_scale, com_displacements_shift = get_scale_shift(
self.cfg.normalization.com_displacement_range)
motor_strengths_scale, motor_strengths_shift = get_scale_shift(self.cfg.normalization.motor_strength_range)
if not self.cfg.env.priv_observe_friction: friction_coeffs_scale = 0
if not self.cfg.env.priv_observe_restitution: restitutions_scale = 0
if not self.cfg.env.priv_observe_base_mass: payloads_scale = 0
if not self.cfg.env.priv_observe_com_displacement: com_displacements_scale = 0
if not self.cfg.env.priv_observe_motor_strength: motor_strengths_scale = 0
self.privileged_obs_buf = torch.cat(
((self.friction_coeffs.unsqueeze(1) - friction_coeffs_shift) * friction_coeffs_scale, # friction coeff
(self.restitutions.unsqueeze(1) - restitutions_shift) * restitutions_scale, # friction coeff
(self.payloads.unsqueeze(1) - payloads_shift) * payloads_scale, # payload
(self.com_displacements - com_displacements_shift) * com_displacements_scale, # payload
(self.motor_strengths - motor_strengths_shift) * motor_strengths_scale, # motor strength
), dim=1)
def create_sim(self):
""" Creates simulation, terrain and evironments
"""
self.up_axis_idx = 2 # 2 for z, 1 for y -> adapt gravity accordingly
self.sim = self.gym.create_sim(self.sim_device_id, self.graphics_device_id, self.physics_engine,
self.sim_params)
mesh_type = self.cfg.terrain.mesh_type
if mesh_type in ['heightfield', 'trimesh']:
if self.eval_cfg is not None:
self.terrain = Terrain(self.cfg.terrain, self.num_train_envs, self.eval_cfg.terrain, self.num_eval_envs)
else:
self.terrain = Terrain(self.cfg.terrain, self.num_train_envs)
if mesh_type == 'plane':
self._create_ground_plane()
elif mesh_type == 'heightfield':
self._create_heightfield()
elif mesh_type == 'trimesh':
self._create_trimesh()
elif mesh_type is not None:
raise ValueError("Terrain mesh type not recognised. Allowed types are [None, plane, heightfield, trimesh]")
self._create_envs()
def set_camera(self, position, lookat):
""" Set camera position and direction
"""
cam_pos = gymapi.Vec3(position[0], position[1], position[2])
cam_target = gymapi.Vec3(lookat[0], lookat[1], lookat[2])
self.gym.viewer_camera_look_at(self.viewer, None, cam_pos, cam_target) \
def set_main_agent_pose(self, loc, quat):
self.root_states[0, 0:3] = torch.Tensor(loc)
self.root_states[0, 3:7] = torch.Tensor(quat)
self.gym.set_actor_root_state_tensor(self.sim, gymtorch.unwrap_tensor(self.root_states))
# ------------- Callbacks --------------
def _call_train_eval(self, func, env_ids):
env_ids_train = env_ids[env_ids < self.num_train_envs]
env_ids_eval = env_ids[env_ids >= self.num_train_envs]
ret, ret_eval = None, None
if len(env_ids_train) > 0:
ret = func(env_ids_train, self.cfg)
if len(env_ids_eval) > 0:
ret_eval = func(env_ids_eval, self.eval_cfg)
if ret is not None and ret_eval is not None: ret = torch.cat((ret, ret_eval), axis=-1)
return ret
def _process_rigid_shape_props(self, props, env_id):
""" Callback allowing to store/change/randomize the rigid shape properties of each environment.
Called During environment creation.
Base behavior: randomizes the friction of each environment
Args:
props (List[gymapi.RigidShapeProperties]): Properties of each shape of the asset
env_id (int): Environment id
Returns:
[List[gymapi.RigidShapeProperties]]: Modified rigid shape properties
"""
for s in range(len(props)):
props[s].friction = self.friction_coeffs[env_id]
props[s].restitution = self.restitutions[env_id]
return props
def _process_dof_props(self, props, env_id):
""" Callback allowing to store/change/randomize the DOF properties of each environment.
Called During environment creation.
Base behavior: stores position, velocity and torques limits defined in the URDF
Args:
props (numpy.array): Properties of each DOF of the asset
env_id (int): Environment id
Returns:
[numpy.array]: Modified DOF properties
"""
if env_id == 0:
self.dof_pos_limits = torch.zeros(self.num_dof, 2, dtype=torch.float, device=self.device,
requires_grad=False)
self.dof_vel_limits = torch.zeros(self.num_dof, dtype=torch.float, device=self.device, requires_grad=False)
self.torque_limits = torch.zeros(self.num_dof, dtype=torch.float, device=self.device, requires_grad=False)
for i in range(len(props)):
self.dof_pos_limits[i, 0] = props["lower"][i].item()
self.dof_pos_limits[i, 1] = props["upper"][i].item()
self.dof_vel_limits[i] = props["velocity"][i].item()
self.torque_limits[i] = props["effort"][i].item()
# soft limits
m = (self.dof_pos_limits[i, 0] + self.dof_pos_limits[i, 1]) / 2
r = self.dof_pos_limits[i, 1] - self.dof_pos_limits[i, 0]
self.dof_pos_limits[i, 0] = m - 0.5 * r * self.cfg.rewards.soft_dof_pos_limit
self.dof_pos_limits[i, 1] = m + 0.5 * r * self.cfg.rewards.soft_dof_pos_limit
return props
def _randomize_rigid_body_props(self, env_ids, cfg):
if cfg.domain_rand.randomize_base_mass:
min_payload, max_payload = cfg.domain_rand.added_mass_range
# self.payloads[env_ids] = -1.0
self.payloads[env_ids] = torch.rand(len(env_ids), dtype=torch.float, device=self.device,
requires_grad=False) * (max_payload - min_payload) + min_payload
if cfg.domain_rand.randomize_com_displacement:
min_com_displacement, max_com_displacement = cfg.domain_rand.com_displacement_range
self.com_displacements[env_ids, :] = torch.rand(len(env_ids), 3, dtype=torch.float, device=self.device,
requires_grad=False) * (
max_com_displacement - min_com_displacement) + min_com_displacement
if cfg.domain_rand.randomize_friction:
min_friction, max_friction = cfg.domain_rand.friction_range
self.friction_coeffs[env_ids] = torch.rand(len(env_ids), dtype=torch.float, device=self.device,
requires_grad=False) * (
max_friction - min_friction) + min_friction
if cfg.domain_rand.randomize_restitution:
min_restitution, max_restitution = cfg.domain_rand.restitution_range
self.restitutions[env_ids] = torch.rand(len(env_ids), dtype=torch.float, device=self.device,
requires_grad=False) * (
max_restitution - min_restitution) + min_restitution
def _randomize_dof_props(self, env_ids, cfg):
if cfg.domain_rand.randomize_motor_strength:
min_strength, max_strength = cfg.domain_rand.motor_strength_range
self.motor_strengths[env_ids, :] = torch.rand(len(env_ids), dtype=torch.float, device=self.device,
requires_grad=False).unsqueeze(1) * (
max_strength - min_strength) + min_strength
if cfg.domain_rand.randomize_Kp_factor:
min_Kp_factor, max_Kp_factor = cfg.domain_rand.Kp_factor_range
self.Kp_factors[env_ids, :] = torch.rand(len(env_ids), dtype=torch.float, device=self.device,
requires_grad=False).unsqueeze(1) * (
max_Kp_factor - min_Kp_factor) + min_Kp_factor
if cfg.domain_rand.randomize_Kd_factor:
min_Kd_factor, max_Kd_factor = cfg.domain_rand.Kd_factor_range
self.Kd_factors[env_ids, :] = torch.rand(len(env_ids), dtype=torch.float, device=self.device,
requires_grad=False).unsqueeze(1) * (
max_Kd_factor - min_Kd_factor) + min_Kd_factor
def _process_rigid_body_props(self, props, env_id):
self.default_body_mass = props[0].mass
props[0].mass = self.default_body_mass + self.payloads[env_id]
props[0].com = gymapi.Vec3(self.com_displacements[env_id, 0], self.com_displacements[env_id, 1],
self.com_displacements[env_id, 2])
return props
def _post_physics_step_callback(self):
""" Callback called before computing terminations, rewards, and observations
Default behaviour: Compute ang vel command based on target and heading, compute measured terrain heights and randomly push robots
"""
# teleport robots to prevent falling off the edge
self._call_train_eval(self._teleport_robots, torch.arange(self.num_envs, device=self.device))
# resample commands
sample_interval = int(self.cfg.commands.resampling_time / self.dt)
env_ids = (self.episode_length_buf % sample_interval == 0).nonzero(as_tuple=False).flatten()
self._resample_commands(env_ids)
# measure terrain heights
if self.cfg.terrain.measure_heights:
self.measured_heights = self._get_heights(torch.arange(self.num_envs, device=self.device), self.cfg)
# push robots
self._call_train_eval(self._push_robots, torch.arange(self.num_envs, device=self.device))
# randomize dof properties
env_ids = (self.episode_length_buf % int(self.cfg.domain_rand.rand_interval) == 0).nonzero(
as_tuple=False).flatten()
self._call_train_eval(self._randomize_dof_props, env_ids)
def _resample_commands(self, env_ids):
if len(env_ids) == 0: return
train_env_ids = env_ids[env_ids < self.num_train_envs]
eval_env_ids = env_ids[env_ids >= self.num_train_envs]
timesteps = int(self.cfg.commands.resampling_time / self.dt)
ep_len = min(self.cfg.env.max_episode_length, timesteps)
lin_vel_rewards = self.command_sums["tracking_lin_vel"][env_ids] / ep_len
ang_vel_rewards = self.command_sums["tracking_ang_vel"][env_ids] / ep_len
lin_vel_threshold = self.cfg.commands.forward_curriculum_threshold * self.reward_scales["tracking_lin_vel"]
ang_vel_threshold = self.cfg.commands.yaw_curriculum_threshold * self.reward_scales["tracking_ang_vel"]
old_bins = self.env_command_bins[env_ids.cpu().numpy()]
# update step just uses train env performance (for now)
self.curriculum.update(old_bins[env_ids.cpu().numpy() < self.num_train_envs],
lin_vel_rewards[env_ids < self.num_train_envs].cpu().numpy(),
ang_vel_rewards[env_ids < self.num_train_envs].cpu().numpy(), lin_vel_threshold,
ang_vel_threshold, local_range=0.5, )
new_commands, new_bin_inds = self.curriculum.sample(batch_size=len(env_ids))
self.env_command_bins[env_ids.cpu().numpy()] = new_bin_inds
self.commands[env_ids, :3] = torch.Tensor(new_commands).to(self.device)
self.commands[env_ids, :2] *= (torch.norm(self.commands[env_ids, :2], dim=1) > 0.2).unsqueeze(1)
# reset command sums
for key in self.command_sums.keys():
self.command_sums[key][env_ids] = 0.
def _resample_commands_uniform(self, env_ids, cfg):
self.commands[env_ids, 0] = torch_rand_float(cfg.command_ranges["lin_vel_x"][0],
cfg.command_ranges["lin_vel_x"][1], (len(env_ids), 1),
device=self.device).squeeze(1)
self.commands[env_ids, 1] = torch_rand_float(cfg.command_ranges["lin_vel_y"][0],
cfg.command_ranges["lin_vel_y"][1], (len(env_ids), 1),
device=self.device).squeeze(1)
if cfg.commands.heading_command:
self.commands[env_ids, 3] = torch_rand_float(cfg.command_ranges["heading"][0],
cfg.command_ranges["heading"][1], (len(env_ids), 1),
device=self.device).squeeze(1)
else:
self.commands[env_ids, 2] = torch_rand_float(cfg.command_ranges["ang_vel_yaw"][0],
cfg.command_ranges["ang_vel_yaw"][1], (len(env_ids), 1),
device=self.device).squeeze(1)
# set small commands to zero
self.commands[env_ids, :2] *= (torch.norm(self.commands[env_ids, :2], dim=1) > 0.2).unsqueeze(1)
if cfg.commands.heading_command:
forward = quat_apply(self.base_quat, self.forward_vec)
heading = torch.atan2(forward[env_ids, 1], forward[env_ids, 0])
self.commands[env_ids, 2] = torch.clip(0.5 * wrap_to_pi(self.commands[env_ids, 3] - heading), -1., 1.)
def _compute_torques(self, actions):
""" Compute torques from actions.
Actions can be interpreted as position or velocity targets given to a PD controller, or directly as scaled torques.
[NOTE]: torques must have the same dimension as the number of DOFs, even if some DOFs are not actuated.
Args:
actions (torch.Tensor): Actions
Returns:
[torch.Tensor]: Torques sent to the simulation
"""
# pd controller
actions_scaled = actions[:, :12] * self.cfg.control.action_scale
actions_scaled[:, [0, 3, 6, 9]] *= self.cfg.control.hip_scale_reduction # scale down hip flexion range
control_type = self.cfg.control.control_type
if control_type == "P":
self.joint_pos_target = actions_scaled + self.default_dof_pos
torques = self.p_gains * self.Kp_factors * (
self.joint_pos_target - self.dof_pos) - self.d_gains * self.Kd_factors * self.dof_vel
elif control_type == "V":
torques = self.p_gains * (actions_scaled - self.dof_vel) - self.d_gains * (
self.dof_vel - self.last_dof_vel) / self.sim_params.dt
elif control_type == "T":
torques = actions_scaled
elif control_type == "P_compliantfeet":
torques = self.p_gains * (
actions_scaled + self.default_dof_pos - self.dof_pos) - self.d_gains * self.dof_vel
spring_idxs = [3, 7, 11, 15]
torques[:, spring_idxs] = 1 + 0 * (self.p_gains[spring_idxs] * (
self.default_dof_pos[:, spring_idxs] - self.dof_pos[:, spring_idxs]) - self.d_gains[
spring_idxs] * self.dof_vel[:, spring_idxs])
else:
raise NameError(f"Unknown controller type: {control_type}")
torques = torques * self.motor_strengths
return torch.clip(torques, -self.torque_limits, self.torque_limits)
def _reset_dofs(self, env_ids, cfg):
""" Resets DOF position and velocities of selected environmments
Positions are randomly selected within 0.5:1.5 x default positions.
Velocities are set to zero.
Args:
env_ids (List[int]): Environemnt ids
"""
self.dof_pos[env_ids] = self.default_dof_pos * torch_rand_float(0.5, 1.5, (len(env_ids), self.num_dof),
device=self.device)
self.dof_vel[env_ids] = 0.
env_ids_int32 = env_ids.to(dtype=torch.int32)
self.gym.set_dof_state_tensor_indexed(self.sim,
gymtorch.unwrap_tensor(self.dof_state),
gymtorch.unwrap_tensor(env_ids_int32), len(env_ids_int32))
def _reset_root_states(self, env_ids, cfg):
""" Resets ROOT states position and velocities of selected environmments
Sets base position based on the curriculum
Selects randomized base velocities within -0.5:0.5 [m/s, rad/s]
Args:
env_ids (List[int]): Environemnt ids
"""
# base position
if self.custom_origins:
self.root_states[env_ids] = self.base_init_state
self.root_states[env_ids, :3] += self.env_origins[env_ids]
self.root_states[env_ids, :2] += torch_rand_float(cfg.terrain.x_init_range,
cfg.terrain.y_init_range, (len(env_ids), 2),
device=self.device) # xy position within 1m of the center
self.root_states[env_ids, 0] += cfg.terrain.x_init_offset
self.root_states[env_ids, 1] += cfg.terrain.y_init_offset
else:
self.root_states[env_ids] = self.base_init_state
self.root_states[env_ids, :3] += self.env_origins[env_ids]
# base velocities
self.root_states[env_ids, 7:13] = torch_rand_float(-0.5, 0.5, (len(env_ids), 6),
device=self.device) # [7:10]: lin vel, [10:13]: ang vel
env_ids_int32 = env_ids.to(dtype=torch.int32)
self.gym.set_actor_root_state_tensor_indexed(self.sim,
gymtorch.unwrap_tensor(self.root_states),
gymtorch.unwrap_tensor(env_ids_int32), len(env_ids_int32))
if cfg.env.record_video and 0 in env_ids:
if self.complete_video_frames is None:
self.complete_video_frames = []
else:
self.complete_video_frames = self.video_frames[:]
self.video_frames = []
if cfg.env.record_video and self.eval_cfg is not None and self.num_train_envs in env_ids:
if self.complete_video_frames_eval is None:
self.complete_video_frames_eval = []
else:
self.complete_video_frames_eval = self.video_frames_eval[:]
self.video_frames_eval = []
def _push_robots(self, env_ids, cfg):
""" Random pushes the robots. Emulates an impulse by setting a randomized base velocity.
"""
if cfg.domain_rand.push_robots:
env_ids = env_ids[self.episode_length_buf[env_ids] % int(cfg.domain_rand.push_interval) == 0]
max_vel = cfg.domain_rand.max_push_vel_xy
self.root_states[env_ids, 7:9] = torch_rand_float(-max_vel, max_vel, (len(env_ids), 2),
device=self.device) # lin vel x/y
self.gym.set_actor_root_state_tensor(self.sim, gymtorch.unwrap_tensor(self.root_states))
def _teleport_robots(self, env_ids, cfg):
""" Teleports any robots that are too close to the edge to the other side
"""
if cfg.terrain.teleport_robots:
thresh = cfg.terrain.teleport_thresh
x_offset = int(cfg.terrain.x_offset * cfg.terrain.horizontal_scale)
low_x_ids = env_ids[self.root_states[env_ids, 0] < thresh + x_offset]
self.root_states[low_x_ids, 0] += cfg.terrain.terrain_length * (cfg.terrain.num_rows - 1)
high_x_ids = env_ids[
self.root_states[env_ids, 0] > cfg.terrain.terrain_length * cfg.terrain.num_rows - thresh + x_offset]
self.root_states[high_x_ids, 0] -= cfg.terrain.terrain_length * (cfg.terrain.num_rows - 1)
low_y_ids = env_ids[self.root_states[env_ids, 1] < thresh]
self.root_states[low_y_ids, 1] += cfg.terrain.terrain_width * (cfg.terrain.num_cols - 1)
high_y_ids = env_ids[
self.root_states[env_ids, 1] > cfg.terrain.terrain_width * cfg.terrain.num_cols - thresh]
self.root_states[high_y_ids, 1] -= cfg.terrain.terrain_width * (cfg.terrain.num_cols - 1)
self.gym.set_actor_root_state_tensor(self.sim, gymtorch.unwrap_tensor(self.root_states))
self.gym.refresh_actor_root_state_tensor(self.sim)
def _update_terrain_curriculum(self, env_ids, cfg):
""" Implements the game-inspired curriculum.
Args:
env_ids (List[int]): ids of environments being reset
"""
if cfg.terrain.curriculum:
if not self.init_done:
# don't change on initial reset
return
distance = torch.norm(self.root_states[env_ids, :2] - self.env_origins[env_ids, :2], dim=1)
# robots that walked far enough progress to harder terains
move_up = distance > cfg.terrain.env_length / 2
# robots that walked less than half of their required distance go to simpler terrains
move_down = (distance < torch.norm(self.commands[env_ids, :2],
dim=1) * cfg.env.episode_length_s * 0.5) * ~move_up
self.terrain_levels[env_ids] += 1 * move_up - 1 * move_down
# Robots that solve the last level are sent to a random one
self.terrain_levels[env_ids] = torch.where(self.terrain_levels[env_ids] >= cfg.terrain.max_terrain_level,
torch.randint_like(self.terrain_levels[env_ids],
cfg.terrain.max_terrain_level),
torch.clip(self.terrain_levels[env_ids],
0)) # (the minumum level is zero)
self.env_origins[env_ids] = cfg.terrain.terrain_origins[
self.terrain_levels[env_ids], self.terrain_types[env_ids]]
def update_command_curriculum(self, env_ids, cfg, episode_sums=None):
""" Implements a curriculum of increasing commands
Args:
env_ids (List[int]): ids of environments being reset
"""
self._update_command_curriculum_uniform(env_ids, cfg, self.episode_sums)
# def _update_command_curriculum_distributional(self, env_ids, cfg, episode_sums=None):
# timesteps = int(self.cfg.commands.resampling_time / self.dt)
# ep_len = min(self.cfg.env.max_episode_length, timesteps)
#
# for i in range(cfg.commands.num_lin_vel_bins):
# for j in range(cfg.commands.num_ang_vel_bins):
# bucket_env_ids = cfg._envs_in_command_bucket[i][j]
# bucket_env_ids = list(set(bucket_env_ids) & set(env_ids.tolist()))
# if len(bucket_env_ids) == 0:
# continue
#
# cond_1 = episode_sums["tracking_lin_vel"][bucket_env_ids].mean() / ep_len > \
# cfg.commands.forward_curriculum_threshold * self.reward_scales["tracking_lin_vel"]
# cond_2 = episode_sums["tracking_ang_vel"][bucket_env_ids].mean() / ep_len > \
# cfg.commands.yaw_curriculum_threshold * self.reward_scales["tracking_ang_vel"]
#
# if cond_1 and cond_2:
# max_probability = 1.
# cfg._command_distribution[i, j] = max_probability
# if i + 1 < cfg.commands.num_lin_vel_bins: cfg._command_distribution[i + 1, j] = max_probability
# if j + 1 < cfg.commands.num_ang_vel_bins: cfg._command_distribution[i, j + 1] = max_probability
def _update_command_curriculum_uniform(self, env_ids, cfg, episode_sums=None):
# If the tracking reward is above 80% of the maximum, increase the range of commands
if cfg.commands.command_curriculum and (self.common_step_counter % self.cfg.env.max_episode_length == 0):
if self.reward_scales["tracking_lin_vel"] > 0:
if (torch.mean(episode_sums["tracking_lin_vel"][
env_ids]) / self.cfg.env.max_episode_length > self.cfg.commands.forward_curriculum_threshold * \
self.reward_scales["tracking_lin_vel"]):
cfg.command_ranges["lin_vel_x"][0] = np.clip(cfg.command_ranges["lin_vel_x"][0] - 0.2,
-cfg.commands.max_reverse_curriculum, 0.)
cfg.command_ranges["lin_vel_x"][1] = np.clip(cfg.command_ranges["lin_vel_x"][1] + 0.2, 0.,
cfg.commands.max_forward_curriculum)
elif self.reward_scales["tracking_lin_vel_long"] > 0:
if (torch.mean(episode_sums["tracking_lin_vel_long"][
env_ids]) / self.cfg.env.max_episode_length > self.cfg.commands.forward_curriculum_threshold * \
self.reward_scales["tracking_lin_vel_long"]):
cfg.command_ranges["lin_vel_x"][0] = np.clip(cfg.command_ranges["lin_vel_x"][0] - 0.2,
-cfg.commands.max_reverse_curriculum, 0.)
cfg.command_ranges["lin_vel_x"][1] = np.clip(cfg.command_ranges["lin_vel_x"][1] + 0.2, 0.,
cfg.commands.max_forward_curriculum)
if cfg.commands.yaw_command_curriculum and (self.common_step_counter % self.cfg.env.max_episode_length == 0):
if self.reward_scales["tracking_ang_vel"] > 0:
if (torch.mean(episode_sums["tracking_ang_vel"][
env_ids]) / self.cfg.env.max_episode_length > self.cfg.commands.yaw_curriculum_threshold * \
self.reward_scales["tracking_ang_vel"]):
cfg.command_ranges["ang_vel_yaw"][0] = np.clip(cfg.command_ranges["ang_vel_yaw"][0] - 0.2,
-cfg.commands.max_yaw_curriculum, 0.)
cfg.command_ranges["ang_vel_yaw"][1] = np.clip(cfg.command_ranges["ang_vel_yaw"][1] + 0.2, 0.,
cfg.commands.max_yaw_curriculum)
def _get_noise_scale_vec(self, cfg):
""" Sets a vector used to scale the noise added to the observations.
[NOTE]: Must be adapted when changing the observations structure
Args:
cfg (Dict): Environment config file
Returns:
[torch.Tensor]: Vector of scales used to multiply a uniform distribution in [-1, 1]
"""
self.add_noise = self.cfg.noise.add_noise
noise_scales = self.cfg.noise.noise_scales
noise_level = self.cfg.noise.noise_level
noise_vec = torch.cat((torch.ones(3) * noise_scales.gravity * noise_level,
torch.ones(12) * noise_scales.dof_pos * noise_level * self.obs_scales.dof_pos,
torch.ones(12) * noise_scales.dof_vel * noise_level * self.obs_scales.dof_vel,
torch.zeros(self.num_actions),
), dim=0)
if self.cfg.env.observe_command:
noise_vec = torch.cat((torch.ones(3) * noise_scales.gravity * noise_level,
torch.zeros(3),
torch.ones(12) * noise_scales.dof_pos * noise_level * self.obs_scales.dof_pos,
torch.ones(12) * noise_scales.dof_vel * noise_level * self.obs_scales.dof_vel,
torch.zeros(self.num_actions),
), dim=0)
if self.cfg.env.observe_vel:
noise_vec = torch.cat((torch.ones(3) * noise_scales.lin_vel * noise_level * self.obs_scales.lin_vel,
torch.ones(3) * noise_scales.ang_vel * noise_level * self.obs_scales.ang_vel,
noise_vec
), dim=0)
if self.cfg.env.observe_only_lin_vel:
noise_vec = torch.cat((torch.ones(3) * noise_scales.lin_vel * noise_level * self.obs_scales.lin_vel,
noise_vec
), dim=0)
if self.cfg.env.observe_yaw:
noise_vec = torch.cat((noise_vec,
torch.zeros(1),
), dim=0)
if self.cfg.terrain.measure_heights:
noise_vec = torch.cat((noise_vec,
torch.ones(
cfg.env.num_height_points) * noise_scales.height_measurements * noise_level * self.obs_scales.height_measurements
), dim=0)
noise_vec = noise_vec.to(self.device)
return noise_vec
# ----------------------------------------
def _init_buffers(self):
""" Initialize torch tensors which will contain simulation states and processed quantities
"""
# get gym GPU state tensors
actor_root_state = self.gym.acquire_actor_root_state_tensor(self.sim)
dof_state_tensor = self.gym.acquire_dof_state_tensor(self.sim)
net_contact_forces = self.gym.acquire_net_contact_force_tensor(self.sim)
rigid_body_state = self.gym.acquire_rigid_body_state_tensor(self.sim)
self.gym.refresh_dof_state_tensor(self.sim)
self.gym.refresh_actor_root_state_tensor(self.sim)
self.gym.refresh_net_contact_force_tensor(self.sim)
self.gym.refresh_rigid_body_state_tensor(self.sim)
self.gym.render_all_camera_sensors(self.sim)
# create some wrapper tensors for different slices
self.root_states = gymtorch.wrap_tensor(actor_root_state)
self.dof_state = gymtorch.wrap_tensor(dof_state_tensor)
self.net_contact_forces = gymtorch.wrap_tensor(net_contact_forces)
self.dof_pos = self.dof_state.view(self.num_envs, self.num_dof, 2)[..., 0]
self.dof_vel = self.dof_state.view(self.num_envs, self.num_dof, 2)[..., 1]
self.base_quat = self.root_states[:, 3:7]
self.rigid_body_state = gymtorch.wrap_tensor(rigid_body_state)
self.foot_velocities = self.rigid_body_state.view(self.num_envs, self.num_bodies, 13)[:,
self.feet_indices,
7:10]
self.contact_forces = gymtorch.wrap_tensor(net_contact_forces).view(self.num_envs, -1,
3) # shape: num_envs, num_bodies, xyz axis
# initialize some data used later on
self.common_step_counter = 0
self.extras = {}
if self.cfg.terrain.measure_heights:
self.height_points = self._init_height_points(torch.arange(self.num_envs, device=self.device), self.cfg)
self.measured_heights = 0
self.noise_scale_vec = self._get_noise_scale_vec(self.cfg) # , self.eval_cfg)
self.gravity_vec = to_torch(get_axis_params(-1., self.up_axis_idx), device=self.device).repeat(
(self.num_envs, 1))
self.forward_vec = to_torch([1., 0., 0.], device=self.device).repeat((self.num_envs, 1))
self.torques = torch.zeros(self.num_envs, self.num_dof, dtype=torch.float, device=self.device,
requires_grad=False)
self.p_gains = torch.zeros(self.num_dof, dtype=torch.float, device=self.device, requires_grad=False)
self.d_gains = torch.zeros(self.num_dof, dtype=torch.float, device=self.device, requires_grad=False)
self.actions = torch.zeros(self.num_envs, self.num_actions, dtype=torch.float, device=self.device,
requires_grad=False)
self.last_actions = torch.zeros(self.num_envs, self.num_actions, dtype=torch.float, device=self.device,
requires_grad=False)
self.last_dof_vel = torch.zeros_like(self.dof_vel)
self.last_root_vel = torch.zeros_like(self.root_states[:, 7:13])
self.commands_value = torch.zeros(self.num_envs, self.cfg.commands.num_commands, dtype=torch.float,
device=self.device, requires_grad=False)
self.commands = torch.zeros_like(self.commands_value) # x vel, y vel, yaw vel, heading
self.commands_scale = torch.tensor([self.obs_scales.lin_vel, self.obs_scales.lin_vel, self.obs_scales.ang_vel],
device=self.device, requires_grad=False, )
self.feet_air_time = torch.zeros(self.num_envs, self.feet_indices.shape[0], dtype=torch.float,
device=self.device, requires_grad=False)
self.last_contacts = torch.zeros(self.num_envs, len(self.feet_indices), dtype=torch.bool, device=self.device,
requires_grad=False)
self.base_lin_vel = quat_rotate_inverse(self.base_quat, self.root_states[:, 7:10])
self.base_ang_vel = quat_rotate_inverse(self.base_quat, self.root_states[:, 10:13])
self.projected_gravity = quat_rotate_inverse(self.base_quat, self.gravity_vec)
# joint positions offsets and PD gains
self.default_dof_pos = torch.zeros(self.num_dof, dtype=torch.float, device=self.device, requires_grad=False)
for i in range(self.num_dofs):
name = self.dof_names[i]
angle = self.cfg.init_state.default_joint_angles[name]
self.default_dof_pos[i] = angle
found = False
for dof_name in self.cfg.control.stiffness.keys():
if dof_name in name:
self.p_gains[i] = self.cfg.control.stiffness[dof_name]
self.d_gains[i] = self.cfg.control.damping[dof_name]
found = True
if not found:
self.p_gains[i] = 0.
self.d_gains[i] = 0.
if self.cfg.control.control_type in ["P", "V"]:
print(f"PD gain of joint {name} were not defined, setting them to zero")
self.default_dof_pos = self.default_dof_pos.unsqueeze(0)
def _init_custom_buffers__(self):
# domain randomization properties
self.friction_coeffs = self.default_friction * torch.ones(self.num_envs, dtype=torch.float, device=self.device,
requires_grad=False)
self.restitutions = self.default_restitution * torch.ones(self.num_envs, dtype=torch.float, device=self.device,
requires_grad=False)
self.payloads = torch.zeros(self.num_envs, dtype=torch.float, device=self.device, requires_grad=False)
self.com_displacements = torch.zeros(self.num_envs, 3, dtype=torch.float, device=self.device,
requires_grad=False)
self.motor_strengths = torch.ones(self.num_envs, self.num_dof, dtype=torch.float, device=self.device,
requires_grad=False)