update Laikago robot with textures, and a version with toes to enable inverse kinematics.

This commit is contained in:
Erwin Coumans
2019-12-04 14:48:28 -08:00
parent 763e25dd37
commit 7c5796b67d
28 changed files with 74259 additions and 15915 deletions

View File

@@ -1,10 +1,13 @@
# Blender MTL File: 'None' # Blender MTL File: 'None'
# Material Count: 1 # Material Count: 1
newmtl None newmtl None.003
Ns 0 Ns 0.000000
Ka 0.000000 0.000000 0.000000 Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8 Kd 0.800000 0.800000 0.800000
Ks 0.8 0.8 0.8 Ks 0.800000 0.800000 0.800000
d 1 Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 2 illum 2
map_Kd laikago_tex.jpg

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,11 @@
# Blender MTL File: 'laikago_textured.blend'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2
map_Kd laikago_tex.jpg

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,11 @@
# Blender MTL File: 'laikago_textured.blend'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2
map_Kd laikago_tex.jpg

File diff suppressed because it is too large Load Diff

View File

@@ -3,108 +3,95 @@ import time
p.connect(p.GUI) p.connect(p.GUI)
plane = p.loadURDF("plane.urdf") plane = p.loadURDF("plane.urdf")
p.setGravity(0, 0, -9.8) p.setGravity(0,0,-9.8)
p.setTimeStep(1. / 500) p.setTimeStep(1./500)
#p.setDefaultContactERP(0) #p.setDefaultContactERP(0)
#urdfFlags = p.URDF_USE_SELF_COLLISION+p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS #urdfFlags = p.URDF_USE_SELF_COLLISION+p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS
urdfFlags = p.URDF_USE_SELF_COLLISION urdfFlags = p.URDF_USE_SELF_COLLISION
quadruped = p.loadURDF("laikago.urdf", [0, 0, .5], [0, 0.5, 0.5, 0], quadruped = p.loadURDF("laikago_toes.urdf",[0,0,.5],[0,0.5,0.5,0], flags = urdfFlags,useFixedBase=False)
flags=urdfFlags,
useFixedBase=False)
#enable collision between lower legs #enable collision between lower legs
for j in range(p.getNumJoints(quadruped)): for j in range (p.getNumJoints(quadruped)):
print(p.getJointInfo(quadruped, j)) print(p.getJointInfo(quadruped,j))
#2,5,8 and 11 are the lower legs #2,5,8 and 11 are the lower legs
lower_legs = [2, 5, 8, 11] lower_legs = [2,5,8,11]
for l0 in lower_legs: for l0 in lower_legs:
for l1 in lower_legs: for l1 in lower_legs:
if (l1 > l0): if (l1>l0):
enableCollision = 1 enableCollision = 1
print("collision for pair", l0, l1, print("collision for pair",l0,l1, p.getJointInfo(quadruped,l0)[12],p.getJointInfo(quadruped,l1)[12], "enabled=",enableCollision)
p.getJointInfo(quadruped, l0)[12], p.setCollisionFilterPair(quadruped, quadruped, 2,5,enableCollision)
p.getJointInfo(quadruped, l1)[12], "enabled=", enableCollision)
p.setCollisionFilterPair(quadruped, quadruped, 2, 5, enableCollision)
jointIds = [] jointIds=[]
paramIds = [] paramIds=[]
jointOffsets = [] jointOffsets=[]
jointDirections = [-1, 1, 1, 1, 1, 1, -1, 1, 1, 1, 1, 1] jointDirections=[-1,1,1,1,1,1,-1,1,1,1,1,1]
jointAngles = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] jointAngles=[0,0,0,0,0,0,0,0,0,0,0,0]
for i in range(4): for i in range (4):
jointOffsets.append(0) jointOffsets.append(0)
jointOffsets.append(-0.7) jointOffsets.append(-0.7)
jointOffsets.append(0.7) jointOffsets.append(0.7)
maxForceId = p.addUserDebugParameter("maxForce", 0, 100, 20) maxForceId = p.addUserDebugParameter("maxForce",0,100,20)
for j in range(p.getNumJoints(quadruped)): for j in range (p.getNumJoints(quadruped)):
p.changeDynamics(quadruped, j, linearDamping=0, angularDamping=0) p.changeDynamics(quadruped,j,linearDamping=0, angularDamping=0)
info = p.getJointInfo(quadruped, j) info = p.getJointInfo(quadruped,j)
#print(info) #print(info)
jointName = info[1] jointName = info[1]
jointType = info[2] jointType = info[2]
if (jointType == p.JOINT_PRISMATIC or jointType == p.JOINT_REVOLUTE): if (jointType==p.JOINT_PRISMATIC or jointType==p.JOINT_REVOLUTE):
jointIds.append(j) jointIds.append(j)
p.getCameraImage(480, 320)
p.getCameraImage(480,320)
p.setRealTimeSimulation(0) p.setRealTimeSimulation(0)
joints = [] joints=[]
with open("data1.txt", "r") as filestream: with open("data1.txt","r") as filestream:
for line in filestream: for line in filestream:
print("line=", line) maxForce = p.readUserDebugParameter(maxForceId)
maxForce = p.readUserDebugParameter(maxForceId) currentline = line.split(",")
currentline = line.split(",") frame = currentline[0]
#print (currentline) t = currentline[1]
#print("-----") joints=currentline[2:14]
frame = currentline[0] for j in range (12):
t = currentline[1] targetPos = float(joints[j])
#print("frame[",frame,"]") p.setJointMotorControl2(quadruped,jointIds[j],p.POSITION_CONTROL,jointDirections[j]*targetPos+jointOffsets[j], force=maxForce)
joints = currentline[2:14] p.stepSimulation()
#print("joints=",joints) for lower_leg in lower_legs:
for j in range(12): #print("points for ", quadruped, " link: ", lower_leg)
targetPos = float(joints[j]) pts = p.getContactPoints(quadruped,-1, lower_leg)
p.setJointMotorControl2(quadruped, #print("num points=",len(pts))
jointIds[j], #for pt in pts:
p.POSITION_CONTROL, # print(pt[9])
jointDirections[j] * targetPos + jointOffsets[j], time.sleep(1./500.)
force=maxForce)
p.stepSimulation()
for lower_leg in lower_legs: index = 0
#print("points for ", quadruped, " link: ", lower_leg) for j in range (p.getNumJoints(quadruped)):
pts = p.getContactPoints(quadruped, -1, lower_leg) p.changeDynamics(quadruped,j,linearDamping=0, angularDamping=0)
#print("num points=",len(pts)) info = p.getJointInfo(quadruped,j)
#for pt in pts: js = p.getJointState(quadruped,j)
# print(pt[9]) #print(info)
time.sleep(1. / 500.) jointName = info[1]
jointType = info[2]
if (jointType==p.JOINT_PRISMATIC or jointType==p.JOINT_REVOLUTE):
paramIds.append(p.addUserDebugParameter(jointName.decode("utf-8"),-4,4,(js[0]-jointOffsets[index])/jointDirections[index]))
index=index+1
for j in range(p.getNumJoints(quadruped)):
p.changeDynamics(quadruped, j, linearDamping=0, angularDamping=0)
info = p.getJointInfo(quadruped, j)
js = p.getJointState(quadruped, j)
#print(info)
jointName = info[1]
jointType = info[2]
if (jointType == p.JOINT_PRISMATIC or jointType == p.JOINT_REVOLUTE):
paramIds.append(
p.addUserDebugParameter(jointName.decode("utf-8"), -4, 4,
(js[0] - jointOffsets[j]) / jointDirections[j]))
p.setRealTimeSimulation(1) p.setRealTimeSimulation(1)
while (1): while (1):
for i in range(len(paramIds)): for i in range(len(paramIds)):
c = paramIds[i] c = paramIds[i]
targetPos = p.readUserDebugParameter(c) targetPos = p.readUserDebugParameter(c)
maxForce = p.readUserDebugParameter(maxForceId) maxForce = p.readUserDebugParameter(maxForceId)
p.setJointMotorControl2(quadruped, p.setJointMotorControl2(quadruped,jointIds[i],p.POSITION_CONTROL,jointDirections[i]*targetPos+jointOffsets[i], force=maxForce)
jointIds[i],
p.POSITION_CONTROL,
jointDirections[i] * targetPos + jointOffsets[i],
force=maxForce)

