more fixes in pybullet_envs: fix path, add missing data resources

This commit is contained in:
Erwin Coumans
2017-08-22 08:59:39 -07:00
parent 21f9d1b816
commit e064d4b837
48 changed files with 28328 additions and 12 deletions

View File

@@ -5,7 +5,7 @@ from gym.utils import seeding
import numpy as np
import time
import pybullet as p
import minitaur_new
from . import minitaur_new
class MinitaurGymEnv(gym.Env):
metadata = {

View File

@@ -1,3 +1,4 @@
import os
import pybullet as p
import numpy as np
import copy
@@ -11,7 +12,7 @@ class Racecar:
self.reset()
def reset(self):
self.racecarUniqueId = p.loadURDF("racecar/racecar.urdf", [0,0,.2])
self.racecarUniqueId = p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","racecar/racecar.urdf"), [0,0,.2])
self.maxForce = 20
self.nMotors = 2
self.motorizedwheels=[2]
@@ -54,4 +55,4 @@ class Racecar:
p.setJointMotorControl2(self.racecarUniqueId,motor,p.VELOCITY_CONTROL,targetVelocity=targetVelocity,force=self.maxForce)
for steer in self.steeringLinks:
p.setJointMotorControl2(self.racecarUniqueId,steer,p.POSITION_CONTROL,targetPosition=steeringAngle)

View File

@@ -1,3 +1,4 @@
import os
import math
import gym
from gym import spaces
@@ -48,8 +49,8 @@ class RacecarGymEnv(gym.Env):
p.resetSimulation()
#p.setPhysicsEngineParameter(numSolverIterations=300)
p.setTimeStep(self._timeStep)
#p.loadURDF("%splane.urdf" % self._urdfRoot)
stadiumobjects = p.loadSDF("%sstadium.sdf" % self._urdfRoot)
#p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","plane.urdf"))
stadiumobjects = p.loadSDF(os.path.join(os.path.dirname(__file__),"../data","stadium.sdf"))
#move the stadium objects slightly above 0
for i in stadiumobjects:
pos,orn = p.getBasePositionAndOrientation(i)
@@ -63,7 +64,7 @@ class RacecarGymEnv(gym.Env):
bally = dist * math.cos(ang)
ballz = 1
self._ballUniqueId = p.loadURDF("sphere2.urdf",[ballx,bally,ballz])
self._ballUniqueId = p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","sphere2.urdf"),[ballx,bally,ballz])
p.setGravity(0,0,-10)
self._racecar = racecar.Racecar(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
self._envStepCounter = 0

View File

@@ -1,3 +1,4 @@
import os
import math
import gym
from gym import spaces
@@ -50,8 +51,8 @@ class RacecarZEDGymEnv(gym.Env):
p.resetSimulation()
#p.setPhysicsEngineParameter(numSolverIterations=300)
p.setTimeStep(self._timeStep)
#p.loadURDF("%splane.urdf" % self._urdfRoot)
stadiumobjects = p.loadSDF("%sstadium.sdf" % self._urdfRoot)
#p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","plane.urdf"))
stadiumobjects = p.loadSDF(os.path.join(os.path.dirname(__file__),"../data","stadium.sdf"))
#move the stadium objects slightly above 0
for i in stadiumobjects:
pos,orn = p.getBasePositionAndOrientation(i)
@@ -65,7 +66,7 @@ class RacecarZEDGymEnv(gym.Env):
bally = dist * math.cos(ang)
ballz = 1
self._ballUniqueId = p.loadURDF("sphere2red.urdf",[ballx,bally,ballz])
self._ballUniqueId = p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","sphere2red.urdf"),[ballx,bally,ballz])
p.setGravity(0,0,-10)
self._racecar = racecar.Racecar(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
self._envStepCounter = 0

View File

@@ -1,3 +1,4 @@
import os
import pybullet as p
import numpy as np
import copy
@@ -18,7 +19,7 @@ class SimpleHumanoid:
def reset(self):
self.initial_z = None
objs = p.loadMJCF("mjcf/humanoid_symmetric_no_ground.xml",flags = p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
objs = p.loadMJCF(os.path.join(os.path.dirname(__file__),"../data","mjcf/humanoid_symmetric_no_ground.xml"),flags = p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
self.human = objs[0]
self.jdict = {}
self.ordered_joints = []

View File

@@ -1,3 +1,4 @@
import os
import math
import gym
from gym import spaces
@@ -47,7 +48,7 @@ class SimpleHumanoidGymEnv(gym.Env):
p.resetSimulation()
#p.setPhysicsEngineParameter(numSolverIterations=300)
p.setTimeStep(self._timeStep)
p.loadURDF("%splane.urdf" % self._urdfRoot)
p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","plane.urdf"))
dist = 5 +2.*random.random()
ang = 2.*3.1415925438*random.random()
@@ -99,4 +100,4 @@ class SimpleHumanoidGymEnv(gym.Env):
def _reward(self):
reward=self._humanoid.distance
print(reward)
return reward
return reward

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.8 KiB

File diff suppressed because one or more lines are too long

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

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

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

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 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

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

File diff suppressed because one or more lines are too long

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,485 @@
<?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"/>
<link name="chassis">
<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>
<material name="white">
<color rgba="1.0 1.0 1.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>

View File

@@ -0,0 +1,32 @@
<?xml version="0.0" ?>
<robot name="urdf_robot">
<link name="baseLink">
<contact>
<rolling_friction value="0.03"/>
<spinning_friction value="0.03"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="10.0"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="textured_sphere_smooth.obj" scale="0.5 0.5 0.5"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
<specular rgb="11 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.5"/>
</geometry>
</collision>
</link>
</robot>

View File

@@ -0,0 +1,32 @@
<?xml version="0.0" ?>
<robot name="urdf_robot">
<link name="baseLink">
<contact>
<rolling_friction value="0.03"/>
<spinning_friction value="0.03"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="10.0"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="sphere_smooth.obj" scale="0.5 0.5 0.5"/>
</geometry>
<material name="red">
<color rgba="1 0.2 0.2 1"/>
<specular rgb="1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.5"/>
</geometry>
</collision>
</link>
</robot>

View File

@@ -0,0 +1,10 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 1. 0.2 0.2
Ks 0.8 0.8 0.8
d 1
illum 2

File diff suppressed because it is too large Load Diff

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 checker_huge.gif

File diff suppressed because it is too large Load Diff