pull regression test fix from 1.0 branch. r28659:r28660

This commit is contained in:
wim 2010-04-08 18:36:06 +00:00
parent a53de106cd
commit b34eed700f
4 changed files with 4 additions and 5 deletions

View File

@ -2,7 +2,7 @@
<robot name="pr2">
<joint name="fl_caster_rotation_joint" type="revolute">
<axis xyz="0 0 1"/>
<axis xyz="0 0 1 /"/>
<anchor xyz="0 0 0"/>
<limit effort="100" k_velocity="10" velocity="100"/>
<calibration reference_position="0.0" values="1.5 -1"/>
@ -11,7 +11,6 @@
<link name="fl_caster_rotation_link">
<parent name="base_link"/>
<origin rpy="0 0 1 }" xyz="0.2225 0.2225 0.0282"/>
<joint name="fl_caster_rotation_joint"/>
<inertial>

View File

@ -11,11 +11,10 @@
<link name="fl_caster_rotation_link">
<parent name="base_link"/>
<origin rpy="0 0 1}" xyz="0.2225 0.2225 0.0282"/>
<joint name="fl_caster_rotation_joint"/>
<inertial>
<mass value="3.473082"/>
<mass value="3.473082}"/>
<com xyz="0 0 0.07"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>

View File

@ -2,7 +2,7 @@
<robot name="pr2">
<joint name="fl_caster_rotation_joint" type="revolute">
<axis xyz="0 0 1"/>
<axis xyz="0 0"/>
<anchor xyz="0 0 0"/>
<limit effort="100" k_velocity="10" velocity="100"/>
<calibration reference_position="0.0" values="1.5 -1"/>

View File

@ -68,6 +68,7 @@ protected:
TEST_F(TestParser, test)
{
for (int i=1; i<g_argc-2; i++){
ROS_ERROR("Testing file %s", g_argv[i]);
ASSERT_FALSE(treeFromFile(g_argv[i], my_tree));
}