Skip to content

Commit e184a9b

Browse files
committed
added knees
1 parent 7752cb3 commit e184a9b

File tree

5 files changed

+90
-27
lines changed

5 files changed

+90
-27
lines changed
102 Bytes
Binary file not shown.

envs/simple_biped_env.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -5,13 +5,13 @@
55
import numpy as np
66

77
class simpleBipedEnv(gym.Env):
8-
def __init__(self, render=False, max_steps=1000):
8+
def __init__(self, render=False, max_steps=10000):
99
super(simpleBipedEnv, self).__init__()
1010
self.render_mode = render
1111
self.physicsClient = p.connect(p.GUI if render else p.DIRECT)
1212
p.setAdditionalSearchPath(pybullet_data.getDataPath())
1313

14-
num_joints = 2 # left_hip, right_hip
14+
num_joints = 4 # left_hip, right_hip, left_knee, right_knee
1515
self.action_space = spaces.Box(low=-1, high=1, shape=(num_joints,), dtype=np.float32)
1616
self.observation_space = spaces.Box(low=-np.inf, high=np.inf, shape=(2*num_joints + 6,), dtype=np.float32)
1717
self.max_steps = max_steps
@@ -78,6 +78,8 @@ def _compute_reward(self):
7878
alive_bonus = 0.5 # encourage staying up
7979
torque_penalty = 0.001 * np.sum(np.square(self.last_action))
8080

81+
print(forward_reward, alive_bonus, torque_penalty)
82+
8183
return forward_reward + alive_bonus - torque_penalty
8284

8385

models/humanoid_ppo.zip

17.7 KB
Binary file not shown.

models/test.py

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@
88
def train():
99
env = DummyVecEnv([lambda: simpleBipedEnv(render=False)])
1010
model = PPO("MlpPolicy", env, verbose=1)
11-
model.learn(total_timesteps=5000)
11+
model.learn(total_timesteps=100000)
1212
model.save("models/humanoid_ppo")
1313
env.close()
1414

@@ -34,5 +34,3 @@ def run():
3434

3535
train()
3636
#run()
37-
38-
input("Press Enter to exit and close the visualization window...")

walkers/simple_biped.urdf

Lines changed: 85 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
2-
<robot name="simple_biped">
2+
<robot name="biped_with_knees">
33

4-
<!-- Torso/Hip Link -->
4+
<!-- Torso -->
55
<link name="torso">
66
<visual>
77
<geometry>
@@ -23,68 +23,131 @@
2323
</inertial>
2424
</link>
2525

26-
<!-- Left Leg -->
27-
<link name="left_leg">
26+
<!-- Upper and lower legs (left) -->
27+
<link name="left_upper_leg">
2828
<visual>
2929
<geometry>
30-
<cylinder length="0.5" radius="0.05"/>
30+
<cylinder length="0.3" radius="0.05"/>
3131
</geometry>
32-
<origin xyz="0 0 -0.25" rpy="0 0 0"/>
32+
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
3333
<material name="blue">
3434
<color rgba="0 0 1 1"/>
3535
</material>
3636
</visual>
3737
<collision>
3838
<geometry>
39-
<cylinder length="0.5" radius="0.05"/>
39+
<cylinder length="0.3" radius="0.05"/>
4040
</geometry>
41-
<origin xyz="0 0 -0.25" rpy="0 0 0"/>
41+
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
4242
</collision>
4343
<inertial>
44-
<mass value="2.0"/>
45-
<inertia ixx="0.02" ixy="0" ixz="0" iyy="0.02" iyz="0" izz="0.01"/>
44+
<mass value="1.5"/>
45+
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
4646
</inertial>
4747
</link>
4848

