From 612d4339201696cc8066977f12f238be0774eb1a Mon Sep 17 00:00:00 2001 From: Jackie Kay Date: Wed, 9 Dec 2015 16:32:45 -0800 Subject: [PATCH] Fix values in kdl_parser test --- kdl_parser/test/test_kdl_parser.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/kdl_parser/test/test_kdl_parser.cpp b/kdl_parser/test/test_kdl_parser.cpp index 59ce8e1..ad0bb98 100644 --- a/kdl_parser/test/test_kdl_parser.cpp +++ b/kdl_parser/test/test_kdl_parser.cpp @@ -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(); }