testImageProcessor.cpp
Go to the documentation of this file.
00001 #include <blort/Tracker/ImageProcessor.h>
00002 #include <blort/TomGine/tgEngine.h>
00003 
00004 #include <ros/ros.h>
00005 #include <ros/package.h>
00006 
00007 void testProcess(Tracking::Texture & out, const std::string & process_name)
00008 {
00009   Tracking::Texture ref;
00010   {
00011     std::string ref_path = ros::package::getPath("blort_ros") + "/test/lenna_" + process_name + ".png";
00012     ref.load(ref_path.c_str());
00013   }
00014   if(out.getWidth() != ref.getWidth())
00015   {
00016     std::cerr << "Output of " << process_name << " has a difference width from the reference" << std::endl;
00017     return;
00018   }
00019   if(out.getHeight() != ref.getHeight())
00020   {
00021     std::cerr << "Output of " << process_name << " has a difference height from the reference" << std::endl;
00022     return;
00023   }
00024   unsigned char * out_data = new unsigned char[out.getWidth()*out.getHeight()*3];
00025   memset(out_data, 0, out.getWidth()*out.getHeight()*3);
00026   out.getImageData(out_data);
00027   unsigned char * ref_data = new unsigned char[ref.getWidth()*ref.getHeight()*3];
00028   memset(ref_data, 0, ref.getWidth()*ref.getHeight()*3);
00029   ref.getImageData(ref_data);
00030   int res = memcmp(out_data, ref_data, out.getWidth()*out.getHeight()*3);
00031   if(res != 0)
00032   {
00033     /* Compute a distance between the two images if the match is not perfect */
00034     unsigned int out_g = 0; unsigned int ref_g = 0;
00035     unsigned int distance = 0;
00036     for(size_t i = 0; i < out.getWidth()*out.getHeight(); ++i)
00037     {
00038       out_g = (out_data[3*i] + out_data[3*i+1] + out_data[3*i+2]);
00039       ref_g = (ref_data[3*i] + ref_data[3*i+1] + ref_data[3*i+2]);
00040       distance += ref_g > out_g ? ref_g - out_g : out_g - ref_g;
00041     }
00042     double d = static_cast<double>(distance)/static_cast<double>(out.getWidth()*out.getHeight());
00043     if(d > 1e-1)
00044     {
00045       std::cerr << "Output data of " << process_name << " does not match the reference" << std::endl;
00046       std::cout << "Average distance: " << d << std::endl;
00047     }
00048   }
00049   delete[] out_data;
00050   delete[] ref_data;
00051 }
00052 
00053 int main(int argc, char * argv[])
00054 {
00055   ros::init(argc, argv, "test_sobel_shader");
00056   std::string lenna_path = ros::package::getPath("blort_ros") + "/test/lenna.png";
00057   /* This create an OpenGL context to work with */
00058   TomGine::tgEngine window(512, 512, 1.0f, 0.1, "Sobel shader test", false);
00059 
00060   /* Load image first */
00061   Tracking::Texture in;
00062   in.load(lenna_path.c_str());
00063   Tracking::Texture out;
00064   float w = static_cast<float>(in.getWidth());
00065   float h = static_cast<float>(in.getHeight());
00066 
00067   std::string shader_path = ros::package::getPath("blort_ros") + "/Tracker/shader/";
00068   g_Resources->SetShaderPath(shader_path.c_str());
00069 
00070   Tracking::ImageProcessor ip;
00071   ip.init(w,h);
00072 
00073   in.save("in.png");
00074 
00075   ip.flipUpsideDown(&in, &out);
00076   out.save("out_flipUpsideDown.png");
00077   testProcess(out, "flipUpsideDown");
00078 
00079   ip.copy(&in, &out);
00080   out.save("out_copy.png");
00081   testProcess(out, "copy");
00082 
00083   ip.rectification(&in, &out);
00084   out.save("out_rectification.png");
00085   testProcess(out, "rectification");
00086 
00087   ip.gauss(&in, &out);
00088   out.save("out_gauss.png");
00089   testProcess(out, "gauss");
00090 
00091   ip.sobel(&in, &out, 0.1, true, false);
00092   out.save("out_sobel.png");
00093   testProcess(out, "sobel");
00094 
00095   ip.thinning(&in, &out);
00096   out.save("out_thinning.png");
00097   testProcess(out, "thinning");
00098 
00099   ip.spreading(&in, &out);
00100   out.save("out_spreading.png");
00101   testProcess(out, "spreading");
00102 
00103   return 0;
00104 }


blort_ros
Author(s): Bence Magyar
autogenerated on Wed Aug 26 2015 15:24:39