main.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include "rtabmap/utilite/ULogger.h"
00029 #include "rtabmap/utilite/UTimer.h"
00030 #include "rtabmap/utilite/UDirectory.h"
00031 #include "rtabmap/utilite/UFile.h"
00032 #include "rtabmap/utilite/UConversion.h"
00033 #include <opencv2/core/core.hpp>
00034 #include <opencv2/highgui/highgui.hpp>
00035 
00036 void showUsage()
00037 {
00038         printf("Usage:\n"
00039                         "imagesJoiner.exe [option] path\n"
00040                         "  Options:\n"
00041                         "    -inv       option for copying odd images on the right\n\n");
00042         exit(1);
00043 }
00044 
00045 int main(int argc, char * argv[])
00046 {
00047         if(argc < 2)
00048         {
00049                 showUsage();
00050         }
00051 
00052         bool inv = false;
00053         for(int i=1; i<argc-1; ++i)
00054         {
00055                 if(strcmp(argv[i], "-inv") == 0)
00056                 {
00057                         inv = true;
00058                         printf(" Inversing option activated...\n");
00059                         continue;
00060                 }
00061                 showUsage();
00062                 printf(" Not recognized option: \"%s\"\n", argv[i]);
00063         }
00064 
00065         std::string path = argv[argc-1];
00066         printf(" Path = %s\n", path.c_str());
00067 
00068         UDirectory dir(path, "jpg bmp png tiff jpeg");
00069         if(!dir.isValid())
00070         {
00071                 printf("Path invalid!\n");
00072                 exit(-1);
00073         }
00074 
00075         std::string targetDirectory = path+"_joined";
00076         UDirectory::makeDir(targetDirectory);
00077         printf(" Creating directory \"%s\"\n", targetDirectory.c_str());
00078 
00079 
00080         std::string fileNameA = dir.getNextFilePath();
00081         std::string fileNameB = dir.getNextFilePath();
00082 
00083         int i=1;
00084         while(!fileNameA.empty() && !fileNameB.empty())
00085         {
00086                 if(inv)
00087                 {
00088                         std::string tmp = fileNameA;
00089                         fileNameA = fileNameB;
00090                         fileNameB = tmp;
00091                 }
00092 
00093                 std::string ext = UFile::getExtension(fileNameA);
00094 
00095                 std::string targetFilePath = targetDirectory+UDirectory::separator()+uNumber2Str(i++)+"."+ext;
00096 
00097                 IplImage * imageA = cvLoadImage(fileNameA.c_str(), CV_LOAD_IMAGE_COLOR);
00098                 IplImage * imageB = cvLoadImage(fileNameB.c_str(), CV_LOAD_IMAGE_COLOR);
00099 
00100                 fileNameA.clear();
00101                 fileNameB.clear();
00102 
00103                 if(imageA && imageB)
00104                 {
00105                         CvSize sizeA = cvGetSize(imageA);
00106                         CvSize sizeB = cvGetSize(imageB);
00107                         CvSize targetSize = {0};
00108                         targetSize.width = sizeA.width + sizeB.width;
00109                         targetSize.height = sizeA.height > sizeB.height ? sizeA.height : sizeB.height;
00110                         IplImage* targetImage = cvCreateImage(targetSize, imageA->depth, imageA->nChannels);
00111                         if(targetImage)
00112                         {
00113                                 cvSetImageROI( targetImage, cvRect( 0, 0, sizeA.width, sizeA.height ) );
00114                                 cvCopy( imageA, targetImage );
00115                                 cvSetImageROI( targetImage, cvRect( sizeA.width, 0, sizeB.width, sizeB.height ) );
00116                                 cvCopy( imageB, targetImage );
00117                                 cvResetImageROI( targetImage );
00118 
00119                                 if(!cvSaveImage(targetFilePath.c_str(), targetImage))
00120                                 {
00121                                         printf("Error : saving to \"%s\" goes wrong...\n", targetFilePath.c_str());
00122                                 }
00123                                 else
00124                                 {
00125                                         printf("Saved \"%s\" \n", targetFilePath.c_str());
00126                                 }
00127 
00128                                 cvReleaseImage(&targetImage);
00129 
00130                                 fileNameA = dir.getNextFilePath();
00131                                 fileNameB = dir.getNextFilePath();
00132                         }
00133                         else
00134                         {
00135                                 printf("Error : can't allocated the target image with size (%d,%d)\n", targetSize.width, targetSize.height);
00136                         }
00137                 }
00138                 else
00139                 {
00140                         printf("Error: loading images failed!\n");
00141                 }
00142 
00143                 if(imageA)
00144                 {
00145                         cvReleaseImage(&imageA);
00146                 }
00147                 if(imageB)
00148                 {
00149                         cvReleaseImage(&imageB);
00150                 }
00151         }
00152         printf("%d files processed\n", i-1);
00153 
00154         return 0;
00155 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:31