View File

@@ -13,24 +13,24 @@
<origin rpy="0 0 0" xyz="0 0 0.043794"/> <origin rpy="0 0 0" xyz="0 0 0.043794"/>
<geometry> <geometry>
<mesh filename="chassis.stl" scale="1 1 1"/> <mesh filename="chassis.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="yellow"> <material name="white">
<color rgba="0.95 0.75 0.05 1"/> <color rgba="1 1 1 1"/>
</material> </material>
</visual> </visual>
<collision> <collision>
<origin rpy="-1.57 0 0" xyz="0 0 0.043794"/> <origin rpy="-1.57 0 0" xyz="0 0 0.043794"/>
<geometry> <geometry>
<mesh filename="chassis_vhacd_mod.obj" scale="1 1 1"/> <mesh filename="chassis_vhacd_mod.obj" scale="1 1 1"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
<link name="FR_hip_motor"> <link name="FR_hip_motor">
<contact> <contact>
<lateral_friction value="1"/> <lateral_friction value="1"/>
</contact> </contact>
@@ -40,30 +40,30 @@
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial> </inertial>
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/> <mesh filename="hip_motor_mirror.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="green"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/> <mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="FR_hip_motor_2_chassis_joint" type="continuous"> <joint name="FR_hip_motor_2_chassis_joint" type="continuous">
<axis xyz="0 0 -1"/> <axis xyz="0 0 -1"/>
<parent link="chassis"/> <parent link="chassis"/>
<child link="FR_hip_motor"/> <child link="FR_hip_motor"/>
<origin rpy="0 0 0" xyz="-0.0817145 0 0.242889"/> <origin rpy="0 0 0" xyz="-0.0817145 0 0.242889"/>
<limit effort="100" velocity="100"/> <limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/> <joint_properties damping=".0" friction=".0"/>
</joint> </joint>
<link name="FR_upper_leg"> <link name="FR_upper_leg">
<contact> <contact>
@@ -77,28 +77,28 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="upper_leg_mirror.stl" scale="1 1 1"/> <mesh filename="upper_leg_mirror.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="blue"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="upper_leg_right_vhacd.obj" scale="1 1 1"/> <mesh filename="upper_leg_right_vhacd.obj" scale="1 1 1"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="FR_upper_leg_2_hip_motor_joint" type="continuous"> <joint name="FR_upper_leg_2_hip_motor_joint" type="continuous">
<axis xyz="1 0 0"/> <axis xyz="1 0 0"/>
<parent link="FR_hip_motor"/> <parent link="FR_hip_motor"/>
<child link="FR_upper_leg"/> <child link="FR_upper_leg"/>
<origin rpy="0 0 0" xyz="-0.053565 0 0"/> <origin rpy="0 0 0" xyz="-0.053565 0 0"/>
<limit effort="100" velocity="100"/> <limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/> <joint_properties damping=".0" friction=".0"/>
</joint> </joint>
<link name="FR_lower_leg"> <link name="FR_lower_leg">
<contact> <contact>
@@ -112,32 +112,32 @@
<visual> <visual>
<origin rpy="0 1.57079 0" xyz="0 0.0 0"/> <origin rpy="0 1.57079 0" xyz="0 0.0 0"/>
<geometry> <geometry>
<mesh filename="lower_leg_3.stl" scale="1 1 1"/> <mesh filename="lower_leg3.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="red"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.57079 0" xyz="0 0.0 0"/> <origin rpy="0 1.57079 0" xyz="0 0.0 0"/>
<geometry> <geometry>
<mesh filename="lower_leg_3.stl" scale="1 1 1"/> <mesh filename="lower_leg_3_collision.stl" scale="1 1 1"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="FR_lower_leg_2_upper_leg_joint" type="continuous"> <joint name="FR_lower_leg_2_upper_leg_joint" type="continuous">
<axis xyz="1 0 0"/> <axis xyz="1 0 0"/>
<parent link="FR_upper_leg"/> <parent link="FR_upper_leg"/>
<child link="FR_lower_leg"/> <child link="FR_lower_leg"/>
<origin rpy="0 0 0" xyz="0.02069 -0.20833 -0.1422"/> <origin rpy="0 0 0" xyz="0.02069 -0.20833 -0.1422"/>
<limit effort="100" velocity="100"/> <limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/> <joint_properties damping=".0" friction=".0"/>
</joint> </joint>
<link name="FL_hip_motor"> <link name="FL_hip_motor">
<contact> <contact>
<lateral_friction value="1"/> <lateral_friction value="1"/>
</contact> </contact>
@@ -149,30 +149,29 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="hip_motor.stl" scale="1 1 1"/> <mesh filename="hip_motor.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="green"> <material name="white">
<color rgba="0.23 0.73 0.33 1"/>
</material> </material>
</visual> </visual>
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="hip_motor.stl" scale="1 1 1"/> <mesh filename="hip_motor.stl" scale="1 1 1"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="FL_hip_motor_2_chassis_joint" type="continuous"> <joint name="FL_hip_motor_2_chassis_joint" type="continuous">
<axis xyz="0 0 1"/> <axis xyz="0 0 1"/>
<parent link="chassis"/> <parent link="chassis"/>
<child link="FL_hip_motor"/> <child link="FL_hip_motor"/>
<origin rpy="0 0 0" xyz="0.0817145 0 0.242889"/> <origin rpy="0 0 0" xyz="0.0817145 0 0.242889"/>
<limit effort="100" velocity="100"/> <limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/> <joint_properties damping=".0" friction=".0"/>
</joint> </joint>
<link name="FL_upper_leg"> <link name="FL_upper_leg">
<contact> <contact>
@@ -187,17 +186,16 @@
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="upper_leg.stl" scale="1 1 1"/> <mesh filename="upper_leg_left.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="blue"> <material name="white">
<color rgba="0.28 0.52 0.93 1"/>
</material> </material>
</visual> </visual>
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="upper_leg_left_vhacd.obj" scale="1 1 1"/> <mesh filename="upper_leg_left_vhacd.obj" scale="1 1 1"/>
</geometry> </geometry>
</collision> </collision>
@@ -205,13 +203,13 @@
<joint name="FL_upper_leg_2_hip_motor_joint" type="continuous"> <joint name="FL_upper_leg_2_hip_motor_joint" type="continuous">
<axis xyz="1 0 0"/> <axis xyz="1 0 0"/>
<parent link="FL_hip_motor"/> <parent link="FL_hip_motor"/>
<child link="FL_upper_leg"/> <child link="FL_upper_leg"/>
<origin rpy="0 0 0" xyz="0.055855 0 0"/> <origin rpy="0 0 0" xyz="0.055855 0 0"/>
<limit effort="100" velocity="100"/> <limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/> <joint_properties damping=".0" friction=".0"/>
</joint> </joint>
<link name="FL_lower_leg"> <link name="FL_lower_leg">
@@ -226,37 +224,36 @@
<visual> <visual>
<origin rpy="0 1.57079 0" xyz="0 0 0"/> <origin rpy="0 1.57079 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="lower_leg_3.stl" scale="1 1 1"/> <mesh filename="lower_leg3.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="red"> <material name="white">
<color rgba="0.85 0.19 0.21 1"/>
</material> </material>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.57079 0" xyz="0 0 0"/> <origin rpy="0 1.57079 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="lower_leg_3.stl" scale="1 1 1"/> <mesh filename="lower_leg_3_collision.stl" scale="1 1 1"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="FL_lower_leg_2_upper_leg_joint" type="continuous"> <joint name="FL_lower_leg_2_upper_leg_joint" type="continuous">
<axis xyz="1 0 0"/> <axis xyz="1 0 0"/>
<parent link="FL_upper_leg"/> <parent link="FL_upper_leg"/>
<child link="FL_lower_leg"/> <child link="FL_lower_leg"/>
<origin rpy="0 0 0" xyz="-0.02069 -0.20833 -0.1422"/> <origin rpy="0 0 0" xyz="-0.02069 -0.20833 -0.1422"/>
<limit effort="100" velocity="100"/> <limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/> <joint_properties damping=".0" friction=".0"/>
</joint> </joint>
<link name="RR_hip_motor"> <link name="RR_hip_motor">
<contact> <contact>
<lateral_friction value="1"/> <lateral_friction value="1"/>
</contact> </contact>
@@ -266,31 +263,31 @@
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial> </inertial>
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/> <mesh filename="hip_motor_mirror.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="green"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/> <mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="RR_hip_motor_2_chassis_joint" type="continuous"> <joint name="RR_hip_motor_2_chassis_joint" type="continuous">
<axis xyz="0 0 -1"/> <axis xyz="0 0 -1"/>
<parent link="chassis"/> <parent link="chassis"/>
<child link="RR_hip_motor"/> <child link="RR_hip_motor"/>
<origin rpy="0 0 0" xyz="-0.0817145 0 -0.194401"/> <origin rpy="0 0 0" xyz="-0.0817145 0 -0.194401"/>
<limit effort="100" velocity="100"/> <limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/> <joint_properties damping=".0" friction=".0"/>
</joint> </joint>
<link name="RR_upper_leg"> <link name="RR_upper_leg">
<contact> <contact>
@@ -304,28 +301,28 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="upper_leg_mirror.stl" scale="1 1 1"/> <mesh filename="upper_leg_mirror2.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="blue"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="upper_leg_right_vhacd.obj" scale="1 1 1"/> <mesh filename="upper_leg_right_vhacd.obj" scale="1 1 1"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="RR_upper_leg_2_hip_motor_joint" type="continuous"> <joint name="RR_upper_leg_2_hip_motor_joint" type="continuous">
<axis xyz="1 0 0"/> <axis xyz="1 0 0"/>
<parent link="RR_hip_motor"/> <parent link="RR_hip_motor"/>
<child link="RR_upper_leg"/> <child link="RR_upper_leg"/>
<origin rpy="0 0 0" xyz="-0.053565 0 0"/> <origin rpy="0 0 0" xyz="-0.053565 0 0"/>
<limit effort="100" velocity="100"/> <limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/> <joint_properties damping=".0" friction=".0"/>
</joint> </joint>
<link name="RR_lower_leg"> <link name="RR_lower_leg">
<contact> <contact>
@@ -339,31 +336,31 @@
<visual> <visual>
<origin rpy="0 1.57079 0" xyz="0 0 0"/> <origin rpy="0 1.57079 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="lower_leg_3.stl" scale="1 1 1"/> <mesh filename="lower_leg3.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="red"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.57079 0" xyz="0 0 0"/> <origin rpy="0 1.57079 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="lower_leg_3.stl" scale="1 1 1"/> <mesh filename="lower_leg_3_collision.stl" scale="1 1 1"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="RR_lower_leg_2_upper_leg_joint" type="continuous"> <joint name="RR_lower_leg_2_upper_leg_joint" type="continuous">
<axis xyz="1 0 0"/> <axis xyz="1 0 0"/>
<parent link="RR_upper_leg"/> <parent link="RR_upper_leg"/>
<child link="RR_lower_leg"/> <child link="RR_lower_leg"/>
<origin rpy="0 0 0" xyz="0.02069 -0.20833 -0.1422"/> <origin rpy="0 0 0" xyz="0.02069 -0.20833 -0.1422"/>
<limit effort="100" velocity="100"/> <limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/> <joint_properties damping=".0" friction=".0"/>
</joint> </joint>
<link name="RL_hip_motor"> <link name="RL_hip_motor">
<contact> <contact>
<lateral_friction value="1"/> <lateral_friction value="1"/>
</contact> </contact>
@@ -375,29 +372,29 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="hip_motor.stl" scale="1 1 1"/> <mesh filename="hip_motor.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="green"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="hip_motor.stl" scale="1 1 1"/> <mesh filename="hip_motor.stl" scale="1 1 1"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="RL_hip_motor_2_chassis_joint" type="continuous"> <joint name="RL_hip_motor_2_chassis_joint" type="continuous">
<axis xyz="0 0 1"/> <axis xyz="0 0 1"/>
<parent link="chassis"/> <parent link="chassis"/>
<child link="RL_hip_motor"/> <child link="RL_hip_motor"/>
<origin rpy="0 0 0" xyz="0.0817145 0 -0.194401"/> <origin rpy="0 0 0" xyz="0.0817145 0 -0.194401"/>
<limit effort="100" velocity="100"/> <limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/> <joint_properties damping=".0" friction=".0"/>
</joint> </joint>
<link name="RL_upper_leg"> <link name="RL_upper_leg">
<contact> <contact>
@@ -411,15 +408,15 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="upper_leg.stl" scale="1 1 1"/> <mesh filename="upper_leg_left2.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="blue"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="upper_leg_left_vhacd.obj" scale="1 1 1"/> <mesh filename="upper_leg_left_vhacd.obj" scale="1 1 1"/>
</geometry> </geometry>
</collision> </collision>
@@ -427,13 +424,13 @@
<joint name="RL_upper_leg_2_hip_motor_joint" type="continuous"> <joint name="RL_upper_leg_2_hip_motor_joint" type="continuous">
<axis xyz="1 0 0"/> <axis xyz="1 0 0"/>
<parent link="RL_hip_motor"/> <parent link="RL_hip_motor"/>
<child link="RL_upper_leg"/> <child link="RL_upper_leg"/>
<origin rpy="0 0 0" xyz="0.055855 0 0"/> <origin rpy="0 0 0" xyz="0.055855 0 0"/>
<limit effort="100" velocity="100"/> <limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/> <joint_properties damping=".0" friction=".0"/>
</joint> </joint>
<link name="RL_lower_leg"> <link name="RL_lower_leg">
@@ -448,28 +445,28 @@
<visual> <visual>
<origin rpy="0 1.57079 0" xyz="0 0 0"/> <origin rpy="0 1.57079 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="lower_leg_3.stl" scale="1 1 1"/> <mesh filename="lower_leg3.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="red"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 1.57079 0" xyz="0 0 0"/> <origin rpy="0 1.57079 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="lower_leg_3.stl" scale="1 1 1"/> <mesh filename="lower_leg_3_collision.stl" scale="1 1 1"/>
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="RL_lower_leg_2_upper_leg_joint" type="continuous"> <joint name="RL_lower_leg_2_upper_leg_joint" type="continuous">
<axis xyz="1 0 0"/> <axis xyz="1 0 0"/>
<parent link="RL_upper_leg"/> <parent link="RL_upper_leg"/>
<child link="RL_lower_leg"/> <child link="RL_lower_leg"/>
<origin rpy="0 0 0" xyz="-0.02069 -0.20833 -0.1422"/> <origin rpy="0 0 0" xyz="-0.02069 -0.20833 -0.1422"/>
<limit effort="100" velocity="100"/> <limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/> <joint_properties damping=".0" friction=".0"/>
</joint> </joint>

Binary file not shown.

After

Width:  |  Height:  |  Size: 252 KiB

View File

@@ -12,10 +12,10 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0.043794"/> <origin rpy="0 0 0" xyz="0 0 0.043794"/>
<geometry> <geometry>
<mesh filename="chassis.stl" scale="1 1 1"/> <mesh filename="chassis.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="yellow"> <material name="white">
<color rgba="0.95 0.75 0.05 1"/> <color rgba="1 1 1 1"/>
</material> </material>
</visual> </visual>
<collision> <collision>
@@ -38,9 +38,9 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/> <mesh filename="hip_motor_mirror.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="green"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
@@ -72,9 +72,9 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="upper_leg_mirror.stl" scale="1 1 1"/> <mesh filename="upper_leg_mirror.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="blue"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
@@ -107,9 +107,9 @@
<visual> <visual>
<origin rpy="0 1.57079 0" xyz="0 0.0 0"/> <origin rpy="0 1.57079 0" xyz="0 0.0 0"/>
<geometry> <geometry>
<mesh filename="lower_leg_3.stl" scale="1 1 1"/> <mesh filename="lower_leg3.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="red"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
@@ -142,10 +142,9 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="hip_motor.stl" scale="1 1 1"/> <mesh filename="hip_motor.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="green"> <material name="white">
<color rgba="0.23 0.73 0.33 1"/>
</material> </material>
</visual> </visual>
@@ -180,10 +179,9 @@
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="upper_leg.stl" scale="1 1 1"/> <mesh filename="upper_leg_left.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="blue"> <material name="white">
<color rgba="0.28 0.52 0.93 1"/>
</material> </material>
</visual> </visual>
@@ -219,11 +217,10 @@
<visual> <visual>
<origin rpy="0 1.57079 0" xyz="0 0 0"/> <origin rpy="0 1.57079 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="lower_leg_3.stl" scale="1 1 1"/> <mesh filename="lower_leg3.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="red"> <material name="white">
<color rgba="0.85 0.19 0.21 1"/> </material>
</material>
</visual> </visual>
<collision> <collision>
@@ -262,9 +259,9 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/> <mesh filename="hip_motor_mirror.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="green"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
@@ -297,9 +294,9 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="upper_leg_mirror.stl" scale="1 1 1"/> <mesh filename="upper_leg_mirror2.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="blue"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
@@ -332,9 +329,9 @@
<visual> <visual>
<origin rpy="0 1.57079 0" xyz="0 0 0"/> <origin rpy="0 1.57079 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="lower_leg_3.stl" scale="1 1 1"/> <mesh filename="lower_leg3.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="red"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
@@ -368,9 +365,9 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="hip_motor.stl" scale="1 1 1"/> <mesh filename="hip_motor.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="green"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
@@ -404,9 +401,9 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="upper_leg.stl" scale="1 1 1"/> <mesh filename="upper_leg_left2.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="blue"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
@@ -441,9 +438,9 @@
<visual> <visual>
<origin rpy="0 1.57079 0" xyz="0 0 0"/> <origin rpy="0 1.57079 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="lower_leg_3.stl" scale="1 1 1"/> <mesh filename="lower_leg3.obj" scale="1 1 1"/>
</geometry> </geometry>
<material name="red"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
@@ -475,9 +472,9 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<sphere radius="0.03"/> <sphere radius="0.0"/>
</geometry> </geometry>
<material name="darkgray"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
@@ -508,9 +505,9 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<sphere radius="0.03"/> <sphere radius="0.0"/>
</geometry> </geometry>
<material name="darkgray"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
@@ -541,9 +538,9 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<sphere radius="0.03"/> <sphere radius="0.0"/>
</geometry> </geometry>
<material name="darkgray"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
@@ -574,9 +571,9 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<sphere radius="0.03"/> <sphere radius="0.0"/>
</geometry> </geometry>
<material name="darkgray"/> <material name="white"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>

