Fix bad sdf based on xml schemas

This commit is contained in:
Nate Koenig 2014-12-17 08:57:44 -08:00
parent 956f832f4a
commit 06eada8617
20 changed files with 15 additions and 33 deletions

View File

@ -33,7 +33,6 @@
<contact>
<ode>
<soft_cfm>0.001 </soft_cfm><!--"sponginess", 0.0=hard-->
<soft_erp> </soft_erp>
<kp>10000.0 </kp>
<kd>1000.0 </kd>
<max_vel>0.01 </max_vel>

View File

@ -34,7 +34,6 @@
<ode>
<soft_cfm>0.001</soft_cfm>
<!--"sponginess", 0.0=hard-->
<soft_erp />
<kp>10000.0</kp>
<kd>1000.0</kd>
<max_vel>0.01</max_vel>

View File

@ -35,7 +35,6 @@
<contact>
<ode>
<soft_cfm>0.01</soft_cfm><!--"sponginess", 0.0=hard-->
<soft_erp></soft_erp>
<kp>10000.0</kp>
<kd>1000.0</kd>
<max_vel>0.01</max_vel>

View File

@ -36,7 +36,6 @@
<ode>
<soft_cfm>0.01</soft_cfm>
<!--"sponginess", 0.0=hard-->
<soft_erp />
<kp>10000.0</kp>
<kd>1000.0</kd>
<max_vel>0.01</max_vel>

View File

@ -36,7 +36,6 @@
<contact>
<ode>
<soft_cfm>0.01</soft_cfm>
<soft_erp></soft_erp>
<kp>1000000.0</kp>
<kd>100000.0</kd>
<max_vel>0.01</max_vel>

View File

@ -34,7 +34,6 @@
<contact>
<ode>
<soft_cfm>0.01</soft_cfm>
<soft_erp />
<kp>1000000.0</kp>
<kd>100000.0</kd>
<max_vel>0.01</max_vel>

View File

@ -23,7 +23,6 @@
<contact>
<ode>
<soft_cfm>0.001 </soft_cfm><!--"sponginess", 0.0=hard-->
<soft_erp> </soft_erp>
<kp>10000.0 </kp>
<kd>1000.0 </kd>
<max_vel>0.01 </max_vel>

View File

@ -24,7 +24,6 @@
<ode>
<soft_cfm>0.001</soft_cfm>
<!--"sponginess", 0.0=hard-->
<soft_erp />
<kp>10000.0</kp>
<kd>1000.0</kd>
<max_vel>0.01</max_vel>

View File

@ -144,8 +144,6 @@
<limit>
<lower>0</lower>
<upper>1.58</upper>
<effort></effort>
<velocity></velocity>
</limit>
<dynamics>
<damping>1.0</damping>

View File

@ -132,8 +132,6 @@
<limit>
<lower>0</lower>
<upper>1.58</upper>
<effort />
<velocity />
</limit>
<dynamics>
<damping>1.0</damping>

View File

@ -597,7 +597,7 @@
</sphere>
</geometry>
<material>
<script>Gazebo/Red</script>
<script><name>Gazebo/Red</name></script>
</material>
</visual>
<collision name='head_tilt_link_geom_head_mount_kinect_rgb_link'>
@ -616,7 +616,7 @@
</sphere>
</geometry>
<material>
<script>Gazebo/Red</script>
<script><name>Gazebo/Red</name></script>
</material>
</visual>
<collision name='head_tilt_link_geom_head_mount_link'>
@ -652,7 +652,7 @@
</sphere>
</geometry>
<material>
<script>Gazebo/Red</script>
<script><name>Gazebo/Red</name></script>
</material>
</visual>
<collision name='head_tilt_link_geom_head_plate_frame'>

View File

