Skip to content

Commit bc68201

Browse files
authored
Merge pull request #61 from forcecore/fix_mutable
Fix mutable default robot object
2 parents 925c8d7 + 1625352 commit bc68201

File tree

6 files changed

+34
-16
lines changed

6 files changed

+34
-16
lines changed

pybulletgym/envs/mujoco/envs/locomotion/humanoid_env.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,8 @@
33

44

55
class HumanoidMuJoCoEnv(WalkerBaseMuJoCoEnv):
6-
def __init__(self, robot=Humanoid()):
7-
self.robot = robot
6+
def __init__(self, robot=None):
7+
self.robot = robot if robot is not None else Humanoid()
88
WalkerBaseMuJoCoEnv.__init__(self, self.robot)
99
self.electricity_cost = 4.25 * WalkerBaseMuJoCoEnv.electricity_cost
1010
self.stall_torque_cost = 4.25 * WalkerBaseMuJoCoEnv.stall_torque_cost

pybulletgym/envs/mujoco/robots/locomotors/humanoid.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ class Humanoid(WalkerBase, MJCFBasedRobot):
77
self_collision = True
88
foot_list = ["right_foot", "left_foot"] # "left_hand", "right_hand"
99

10-
def __init__(self, random_yaw = False, random_lean=False):
10+
def __init__(self, random_yaw=False, random_lean=False):
1111
WalkerBase.__init__(self, power=0.41)
1212
MJCFBasedRobot.__init__(self, 'humanoid_symmetric.xml', 'torso', action_dim=17, obs_dim=376)
1313
# 17 joints, 4 of them important for walking (hip, knee), others may as well be turned off, 17/4 = 4.25

pybulletgym/envs/mujoco/robots/robot_bases.py

+14-5
Original file line numberDiff line numberDiff line change
@@ -140,12 +140,12 @@ class URDFBasedRobot(XmlBasedRobot):
140140
Base class for URDF .xml based robots.
141141
"""
142142

143-
def __init__(self, model_urdf, robot_name, action_dim, obs_dim, basePosition=[0, 0, 0], baseOrientation=[0, 0, 0, 1], fixed_base=False, self_collision=False):
143+
def __init__(self, model_urdf, robot_name, action_dim, obs_dim, basePosition=None, baseOrientation=None, fixed_base=False, self_collision=False):
144144
XmlBasedRobot.__init__(self, robot_name, action_dim, obs_dim, self_collision)
145145

146146
self.model_urdf = model_urdf
147-
self.basePosition = basePosition
148-
self.baseOrientation = baseOrientation
147+
self.basePosition = basePosition if basePosition is not None else [0, 0, 0]
148+
self.baseOrientation = baseOrientation if baseOrientation is not None else [0, 0, 0, 1]
149149
self.fixed_base = fixed_base
150150

151151
def reset(self, bullet_client):
@@ -185,9 +185,14 @@ class SDFBasedRobot(XmlBasedRobot):
185185
Base class for SDF robots in a Scene.
186186
"""
187187

188-
def __init__(self, model_sdf, robot_name, action_dim, obs_dim, basePosition=[0, 0, 0], baseOrientation=[0, 0, 0, 1], fixed_base=False, self_collision=False):
188+
def __init__(self, model_sdf, robot_name, action_dim, obs_dim, basePosition=None, baseOrientation=None, fixed_base=False, self_collision=False):
189189
XmlBasedRobot.__init__(self, robot_name, action_dim, obs_dim, self_collision)
190190

191+
if basePosition is None:
192+
basePosition = [0, 0, 0]
193+
if baseOrientation is None:
194+
baseOrientation = [0, 0, 0, 1]
195+
191196
self.model_sdf = model_sdf
192197
self.fixed_base = fixed_base
193198

@@ -275,7 +280,11 @@ def reset_position(self, position):
275280
def reset_orientation(self, orientation):
276281
self._p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], self.get_position(), orientation)
277282

278-
def reset_velocity(self, linearVelocity=[0,0,0], angularVelocity =[0,0,0]):
283+
def reset_velocity(self, linearVelocity=None, angularVelocity=None):
284+
if linearVelocity is None:
285+
linearVelocity = [0, 0, 0]
286+
if angularVelocity is None:
287+
angularVelocity = [0, 0, 0]
279288
self._p.resetBaseVelocity(self.bodies[self.bodyIndex], linearVelocity, angularVelocity)
280289