49-
<!-- Right Leg -->
50-
<link name="right_leg">
49+
<link name="left_lower_leg">
5150
<visual>
5251
<geometry>
53-
<cylinder length="0.5" radius="0.05"/>
52+
<cylinder length="0.3" radius="0.04"/>
5453
</geometry>
55-
<origin xyz="0 0 -0.25" rpy="0 0 0"/>
54+
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
55+
<material name="cyan">
56+
<color rgba="0 1 1 1"/>
57+
</material>
58+
</visual>
59+
<collision>
60+
<geometry>
61+
<cylinder length="0.3" radius="0.04"/>
62+
</geometry>
63+
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
64+
</collision>
65+
<inertial>
66+
<mass value="1.0"/>
67+
<inertia ixx="0.005" ixy="0" ixz="0" iyy="0.005" iyz="0" izz="0.005"/>
68+
</inertial>
69+
</link>
70+
71+
<!-- Upper and lower legs (right) -->
72+
<link name="right_upper_leg">
73+
<visual>
74+
<geometry>
75+
<cylinder length="0.3" radius="0.05"/>
76+
</geometry>
77+
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
5678
<material name="red">
5779
<color rgba="1 0 0 1"/>
5880
</material>
5981
</visual>
6082
<collision>
6183
<geometry>
62-
<cylinder length="0.5" radius="0.05"/>
84+
<cylinder length="0.3" radius="0.05"/>
85+
</geometry>
86+
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
87+
</collision>
88+
<inertial>
89+
<mass value="1.5"/>
90+
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
91+
</inertial>
92+
</link>
93+
94+
<link name="right_lower_leg">
95+
<visual>
96+
<geometry>
97+
<cylinder length="0.3" radius="0.04"/>
98+
</geometry>
99+
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
100+
<material name="pink">
101+
<color rgba="1 0 1 1"/>
102+
</material>
103+
</visual>
104+
<collision>
105+
<geometry>
106+
<cylinder length="0.3" radius="0.04"/>
63107
</geometry>
64-
<origin xyz="0 0 -0.25" rpy="0 0 0"/>
108+
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
65109
</collision>
66110
<inertial>
67-
<mass value="2.0"/>
68-
<inertia ixx="0.02" ixy="0" ixz="0" iyy="0.02" iyz="0" izz="0.01"/>
111+
<mass value="1.0"/>
112+
<inertia ixx="0.005" ixy="0" ixz="0" iyy="0.005" iyz="0" izz="0.005"/>
69113
</inertial>
70114
</link>
71115

72-
<!-- Left Hip Joint -->
116+
<!-- Joints -->
117+
<!-- Left hip -->
73118
<joint name="left_hip_joint" type="revolute">
74119
<parent link="torso"/>
75-
<child link="left_leg"/>
120+
<child link="left_upper_leg"/>
76121
<origin xyz="0.1 0 -0.15" rpy="0 0 0"/>
77122
<axis xyz="1 0 0"/>
78123
<limit effort="20" lower="-1.57" upper="1.57" velocity="2.0"/>
79124
</joint>
80125

81-
<!-- Right Hip Joint -->
126+
<!-- Left knee -->
127+
<joint name="left_knee_joint" type="revolute">
128+
<parent link="left_upper_leg"/>
129+
<child link="left_lower_leg"/>
130+
<origin xyz="0 0 -0.3" rpy="0 0 0"/>
131+
<axis xyz="1 0 0"/>
132+
<limit effort="20" lower="0" upper="2.0" velocity="2.0"/>
133+
</joint>
134+
135+
<!-- Right hip -->
82136
<joint name="right_hip_joint" type="revolute">
83137
<parent link="torso"/>
84-
<child link="right_leg"/>
138+
<child link="right_upper_leg"/>
85139
<origin xyz="-0.1 0 -0.15" rpy="0 0 0"/>
86140
<axis xyz="1 0 0"/>
87141
<limit effort="20" lower="-1.57" upper="1.57" velocity="2.0"/>
88142
</joint>
89143

144+
<!-- Right knee -->
145+
<joint name="right_knee_joint" type="revolute">
146+
<parent link="right_upper_leg"/>
147+
<child link="right_lower_leg"/>
148+
<origin xyz="0 0 -0.3" rpy="0 0 0"/>
149+
<axis xyz="1 0 0"/>
150+
<limit effort="20" lower="0" upper="2.0" velocity="2.0"/>
151+
</joint>
152+
90153
</robot>

0 commit comments

Comments
 (0)