Fix values in kdl_parser test
This commit is contained in:
parent
9869a67924
commit
612d433920
|
@ -71,13 +71,13 @@ TEST_F(TestParser, test)
|
|||
}
|
||||
|
||||
ASSERT_TRUE(treeFromFile(g_argv[g_argc-1], my_tree));
|
||||
ASSERT_EQ(my_tree.getNrOfJoints(), 3);
|
||||
ASSERT_EQ(my_tree.getNrOfSegments(), 4);
|
||||
ASSERT_TRUE(my_tree.getSegment("link1") == my_tree.getRootSegment());
|
||||
ASSERT_EQ(my_tree.getNrOfJoints(), 8);
|
||||
ASSERT_EQ(my_tree.getNrOfSegments(), 16);
|
||||
ASSERT_TRUE(my_tree.getSegment("dummy_link") == my_tree.getRootSegment());
|
||||
ASSERT_EQ(my_tree.getRootSegment()->second.children.size(), (unsigned int)1);
|
||||
ASSERT_TRUE(my_tree.getSegment("base_link")->second.parent == my_tree.getRootSegment());
|
||||
ASSERT_EQ(my_tree.getSegment("base_link")->second.segment.getInertia().getMass(), 116.0);
|
||||
ASSERT_NEAR(my_tree.getSegment("base_link")->second.segment.getInertia().getRotationalInertia().data[0], 15.6107, 0.001);
|
||||
ASSERT_EQ(my_tree.getSegment("base_link")->second.segment.getInertia().getMass(), 10.0);
|
||||
ASSERT_NEAR(my_tree.getSegment("base_link")->second.segment.getInertia().getRotationalInertia().data[0], 1.000, 0.001);
|
||||
SUCCEED();
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue