add missing 'wheel.urdf" and very simple procedural terrain generation (sine wave)

This commit is contained in:
Erwin Coumans
2017-06-08 14:28:33 -07:00
parent 9d422c9b08
commit b325844b9a
4 changed files with 2713 additions and 0 deletions

2583
data/terrain.obj Normal file

File diff suppressed because it is too large Load Diff

59
data/terrain.py Normal file
View File

@@ -0,0 +1,59 @@
import math
NUM_VERTS_X = 30
NUM_VERTS_Y = 30
totalVerts = NUM_VERTS_X*NUM_VERTS_Y
totalTriangles = 2*(NUM_VERTS_X-1)*(NUM_VERTS_Y-1)
offset = -50.0
TRIANGLE_SIZE = 1.
waveheight=0.1
gGroundVertices = [None] * totalVerts*3
gGroundIndices = [None] * totalTriangles*3
i=0
for i in range (NUM_VERTS_X):
for j in range (NUM_VERTS_Y):
gGroundVertices[(i+j*NUM_VERTS_X)*3+0] = (i-NUM_VERTS_X*0.5)*TRIANGLE_SIZE
gGroundVertices[(i+j*NUM_VERTS_X)*3+1] = (j-NUM_VERTS_Y*0.5)*TRIANGLE_SIZE
gGroundVertices[(i+j*NUM_VERTS_X)*3+2] = waveheight*math.sin(float(i))*math.cos(float(j)+offset)
index=0
for i in range (NUM_VERTS_X-1):
for j in range (NUM_VERTS_Y-1):
gGroundIndices[index] = 1+j*NUM_VERTS_X+i
index+=1
gGroundIndices[index] = 1+j*NUM_VERTS_X+i+1
index+=1
gGroundIndices[index] = 1+(j+1)*NUM_VERTS_X+i+1
index+=1
gGroundIndices[index] = 1+j*NUM_VERTS_X+i
index+=1
gGroundIndices[index] = 1+(j+1)*NUM_VERTS_X+i+1
index+=1
gGroundIndices[index] = 1+(j+1)*NUM_VERTS_X+i
index+=1
#print(gGroundVertices)
#print(gGroundIndices)
print("o Terrain")
for i in range (totalVerts):
print("v "),
print(gGroundVertices[i*3+0]),
print(" "),
print(gGroundVertices[i*3+1]),
print(" "),
print(gGroundVertices[i*3+2])
for i in range (totalTriangles):
print("f "),
print(gGroundIndices[i*3+0]),
print(" "),
print(gGroundIndices[i*3+1]),
print(" "),
print(gGroundIndices[i*3+2]),
print(" ")

29
data/terrain.urdf Normal file
View File

@@ -0,0 +1,29 @@
<?xml version="0.0" ?>
<robot name="terrain">
<link name="terrainLink">
<contact>
<lateral_friction value="1"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value=".0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="terrain.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision concave="yes">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="terrain.obj" scale="1 1 1"/>
</geometry>
</collision>
</link>
</robot>

42
data/wheel.urdf Normal file
View File

@@ -0,0 +1,42 @@
<?xml version="1.0" ?>
<robot name="husky_robot" xmlns:xacro="http://ros.org/wiki/xacro">
<material name="White">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<link name="world"/>
<link name="front_left_wheel_link">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<mass value="2.637"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="husky/meshes/wheel.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.1143" radius="0.17775"/>
</geometry>
</collision>
</link>
<joint name="front_left_wheel" type="continuous">
<parent link="world"/>
<child link="front_left_wheel_link"/>
<origin rpy="0 0 0" xyz="0.256 0.2854 0.03282"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
</robot>