View File

@@ -0,0 +1,11 @@
# Blender MTL File: 'laikago_textured.blend'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2
map_Kd laikago_tex.jpg

File diff suppressed because it is too large Load Diff

View File

@@ -1,10 +1,13 @@
# Blender MTL File: 'None' # Blender MTL File: 'laikago_textured.blend'
# Material Count: 1 # Material Count: 1
newmtl None newmtl None.005
Ns 0 Ns 0.000000
Ka 0.000000 0.000000 0.000000 Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8 Kd 0.800000 0.800000 0.800000
Ks 0.8 0.8 0.8 Ks 0.800000 0.800000 0.800000
d 1 Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 2 illum 2
map_Kd laikago_tex.jpg

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,13 @@
# Blender MTL File: 'laikago_textured.blend'
# Material Count: 1
newmtl None.004
Ns 0.000000
Ka 0.000000 0.000000 0.000000
Kd 0.800000 0.800000 0.800000
Ks 0.800000 0.800000 0.800000
Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 2
map_Kd laikago_tex.jpg

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,11 @@
# Blender MTL File: 'laikago_textured.blend'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2
map_Kd laikago_tex.jpg

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,11 @@
# Blender MTL File: 'laikago_textured.blend'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2
map_Kd laikago_tex.jpg

File diff suppressed because it is too large Load Diff

