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
00039 #include <gtest/gtest.h>
00040 #include <cstdlib>
00041
00042 #include <dirent.h>
00043 #include <sys/types.h>
00044 #include <sys/param.h>
00045 #include <sys/stat.h>
00046 #include <unistd.h>
00047 #include <stdio.h>
00048 #include <string.h>
00049
00050 #include <iostream>
00051
00052 int runExternalProcess(const std::string &executable, const std::string &args)
00053 {
00054 return system((executable + " " + args).c_str());
00055 }
00056
00057 std::string getCommandOutput(std::string cmd) {
00058
00059 std::string data;
00060 FILE * stream;
00061 char buffer[MAXPATHLEN];
00062
00063 stream = popen(cmd.c_str(), "r");
00064 if (stream) {
00065 while (!feof(stream))
00066 if (fgets(buffer, MAXPATHLEN, stream) != NULL) data.append(buffer);
00067 pclose(stream);
00068 }
00069
00070 unsigned pos = data.find_first_of('\n');
00071 return data.substr(0,pos);
00072 }
00073
00074 int walker( char *result, int& test_result)
00075 {
00076 std::string package_path = getCommandOutput("rospack find sr_description");
00077
00078 if (package_path.find("sr_description")==std::string::npos)
00079 {
00080 printf("cannot find package in path %s\n",package_path.c_str());
00081 test_result = 1;
00082 return 1;
00083 }
00084 else
00085 {
00086 printf("sr_description robots path : %s\n",(package_path+"/robots").c_str());
00087 }
00088
00089 DIR *d;
00090 struct dirent *dir;
00091 d = opendir( (package_path+"/robots").c_str() );
00092 if( d == NULL )
00093 {
00094 printf("no robots found\n");
00095 test_result = 1;
00096 return 1;
00097 }
00098 while( ( dir = readdir( d ) ) )
00099 {
00100 if( strcmp( dir->d_name, "." ) == 0 ||
00101 strcmp( dir->d_name, ".." ) == 0 )
00102 {
00103 continue;
00104 }
00105 if( dir->d_type != DT_DIR )
00106 {
00107 std::string dir_name = dir->d_name;
00108 if (dir_name.find(std::string(".urdf.xacro")) == dir_name.size()-11)
00109 {
00110 printf("\n\ntesting: %s\n",(package_path+"/robots/"+dir_name).c_str());
00111 printf("python `rospack find xacro`/xacro.py %s/robots/%s > `rospack find sr_description`/test/tmp.urdf", package_path.c_str(), dir_name.c_str() );
00112 runExternalProcess("python `rospack find xacro`/xacro.py", package_path+"/robots/"+dir_name+" > `rospack find sr_description`/test/tmp.urdf" );
00113
00114 test_result = test_result || runExternalProcess("check_urdf", "`rospack find sr_description`/test/tmp.urdf");
00115 printf("\n looking for unexpanded xacro tags\n");
00116
00117 test_result = test_result || not runExternalProcess("grep","'<xacro:' `rospack find sr_description`/test/tmp.urdf");
00118 }
00119 if (test_result!=0)
00120 return *result == 0;
00121 }
00122 }
00123 closedir( d );
00124 return *result == 0;
00125 }
00126
00127 TEST(URDF, CorrectFormat)
00128 {
00129 int test_result = 0;
00130
00131 char buf[MAXPATHLEN] = { 0 };
00132 if( walker( buf, test_result ) == 0 )
00133 {
00134 printf( "Found: %s\n", buf );
00135 }
00136 else
00137 {
00138 puts( "Not found" );
00139 }
00140
00141 EXPECT_TRUE(test_result == 0);
00142 }
00143
00144 int main(int argc, char **argv)
00145 {
00146 testing::InitGoogleTest(&argc, argv);
00147 return RUN_ALL_TESTS();
00148 }