33 #include <gtest/gtest.h>    46     nav_msgs::GetMap::Response map_resp;
    47     double origin[3] = { 0.0, 0.0, 0.0 };
    52     for(
unsigned int i=0; i < map_resp.map.info.width * map_resp.map.info.height; i++)
    57     ADD_FAILURE() << 
"Uncaught exception : " << 
"This is OK on OS X";
    67     nav_msgs::GetMap::Response map_resp;
    68     double origin[3] = { 0.0, 0.0, 0.0 };
    73     for(
unsigned int i=0; i < map_resp.map.info.width * map_resp.map.info.height; i++)
    78     ADD_FAILURE() << 
"Uncaught exception";
    88     nav_msgs::GetMap::Response map_resp;
    89     double origin[3] = { 0.0, 0.0, 0.0 };
    92   catch(std::runtime_error &e)
    99     FAIL() << 
"Uncaught exception";
   101   ADD_FAILURE() << 
"Didn't throw exception as expected";
   104 int main(
int argc, 
char **argv)
   106   testing::InitGoogleTest(&argc, argv);
   107   return RUN_ALL_TESTS();
 TEST(MapServer, loadValidPNG)
const unsigned int g_valid_image_height
const unsigned int g_valid_image_width
int main(int argc, char **argv)
void loadMapFromFile(nav_msgs::GetMap::Response *resp, const char *fname, double res, bool negate, double occ_th, double free_th, double *origin, MapMode mode=TRINARY)
const float g_valid_image_res
const char * g_valid_png_file
const char * g_valid_bmp_file
const char g_valid_image_content[]