updated racecar files

master
mcarfagno 2020-07-01 14:33:16 +01:00
parent 6d3f0005ad
commit f7a46f2ead
70 changed files with 173107 additions and 126 deletions

File diff suppressed because one or more lines are too long

View File

@ -11,7 +11,7 @@
},
{
"cell_type": "code",
"execution_count": 1,
"execution_count": 2,
"metadata": {},
"outputs": [
{
@ -28,7 +28,7 @@
"[0, 0, 0, v*cos(psi), 0]])"
]
},
"execution_count": 1,
"execution_count": 2,
"metadata": {},
"output_type": "execute_result"
}
@ -52,7 +52,7 @@
},
{
"cell_type": "code",
"execution_count": 2,
"execution_count": 3,
"metadata": {},
"outputs": [
{
@ -69,7 +69,7 @@
"[ sin(psi), 0]])"
]
},
"execution_count": 2,
"execution_count": 3,
"metadata": {},
"output_type": "execute_result"
}
@ -83,7 +83,7 @@
},
{
"cell_type": "code",
"execution_count": 3,
"execution_count": 4,
"metadata": {},
"outputs": [
{
@ -98,7 +98,7 @@
"[0, 0, 1]])"
]
},
"execution_count": 3,
"execution_count": 4,
"metadata": {},
"output_type": "execute_result"
}
@ -120,7 +120,7 @@
},
{
"cell_type": "code",
"execution_count": 4,
"execution_count": 5,
"metadata": {},
"outputs": [
{
@ -135,7 +135,7 @@
"[ 0, dt]])"
]
},
"execution_count": 4,
"execution_count": 5,
"metadata": {},
"output_type": "execute_result"
}
@ -156,27 +156,9 @@
},
{
"cell_type": "code",
"execution_count": 8,
"execution_count": 6,
"metadata": {},
"outputs": [
{
"data": {
"text/latex": [
"$\\displaystyle \\left[\\begin{matrix}0 & 0 & \\cos{\\left(\\theta \\right)} & - v \\sin{\\left(\\theta \\right)}\\\\0 & 0 & \\sin{\\left(\\theta \\right)} & v \\cos{\\left(\\theta \\right)}\\\\0 & 0 & 0 & 0\\\\0 & 0 & \\frac{\\tan{\\left(\\delta \\right)}}{L} & 0\\end{matrix}\\right]$"
],
"text/plain": [
"Matrix([\n",
"[0, 0, cos(theta), -v*sin(theta)],\n",
"[0, 0, sin(theta), v*cos(theta)],\n",
"[0, 0, 0, 0],\n",
"[0, 0, tan(delta)/L, 0]])"
]
},
"execution_count": 8,
"metadata": {},
"output_type": "execute_result"
}
],
"outputs": [],
"source": [
"x,y,theta,v,delta,L,a = sp.symbols(\"x y theta v delta L a\")\n",
"\n",
@ -185,15 +167,20 @@
" [a],\n",
" [ v*sp.tan(delta)/L]])\n",
"\n",
"state = sp.Matrix([x,y,v,theta])\n",
"X = sp.Matrix([x,y,v,theta])\n",
"\n",
"#A\n",
"gs.jacobian(state)"
"A=gs.jacobian(X)\n",
"\n",
"U = sp.Matrix([a,delta])\n",
"\n",
"#B\n",
"B=gs.jacobian(U)#.subs({x:0,y:0,theta:0})B="
]
},
{
"cell_type": "code",
"execution_count": 7,
"execution_count": 15,
"metadata": {},
"outputs": [
{
@ -209,16 +196,96 @@
"[0, v*(tan(delta)**2 + 1)/L]])"
]
},
"execution_count": 7,
"execution_count": 15,
"metadata": {},
"output_type": "execute_result"
}
],
"source": [
"state = sp.Matrix([a,delta])\n",
"\n",
"#B\n",
"gs.jacobian(state)#.subs({x:0,y:0,theta:0})"
"B"
]
},
{
"cell_type": "code",
"execution_count": 10,
"metadata": {},
"outputs": [
{
"data": {
"text/latex": [
"$\\displaystyle \\left[\\begin{matrix}1 & 0 & dt \\cos{\\left(\\theta \\right)} & - dt v \\sin{\\left(\\theta \\right)}\\\\0 & 1 & dt \\sin{\\left(\\theta \\right)} & dt v \\cos{\\left(\\theta \\right)}\\\\0 & 0 & 1 & 0\\\\0 & 0 & \\frac{dt \\tan{\\left(\\delta \\right)}}{L} & 1\\end{matrix}\\right]$"
],
"text/plain": [
"Matrix([\n",
"[1, 0, dt*cos(theta), -dt*v*sin(theta)],\n",
"[0, 1, dt*sin(theta), dt*v*cos(theta)],\n",
"[0, 0, 1, 0],\n",
"[0, 0, dt*tan(delta)/L, 1]])"
]
},
"execution_count": 10,
"metadata": {},
"output_type": "execute_result"
}
],
"source": [
"#A LIN\n",
"DT = sp.symbols(\"dt\")\n",
"sp.eye(4)+A*DT"
]
},
{
"cell_type": "code",
"execution_count": 11,
"metadata": {},
"outputs": [
{
"data": {
"text/latex": [
"$\\displaystyle \\left[\\begin{matrix}0 & 0\\\\0 & 0\\\\dt & 0\\\\0 & \\frac{dt v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]$"
],
"text/plain": [
"Matrix([\n",
"[ 0, 0],\n",
"[ 0, 0],\n",
"[dt, 0],\n",
"[ 0, dt*v*(tan(delta)**2 + 1)/L]])"
]
},
"execution_count": 11,
"metadata": {},
"output_type": "execute_result"
}
],
"source": [
"B*DT"
]
},
{
"cell_type": "code",
"execution_count": 13,
"metadata": {},
"outputs": [
{
"data": {
"text/latex": [
"$\\displaystyle \\left[\\begin{matrix}dt \\theta v \\sin{\\left(\\theta \\right)}\\\\- dt \\theta v \\cos{\\left(\\theta \\right)}\\\\0\\\\- \\frac{\\delta dt v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]$"
],
"text/plain": [
"Matrix([\n",
"[ dt*theta*v*sin(theta)],\n",
"[ -dt*theta*v*cos(theta)],\n",
"[ 0],\n",
"[-delta*dt*v*(tan(delta)**2 + 1)/L]])"
]
},
"execution_count": 13,
"metadata": {},
"output_type": "execute_result"
}
],
"source": [
"DT*(gs - A*X - B*U)"
]
},
{
@ -422,6 +489,8 @@
"source": [
"It is necessary to take *actuation latency* into account: so instead of using the actual state as estimated, the delay factored in using the kinematic model\n",
"\n",
"Starting State is :\n",
"\n",
"* $x_{delay} = 0.0 + v * dt$\n",
"* $y_{delay} = 0.0$\n",
"* $psi_{delay} = 0.0 + w * dt$\n",

View File

@ -1,52 +0,0 @@
import pybullet as p
import pybullet_data
import time
import os
p.connect(p.GUI)
p.resetSimulation()
p.setGravity(0, 0, -10)
useRealTimeSim = 1
#for video recording (works best on Mac and Linux, not well on Windows)
#p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, "racecar.mp4")
p.setRealTimeSimulation(useRealTimeSim) # either this
p.loadURDF(os.path.join(pybullet_data.getDataPath(), "plane.urdf"))
car = p.loadURDF(os.path.join(pybullet_data.getDataPath(), "racecar/racecar.urdf"))
for i in range(p.getNumJoints(car)):
print(p.getJointInfo(car, i))
inactive_wheels = [3, 5, 7]
wheels = [2]
for wheel in inactive_wheels:
p.setJointMotorControl2(car, wheel, p.VELOCITY_CONTROL, targetVelocity=0, force=0)
steering = [4, 6]
targetVelocitySlider = p.addUserDebugParameter("wheelVelocity", -10, 10, 0)
maxForceSlider = p.addUserDebugParameter("maxForce", 0, 10, 10)
steeringSlider = p.addUserDebugParameter("steering", -0.5, 0.5, 0)
while (True):
maxForce = p.readUserDebugParameter(maxForceSlider)
targetVelocity = p.readUserDebugParameter(targetVelocitySlider)
steeringAngle = p.readUserDebugParameter(steeringSlider)
for wheel in wheels:
p.setJointMotorControl2(car,
wheel,
p.VELOCITY_CONTROL,
targetVelocity=targetVelocity,
force=maxForce)
for steer in steering:
p.setJointMotorControl2(car, steer, p.POSITION_CONTROL, targetPosition=steeringAngle)
if (useRealTimeSim == 0):
p.stepSimulation()
time.sleep(0.01)

BIN
racecar/checker_blue.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 6.2 KiB

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@ -0,0 +1,198 @@
<?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="diff_ring">
<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="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_ring.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<visual>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_carrier.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0.025 0"/>
<geometry>
<cylinder length="0.01" radius="0.05"/>
</geometry>
</collision>
</link>
<joint name="diff_ring_world" type="continuous">
<parent link="world"/>
<child link="diff_ring"/>
<origin rpy="0 0 0" xyz="0.256 0.2854 0.03282"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<link name="diff_spiderA">
<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="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_spider.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0.01 0"/>
<geometry>
<cylinder length="0.01" radius="0.015"/>
</geometry>
</collision>
</link>
<joint name="diff_spiderA_ring" type="continuous">
<parent link="diff_ring"/>
<child link="diff_spiderA"/>
<origin rpy="0 0 1.570795" xyz="0.0 0.0 0.0"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<link name="diff_spiderB">
<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="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_spider.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0.01 0"/>
<geometry>
<cylinder length="0.01" radius="0.015"/>
</geometry>
</collision>
</link>
<joint name="diff_spiderB_ring" type="continuous">
<parent link="diff_ring"/>
<child link="diff_spiderB"/>
<origin rpy="0 0 -1.570795" xyz="0.0 0.0 0.0"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<link name="diff_sideA">
<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="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_side.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0.01 0"/>
<geometry>
<cylinder length="0.01" radius="0.015"/>
</geometry>
</collision>
</link>
<joint name="diff_sideA_ring" type="continuous">
<parent link="diff_ring"/>
<child link="diff_sideA"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<link name="diff_sideB">
<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="-1.570795 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_side.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="-1.570795 0 0" xyz="0 -0.01 0"/>
<geometry>
<cylinder length="0.01" radius="0.015"/>
</geometry>
</collision>
</link>
<joint name="diff_sideB_ring" type="continuous">
<parent link="diff_ring"/>
<child link="diff_sideB"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
</robot>

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@ -0,0 +1,2 @@
stl files were copied from http://www.otvinta.com/download09.html
URDF file was manually created, along with mimicJointConstraint.py

View File

@ -0,0 +1,65 @@
# Blender MTL File: 'None'
# Material Count: 7
newmtl Grass
Ns 1.960784
Ka 0.000000 0.000000 0.000000
Kd 0.034510 0.131765 0.028235
Ks 0.000000 0.000000 0.000000
Ni -1.000000
d 1.000000
illum 2
newmtl Road
Ns 1.960784
Ka 0.000000 0.000000 0.000000
Kd 0.172549 0.172549 0.172549
Ks 0.000000 0.000000 0.000000
Ni -1.000000
d 1.000000
illum 2
newmtl Text
Ns 1.960784
Ka 0.000000 0.000000 0.000000
Kd 0.608627 0.445490 0.163138
Ks 0.000000 0.000000 0.000000
Ni -1.000000
d 1.000000
illum 2
newmtl Wall-top
Ns 1.960784
Ka 0.000000 0.000000 0.000000
Kd 0.040784 0.087843 0.235294
Ks 0.000000 0.000000 0.000000
Ni -1.000000
d 1.000000
illum 2
newmtl Walls
Ns 1.960784
Ka 0.000000 0.000000 0.000000
Kd 0.288627 0.649412 0.652549
Ks 0.000000 0.000000 0.000000
Ni -1.000000
d 1.000000
illum 2
newmtl Water
Ns 1.960784
Ka 0.000000 0.000000 0.000000
Kd 0.131765 0.250981 0.495686
Ks 0.000000 0.000000 0.000000
Ni -1.000000
d 1.000000
illum 2
newmtl water-wall
Ns 1.960784
Ka 0.000000 0.000000 0.000000
Kd 0.564706 0.125490 0.125490
Ks 0.000000 0.000000 0.000000
Ni -1.000000
d 1.000000
illum 2

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,279 @@
<sdf version='1.6'>
<world name='default'>
<gravity>0 0 -9.8</gravity>
<model name='part0.obj'>
<static>1</static>
<pose frame=''>0 0 0 0 0 0</pose>
<link name='link_d0'>
<inertial>
<mass>0</mass>
<inertia>
<ixx>0.166667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.166667</iyy>
<iyz>0</iyz>
<izz>0.166667</izz>
</inertia>
</inertial>
<collision concave='yes' name='collision_0'>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>part0.obj</uri>
</mesh>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>part0.obj</uri>
</mesh>
</geometry>
<material>
<ambient>1 1 1 1</ambient>
<diffuse>1 1 1 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
</model>
<model name='part1.obj'>
<static>1</static>
<pose frame=''>0 0 0 0 0 0</pose>
<link name='link_d1'>
<inertial>
<mass>0</mass>
<inertia>
<ixx>0.166667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.166667</iyy>
<iyz>0</iyz>
<izz>0.166667</izz>
</inertia>
</inertial>
<collision concave='yes' name='collision_1'>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>part1.obj</uri>
</mesh>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>part1.obj</uri>
</mesh>
</geometry>
<material>
<ambient>1 1 1 1</ambient>
<diffuse>0.2 0.6 0.2 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
</model>
<model name='part2.obj'>
<static>1</static>
<pose frame=''>0 0 0 0 0 0</pose>
<link name='link_d2'>
<inertial>
<mass>0</mass>
<inertia>
<ixx>0.166667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.166667</iyy>
<iyz>0</iyz>
<izz>0.166667</izz>
</inertia>
</inertial>
<collision concave='yes' name='collision_2'>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>part2.obj</uri>
</mesh>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>part2.obj</uri>
</mesh>
</geometry>
<material>
<ambient>1 1 1 1</ambient>
<diffuse>1 1 0 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
</model>
<model name='part3.obj'>
<static>1</static>
<pose frame=''>0 0 0 0 0 0</pose>
<link name='link_d3'>
<inertial>
<mass>0</mass>
<inertia>
<ixx>0.166667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.166667</iyy>
<iyz>0</iyz>
<izz>0.166667</izz>
</inertia>
</inertial>
<collision concave='yes' name='collision_3'>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>part3.obj</uri>
</mesh>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>part3.obj</uri>
</mesh>
</geometry>
<material>
<ambient>1 1 1 1</ambient>
<diffuse>1 1 0 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
</model>
<model name='part4.obj'>
<static>1</static>
<pose frame=''>0 0 0 0 0 0</pose>
<link name='link_d4'>
<inertial>
<mass>0</mass>
<inertia>
<ixx>0.166667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.166667</iyy>
<iyz>0</iyz>
<izz>0.166667</izz>
</inertia>
</inertial>
<collision concave='yes' name='collision_4'>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>part4.obj</uri>
</mesh>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>part4.obj</uri>
</mesh>
</geometry>
<material>
<ambient>1 1 1 1</ambient>
<diffuse>0.5 0.5 1 1.000000</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
</model>
<model name='part5.obj'>
<static>1</static>
<pose frame=''>0 0 0 0 0 0</pose>
<link name='link_d5'>
<inertial>
<mass>0</mass>
<inertia>
<ixx>0.166667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.166667</iyy>
<iyz>0</iyz>
<izz>0.166667</izz>
</inertia>
</inertial>
<collision concave='yes' name='collision_5'>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>part5.obj</uri>
</mesh>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>part5.obj</uri>
</mesh>
</geometry>
<material>
<ambient>1 1 1 1</ambient>
<diffuse>0.6 0.6 1 .6</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
</model>
<model name='part6.obj'>
<static>1</static>
<pose frame=''>0 0 0 0 0 0</pose>
<link name='link_d6'>
<inertial>
<mass>0</mass>
<inertia>
<ixx>0.166667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.166667</iyy>
<iyz>0</iyz>
<izz>0.166667</izz>
</inertia>
</inertial>
<collision concave='yes' name='collision_6'>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>part6.obj</uri>
</mesh>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>part6.obj</uri>
</mesh>
</geometry>
<material>
<ambient>1 1 1 1</ambient>
<diffuse>0.6 0.6 0.6 1.000000</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
</model>
</world>
</sdf>

Binary file not shown.

File diff suppressed because one or more lines are too long

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 6.2 KiB

View File

@ -0,0 +1,123 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<authoring_tool>SketchUp 15.3.331</authoring_tool>
</contributor>
<created>2016-03-10T00:21:04Z</created>
<modified>2016-03-10T00:21:04Z</modified>
<unit meter="0.0254" name="inch" />
<up_axis>Z_UP</up_axis>
</asset>
<library_visual_scenes>
<visual_scene id="ID1">
<node name="SketchUp">
<instance_geometry url="#ID2">
<bind_material>
<technique_common>
<instance_material symbol="Material2" target="#ID3">
<bind_vertex_input semantic="UVSET0" input_semantic="TEXCOORD" input_set="0" />
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
<instance_geometry url="#ID10">
<bind_material>
<technique_common>
<instance_material symbol="Material2" target="#ID3">
<bind_vertex_input semantic="UVSET0" input_semantic="TEXCOORD" input_set="0" />
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<library_geometries>
<geometry id="ID2">
<mesh>
<source id="ID5">
<float_array id="ID8" count="108">2.952756 2.952756 0 -2.952756 -2.952756 0 -2.952756 2.952756 0 2.952756 -2.952756 0 -2.952756 2.952756 0.1968504 2.952756 2.952756 0 -2.952756 2.952756 0 2.952756 2.952756 0.1968504 2.952756 2.952756 0 2.952756 -2.952756 0.1968504 2.952756 -2.952756 0 2.952756 2.952756 0.1968504 2.952756 -2.952756 0.1968504 -2.952756 -2.952756 0 2.952756 -2.952756 0 -2.952756 -2.952756 0.1968504 -2.952756 2.952756 0.1968504 -2.952756 -2.952756 0 -2.952756 -2.952756 0.1968504 -2.952756 2.952756 0 -2.952756 -2.952756 0.1968504 -2.362205 0 0.1968504 -2.952756 2.952756 0.1968504 -2.045729 -1.181102 0.1968504 -1.181102 -2.045729 0.1968504 4.440892e-016 -2.362205 0.1968504 2.952756 -2.952756 0.1968504 1.181102 -2.045729 0.1968504 2.045729 -1.181102 0.1968504 2.362205 4.440892e-016 0.1968504 0 2.362205 0.1968504 2.952756 2.952756 0.1968504 -1.181102 2.045729 0.1968504 -2.045729 1.181102 0.1968504 1.181102 2.045729 0.1968504 2.045729 1.181102 0.1968504</float_array>
<technique_common>
<accessor count="36" source="#ID8" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<source id="ID6">
<float_array id="ID9" count="108">0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1</float_array>
<technique_common>
<accessor count="36" source="#ID9" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<vertices id="ID7">
<input semantic="POSITION" source="#ID5" />
<input semantic="NORMAL" source="#ID6" />
</vertices>
<triangles count="26" material="Material2">
<input offset="0" semantic="VERTEX" source="#ID7" />
<p>0 1 2 1 0 3 4 5 6 5 4 7 8 9 10 9 8 11 12 13 14 13 12 15 16 17 18 17 16 19 20 21 22 21 20 23 23 20 24 24 20 25 25 20 26 25 26 27 27 26 28 28 26 29 22 30 31 30 22 32 32 22 33 33 22 21 31 30 34 31 34 35 31 35 29 31 29 26</p>
</triangles>
</mesh>
</geometry>
<geometry id="ID10">
<mesh>
<source id="ID11">
<float_array id="ID14" count="72">-2.045729 1.181102 0.1968504 -2.362205 0 0.1968504 0 0 6.692913 -2.045729 -1.181102 0.1968504 0 0 6.692913 -1.181102 2.045729 0.1968504 0 0 6.692913 0 0 6.692913 -1.181102 -2.045729 0.1968504 0 0 6.692913 0 2.362205 0.1968504 0 0 6.692913 4.440892e-016 -2.362205 0.1968504 0 0 6.692913 1.181102 2.045729 0.1968504 0 0 6.692913 1.181102 -2.045729 0.1968504 0 0 6.692913 2.045729 1.181102 0.1968504 0 0 6.692913 2.045729 -1.181102 0.1968504 0 0 6.692913 2.362205 4.440892e-016 0.1968504 0 0 6.692913</float_array>
<technique_common>
<accessor count="24" source="#ID14" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<source id="ID12">
<float_array id="ID15" count="72">-0.813885 0.4698967 0.3417431 -0.9397934 -3.08962e-016 0.3417431 -0.9113426 0.2441935 0.3313973 -0.813885 -0.4698967 0.3417431 -0.9113426 -0.2441935 0.3313973 -0.4698967 0.813885 0.3417431 -0.6671491 0.6671491 0.3313973 -0.6671491 -0.6671491 0.3313973 -0.4698967 -0.813885 0.3417431 -0.2441935 0.9113426 0.3313973 -1.737911e-016 0.9397934 0.3417431 -0.2441935 -0.9113426 0.3313973 2.317215e-016 -0.9397934 0.3417431 0.2441935 0.9113426 0.3313973 0.4698967 0.813885 0.3417431 0.2441935 -0.9113426 0.3313973 0.4698967 -0.813885 0.3417431 0.6671491 0.6671491 0.3313973 0.813885 0.4698967 0.3417431 0.6671491 -0.6671491 0.3313973 0.813885 -0.4698967 0.3417431 0.9113426 0.2441935 0.3313973 0.9397934 -2.896519e-016 0.3417431 0.9113426 -0.2441935 0.3313973</float_array>
<technique_common>
<accessor count="24" source="#ID15" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<vertices id="ID13">
<input semantic="POSITION" source="#ID11" />
<input semantic="NORMAL" source="#ID12" />
</vertices>
<triangles count="12" material="Material2">
<input offset="0" semantic="VERTEX" source="#ID13" />
<p>0 1 2 1 3 4 5 0 6 7 3 8 9 10 5 11 8 12 13 14 10 15 12 16 17 18 14 19 16 20 18 21 22 22 23 20</p>
</triangles>
</mesh>
</geometry>
</library_geometries>
<library_materials>
<material id="ID3" name="material_1">
<instance_effect url="#ID4" />
</material>
</library_materials>
<library_effects>
<effect id="ID4">
<profile_COMMON>
<technique sid="COMMON">
<lambert>
<diffuse>
<color>0.7529412 0.3764706 0.0627451 1</color>
</diffuse>
</lambert>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<scene>
<instance_visual_scene url="#ID1" />
</scene>
</COLLADA>

View File

@ -0,0 +1,11 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl material_1
Ns 96.078431
Ka 0.000000 0.000000 0.000000
Kd 0.602353 0.301176 0.050196
Ks 0.500000 0.500000 0.500000
Ni -1.000000
d 1.000000
illum 2

View File

@ -0,0 +1,125 @@
# Blender v2.71 (sub 0) OBJ File: ''
# www.blender.org
mtllib cone.mtl
o SketchUp.001_ID10
v -0.051962 0.030000 0.005000
v -0.060000 0.000000 0.005000
v 0.000000 0.000000 0.170000
v -0.051962 -0.030000 0.005000
v 0.000000 0.000000 0.170000
v -0.030000 0.051962 0.005000
v 0.000000 0.000000 0.170000
v 0.000000 0.000000 0.170000
v -0.030000 -0.051962 0.005000
v 0.000000 0.000000 0.170000
v 0.000000 0.060000 0.005000
v 0.000000 0.000000 0.170000
v 0.000000 -0.060000 0.005000
v 0.000000 0.000000 0.170000
v 0.030000 0.051962 0.005000
v 0.000000 0.000000 0.170000
v 0.030000 -0.051962 0.005000
v 0.000000 0.000000 0.170000
v 0.051962 0.030000 0.005000
v 0.000000 0.000000 0.170000
v 0.051962 -0.030000 0.005000
v 0.000000 0.000000 0.170000
v 0.060000 0.000000 0.005000
v 0.000000 0.000000 0.170000
vn -0.911300 0.244200 0.331400
vn -0.911300 -0.244200 0.331400
vn -0.667100 0.667100 0.331400
vn -0.667100 -0.667100 0.331400
vn -0.244200 0.911300 0.331400
vn -0.244200 -0.911300 0.331400
vn 0.244200 0.911300 0.331400
vn 0.244200 -0.911300 0.331400
vn 0.667100 0.667100 0.331400
vn 0.667100 -0.667100 0.331400
vn 0.911300 0.244200 0.331400
vn 0.911300 -0.244200 0.331400
usemtl material_1
s 1
f 1//1 2//1 3//1
f 2//2 4//2 5//2
f 6//3 1//3 7//3
f 8//4 4//4 9//4
f 10//5 11//5 6//5
f 12//6 9//6 13//6
f 14//7 15//7 11//7
f 16//8 13//8 17//8
f 18//9 19//9 15//9
f 20//10 17//10 21//10
f 19//11 22//11 23//11
f 23//12 24//12 21//12
o SketchUp_ID2
v 0.075000 0.075000 0.000000
v -0.075000 -0.075000 0.000000
v -0.075000 0.075000 0.000000
v 0.075000 -0.075000 0.000000
v -0.075000 0.075000 0.005000
v 0.075000 0.075000 0.000000
v -0.075000 0.075000 0.000000
v 0.075000 0.075000 0.005000
v 0.075000 0.075000 0.000000
v 0.075000 -0.075000 0.005000
v 0.075000 -0.075000 0.000000
v 0.075000 0.075000 0.005000
v 0.075000 -0.075000 0.005000
v -0.075000 -0.075000 0.000000
v 0.075000 -0.075000 0.000000
v -0.075000 -0.075000 0.005000
v -0.075000 0.075000 0.005000
v -0.075000 -0.075000 0.000000
v -0.075000 -0.075000 0.005000
v -0.075000 0.075000 0.000000
v -0.075000 -0.075000 0.005000
v -0.060000 0.000000 0.005000
v -0.075000 0.075000 0.005000
v -0.051962 -0.030000 0.005000
v -0.030000 -0.051962 0.005000
v 0.000000 -0.060000 0.005000
v 0.075000 -0.075000 0.005000
v 0.030000 -0.051962 0.005000
v 0.051962 -0.030000 0.005000
v 0.060000 0.000000 0.005000
v 0.000000 0.060000 0.005000
v 0.075000 0.075000 0.005000
v -0.030000 0.051962 0.005000
v -0.051962 0.030000 0.005000
v 0.030000 0.051962 0.005000
v 0.051962 0.030000 0.005000
vn 0.000000 0.000000 -1.000000
vn 0.000000 1.000000 0.000000
vn 1.000000 0.000000 0.000000
vn 0.000000 -1.000000 0.000000
vn -1.000000 0.000000 0.000000
vn 0.000000 0.000000 1.000000
usemtl material_1
s 1
f 25//13 26//13 27//13
f 26//13 25//13 28//13
f 29//14 30//14 31//14
f 30//14 29//14 32//14
f 33//15 34//15 35//15
f 34//15 33//15 36//15
f 37//16 38//16 39//16
f 38//16 37//16 40//16
f 41//17 42//17 43//17
f 42//17 41//17 44//17
f 45//18 46//18 47//18
f 46//18 45//18 48//18
f 48//18 45//18 49//18
f 49//18 45//18 50//18
f 50//18 45//18 51//18
f 50//18 51//18 52//18
f 52//18 51//18 53//18
f 53//18 51//18 54//18
f 47//18 55//18 56//18
f 55//18 47//18 57//18
f 57//18 47//18 58//18
f 58//18 47//18 46//18
f 56//18 55//18 59//18
f 56//18 59//18 60//18
f 56//18 60//18 54//18
f 56//18 54//18 51//18

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,20 @@
# Blender MTL File: 'None'
# Material Count: 2
newmtl black-material
Ns 21.568627
Ka 0.000000 0.000000 0.000000
Kd 0.016250 0.016250 0.016250
Ks 0.125000 0.125000 0.125000
Ni 1.000000
d 1.000000
illum 2
newmtl white_001-material
Ns -1.960784
Ka 0.000000 0.000000 0.000000
Kd 0.556090 0.556090 0.556090
Ks 0.031250 0.031250 0.031250
Ni 1.000000
d 1.000000
illum 2

File diff suppressed because it is too large Load Diff

Binary file not shown.

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,11 @@
# Blender MTL File: 'None'
# 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 wheel.jpg

File diff suppressed because it is too large Load Diff

Binary file not shown.

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,11 @@
# Blender MTL File: 'None'
# 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 wheel.jpg

File diff suppressed because it is too large Load Diff

Binary file not shown.

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,310 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Blender User</author>
<authoring_tool>Blender 2.78.0</authoring_tool>
</contributor>
<created>2017-04-24T15:08:21</created>
<modified>2017-04-24T15:08:21</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_cameras>
<camera id="Camera-camera" name="Camera">
<optics>
<technique_common>
<perspective>
<xfov sid="xfov">49.13434</xfov>
<aspect_ratio>1.777778</aspect_ratio>
<znear sid="znear">0.1</znear>
<zfar sid="zfar">100</zfar>
</perspective>
</technique_common>
</optics>
<extra>
<technique profile="blender">
<YF_dofdist>0</YF_dofdist>
<shiftx>0</shiftx>
<shifty>0</shifty>
</technique>
</extra>
</camera>
</library_cameras>
<library_lights>
<light id="Lamp-light" name="Lamp">
<technique_common>
<point>
<color sid="color">1 1 1</color>
<constant_attenuation>1</constant_attenuation>
<linear_attenuation>0</linear_attenuation>
<quadratic_attenuation>0.00111109</quadratic_attenuation>
</point>
</technique_common>
<extra>
<technique profile="blender">
<adapt_thresh>0.000999987</adapt_thresh>
<area_shape>1</area_shape>
<area_size>0.1</area_size>
<area_sizey>0.1</area_sizey>
<area_sizez>1</area_sizez>
<atm_distance_factor>1</atm_distance_factor>
<atm_extinction_factor>1</atm_extinction_factor>
<atm_turbidity>2</atm_turbidity>
<att1>0</att1>
<att2>1</att2>
<backscattered_light>1</backscattered_light>
<bias>1</bias>
<blue>1</blue>
<buffers>1</buffers>
<bufflag>0</bufflag>
<bufsize>2880</bufsize>
<buftype>2</buftype>
<clipend>30.002</clipend>
<clipsta>1.000799</clipsta>
<compressthresh>0.04999995</compressthresh>
<dist sid="blender_dist">29.99998</dist>
<energy sid="blender_energy">1</energy>
<falloff_type>2</falloff_type>
<filtertype>0</filtertype>
<flag>0</flag>
<gamma sid="blender_gamma">1</gamma>
<green>1</green>
<halo_intensity sid="blnder_halo_intensity">1</halo_intensity>
<horizon_brightness>1</horizon_brightness>
<mode>8192</mode>
<ray_samp>1</ray_samp>
<ray_samp_method>1</ray_samp_method>
<ray_samp_type>0</ray_samp_type>
<ray_sampy>1</ray_sampy>
<ray_sampz>1</ray_sampz>
<red>1</red>
<samp>3</samp>
<shadhalostep>0</shadhalostep>
<shadow_b sid="blender_shadow_b">0</shadow_b>
<shadow_g sid="blender_shadow_g">0</shadow_g>
<shadow_r sid="blender_shadow_r">0</shadow_r>
<sky_colorspace>0</sky_colorspace>
<sky_exposure>1</sky_exposure>
<skyblendfac>1</skyblendfac>
<skyblendtype>1</skyblendtype>
<soft>3</soft>
<spotblend>0.15</spotblend>
<spotsize>75</spotsize>
<spread>1</spread>
<sun_brightness>1</sun_brightness>
<sun_effect_type>0</sun_effect_type>
<sun_intensity>1</sun_intensity>
<sun_size>1</sun_size>
<type>0</type>
</technique>
</extra>
</light>
</library_lights>
<library_images/>
<library_effects>
<effect id="Material_001-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.64 0.03905561 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material_001-material" name="Material_001">
<instance_effect url="#Material_001-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube_004-mesh" name="Cube.004">
<mesh>
<source id="Cube_004-mesh-positions">
<float_array id="Cube_004-mesh-positions-array" count="24">-1 -1 -1 -1 -1 1 -1 1 -1 -1 1 1 1 -1 -1 1 -1 1 1 1 -1 1 1 1</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_004-mesh-normals">
<float_array id="Cube_004-mesh-normals-array" count="18">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-normals-array" count="6" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_004-mesh-vertices">
<input semantic="POSITION" source="#Cube_004-mesh-positions"/>
</vertices>
<polylist count="12">
<input semantic="VERTEX" source="#Cube_004-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_004-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>3 0 0 0 1 0 7 1 2 1 3 1 5 2 6 2 7 2 1 3 4 3 5 3 2 4 4 4 0 4 7 5 1 5 5 5 3 0 2 0 0 0 7 1 6 1 2 1 5 2 4 2 6 2 1 3 0 3 4 3 2 4 6 4 4 4 7 5 3 5 1 5</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_002-mesh" name="Cube.002">
<mesh>
<source id="Cube_002-mesh-positions">
<float_array id="Cube_002-mesh-positions-array" count="24">-1 -1 -1 -1 -1 1 -1 1 -1 -1 1 1 1 -1 -1 1 -1 1 1 1 -1 1 1 1</float_array>
<technique_common>
<accessor source="#Cube_002-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_002-mesh-normals">
<float_array id="Cube_002-mesh-normals-array" count="18">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_002-mesh-normals-array" count="6" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_002-mesh-vertices">
<input semantic="POSITION" source="#Cube_002-mesh-positions"/>
</vertices>
<polylist count="12">
<input semantic="VERTEX" source="#Cube_002-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_002-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>3 0 0 0 1 0 7 1 2 1 3 1 5 2 6 2 7 2 1 3 4 3 5 3 2 4 4 4 0 4 7 5 1 5 5 5 3 0 2 0 0 0 7 1 6 1 2 1 5 2 4 2 6 2 1 3 0 3 4 3 2 4 6 4 4 4 7 5 3 5 1 5</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_003-mesh" name="Cube.003">
<mesh>
<source id="Cube_003-mesh-positions">
<float_array id="Cube_003-mesh-positions-array" count="24">-1 -1 -1 -1 -1 1 -1 1 -1 -1 1 1 1 -1 -1 1 -1 1 1 1 -1 1 1 1</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_003-mesh-normals">
<float_array id="Cube_003-mesh-normals-array" count="18">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-normals-array" count="6" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_003-mesh-vertices">
<input semantic="POSITION" source="#Cube_003-mesh-positions"/>
</vertices>
<polylist count="12">
<input semantic="VERTEX" source="#Cube_003-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_003-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>3 0 0 0 1 0 7 1 2 1 3 1 5 2 6 2 7 2 1 3 4 3 5 3 2 4 4 4 0 4 7 5 1 5 5 5 3 0 2 0 0 0 7 1 6 1 2 1 5 2 4 2 6 2 1 3 0 3 4 3 2 4 6 4 4 4 7 5 3 5 1 5</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">-1 -1 -1 -1 -1 1 -1 1 -1 -1 1 1 1 -1 -1 1 -1 1 1 1 -1 1 1 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="18">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="6" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material_001-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 0 0 3 1 6 1 2 1 7 2 4 2 6 2 5 3 0 3 4 3 6 4 0 4 2 4 3 5 5 5 7 5 1 0 3 0 2 0 3 1 7 1 6 1 7 2 5 2 4 2 5 3 1 3 0 3 6 4 4 4 0 4 3 5 1 5 5 5</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube_002" name="Cube_002" type="NODE">
<matrix sid="transform">0.1354637 0 0 -3.735135 0 0.3 0 3.623344 0 0 0.15 0.1530263 0 0 0 1</matrix>
<instance_geometry url="#Cube_004-mesh" name="Cube_002"/>
</node>
<node id="Camera" name="Camera" type="NODE">
<matrix sid="transform">0.6858805 -0.3173701 0.6548619 7.481132 0.7276338 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953432 0.4452454 5.343665 0 0 0 1</matrix>
<instance_camera url="#Camera-camera"/>
</node>
<node id="Lamp" name="Lamp" type="NODE">
<matrix sid="transform">-0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1</matrix>
<instance_light url="#Lamp-light"/>
</node>
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.173696 0 0 -4.197643 0 5.482737 0 4.50726 0 0 1 1.015023 0 0 0 1</matrix>
<instance_geometry url="#Cube_002-mesh" name="Cube"/>
</node>
<node id="Cube_001" name="Cube_001" type="NODE">
<matrix sid="transform">0.1354637 0 0 -3.735135 0 0.3 0 5.201571 0 0 0.15 0.1727542 0 0 0 1</matrix>
<instance_geometry url="#Cube_003-mesh" name="Cube_001"/>
</node>
<node id="Cube_003" name="Cube_003" type="NODE">
<matrix sid="transform">0.225 0 0 -3.795233 0 0.38 0 4.425851 0 0 0.005 0.01 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh" name="Cube_003">
<bind_material>
<technique_common>
<instance_material symbol="Material_001-material" target="#Material_001-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,60 @@
# Exported using automatic converter by Erwin Coumans
mtllib barca_track.mtl
#object Box001_Box001Mesh
v -29.086922 9.944676 0.000000
v 40.913078 9.944676 0.000000
v -29.086922 -15.055324 0.000000
v 40.913078 -15.055324 0.000000
v 40.913078 9.944676 0.020000
v -29.086922 9.944676 0.020000
v -29.086922 -15.055324 0.020000
v 40.913078 -15.055324 0.020000
v 40.913078 -15.055324 0.020000
v -29.086922 -15.055324 0.020000
v -29.086922 -15.055324 0.000000
v 40.913078 -15.055324 0.000000
v 40.913078 -15.055324 0.020000
v 40.913078 9.944676 0.000000
v -29.086922 9.944676 0.020000
v 40.913078 9.944676 0.020000
v 40.913078 9.944676 0.000000
v -29.086922 9.944676 0.000000
v -29.086922 -15.055324 0.020000
v -29.086922 9.944676 0.000000
usemtl Grass
vt 1.000000 1.000000
vt 0.000000 1.000000
vt 1.000000 0.000000
vt 0.000000 0.000000
vt 1.000000 1.000000
vt 0.000000 1.000000
vt 0.000000 0.000000
vt 1.000000 0.000000
vt 1.000000 1.000000
vt 0.000000 1.000000
vt 0.000000 0.000000
vt 1.000000 0.000000
vt 0.000000 1.000000
vt 1.000000 0.000000
vt 1.000000 1.000000
vt 0.000000 1.000000
vt 0.000000 0.000000
vt 1.000000 0.000000
vt 1.000000 1.000000
vt 0.000000 0.000000
s off
f 1/1/1 2/2/2 3/3/3
f 4/4/4 3/3/3 2/2/2
f 5/5/5 6/6/6 7/7/7
f 5/5/5 7/7/7 8/8/8
f 9/9/9 10/10/10 11/11/11
f 9/9/9 11/11/11 12/12/12
f 5/5/5 13/13/13 4/4/4
f 5/5/5 4/4/4 14/14/14
f 15/15/15 16/16/16 17/17/17
f 15/15/15 17/17/17 18/18/18
f 19/19/19 6/6/6 20/20/20
f 19/19/19 20/20/20 3/3/3

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,596 @@
# Exported using automatic converter by Erwin Coumans
mtllib barca_track.mtl
#object Line003_Line003Mesh
v 2.421222 -0.056734 0.000000
v 2.016600 -0.915003 0.000000
v 2.016600 -0.915003 0.050000
v 2.421222 -0.056734 0.050000
v 25.725058 -7.755845 0.000000
v 25.943077 -6.713602 0.000000
v 26.076797 -7.281773 0.000000
v 24.768164 -8.115381 0.000000
v 25.443592 -6.071772 0.000000
v 24.698034 -5.376718 0.000000
v 22.918129 -8.349623 0.000000
v 23.826099 -4.648877 0.000000
v 20.185341 -8.473146 0.000000
v 22.947475 -3.908688 0.000000
v 21.930237 -3.090331 0.000000
v 20.624008 -2.153702 0.000000
v 16.897701 -8.503529 0.000000
v 19.120823 -1.157807 0.000000
v 17.512718 -0.161649 0.000000
v 13.383091 -8.458340 0.000000
v 15.891727 0.775766 0.000000
v 14.349886 1.595434 0.000000
v 9.969400 -8.355156 0.000000
v 12.979229 2.238349 0.000000
v 11.736139 2.739689 0.000000
v 6.984523 -8.211549 0.000000
v 10.524273 3.163628 0.000000
v 9.356565 3.494656 0.000000
v 8.245951 3.717267 0.000000
v 7.205369 3.815950 0.000000
v 6.247754 3.775198 0.000000
v 5.386044 3.579500 0.000000
v 4.627831 3.166082 0.000000
v 3.964148 2.527806 0.000000
v 3.383090 1.732615 0.000000
v 2.872750 0.848454 0.000000
v 2.421222 -0.056734 0.000000
v 2.016600 -0.915003 0.000000
v 4.756348 -8.045094 0.000000
v 1.646977 -1.658409 0.000000
v 1.289131 -2.314162 0.000000
v 3.263519 -7.845060 0.000000
v 0.945906 -2.951725 0.000000
v 2.207457 -7.592249 0.000000
v 0.644491 -3.566539 0.000000
v 0.412079 -4.154041 0.000000
v 1.500222 -7.291535 0.000000
v 0.275862 -4.709673 0.000000
v 0.263029 -5.228873 0.000000
v 0.400775 -5.707081 0.000000
v 0.592093 -6.150689 0.000000
v 1.053878 -6.947789 0.000000
v 0.780479 -6.565883 0.000000
v 25.725058 -7.755845 0.050000
v 26.076797 -7.281773 0.050000
v 25.943077 -6.713602 0.050000
v 24.768164 -8.115381 0.050000
v 25.443592 -6.071772 0.050000
v 24.698034 -5.376718 0.050000
v 22.918129 -8.349623 0.050000
v 23.826099 -4.648877 0.050000
v 20.185341 -8.473146 0.050000
v 22.947475 -3.908688 0.050000
v 21.930237 -3.090331 0.050000
v 20.624008 -2.153702 0.050000
v 16.897701 -8.503529 0.050000
v 19.120823 -1.157807 0.050000
v 17.512718 -0.161649 0.050000
v 13.383091 -8.458340 0.050000
v 15.891727 0.775766 0.050000
v 14.349886 1.595434 0.050000
v 9.969400 -8.355156 0.050000
v 12.979229 2.238349 0.050000
v 11.736139 2.739689 0.050000
v 6.984523 -8.211549 0.050000
v 10.524273 3.163628 0.050000
v 9.356565 3.494656 0.050000
v 8.245951 3.717267 0.050000
v 7.205369 3.815950 0.050000
v 6.247754 3.775198 0.050000
v 5.386044 3.579500 0.050000
v 4.627831 3.166082 0.050000
v 3.964148 2.527806 0.050000
v 3.383090 1.732615 0.050000
v 2.872750 0.848454 0.050000
v 2.421222 -0.056734 0.050000
v 2.016600 -0.915003 0.050000
v 4.756348 -8.045094 0.050000
v 1.646977 -1.658409 0.050000
v 1.289131 -2.314162 0.050000
v 3.263519 -7.845060 0.050000
v 0.945906 -2.951725 0.050000
v 2.207457 -7.592249 0.050000
v 0.644491 -3.566539 0.050000
v 0.412079 -4.154041 0.050000
v 1.500222 -7.291535 0.050000
v 0.275862 -4.709673 0.050000
v 0.263029 -5.228873 0.050000
v 0.400775 -5.707081 0.050000
v 0.592093 -6.150689 0.050000
v 1.053878 -6.947789 0.050000
v 0.780479 -6.565883 0.050000
v 5.386044 3.579500 0.000000
v 4.627831 3.166082 0.000000
v 4.627831 3.166082 0.050000
v 5.386044 3.579500 0.050000
v 3.964148 2.527806 0.000000
v 3.964148 2.527806 0.050000
v 3.383090 1.732615 0.000000
v 3.383090 1.732615 0.050000
v 2.872750 0.848454 0.000000
v 2.872750 0.848454 0.050000
v 1.646977 -1.658409 0.000000
v 1.646977 -1.658409 0.050000
v 1.289131 -2.314162 0.000000
v 1.289131 -2.314162 0.050000
v 0.945906 -2.951725 0.000000
v 0.945906 -2.951725 0.050000
v 0.644491 -3.566539 0.000000
v 0.644491 -3.566539 0.050000
v 0.412079 -4.154041 0.000000
v 0.412079 -4.154041 0.050000
v 0.275862 -4.709673 0.000000
v 0.275862 -4.709673 0.050000
v 0.263029 -5.228873 0.000000
v 0.263029 -5.228873 0.050000
v 0.400775 -5.707081 0.000000
v 0.400775 -5.707081 0.050000
v 0.592093 -6.150689 0.000000
v 0.592093 -6.150689 0.050000
v 0.780479 -6.565883 0.000000
v 0.780479 -6.565883 0.050000
v 1.053878 -6.947789 0.000000
v 1.053878 -6.947789 0.050000
v 1.500222 -7.291535 0.000000
v 1.500222 -7.291535 0.050000
v 2.207457 -7.592249 0.000000
v 2.207457 -7.592249 0.050000
v 3.263519 -7.845060 0.000000
v 3.263519 -7.845060 0.050000
v 4.756348 -8.045094 0.000000
v 4.756348 -8.045094 0.050000
v 6.984523 -8.211549 0.000000
v 6.984523 -8.211549 0.050000
v 9.969400 -8.355156 0.000000
v 9.969400 -8.355156 0.050000
v 13.383091 -8.458340 0.000000
v 13.383091 -8.458340 0.050000
v 16.897701 -8.503529 0.000000
v 16.897701 -8.503529 0.050000
v 20.185341 -8.473146 0.000000
v 20.185341 -8.473146 0.050000
v 22.918129 -8.349623 0.000000
v 22.918129 -8.349623 0.050000
v 24.768164 -8.115381 0.000000
v 24.768164 -8.115381 0.050000
v 25.725058 -7.755845 0.000000
v 25.725058 -7.755845 0.050000
v 26.076797 -7.281773 0.000000
v 26.076797 -7.281773 0.050000
v 25.943077 -6.713602 0.000000
v 25.943077 -6.713602 0.050000
v 25.443592 -6.071772 0.000000
v 25.443592 -6.071772 0.050000
v 24.698034 -5.376718 0.000000
v 24.698034 -5.376718 0.050000
v 23.826099 -4.648877 0.000000
v 23.826099 -4.648877 0.050000
v 22.947475 -3.908688 0.000000
v 22.947475 -3.908688 0.050000
v 21.930237 -3.090331 0.000000
v 21.930237 -3.090331 0.050000
v 20.624008 -2.153702 0.000000
v 20.624008 -2.153702 0.050000
v 19.120823 -1.157807 0.000000
v 19.120823 -1.157807 0.050000
v 17.512718 -0.161649 0.000000
v 17.512718 -0.161649 0.050000
v 15.891727 0.775766 0.000000
v 15.891727 0.775766 0.050000
v 14.349886 1.595434 0.000000
v 14.349886 1.595434 0.050000
v 12.979229 2.238349 0.000000
v 12.979229 2.238349 0.050000
v 11.736139 2.739689 0.000000
v 11.736139 2.739689 0.050000
v 10.524273 3.163628 0.000000
v 10.524273 3.163628 0.050000
v 9.356565 3.494656 0.000000
v 9.356565 3.494656 0.050000
v 8.245951 3.717267 0.000000
v 8.245951 3.717267 0.050000
v 7.205369 3.815950 0.000000
v 7.205369 3.815950 0.050000
v 6.247754 3.775198 0.000000
v 6.247754 3.775198 0.050000
v 5.386044 3.579500 0.000000
v 5.386044 3.579500 0.050000
usemtl Water
vt 0.077144 0.000000
vt 0.092389 0.000000
vt 0.092389 1.000000
vt 0.077144 1.000000
vt 0.986374 0.060691
vt 0.994820 0.145292
vt 1.000000 0.099173
vt 0.949305 0.031507
vt 0.975470 0.197391
vt 0.946588 0.253810
vt 0.877636 0.012493
vt 0.912810 0.312891
vt 0.771771 0.002466
vt 0.878773 0.372974
vt 0.839366 0.439402
vt 0.788764 0.515430
vt 0.644411 0.000000
vt 0.730532 0.596269
vt 0.668236 0.677129
vt 0.508258 0.003668
vt 0.605440 0.753221
vt 0.545711 0.819756
vt 0.376015 0.012044
vt 0.492613 0.871943
vt 0.444457 0.912637
vt 0.260384 0.023701
vt 0.397510 0.947049
vt 0.352275 0.973920
vt 0.309251 0.991990
vt 0.268939 1.000000
vt 0.231842 0.996692
vt 0.198461 0.980807
vt 0.169088 0.947249
vt 0.143378 0.895438
vt 0.120868 0.830891
vt 0.101098 0.759122
vt 0.083606 0.685645
vt 0.067932 0.615978
vt 0.174067 0.037212
vt 0.053613 0.555634
vt 0.039750 0.502405
vt 0.116236 0.053449
vt 0.026454 0.450652
vt 0.075325 0.073971
vt 0.014777 0.400747
vt 0.005774 0.353058
vt 0.047928 0.098380
vt 0.000497 0.307956
vt 0.000000 0.265811
vt 0.005336 0.226994
vt 0.012748 0.190985
vt 0.030637 0.126283
vt 0.020046 0.157283
vt 0.986374 0.060691
vt 1.000000 0.099173
vt 0.994820 0.145292
vt 0.949305 0.031507
vt 0.975470 0.197391
vt 0.946588 0.253810
vt 0.877636 0.012493
vt 0.912810 0.312891
vt 0.771771 0.002466
vt 0.878773 0.372974
vt 0.839366 0.439402
vt 0.788764 0.515430
vt 0.644411 0.000000
vt 0.730532 0.596269
vt 0.668236 0.677129
vt 0.508258 0.003668
vt 0.605440 0.753221
vt 0.545711 0.819756
vt 0.376015 0.012044
vt 0.492613 0.871943
vt 0.444457 0.912637
vt 0.260384 0.023701
vt 0.397510 0.947049
vt 0.352275 0.973920
vt 0.309251 0.991990
vt 0.268939 1.000000
vt 0.231842 0.996692
vt 0.198461 0.980807
vt 0.169088 0.947249
vt 0.143378 0.895438
vt 0.120868 0.830891
vt 0.101098 0.759122
vt 0.083606 0.685645
vt 0.067932 0.615978
vt 0.174067 0.037212
vt 0.053613 0.555634
vt 0.039750 0.502405
vt 0.116236 0.053449
vt 0.026454 0.450652
vt 0.075325 0.073971
vt 0.014777 0.400747
vt 0.005774 0.353058
vt 0.047928 0.098380
vt 0.000497 0.307956
vt 0.000000 0.265811
vt 0.005336 0.226994
vt 0.012748 0.190985
vt 0.030637 0.126283
vt 0.020046 0.157283
vt 0.000000 0.000000
vt 0.013875 0.000000
vt 0.013875 1.000000
vt 0.000000 1.000000
vt 0.028668 0.000000
vt 0.028668 1.000000
vt 0.044491 0.000000
vt 0.044491 1.000000
vt 0.060893 0.000000
vt 0.060893 1.000000
vt 0.105727 0.000000
vt 0.105727 1.000000
vt 0.117729 0.000000
vt 0.117729 1.000000
vt 0.129362 0.000000
vt 0.129362 1.000000
vt 0.140363 0.000000
vt 0.140363 1.000000
vt 0.150514 0.000000
vt 0.150514 1.000000
vt 0.159705 0.000000
vt 0.159705 1.000000
vt 0.168049 0.000000
vt 0.168049 1.000000
vt 0.176044 0.000000
vt 0.176044 1.000000
vt 0.183806 0.000000
vt 0.183806 1.000000
vt 0.191131 0.000000
vt 0.191131 1.000000
vt 0.198677 0.000000
vt 0.198677 1.000000
vt 0.207728 0.000000
vt 0.207728 1.000000
vt 0.220075 0.000000
vt 0.220075 1.000000
vt 0.237521 0.000000
vt 0.237521 1.000000
vt 0.261719 0.000000
vt 0.261719 1.000000
vt 0.297617 0.000000
vt 0.297617 1.000000
vt 0.345627 0.000000
vt 0.345627 1.000000
vt 0.400497 0.000000
vt 0.400497 1.000000
vt 0.456967 0.000000
vt 0.456967 1.000000
vt 0.509789 0.000000
vt 0.509789 1.000000
vt 0.553739 0.000000
vt 0.553739 1.000000
vt 0.583699 0.000000
vt 0.583699 1.000000
vt 0.600122 0.000000
vt 0.600122 1.000000
vt 0.609606 0.000000
vt 0.609606 1.000000
vt 0.618984 0.000000
vt 0.618984 1.000000
vt 0.632050 0.000000
vt 0.632050 1.000000
vt 0.648426 0.000000
vt 0.648426 1.000000
vt 0.666673 0.000000
vt 0.666673 1.000000
vt 0.685131 0.000000
vt 0.685131 1.000000
vt 0.706106 0.000000
vt 0.706106 1.000000
vt 0.731929 0.000000
vt 0.731929 1.000000
vt 0.760899 0.000000
vt 0.760899 1.000000
vt 0.791290 0.000000
vt 0.791290 1.000000
vt 0.821375 0.000000
vt 0.821375 1.000000
vt 0.849429 0.000000
vt 0.849429 1.000000
vt 0.873752 0.000000
vt 0.873752 1.000000
vt 0.895286 0.000000
vt 0.895286 1.000000
vt 0.915913 0.000000
vt 0.915913 1.000000
vt 0.935413 0.000000
vt 0.935413 1.000000
vt 0.953611 0.000000
vt 0.953611 1.000000
vt 0.970404 0.000000
vt 0.970404 1.000000
vt 0.985803 0.000000
vt 0.985803 1.000000
vt 1.000000 0.000000
vt 1.000000 1.000000
s off
f 1/1/1 2/2/2 3/3/3
f 1/1/1 3/3/3 4/4/4
f 5/5/5 6/6/6 7/7/7
f 8/8/8 6/6/6 5/5/5
f 8/8/8 9/9/9 6/6/6
f 8/8/8 10/10/10 9/9/9
f 11/11/11 10/10/10 8/8/8
f 11/11/11 12/12/12 10/10/10
f 13/13/13 12/12/12 11/11/11
f 13/13/13 14/14/14 12/12/12
f 13/13/13 15/15/15 14/14/14
f 13/13/13 16/16/16 15/15/15
f 17/17/17 16/16/16 13/13/13
f 17/17/17 18/18/18 16/16/16
f 17/17/17 19/19/19 18/18/18
f 20/20/20 19/19/19 17/17/17
f 20/20/20 21/21/21 19/19/19
f 20/20/20 22/22/22 21/21/21
f 23/23/23 22/22/22 20/20/20
f 23/23/23 24/24/24 22/22/22
f 23/23/23 25/25/25 24/24/24
f 26/26/26 25/25/25 23/23/23
f 26/26/26 27/27/27 25/25/25
f 26/26/26 28/28/28 27/27/27
f 26/26/26 29/29/29 28/28/28
f 26/26/26 30/30/30 29/29/29
f 26/26/26 31/31/31 30/30/30
f 26/26/26 32/32/32 31/31/31
f 26/26/26 33/33/33 32/32/32
f 26/26/26 34/34/34 33/33/33
f 26/26/26 35/35/35 34/34/34
f 26/26/26 36/36/36 35/35/35
f 26/26/26 37/37/37 36/36/36
f 26/26/26 38/38/38 37/37/37
f 39/39/39 38/38/38 26/26/26
f 39/39/39 40/40/40 38/38/38
f 39/39/39 41/41/41 40/40/40
f 42/42/42 41/41/41 39/39/39
f 42/42/42 43/43/43 41/41/41
f 44/44/44 43/43/43 42/42/42
f 44/44/44 45/45/45 43/43/43
f 44/44/44 46/46/46 45/45/45
f 47/47/47 46/46/46 44/44/44
f 47/47/47 48/48/48 46/46/46
f 47/47/47 49/49/49 48/48/48
f 47/47/47 50/50/50 49/49/49
f 47/47/47 51/51/51 50/50/50
f 52/52/52 51/51/51 47/47/47
f 53/53/53 51/51/51 52/52/52
f 54/54/54 55/55/55 56/56/56
f 57/57/57 54/54/54 56/56/56
f 57/57/57 56/56/56 58/58/58
f 57/57/57 58/58/58 59/59/59
f 60/60/60 57/57/57 59/59/59
f 60/60/60 59/59/59 61/61/61
f 62/62/62 60/60/60 61/61/61
f 62/62/62 61/61/61 63/63/63
f 62/62/62 63/63/63 64/64/64
f 62/62/62 64/64/64 65/65/65
f 66/66/66 62/62/62 65/65/65
f 66/66/66 65/65/65 67/67/67
f 66/66/66 67/67/67 68/68/68
f 69/69/69 66/66/66 68/68/68
f 69/69/69 68/68/68 70/70/70
f 69/69/69 70/70/70 71/71/71
f 72/72/72 69/69/69 71/71/71
f 72/72/72 71/71/71 73/73/73
f 72/72/72 73/73/73 74/74/74
f 75/75/75 72/72/72 74/74/74
f 75/75/75 74/74/74 76/76/76
f 75/75/75 76/76/76 77/77/77
f 75/75/75 77/77/77 78/78/78
f 75/75/75 78/78/78 79/79/79
f 75/75/75 79/79/79 80/80/80
f 75/75/75 80/80/80 81/81/81
f 75/75/75 81/81/81 82/82/82
f 75/75/75 82/82/82 83/83/83
f 75/75/75 83/83/83 84/84/84
f 75/75/75 84/84/84 85/85/85
f 75/75/75 85/85/85 86/86/86
f 75/75/75 86/86/86 87/87/87
f 88/88/88 75/75/75 87/87/87
f 88/88/88 87/87/87 89/89/89
f 88/88/88 89/89/89 90/90/90
f 91/91/91 88/88/88 90/90/90
f 91/91/91 90/90/90 92/92/92
f 93/93/93 91/91/91 92/92/92
f 93/93/93 92/92/92 94/94/94
f 93/93/93 94/94/94 95/95/95
f 96/96/96 93/93/93 95/95/95
f 96/96/96 95/95/95 97/97/97
f 96/96/96 97/97/97 98/98/98
f 96/96/96 98/98/98 99/99/99
f 96/96/96 99/99/99 100/100/100
f 101/101/101 96/96/96 100/100/100
f 102/102/102 101/101/101 100/100/100
f 103/103/103 104/104/104 105/105/105
f 103/103/103 105/105/105 106/106/106
f 104/104/104 107/107/107 108/108/108
f 104/104/104 108/108/108 105/105/105
f 107/107/107 109/109/109 110/110/110
f 107/107/107 110/110/110 108/108/108
f 109/109/109 111/111/111 112/112/112
f 109/109/109 112/112/112 110/110/110
f 111/111/111 1/1/1 4/4/4
f 111/111/111 4/4/4 112/112/112
f 2/2/2 113/113/113 114/114/114
f 2/2/2 114/114/114 3/3/3
f 113/113/113 115/115/115 116/116/116
f 113/113/113 116/116/116 114/114/114
f 115/115/115 117/117/117 118/118/118
f 115/115/115 118/118/118 116/116/116
f 117/117/117 119/119/119 120/120/120
f 117/117/117 120/120/120 118/118/118
f 119/119/119 121/121/121 122/122/122
f 119/119/119 122/122/122 120/120/120
f 121/121/121 123/123/123 124/124/124
f 121/121/121 124/124/124 122/122/122
f 123/123/123 125/125/125 126/126/126
f 123/123/123 126/126/126 124/124/124
f 125/125/125 127/127/127 128/128/128
f 125/125/125 128/128/128 126/126/126
f 127/127/127 129/129/129 130/130/130
f 127/127/127 130/130/130 128/128/128
f 129/129/129 131/131/131 132/132/132
f 129/129/129 132/132/132 130/130/130
f 131/131/131 133/133/133 134/134/134
f 131/131/131 134/134/134 132/132/132
f 133/133/133 135/135/135 136/136/136
f 133/133/133 136/136/136 134/134/134
f 135/135/135 137/137/137 138/138/138
f 135/135/135 138/138/138 136/136/136
f 137/137/137 139/139/139 140/140/140
f 137/137/137 140/140/140 138/138/138
f 139/139/139 141/141/141 142/142/142
f 139/139/139 142/142/142 140/140/140
f 141/141/141 143/143/143 144/144/144
f 141/141/141 144/144/144 142/142/142
f 143/143/143 145/145/145 146/146/146
f 143/143/143 146/146/146 144/144/144
f 145/145/145 147/147/147 148/148/148
f 145/145/145 148/148/148 146/146/146
f 147/147/147 149/149/149 150/150/150
f 147/147/147 150/150/150 148/148/148
f 149/149/149 151/151/151 152/152/152
f 149/149/149 152/152/152 150/150/150
f 151/151/151 153/153/153 154/154/154
f 151/151/151 154/154/154 152/152/152
f 153/153/153 155/155/155 156/156/156
f 153/153/153 156/156/156 154/154/154
f 155/155/155 157/157/157 158/158/158
f 155/155/155 158/158/158 156/156/156
f 157/157/157 159/159/159 160/160/160
f 157/157/157 160/160/160 158/158/158
f 159/159/159 161/161/161 162/162/162
f 159/159/159 162/162/162 160/160/160
f 161/161/161 163/163/163 164/164/164
f 161/161/161 164/164/164 162/162/162
f 163/163/163 165/165/165 166/166/166
f 163/163/163 166/166/166 164/164/164
f 165/165/165 167/167/167 168/168/168
f 165/165/165 168/168/168 166/166/166
f 167/167/167 169/169/169 170/170/170
f 167/167/167 170/170/170 168/168/168
f 169/169/169 171/171/171 172/172/172
f 169/169/169 172/172/172 170/170/170
f 171/171/171 173/173/173 174/174/174
f 171/171/171 174/174/174 172/172/172
f 173/173/173 175/175/175 176/176/176
f 173/173/173 176/176/176 174/174/174
f 175/175/175 177/177/177 178/178/178
f 175/175/175 178/178/178 176/176/176
f 177/177/177 179/179/179 180/180/180
f 177/177/177 180/180/180 178/178/178
f 179/179/179 181/181/181 182/182/182
f 179/179/179 182/182/182 180/180/180
f 181/181/181 183/183/183 184/184/184
f 181/181/181 184/184/184 182/182/182
f 183/183/183 185/185/185 186/186/186
f 183/183/183 186/186/186 184/184/184
f 185/185/185 187/187/187 188/188/188
f 185/185/185 188/188/188 186/186/186
f 187/187/187 189/189/189 190/190/190
f 187/187/187 190/190/190 188/188/188
f 189/189/189 191/191/191 192/192/192
f 189/189/189 192/192/192 190/190/190
f 191/191/191 193/193/193 194/194/194
f 191/191/191 194/194/194 192/192/192
f 193/193/193 195/195/195 196/196/196
f 193/193/193 196/196/196 194/194/194
f 195/195/195 197/197/197 198/198/198
f 195/195/195 198/198/198 196/196/196

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,21 @@
# Blender MTL File: 'None'
# Material Count: 2
newmtl Road.004
Ns 0.000000
Ka 0.000000 0.000000 0.000000
Kd 0.138039 0.138039 0.138039
Ks 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 2
newmtl Road.005
Ns 0.000000
Ka 0.000000 0.000000 0.000000
Kd 0.138039 0.138039 0.138039
Ks 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 2
map_Kd road.png

File diff suppressed because it is too large Load Diff

File diff suppressed because one or more lines are too long

Binary file not shown.

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,11 @@
# Blender MTL File: 'None'
# 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 wheel.jpg

File diff suppressed because it is too large Load Diff

Binary file not shown.

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,11 @@
# Blender MTL File: 'None'
# 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 wheel.jpg

File diff suppressed because it is too large Load Diff

Binary file not shown.

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 992 KiB

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 89 KiB

View File

@ -0,0 +1,493 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from racecar.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="racecar" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- inertial parameter macros -->
<!-- geometry macros -->
<!-- transmission macros -->
<!-- Add chassis and it's inertia link -->
<link name="base_link">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value=".1"/>
<inertia ixx="0.010609" ixy="0" ixz="0" iyy="0.050409" iyz="0" izz="0.05865"/>
</inertial>
</link>
<link name="chassis">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value=".1"/>
<inertia ixx="0.010609" ixy="0" ixz="0" iyy="0.050409" iyz="0" izz="0.05865"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/chassis.STL"/>
</geometry>
<material name="blue"/>
</visual>
</link>
<joint name="base_link_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.05"/>
<parent link="base_link"/>
<child link="chassis"/>
</joint>
<link name="chassis_inertia">
<inertial>
<origin rpy="0 0 0" xyz="0.1477 0 0"/>
<mass value="4.0"/>
<inertia ixx="0.010609" ixy="0" ixz="0" iyy="0.050409" iyz="0" izz="0.05865"/>
</inertial>
</link>
<joint name="chassis_inertia_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="chassis"/>
<child link="chassis_inertia"/>
</joint>
<!-- Add the left rear wheel with its joints and tranmissions -->
<link name="left_rear_wheel">
<inertial>
<origin rpy="0 0 0" xyz="0 0 -0.0225"/>
<mass value="0.34055"/>
<inertia ixx="0.00026046" ixy="0" ixz="0" iyy="0.00026046" iyz="0" izz="0.00041226"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/left_rear_wheel.obj"/>
</geometry>
<material name="white"/>
</visual>
<collision>
robot
<origin rpy="0 0 0" xyz="0 0 -0.0225"/>
<geometry>
<cylinder length="0.045" radius="0.05"/>
</geometry>
</collision>
</link>
<joint name="left_rear_wheel_joint" type="continuous">
<origin rpy="1.5708 0 0" xyz="0 0.1 0"/>
<parent link="chassis"/>
<child link="left_rear_wheel"/>
<axis xyz="0 0 -1"/>
<limit effort="10" velocity="100"/>
</joint>
<transmission name="left_rear_wheel_transmission" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="left_rear_wheel_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="left_rear_wheel_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Add the right rear wheel with its joints and tranmissions -->
<link name="right_rear_wheel">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.0225"/>
<mass value="0.34055"/>
<inertia ixx="0.00026046" ixy="0" ixz="0" iyy="0.00026046" iyz="0" izz="0.00041226"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/right_rear_wheel.obj"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0225"/>
<geometry>
<cylinder length="0.045" radius="0.05"/>
</geometry>
</collision>
</link>
<joint name="right_rear_wheel_joint" type="continuous">
<origin rpy="1.5708 0 0" xyz="0 -0.1 0"/>
<parent link="chassis"/>
<child link="right_rear_wheel"/>
<axis xyz="0 0 -1"/>
<limit effort="10" velocity="100"/>
</joint>
<transmission name="right_rear_wheel_transmission" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="right_rear_wheel_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="right_rear_wheel_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Add the left steering hinge with its joints and tranmissions -->
<link name="left_steering_hinge">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.100"/>
<inertia ixx="4E-06" ixy="0" ixz="0" iyy="4E-06" iyz="0" izz="4E-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/left_steering_hinge.STL"/>
</geometry>
<material name="grey"/>
</visual>
</link>
<joint name="left_steering_hinge_joint" type="revolute">
<origin rpy="0 1.5708 0" xyz="0.325 0.1 0"/>
<parent link="chassis"/>
<child link="left_steering_hinge"/>
<axis xyz="-1 0 0"/>
<limit effort="10" lower="-1.0" upper="1.0" velocity="100"/>
</joint>
<transmission name="left_steering_hinge_transmission" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="left_steering_hinge_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="left_steering_hinge_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Add the right steering hinge with its joints and tranmissions -->
<link name="right_steering_hinge">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.100"/>
<inertia ixx="4E-06" ixy="0" ixz="0" iyy="4E-06" iyz="0" izz="4E-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/right_steering_hinge.STL"/>
</geometry>
<material name="grey"/>
</visual>
</link>
<joint name="right_steering_hinge_joint" type="continuous">
<origin rpy="0 1.5708 0" xyz="0.325 -0.1 0"/>
<parent link="chassis"/>
<child link="right_steering_hinge"/>
<axis xyz="-1 0 0"/>
<limit effort="10" lower="-1.0" upper="1.0" velocity="100"/>
</joint>
<transmission name="right_steering_hinge_transmission" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="right_steering_hinge_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="right_steering_hinge_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Add the left front wheel with its joints and tranmissions -->
<link name="left_front_wheel">
<inertial>
<origin rpy="0 0 0" xyz="0 0 -0.0225"/>
<mass value="0.34055"/>
<inertia ixx="0.00026046" ixy="0" ixz="0" iyy="0.00026046" iyz="0" izz="0.00041226"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/left_front_wheel.obj"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.0225"/>
<geometry>
<cylinder length="0.045" radius="0.05"/>
</geometry>
</collision>
</link>
<joint name="left_front_wheel_joint" type="continuous">
<origin rpy="1.5708 0 0" xyz="0 0 0"/>
<parent link="left_steering_hinge"/>
<child link="left_front_wheel"/>
<axis xyz="0 0 -1"/>
<limit effort="10" velocity="100"/>
</joint>
<transmission name="left_front_wheel_transmission" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="left_front_wheel_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="left_front_wheel_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Add the left front wheel with its joints and tranmissions -->
<link name="right_front_wheel">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.0225"/>
<mass value="0.34055"/>
<inertia ixx="0.00026046" ixy="0" ixz="0" iyy="0.00026046" iyz="0" izz="0.00041226"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/right_front_wheel.obj"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0225"/>
<geometry>
<cylinder length="0.045" radius="0.05"/>
</geometry>
</collision>
</link>
<joint name="right_front_wheel_joint" type="continuous">
<origin rpy="1.5708 0 0" xyz="0 0 0"/>
<parent link="right_steering_hinge"/>
<child link="right_front_wheel"/>
<axis xyz="0 0 -1"/>
<limit effort="10" velocity="100"/>
</joint>
<transmission name="right_front_wheel_transmission" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="right_front_wheel_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="right_front_wheel_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Add Hokuyo laser scanner -->
<link name="laser">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.130"/>
<inertia ixx="4E-06" ixy="0" ixz="0" iyy="4E-06" iyz="0" izz="4E-06"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/hokuyo.obj"/>
<material name="grey"/>
</geometry>
</visual>
</link>
<joint name="hokuyo_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.265 0.0 0.075"/>
<parent link="chassis"/>
<child link="laser"/>
<axis xyz="0 0 1"/>
</joint>
<!-- zed camera -->
<link name="zed_camera_link">
<inertial>
<mass value="1e-5"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.033 0.175 0.030"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.033 0.175 0.030"/>
</geometry>
<material name="red"/>
</visual>
</link>
<joint name="zed_camera_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.390 0 0.04"/>
<parent link="chassis"/>
<child link="zed_camera_link"/>
<axis xyz="0 0 1"/>
<!-- <limit lower="0.0" upper="0.0" effort="0.0" velocity="0.0" /> -->
</joint>
<!-- zed camera lenses -->
<!-- It seems these have to have a non-zero mass to have a camera attached? -->
<link name="camera_link">
<!-- this needs to match the name in zed_wrapper/zed_tf.launch -->
<inertial>
<mass value="1e-5"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
</inertial>
</link>
<link name="zed_camera_right_link">
<inertial>
<mass value="1e-5"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
</inertial>
</link>
<joint name="zed_camera_left_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.06 0"/>
<parent link="zed_camera_link"/>
<child link="camera_link"/>
<axis xyz="0 0 1"/>
</joint>
<joint name="zed_camera_right_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.06 0"/>
<parent link="zed_camera_link"/>
<child link="zed_camera_right_link"/>
<axis xyz="0 0 1"/>
</joint>
<!-- Add the remaining xacros -->
<!-- Gazebo references -->
<gazebo reference="chassis">
<mu1 value="0.0"/>
<mu2 value="0.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="left_rear_wheel">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="1 0 0"/>
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="right_rear_wheel">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="1 0 0"/>
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="left_front_wheel">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="0 0 1"/>
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="right_front_wheel">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="0 0 1"/>
<material>Gazebo/Black</material>
</gazebo>
<!-- Gazebo plugins -->
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
<robotNamespace>/racecar</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
</gazebo>
<gazebo reference="laser">
<material>Gazebo/Grey</material>
<sensor name="hokuyo_sensor" type="ray">
<pose>0 0 0.0124 0 0 0</pose>
<visualize>true</visualize>
<update_rate>40</update_rate>
<ray>
<scan>
<horizontal>
<samples>1081</samples>
<resolution>1</resolution>
<min_angle>-2.3561944902</min_angle>
<max_angle>2.3561944902</max_angle>
</horizontal>
</scan>
<range>
<min>0.1</min>
<max>10.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin filename="libgazebo_ros_laser.so" name="gazebo_ros_hokuyo_controller">
<topicName>/scan</topicName>
<frameName>laser</frameName>
</plugin>
</sensor>
</gazebo>
<gazebo reference="camera_link">
<sensor name="zed_camera_left_sensor" type="camera">
<update_rate>30.0</update_rate>
<!-- math.atan(320 / 687.8065795898438) * 2 -->
<camera name="zed_camera_left_camera">
<horizontal_fov>0.8709216071359963</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>B8G8R8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin filename="libgazebo_ros_camera.so" name="camera_controller">
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<cameraName>/camera/zed</cameraName>
<imageTopicName>rgb/image_rect_color</imageTopicName>
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<frameName>camera_link</frameName>
<hackBaseline>0</hackBaseline>
<!-- set this to 0.12 for the second camera -->
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
<material name="white">
<color rgba="1. 1. 1. 1.0"/>
</material>
<material name="black">
<color rgba="0. 0. 0. 1.0"/>
</material>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="orange">
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
</material>
<material name="brown">
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
</material>
<material name="red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
</robot>

View File

@ -0,0 +1,743 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from racecar.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="racecar" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- inertial parameter macros -->
<!-- geometry macros -->
<!-- transmission macros -->
<!-- Add chassis and it's inertia link -->
<link name="chassis">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="1 1 1 1" filename="meshes/chassis_differential.STL"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="1 1 1 1" filename="meshes/chassis_differential.STL"/>
</geometry>
<material name="blue"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.2 0 0."/>
<mass value="4.0"/>
<inertia ixx="0.010609" ixy="0" ixz="0" iyy="0.050409" iyz="0" izz="0.05865"/>
</inertial>
</link>
<!-- Add the left rear wheel with its joints and tranmissions -->
<link name="left_rear_wheel">
<contact>
<lateral_friction value=".5"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 -0.0225"/>
<mass value="0.34055"/>
<inertia ixx="0.00026046" ixy="0" ixz="0" iyy="0.00026046" iyz="0" izz="0.00041226"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/left_rear_wheel.obj"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.0225"/>
<geometry>
<cylinder length="0.045" radius="0.05"/>
</geometry>
</collision>
</link>
<joint name="left_rear_wheel_joint" type="fixed">
<origin rpy="1.5708 0 0" xyz="0 0.1 0"/>
<parent link="diff_sideA"/>
<child link="left_rear_wheel"/>
</joint>
<!-- Add the right rear wheel with its joints and tranmissions -->
<link name="right_rear_wheel">
<contact>
<lateral_friction value=".5"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.0225"/>
<mass value="0.34055"/>
<inertia ixx="0.00026046" ixy="0" ixz="0" iyy="0.00026046" iyz="0" izz="0.00041226"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/right_rear_wheel.obj"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0225"/>
<geometry>
<cylinder length="0.045" radius="0.05"/>
</geometry>
</collision>
</link>
<joint name="right_rear_wheel_joint" type="fixed">
<origin rpy="1.5708 0 0" xyz="0 -0.1 0"/>
<parent link="diff_sideB"/>
<child link="right_rear_wheel"/>
</joint>
<!-- Add the left steering hinge with its joints and tranmissions -->
<link name="left_steering_hinge">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.100"/>
<inertia ixx="4E-06" ixy="0" ixz="0" iyy="4E-06" iyz="0" izz="4E-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/left_steering_hinge.STL"/>
</geometry>
<material name="grey"/>
</visual>
</link>
<joint name="left_steering_hinge_joint" type="revolute">
<origin rpy="0 1.5708 0" xyz="0.325 0.1 0"/>
<parent link="chassis"/>
<child link="left_steering_hinge"/>
<axis xyz="-1 0 0"/>
<limit effort="10" lower="-1.0" upper="1.0" velocity="100"/>
</joint>
<transmission name="left_steering_hinge_transmission" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="left_steering_hinge_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="left_steering_hinge_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Add the right steering hinge with its joints and tranmissions -->
<link name="right_steering_hinge">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.100"/>
<inertia ixx="4E-06" ixy="0" ixz="0" iyy="4E-06" iyz="0" izz="4E-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/right_steering_hinge.STL"/>
</geometry>
<material name="grey"/>
</visual>
</link>
<joint name="right_steering_hinge_joint" type="continuous">
<origin rpy="0 1.5708 0" xyz="0.325 -0.1 0"/>
<parent link="chassis"/>
<child link="right_steering_hinge"/>
<axis xyz="-1 0 0"/>
<limit effort="10" lower="-1.0" upper="1.0" velocity="100"/>
</joint>
<transmission name="right_steering_hinge_transmission" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="right_steering_hinge_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="right_steering_hinge_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Add the left front wheel with its joints and tranmissions -->
<link name="left_front_wheel">
<contact>
<lateral_friction value=".8"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 -0.0225"/>
<mass value="0.34055"/>
<inertia ixx="0.00026046" ixy="0" ixz="0" iyy="0.00026046" iyz="0" izz="0.00041226"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/left_front_wheel.obj"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.0225"/>
<geometry>
<cylinder length="0.045" radius="0.05"/>
</geometry>
</collision>
</link>
<joint name="left_front_wheel_joint" type="continuous">
<origin rpy="1.5708 0 0" xyz="0 0 0"/>
<parent link="left_steering_hinge"/>
<child link="left_front_wheel"/>
<axis xyz="0 0 -1"/>
<limit effort="10" velocity="100"/>
</joint>
<transmission name="left_front_wheel_transmission" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="left_front_wheel_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="left_front_wheel_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Add the left front wheel with its joints and tranmissions -->
<link name="right_front_wheel">
<contact>
<lateral_friction value="0.8"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.0225"/>
<mass value="0.34055"/>
<inertia ixx="0.00026046" ixy="0" ixz="0" iyy="0.00026046" iyz="0" izz="0.00041226"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/right_front_wheel.obj"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0225"/>
<geometry>
<cylinder length="0.045" radius="0.05"/>
</geometry>
</collision>
</link>
<joint name="right_front_wheel_joint" type="continuous">
<origin rpy="1.5708 0 0" xyz="0 0 0"/>
<parent link="right_steering_hinge"/>
<child link="right_front_wheel"/>
<axis xyz="0 0 -1"/>
<limit effort="10" velocity="100"/>
</joint>
<transmission name="right_front_wheel_transmission" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="right_front_wheel_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="right_front_wheel_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Add Hokuyo laser scanner -->
<link name="laser">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.130"/>
<inertia ixx="4E-06" ixy="0" ixz="0" iyy="4E-06" iyz="0" izz="4E-06"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/hokuyo.obj"/>
<material name="grey"/>
</geometry>
</visual>
</link>
<joint name="hokuyo_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.265 0.0 0.075"/>
<parent link="chassis"/>
<child link="laser"/>
<axis xyz="0 0 1"/>
</joint>
<!-- zed camera -->
<link name="zed_camera_link">
<inertial>
<mass value="0.1"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.033 0.175 0.030"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.033 0.175 0.030"/>
</geometry>
<material name="red"/>
</visual>
</link>
<joint name="zed_camera_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.390 0 0.04"/>
<parent link="chassis"/>
<child link="zed_camera_link"/>
<axis xyz="0 0 1"/>
<!-- <limit lower="0.0" upper="0.0" effort="0.0" velocity="0.0" /> -->
</joint>
<!-- zed camera lenses -->
<!-- It seems these have to have a non-zero mass to have a camera attached? -->
<link name="camera_link">
<!-- this needs to match the name in zed_wrapper/zed_tf.launch -->
<inertial>
<mass value="0.01"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
</inertial>
</link>
<link name="zed_camera_right_link">
<inertial>
<mass value="0.01"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
</inertial>
</link>
<joint name="zed_camera_left_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.06 0"/>
<parent link="zed_camera_link"/>
<child link="camera_link"/>
<axis xyz="0 0 1"/>
</joint>
<joint name="zed_camera_right_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.06 0"/>
<parent link="zed_camera_link"/>
<child link="zed_camera_right_link"/>
<axis xyz="0 0 1"/>
</joint>
<!-- Add the remaining xacros -->
<link name="diff_ring">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<mass value="0.0637"/>
<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="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.0005 0.0005 0.001" filename="differential/diff_ring.stl"/>
</geometry>
<material name="green"/>
</visual>
<visual>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_carrier.stl"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0.025 0"/>
<geometry>
<cylinder length="0.01" radius="0.025"/>
</geometry>
</collision>
</link>
<joint name="diff_ring_chassis" type="continuous">
<parent link="chassis"/>
<child link="diff_ring"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0."/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<link name="diff_spiderA">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<mass value="0.056"/>
<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="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_spider.stl"/>
</geometry>
<material name="red"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0.01 0"/>
<geometry>
<cylinder length="0.01" radius="0.015"/>
</geometry>
</collision>
</link>
<joint name="diff_spiderA_ring" type="continuous">
<parent link="diff_ring"/>
<child link="diff_spiderA"/>
<origin rpy="0 0 1.570795" xyz="0.0 0.0 0.0"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<link name="diff_spiderB">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<mass value="0.056"/>
<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="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_spider.stl"/>
</geometry>
<material name="brown"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0.01 0"/>
<geometry>
<cylinder length="0.01" radius="0.015"/>
</geometry>
</collision>
</link>
<joint name="diff_spiderB_ring" type="continuous">
<parent link="diff_ring"/>
<child link="diff_spiderB"/>
<origin rpy="0 0 -1.570795" xyz="0.0 0.0 0.0"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<link name="diff_sideA">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<mass value="0.056"/>
<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="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_side.stl"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0.01 0"/>
<geometry>
<cylinder length="0.01" radius="0.015"/>
</geometry>
</collision>
</link>
<joint name="diff_sideA_ring" type="continuous">
<parent link="diff_ring"/>
<child link="diff_sideA"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<link name="diff_sideB">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<mass value="0.056"/>
<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="-1.570795 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_side.stl"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin rpy="-1.570795 0 0" xyz="0 -0.01 0"/>
<geometry>
<cylinder length="0.01" radius="0.015"/>
</geometry>
</collision>
</link>
<joint name="diff_sideB_ring" type="continuous">
<parent link="diff_ring"/>
<child link="diff_sideB"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<link name="diff2_ring">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<mass value="0.0637"/>
<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="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.0005 0.0005 0.001" filename="differential/diff_ring.stl"/>
</geometry>
<material name="green"/>
</visual>
<visual>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_carrier.stl"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0.025 0"/>
<geometry>
<cylinder length="0.01" radius="0.025"/>
</geometry>
</collision>
</link>
<joint name="diff2_ring_chassis" type="continuous">
<parent link="chassis"/>
<child link="diff2_ring"/>
<origin rpy="0 0 0" xyz="0.32 0.0 0.0"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<link name="diff2_spiderA">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<mass value="0.056"/>
<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="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_spider.stl"/>
</geometry>
<material name="red"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0.01 0"/>
<geometry>
<cylinder length="0.01" radius="0.015"/>
</geometry>
</collision>
</link>
<joint name="diff2_spiderA_ring" type="continuous">
<parent link="diff2_ring"/>
<child link="diff2_spiderA"/>
<origin rpy="0 0 1.570795" xyz="0.0 0.0 0.0"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<link name="diff2_spiderB">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<mass value="0.056"/>
<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="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_spider.stl"/>
</geometry>
<material name="brown"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0.01 0"/>
<geometry>
<cylinder length="0.01" radius="0.015"/>
</geometry>
</collision>
</link>
<joint name="diff2_spiderB_ring" type="continuous">
<parent link="diff2_ring"/>
<child link="diff2_spiderB"/>
<origin rpy="0 0 -1.570795" xyz="0.0 0.0 0.0"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<link name="diff2_sideA">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<mass value="0.056"/>
<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="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_side.stl"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0.01 0"/>
<geometry>
<cylinder length="0.01" radius="0.015"/>
</geometry>
</collision>
</link>
<joint name="diff2_sideA_ring" type="continuous">
<parent link="diff2_ring"/>
<child link="diff2_sideA"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<link name="diff2_sideB">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<mass value="0.056"/>
<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="-1.570795 0 0" xyz="0 0 0"/>
<geometry>
<mesh scale="0.001 0.001 0.001" filename="differential/diff_side.stl"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin rpy="-1.570795 0 0" xyz="0 -0.01 0"/>
<geometry>
<cylinder length="0.01" radius="0.015"/>
</geometry>
</collision>
</link>
<joint name="diff2_sideB_ring" type="continuous">
<parent link="diff2_ring"/>
<child link="diff2_sideB"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<material name="white">
<color rgba="1. 1. 1. 1.0"/>
</material>
<material name="black">
<color rgba="0. 0. 0. 1.0"/>
</material>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="orange">
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
</material>
<material name="brown">
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
</material>
<material name="red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
</robot>

15
racecar/plane.mtl Normal file
View File

@ -0,0 +1,15 @@
newmtl Material
Ns 10.0000
Ni 1.5000
d 1.0000
Tr 0.0000
Tf 1.0000 1.0000 1.0000
illum 2
Ka 0.0000 0.0000 0.0000
Kd 0.5880 0.5880 0.5880
Ks 0.0000 0.0000 0.0000
Ke 0.0000 0.0000 0.0000
map_Ka cube.tga
map_Kd checker_blue.png

18
racecar/plane.obj Normal file
View File

@ -0,0 +1,18 @@
# Blender v2.66 (sub 1) OBJ File: ''
# www.blender.org
mtllib plane.mtl
o Plane
v 15.000000 -15.000000 0.000000
v 15.000000 15.000000 0.000000
v -15.000000 15.000000 0.000000
v -15.000000 -15.000000 0.000000
vt 15.000000 0.000000
vt 15.000000 15.000000
vt 0.000000 15.000000
vt 0.000000 0.000000
usemtl Material
s off
f 1/1 2/2 3/3
f 1/1 3/3 4/4

29
racecar/plane.urdf Normal file
View File

@ -0,0 +1,29 @@
<?xml version="0.0" ?>
<robot name="plane">
<link name="planeLink">
<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="plane.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<plane normal="0 0 1"/>
</geometry>
</collision>
</link>
</robot>

198
racecar/racecar.py Normal file
View File

@ -0,0 +1,198 @@
import pybullet as p
import time
import math
import os
import pybullet_data
p.connect(p.GUI)
p.resetSimulation()
p.setGravity(0,0,-10)
useRealTimeSim = 0
p.setTimeStep(1./120.)
p.setRealTimeSimulation(useRealTimeSim) # either this
track = p.loadURDF("plane.urdf")
#track = p.loadSDF("f10_racecar/meshes/barca_track.sdf", globalScaling=1)
#otherCar = p.loadURDF("f10_racecar/racecar_differential.urdf", [0,1,.3])
car = p.loadURDF("f10_racecar/racecar_differential.urdf", [0,0,.3])
for wheel in range(p.getNumJoints(car)):
print("joint[",wheel,"]=", p.getJointInfo(car,wheel))
p.setJointMotorControl2(car,wheel,p.VELOCITY_CONTROL,targetVelocity=0,force=0)
p.getJointInfo(car,wheel)
wheels = [8,15]
print("----------------")
#p.setJointMotorControl2(car,10,p.VELOCITY_CONTROL,targetVelocity=1,force=10)
c = p.createConstraint(car,9,car,11,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
p.changeConstraint(c,gearRatio=1, maxForce=10000)
c = p.createConstraint(car,10,car,13,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
c = p.createConstraint(car,9,car,13,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
c = p.createConstraint(car,16,car,18,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
p.changeConstraint(c,gearRatio=1, maxForce=10000)
c = p.createConstraint(car,16,car,19,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
c = p.createConstraint(car,17,car,19,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
c = p.createConstraint(car,1,car,18,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
p.changeConstraint(c,gearRatio=-1, gearAuxLink = 15, maxForce=10000)
c = p.createConstraint(car,3,car,19,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
p.changeConstraint(c,gearRatio=-1, gearAuxLink = 15,maxForce=10000)
steering = [0,2]
hokuyo_joint=4
zed_camera_joint = 5
targetVelocitySlider = p.addUserDebugParameter("wheelVelocity",-2,2,0)
maxForceSlider = p.addUserDebugParameter("maxForce",0,50,20)
steeringSlider = p.addUserDebugParameter("steering",-1,1,0)
# replaceLines=True
# numRays=100
# rayFrom=[]
# rayTo=[]
# rayIds=[]
# rayHitColor = [1,0,0]
# rayMissColor = [0,1,0]
# rayLen = 8
# rayStartLen=0.25
# for i in range (numRays):
# #rayFrom.append([0,0,0])
# rayFrom.append([rayStartLen*math.sin(-0.5*0.25*2.*math.pi+0.75*2.*math.pi*float(i)/numRays), rayStartLen*math.cos(-0.5*0.25*2.*math.pi+0.75*2.*math.pi*float(i)/numRays),0])
# rayTo.append([rayLen*math.sin(-0.5*0.25*2.*math.pi+0.75*2.*math.pi*float(i)/numRays), rayLen*math.cos(-0.5*0.25*2.*math.pi+0.75*2.*math.pi*float(i)/numRays),0])
# if (replaceLines):
# rayIds.append(p.addUserDebugLine(rayFrom[i], rayTo[i], rayMissColor,parentObjectUniqueId=car, parentLinkIndex=hokuyo_joint ))
# else:
# rayIds.append(-1)
#def getCarYaw(car):
# carPos,carOrn = p.getBasePositionAndOrientation(car)
# carEuler = p.getEulerFromQuaternion(carOrn)
# carYaw = carEuler[2]*360/(2.*math.pi)-90
# return carYaw
#prevCarYaw = getCarYaw(car)
frame = 0
lineId = p.addUserDebugLine([0,0,0],[0,0,1],[1,0,0])
lineId2 = p.addUserDebugLine([0,0,0],[0,0,1],[1,0,0])
lineId3= p.addUserDebugLine([0,0,0],[0,0,1],[1,0,0])
print("lineId=",lineId)
#camInfo = p.getDebugVisualizerCamera()
lastTime = time.time()
lastControlTime = time.time()
#lastLidarTime = time.time()
def getCarVel(car):
linVel,angVel = p.getBaseVelocity(car)
return linVel[0]
#frame=0
while (True):
#print (getCarVel(car))
nowTime = time.time()
#render Camera at 10Hertz
# if (nowTime-lastTime>.1):
# ls = p.getLinkState(car,zed_camera_joint, computeForwardKinematics=True)
# camPos = ls[0]
# camOrn = ls[1]
# camMat = p.getMatrixFromQuaternion(camOrn)
# upVector = [0,0,1]
# forwardVec = [camMat[0],camMat[3],camMat[6]]
# #sideVec = [camMat[1],camMat[4],camMat[7]]
# camUpVec = [camMat[2],camMat[5],camMat[8]]
# camTarget = [camPos[0]+forwardVec[0]*10,camPos[1]+forwardVec[1]*10,camPos[2]+forwardVec[2]*10]
# camUpTarget = [camPos[0]+camUpVec[0],camPos[1]+camUpVec[1],camPos[2]+camUpVec[2]]
# viewMat = p.computeViewMatrix(camPos, camTarget, camUpVec)
# projMat = camInfo[3]
# #p.getCameraImage(320,200,viewMatrix=viewMat,projectionMatrix=projMat, flags=p.ER_NO_SEGMENTATION_MASK, renderer=p.ER_BULLET_HARDWARE_OPENGL)
# p.getCameraImage(320,200,viewMatrix=viewMat,projectionMatrix=projMat, renderer=p.ER_BULLET_HARDWARE_OPENGL)
# lastTime=nowTime
nowControlTime = time.time()
nowLidarTime = time.time()
#lidar at 20Hz
# if (nowLidarTime-lastLidarTime>.3):
# #print("Lidar!")
# numThreads=0
# results = p.rayTestBatch(rayFrom,rayTo,numThreads, parentObjectUniqueId=car, parentLinkIndex=hokuyo_joint)
# for i in range (numRays):
# hitObjectUid=results[i][0]
# hitFraction = results[i][2]
# hitPosition = results[i][3]
# if (hitFraction==1.):
# p.addUserDebugLine(rayFrom[i],rayTo[i], rayMissColor,replaceItemUniqueId=rayIds[i],parentObjectUniqueId=car, parentLinkIndex=hokuyo_joint)
# else:
# localHitTo = [rayFrom[i][0]+hitFraction*(rayTo[i][0]-rayFrom[i][0]),
# rayFrom[i][1]+hitFraction*(rayTo[i][1]-rayFrom[i][1]),
# rayFrom[i][2]+hitFraction*(rayTo[i][2]-rayFrom[i][2])]
# p.addUserDebugLine(rayFrom[i],localHitTo, rayHitColor,replaceItemUniqueId=rayIds[i],parentObjectUniqueId=car, parentLinkIndex=hokuyo_joint)
# lastLidarTime = nowLidarTime
#control at 100Hz
if (nowControlTime-lastControlTime>.01):
carPos,carOrn = p.getBasePositionAndOrientation(car)
# Keep the previous orientation of the camera set by the user.
# yaw = camInfo[8]
# pitch = camInfo[9]
# distance = camInfo[10]
# targetPos = camInfo[11]
# camFwd = camInfo[5]
# carYaw = getCarYaw(car)
#
# #the car yaw is clamped between -90 and 270, make sure to deal with angles that wrap around
# if (carYaw-prevCarYaw>45):
# yaw+=360
# if (carYaw-prevCarYaw<-45):
# yaw-=360
# prevCarYaw = carYaw
#print("carYaw=", carYaw)
#print("camYaw=", yaw)
#slowly rotate the camera behind the car
#diffYaw = (carYaw-yaw)*0.03
#track the position of the car as target
#p.resetDebugVisualizerCamera(distance, yaw+diffYaw, pitch, carPos)
maxForce = p.readUserDebugParameter(maxForceSlider)
targetVelocity = p.readUserDebugParameter(targetVelocitySlider)
steeringAngle = p.readUserDebugParameter(steeringSlider)
#print(targetVelocity)
gearRatio=1./21
for wheel in wheels:
p.setJointMotorControl2(car,wheel,p.VELOCITY_CONTROL,targetVelocity=targetVelocity/gearRatio,force=maxForce)
for steer in steering:
p.setJointMotorControl2(car,steer,p.POSITION_CONTROL,targetPosition=steeringAngle)
if (useRealTimeSim==0):
frame+=1
p.stepSimulation()
lastControlTime=nowControlTime