@ -597,7 +597,7 @@
</sphere>
</geometry>
<material>
<script>Gazebo/Red</script>
<script><name>Gazebo/Red</name></script>
</material>
</visual>
<collision name='head_tilt_link_geom_head_mount_kinect_rgb_link'>
@ -616,7 +616,7 @@
</sphere>
</geometry>
<material>
<script>Gazebo/Red</script>
<script><name>Gazebo/Red</name></script>
</material>
</visual>
<collision name='head_tilt_link_geom_head_mount_link'>
@ -652,7 +652,7 @@
</sphere>
</geometry>
<material>
<script>Gazebo/Red</script>
<script><name>Gazebo/Red</name></script>
</material>
</visual>
<collision name='head_tilt_link_geom_head_plate_frame'>

View File

@ -596,7 +596,7 @@
</sphere>
</geometry>
<material>
<script>Gazebo/Red</script>
<script><name>Gazebo/Red</name></script>
</material>
</visual>
<collision name="head_tilt_link_geom_head_mount_kinect_rgb_link">
@ -615,7 +615,7 @@
</sphere>
</geometry>
<material>
<script>Gazebo/Red</script>
<script><name>Gazebo/Red</name></script>
</material>
</visual>
<collision name="head_tilt_link_geom_head_mount_link">
@ -651,7 +651,7 @@
</sphere>
</geometry>
<material>
<script>Gazebo/Red</script>
<script><name>Gazebo/Red</name></script>
</material>
</visual>
<collision name="head_tilt_link_geom_head_plate_frame">
@ -670,7 +670,7 @@
</box>
</geometry>
<material>
<script>Gazebo/Grey</script>
<script><name>Gazebo/Grey</name></script>
</material>
</visual>
<sensor name="head_mount_sensor" type="camera">

View File

@ -714,4 +714,3 @@
<static>0</static>
</model>
</gazebo>
Success

View File

@ -173,7 +173,7 @@
</visual>
</link>
<link name="center_support_horiz_lower">_h
<link name="center_support_horiz_lower">
<pose>0.44 0 0.01 0 1.5708 0</pose>
<collision name="collision">
<geometry>
@ -197,7 +197,7 @@
</visual>
</link>
<link name="center_support_horiz_upper">_
<link name="center_support_horiz_upper">
<pose>0.44 0 0.79 0 1.5708 0</pose>
<collision name="collision">
<geometry>

View File

@ -166,7 +166,6 @@
</visual>
</link>
<link name="center_support_horiz_lower">
_h
<pose>0.44 0 0.01 0 1.5708 0</pose>
<collision name="collision">
<geometry>
@ -190,7 +189,6 @@
</visual>
</link>
<link name="center_support_horiz_upper">
_
<pose>0.44 0 0.79 0 1.5708 0</pose>
<collision name="collision">
<geometry>

View File

@ -173,7 +173,7 @@
</visual>
</link>
<link name="center_support_horiz_lower">_h
<link name="center_support_horiz_lower">
<pose>0.44 0 0.01 0 1.5708 0</pose>
<collision name="collision">
<geometry>
@ -197,7 +197,7 @@
</visual>
</link>
<link name="center_support_horiz_upper">_
<link name="center_support_horiz_upper">
<pose>0.44 0 0.79 0 1.5708 0</pose>
<collision name="collision">
<geometry>

View File

@ -166,7 +166,6 @@
</visual>
</link>
<link name="center_support_horiz_lower">
_h
<pose>0.44 0 0.01 0 1.5708 0</pose>
<collision name="collision">
<geometry>
@ -190,7 +189,6 @@
</visual>
</link>
<link name="center_support_horiz_upper">
_
<pose>0.44 0 0.79 0 1.5708 0</pose>
<collision name="collision">
<geometry>

View File

@ -55,7 +55,7 @@
<box>
<size>4.25 0.45 4.28</size>
</box>
</geometry>hg
</geometry>
</collision>
<collision name="wall_07">

View File

@ -50,7 +50,6 @@
<size>4.25 0.45 4.28</size>
</box>
</geometry>
hg
</collision>
<collision name="wall_07">
<pose>1.94 12.3 2.14 0 0 0</pose>