11import os
2+
23import numpy as np
34
5+ from urdfenvs .robots .generic_urdf import GenericDiffDriveRobot , GenericUrdfReacher
46from urdfenvs .urdf_common .urdf_env import UrdfEnv
5- from urdfenvs .robots .generic_urdf import GenericUrdfReacher
6- from urdfenvs .robots .generic_urdf import GenericDiffDriveRobot
7+
78
89def run_multi_robot (n_steps = 1000 , render = False , obstacles = False , goal = False ):
910 jackal_1 = GenericDiffDriveRobot (
@@ -16,8 +17,8 @@ def run_multi_robot(n_steps=1000, render=False, obstacles=False, goal=False):
1617 "front_left_wheel" ,
1718 ],
1819 castor_wheels = [],
19- wheel_radius = 0.098 ,
20- wheel_distance = 2 * 0.187795 + 0.08 ,
20+ wheel_radius = 0.098 ,
21+ wheel_distance = 2 * 0.187795 + 0.08 ,
2122 )
2223 jackal_2 = GenericDiffDriveRobot (
2324 urdf = "jackal.urdf" ,
@@ -29,16 +30,16 @@ def run_multi_robot(n_steps=1000, render=False, obstacles=False, goal=False):
2930 "front_left_wheel" ,
3031 ],
3132 castor_wheels = [],
32- wheel_radius = 0.098 ,
33- wheel_distance = 2 * 0.187795 + 0.08 ,
33+ wheel_radius = 0.098 ,
34+ wheel_distance = 2 * 0.187795 + 0.08 ,
3435 )
3536 boxer = GenericDiffDriveRobot (
3637 urdf = "boxer.urdf" ,
3738 mode = "vel" ,
3839 actuated_wheels = ["wheel_right_joint" , "wheel_left_joint" ],
3940 castor_wheels = ["rotacastor_right_joint" , "rotacastor_left_joint" ],
40- wheel_radius = 0.08 ,
41- wheel_distance = 0.494 ,
41+ wheel_radius = 0.08 ,
42+ wheel_distance = 0.494 ,
4243 )
4344 ur5_urdf_file = os .path .dirname (os .path .abspath (__file__ )) + "/ur5.urdf"
4445 robots = [
@@ -49,32 +50,43 @@ def run_multi_robot(n_steps=1000, render=False, obstacles=False, goal=False):
4950 boxer ,
5051 ]
5152
52- env : UrdfEnv = UrdfEnv (
53- dt = 0.01 , robots = robots , render = render
54- )
53+ env : UrdfEnv = UrdfEnv (dt = 0.01 , robots = robots , render = render )
5554 n = env .n ()
5655 action = np .ones (n ) * - 0.2
5756 pos0 = np .zeros (n )
5857 pos0 [1 ] = - 0.0
5958 ns_per_robot = env .ns_per_robot ()
6059 n_per_robot = env .n_per_robot ()
61- initial_positions = np .array ([np .zeros (n ) for n in ns_per_robot ])
60+ initial_positions = [np .zeros (n ) for n in ns_per_robot ]
61+ max_len = max ([len (arr ) for arr in initial_positions ])
62+ padded_initial_positions = np .array (
63+ [
64+ np .pad (
65+ arr ,
66+ (0 , max_len - len (arr )),
67+ mode = "constant" ,
68+ constant_values = np .nan ,
69+ )
70+ for arr in initial_positions
71+ ]
72+ )
73+
6274 for i in range (len (initial_positions )):
6375 if ns_per_robot [i ] != n_per_robot [i ]:
64- initial_positions [i ][0 :2 ] = np .array ([0.0 , i ])
76+ padded_initial_positions [i ][0 :2 ] = np .array ([0.0 , i ])
6577 mount_positions = np .array (
66- [
67- np .array ([0.0 , i , 0.0 ]) for i in range (len (ns_per_robot ))
68- ]
78+ [np .array ([0.0 , i , 0.0 ]) for i in range (len (ns_per_robot ))]
6979 )
70- ob = env .reset (pos = initial_positions , mount_positions = mount_positions )
80+ ob = env .reset (pos = padded_initial_positions , mount_positions = mount_positions )
7181 print (f"Initial observation : { ob } " )
7282 if goal :
7383 from urdfenvs .scene_examples .goal import dynamicGoal
84+
7485 env .add_goal (dynamicGoal )
7586
7687 if obstacles :
7788 from urdfenvs .scene_examples .obstacles import dynamicSphereObst2
89+
7890 env .add_obstacle (dynamicSphereObst2 )
7991
8092 print ("Starting episode" )
0 commit comments