Skip to content

Commit fa50f19

Browse files
author
erwincoumans
authored
Merge pull request #4048 from priority-kew/aliengo_reduced_meshes
Import Aliengo URDF
2 parents 946d500 + adf7516 commit fa50f19

File tree

8 files changed

+1063
-0
lines changed

8 files changed

+1063
-0
lines changed

examples/pybullet/gym/pybullet_data/aliengo/LICENSE

Lines changed: 373 additions & 0 deletions
Large diffs are not rendered by default.
Lines changed: 58 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
import pybullet as p
2+
import time
3+
import pybullet_data as pd
4+
import numpy as np
5+
p.connect(p.GUI)
6+
p.setAdditionalSearchPath(pd.getDataPath())
7+
dt = 1./240.
8+
9+
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
10+
p.loadURDF("plane.urdf")
11+
robot = p.loadURDF("aliengo/aliengo.urdf",[0,0,0.5])
12+
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
13+
p.setGravity(0,0,-9.8)
14+
15+
ALIENGO_DEFAULT_ABDUCTION_ANGLE = 0
16+
ALIENGO_DEFAULT_HIP_ANGLE = 1.2
17+
ALIENGO_DEFAULT_KNEE_ANGLE = -2.0
18+
NUM_LEGS = 4
19+
INIT_MOTOR_ANGLES = np.array([
20+
ALIENGO_DEFAULT_ABDUCTION_ANGLE,
21+
ALIENGO_DEFAULT_HIP_ANGLE,
22+
ALIENGO_DEFAULT_KNEE_ANGLE
23+
] * NUM_LEGS)
24+
25+
MOTOR_NAMES = [
26+
"FR_hip_joint",
27+
"FR_upper_joint",
28+
"FR_lower_joint",
29+
"FL_hip_joint",
30+
"FL_upper_joint",
31+
"FL_lower_joint",
32+
"RR_hip_joint",
33+
"RR_upper_joint",
34+
"RR_lower_joint",
35+
"RL_hip_joint",
36+
"RL_upper_joint",
37+
"RL_lower_joint",
38+
]
39+
motor_ids = []
40+
41+
for j in range (p.getNumJoints(robot)):
42+
joint_info = p.getJointInfo(robot,j)
43+
name = joint_info[1].decode('utf-8')
44+
print("joint_info[1]=",name)
45+
if name in MOTOR_NAMES:
46+
motor_ids.append(j)
47+
48+
for index in range (12):
49+
joint_id = motor_ids[index]
50+
p.setJointMotorControl2(robot, joint_id, p.POSITION_CONTROL, INIT_MOTOR_ANGLES[index])
51+
p.resetJointState(robot, joint_id, INIT_MOTOR_ANGLES[index])
52+
53+
print("motor_ids=",motor_ids)
54+
while p.isConnected():
55+
p.stepSimulation()
56+
time.sleep(dt)
57+
58+

0 commit comments

Comments
 (0)