View File

@@ -1,10 +1,13 @@
# Blender MTL File: 'None' # Blender MTL File: 'laikago_textured.blend'
# Material Count: 1 # Material Count: 1
newmtl None newmtl None.002
Ns 0 Ns 0.000000
Ka 0.000000 0.000000 0.000000 Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8 Kd 0.800000 0.800000 0.800000
Ks 0.8 0.8 0.8 Ks 0.800000 0.800000 0.800000
d 1 Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 2 illum 2
map_Kd laikago_tex.jpg

File diff suppressed because it is too large Load Diff

View File

@@ -12,7 +12,7 @@ p.setTimeStep(1. / 500)
#p.setDefaultContactERP(0) #p.setDefaultContactERP(0)
#urdfFlags = p.URDF_USE_SELF_COLLISION+p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS #urdfFlags = p.URDF_USE_SELF_COLLISION+p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS
urdfFlags = p.URDF_USE_SELF_COLLISION urdfFlags = p.URDF_USE_SELF_COLLISION
quadruped = p.loadURDF("laikago/laikago.urdf", [0, 0, .5], [0, 0.5, 0.5, 0], quadruped = p.loadURDF("laikago/laikago_toes.urdf", [0, 0, .5], [0, 0.5, 0.5, 0],
flags=urdfFlags, flags=urdfFlags,
useFixedBase=False) useFixedBase=False)
@@ -87,6 +87,7 @@ with open(pd.getDataPath() + "/laikago/data1.txt", "r") as filestream:
# print(pt[9]) # print(pt[9])
time.sleep(1. / 500.) time.sleep(1. / 500.)
index = 0
for j in range(p.getNumJoints(quadruped)): for j in range(p.getNumJoints(quadruped)):
p.changeDynamics(quadruped, j, linearDamping=0, angularDamping=0) p.changeDynamics(quadruped, j, linearDamping=0, angularDamping=0)
info = p.getJointInfo(quadruped, j) info = p.getJointInfo(quadruped, j)
@@ -95,9 +96,10 @@ for j in range(p.getNumJoints(quadruped)):
jointName = info[1] jointName = info[1]
jointType = info[2] jointType = info[2]
if (jointType == p.JOINT_PRISMATIC or jointType == p.JOINT_REVOLUTE): if (jointType == p.JOINT_PRISMATIC or jointType == p.JOINT_REVOLUTE):
paramIds.append( paramIds.append(p.addUserDebugParameter(jointName.decode("utf-8"), -4, 4,
p.addUserDebugParameter(jointName.decode("utf-8"), -4, 4, (js[0] - jointOffsets[index]) / jointDirections[index]))
(js[0] - jointOffsets[j]) / jointDirections[j])) index = index+1
p.setRealTimeSimulation(1) p.setRealTimeSimulation(1)