281290
def reset_pose(self, position, orientation):

pybulletgym/envs/roboschool/envs/locomotion/humanoid_env.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,8 @@
33

44

55
class HumanoidBulletEnv(WalkerBaseBulletEnv):
6-
def __init__(self, robot=Humanoid()):
7-
self.robot = robot
6+
def __init__(self, robot=None):
7+
self.robot = robot if robot is not None else Humanoid()
88
WalkerBaseBulletEnv.__init__(self, self.robot)
99
self.electricity_cost = 4.25 * WalkerBaseBulletEnv.electricity_cost
1010
self.stall_torque_cost = 4.25 * WalkerBaseBulletEnv.stall_torque_cost

pybulletgym/envs/roboschool/robots/locomotors/humanoid.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ class Humanoid(WalkerBase, MJCFBasedRobot):
77
self_collision = True
88
foot_list = ["right_foot", "left_foot"] # "left_hand", "right_hand"
99

10-
def __init__(self, random_yaw = False, random_lean=False):
10+
def __init__(self, random_yaw=False, random_lean=False):
1111
WalkerBase.__init__(self, power=0.41)
1212
MJCFBasedRobot.__init__(self, 'humanoid_symmetric.xml', 'torso', action_dim=17, obs_dim=44)
1313
# 17 joints, 4 of them important for walking (hip, knee), others may as well be turned off, 17/4 = 4.25

pybulletgym/envs/roboschool/robots/robot_bases.py

+14-5
Original file line numberDiff line numberDiff line change
@@ -137,12 +137,12 @@ class URDFBasedRobot(XmlBasedRobot):
137137
Base class for URDF .xml based robots.
138138
"""
139139

140-
def __init__(self, model_urdf, robot_name, action_dim, obs_dim, basePosition=[0, 0, 0], baseOrientation=[0, 0, 0, 1], fixed_base=False, self_collision=False):
140+
def __init__(self, model_urdf, robot_name, action_dim, obs_dim, basePosition=None, baseOrientation=None, fixed_base=False, self_collision=False):
141141
XmlBasedRobot.__init__(self, robot_name, action_dim, obs_dim, self_collision)
142142

143143
self.model_urdf = model_urdf
144-
self.basePosition = basePosition
145-
self.baseOrientation = baseOrientation
144+
self.basePosition = basePosition if basePosition is not None else [0, 0, 0]
145+
self.baseOrientation = baseOrientation if baseOrientation is not None else [0, 0, 0, 1]
146146
self.fixed_base = fixed_base
147147

148148
def reset(self, bullet_client):
@@ -183,9 +183,14 @@ class SDFBasedRobot(XmlBasedRobot):
183183
Base class for SDF robots in a Scene.
184184
"""
185185

186-
def __init__(self, model_sdf, robot_name, action_dim, obs_dim, basePosition=[0, 0, 0], baseOrientation=[0, 0, 0, 1], fixed_base=False, self_collision=False):
186+
def __init__(self, model_sdf, robot_name, action_dim, obs_dim, basePosition=None, baseOrientation=None, fixed_base=False, self_collision=False):
187187
XmlBasedRobot.__init__(self, robot_name, action_dim, obs_dim, self_collision)
188188

189+
if basePosition is None:
190+
basePosition = [0, 0, 0]
191+
if baseOrientation is None:
192+
baseOrientation = [0, 0, 0, 1]
193+
189194
self.model_sdf = model_sdf
190195
self.fixed_base = fixed_base
191196

@@ -271,7 +276,11 @@ def reset_position(self, position):
271276
def reset_orientation(self, orientation):
272277
self._p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], self.get_position(), orientation)
273278

274-
def reset_velocity(self, linearVelocity=[0,0,0], angularVelocity =[0,0,0]):
279+
def reset_velocity(self, linearVelocity=None, angularVelocity=None):
280+
if linearVelocity is None:
281+
linearVelocity = [0, 0, 0]
282+
if angularVelocity is None:
283+
angularVelocity = [0, 0, 0]
275284
self._p.resetBaseVelocity(self.bodies[self.bodyIndex], linearVelocity, angularVelocity)
276285

277286
def reset_pose(self, position, orientation):

0 commit comments

Comments
 (0)