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 #include <fstream>
00050 
00051 #include <urdf_parser/urdf_parser.h>
00052 #include <boost/function.hpp>
00053 #include <urdf_model/model.h>
00054 
00055 int runExternalProcess(const std::string &executable, const std::string &args)
00056 {
00057     return system((executable + " " + args).c_str());
00058 }
00059 
00060 int walker( std::string & result, int& test_result)
00061 {
00062   DIR           *d;
00063   struct dirent *dir;
00064   d = opendir( "robots" );
00065   if( d == NULL )
00066   {
00067     return 1;
00068   }
00069   while( ( dir = readdir( d ) ) )
00070   {
00071     if( strcmp( dir->d_name, "." ) == 0 || 
00072         strcmp( dir->d_name, ".." ) == 0 )
00073     {
00074       continue;
00075     }
00076     if( dir->d_type != DT_DIR )
00077     {
00078       std::string dir_name = dir->d_name;
00079       if (dir_name.find(std::string(".urdf.xacro")) == dir_name.size()-11)
00080       {
00081         char pwd[MAXPATHLEN];
00082         getcwd( pwd, MAXPATHLEN );
00083         std::string name = std::string(pwd)+"/robots/"+dir_name;
00084         printf("\n\ntesting: %s\n",name.c_str());
00085         result += name;
00086         result += " ";
00087 
00088         runExternalProcess("python `rospack find xacro`/xacro.py", name+" > `rospack find pr2_description`/test/tmp.urdf" );
00089 
00090         std::string path = std::string(pwd)+"/test/tmp.urdf";
00091 
00092 
00093         std::string xml_string;
00094         std::fstream xml_file(path.c_str(), std::fstream::in);
00095         while ( xml_file.good() )
00096         {
00097             std::string line;
00098             std::getline( xml_file, line);
00099             xml_string += (line + "\n");
00100         }
00101         xml_file.close();
00102 
00103         boost::shared_ptr<urdf::ModelInterface> robot = urdf::parseURDF(xml_string);
00104         if (!robot) test_result = test_result || 1;
00105 
00106       }
00107     }
00108   }
00109   closedir( d );
00110   return test_result;
00111 }
00112 
00113 TEST(URDF, CorrectFormat)
00114 {
00115   int test_result = 0;
00116 
00117   std::string result;
00118   if( walker( result, test_result ) == 0 )
00119   {
00120     printf( "Found: %s\n", result.c_str() );
00121   }
00122   else
00123   {
00124     puts( "Not found" );
00125     test_result = -1;
00126   }
00127 
00128   EXPECT_TRUE(test_result == 0);
00129 }
00130 
00131 int main(int argc, char **argv)
00132 {
00133     testing::InitGoogleTest(&argc, argv);
00134     return RUN_ALL_TESTS();
00135 }