diff --git a/urdf/test/singularity.urdf b/urdf/test/singularity.urdf new file mode 100644 index 0000000..f86fa92 --- /dev/null +++ b/urdf/test/singularity.urdf @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/urdf/test/test_robot_model_parser.cpp b/urdf/test/test_robot_model_parser.cpp index 0be1a77..f238762 100644 --- a/urdf/test/test_robot_model_parser.cpp +++ b/urdf/test/test_robot_model_parser.cpp @@ -52,6 +52,21 @@ class TestParser : public testing::Test public: Model robot; + bool checkModel() + { + // get root link + boost::shared_ptr root_link=this->robot.getRoot(); + if (!root_link) + { + ROS_ERROR("no root link %s",this->robot.getName().c_str()); + return false; + } + + // go through entire tree + return this->traverse_tree(root_link); + + }; + protected: /// constructor TestParser() @@ -63,6 +78,36 @@ protected: ~TestParser() { } + + bool traverse_tree(boost::shared_ptr link,int level = 0) + { + level+=2; + int count = 0; + for (std::vector >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) + { + if (*child) + { + // check rpy + double roll,pitch,yaw; + (*child)->parent_joint->parent_to_joint_origin_transform.rotation.getRPY(roll,pitch,yaw); + + if (isnan(roll) || isnan(pitch) || isnan(yaw)) + { + ROS_ERROR("getRPY() returned nan!"); + return false; + } + // recurse down the tree + return this->traverse_tree(*child,level); + } + else + { + ROS_ERROR("root link: %s has a null child!",link->name.c_str()); + return false; + } + } + // no children + return true; + }; }; @@ -71,15 +116,18 @@ protected: TEST_F(TestParser, test) { std::string folder = std::string(g_argv[1]) + "/test/"; - printf("Folder %s",folder.c_str()); + ROS_INFO("Folder %s",folder.c_str()); for (int i=2; i - +