test_urdf.cpp
Go to the documentation of this file.
00001 #include <gtest/gtest.h>
00002 #include <ros/ros.h>
00003 
00004 int my_argc;
00005 char** my_argv;
00006 
00007 TEST(URDF, CorrectFormat)
00008 {
00009   int test_result = 0;
00010 
00011   // check if input file is given
00012   if ( my_argc <= 1 )
00013   {
00014     ROS_ERROR("No urdf file given");
00015     EXPECT_TRUE( false );
00016   }
00017   
00018   // urdf.xacro to test
00019   std::string file_to_test = std::string(my_argv[1]);
00020   ROS_INFO("testing: %s", file_to_test.c_str());
00021   
00022   // convert xacro to urdf
00023   std::string convert = "python `rospack find xacro`/xacro.py " + file_to_test + " > tmp.urdf";
00024   test_result = system(convert.c_str());
00025   EXPECT_TRUE(test_result == 0);
00026   
00027   // do urdf check
00028   test_result = system("`rospack find urdf_parser`/bin/check_urdf tmp.urdf");
00029   EXPECT_TRUE(test_result == 0);
00030 }
00031 
00032 int main(int argc, char **argv)
00033 {
00034     my_argc = argc;
00035     my_argv = argv;
00036         
00037     testing::InitGoogleTest(&argc, argv);
00038     return RUN_ALL_TESTS();
00039 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


cob_description
Author(s): Florian Weisshardt
autogenerated on Fri Mar 1 2013 17:46:12