Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #include <gtest/gtest.h>
00038 #include <cstdlib>
00039
00040 #include <dirent.h>
00041 #include <sys/types.h>
00042 #include <sys/param.h>
00043 #include <sys/stat.h>
00044 #include <unistd.h>
00045 #include <stdio.h>
00046 #include <string.h>
00047
00048 #include <iostream>
00049
00050 int runExternalProcess(const std::string &executable, const std::string &args)
00051 {
00052 return system((executable + " " + args).c_str());
00053 }
00054
00055 int walker( char *result, int& test_result)
00056 {
00057 DIR *d;
00058 struct dirent *dir;
00059 d = opendir( "robots" );
00060 if( d == NULL )
00061 {
00062 return 1;
00063 }
00064 while( ( dir = readdir( d ) ) )
00065 {
00066 if( strcmp( dir->d_name, "." ) == 0 ||
00067 strcmp( dir->d_name, ".." ) == 0 )
00068 {
00069 continue;
00070 }
00071 if( dir->d_type != DT_DIR )
00072 {
00073 std::string dir_name = dir->d_name;
00074 if (dir_name.find(std::string(".urdf.xacro")) == dir_name.size()-11)
00075 {
00076 char pwd[MAXPATHLEN];
00077 getcwd( pwd, MAXPATHLEN );
00078 printf("\n\ntesting: %s\n",(std::string(pwd)+"/robots/"+dir_name).c_str());
00079 printf("python `rospack find xacro`/xacro.py %s/robots/%s > `rospack find sr_description`/test/tmp.urdf", pwd, dir_name.c_str() );
00080 runExternalProcess("python `rospack find xacro`/xacro.py", std::string(pwd)+"/robots/"+dir_name+" > `rospack find sr_description`/test/tmp.urdf" );
00081
00082 test_result = test_result || runExternalProcess("`rospack find urdf_parser`/bin/check_urdf", "`rospack find sr_description`/test/tmp.urdf");
00083 }
00084 }
00085 }
00086 closedir( d );
00087 return *result == 0;
00088 }
00089
00090 TEST(URDF, CorrectFormat)
00091 {
00092 int test_result = 0;
00093
00094 char buf[MAXPATHLEN] = { 0 };
00095 if( walker( buf, test_result ) == 0 )
00096 {
00097 printf( "Found: %s\n", buf );
00098 }
00099 else
00100 {
00101 puts( "Not found" );
00102 }
00103
00104 EXPECT_TRUE(test_result == 0);
00105 }
00106
00107 int main(int argc, char **argv)
00108 {
00109 testing::InitGoogleTest(&argc, argv);
00110 return RUN_ALL_TESTS();
00111 }