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
00040 #include <gtest/gtest.h>
00041 #include <cstdlib>
00042
00043 #include <dirent.h>
00044 #include <sys/types.h>
00045 #include <sys/param.h>
00046 #include <sys/stat.h>
00047 #include <unistd.h>
00048 #include <stdio.h>
00049 #include <string.h>
00050
00051 #include <iostream>
00052
00053 int runExternalProcess(const std::string &executable, const std::string &args)
00054 {
00055 return system((executable + " " + args).c_str());
00056 }
00057
00058 int walker(std::string dir_str, char *result, int& test_result)
00059 {
00060 DIR *d;
00061 struct dirent *dir;
00062 d = opendir( dir_str.c_str() );
00063 if( d == NULL )
00064 {
00065 return 1;
00066 }
00067 while( ( dir = readdir( d ) ) )
00068 {
00069 if( strcmp( dir->d_name, "." ) == 0 ||
00070 strcmp( dir->d_name, ".." ) == 0 )
00071 {
00072 continue;
00073 }
00074 if( dir->d_type != DT_DIR )
00075 {
00076 std::string dir_name = dir->d_name;
00077 if (dir_name.find(std::string(".urdf.xacro")) == dir_name.size()-11)
00078 {
00079 char pwd[MAXPATHLEN];
00080 getcwd( pwd, MAXPATHLEN );
00081 printf("\n\ntesting: %s\n",(std::string(pwd) + "/" + dir_str + "/" + dir_name).c_str());
00082 runExternalProcess("python `rospack find xacro`/xacro.py", std::string(pwd) + "/" + dir_str + "/" + dir_name + " > `rospack find pr2_component_descriptions`/test/tmp.urdf" );
00083 test_result = test_result || runExternalProcess("`rospack find urdf_parser`/bin/check_urdf", "`rospack find pr2_component_descriptions`/test/tmp.urdf");
00084 }
00085 }
00086 }
00087 closedir( d );
00088 return *result == 0;
00089 }
00090
00091 TEST(URDF, CheckRobots)
00092 {
00093 int test_result = 0;
00094
00095 char buf[MAXPATHLEN] = { 0 };
00096 if( walker("robots", buf, test_result ) == 0 )
00097 {
00098 printf( "Found: %s\n", buf );
00099 }
00100 else
00101 {
00102 puts( "Not found" );
00103 }
00104
00105 EXPECT_TRUE(test_result == 0);
00106 }
00107
00108 TEST(URDF, CheckRobotMotors)
00109 {
00110 int test_result = 0;
00111
00112 char buf[MAXPATHLEN] = { 0 };
00113 if( walker("robot_motors", buf, test_result ) == 0 )
00114 {
00115 printf( "Found: %s\n", buf );
00116 }
00117 else
00118 {
00119 puts( "Not found" );
00120 }
00121
00122 EXPECT_TRUE(test_result == 0);
00123 }
00124
00125 int main(int argc, char **argv)
00126 {
00127 testing::InitGoogleTest(&argc, argv);
00128 return RUN_ALL_TESTS();
00129 }