photo_image.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2012, Robert Bosch LLC.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Robert Bosch nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  *********************************************************************/
00036 #include <opencv2/core/core.hpp>
00037 #include <opencv2/highgui/highgui.hpp>
00038 
00039 #include <iostream>
00040 
00041 #include <photo/photo_image.hpp>
00042 
00043 photo_image::photo_image( void ) :
00044   width_(0),
00045   height_(0),
00046   bytes_per_pixel_(3),
00047   image_size_(0),
00048   data_(NULL)
00049 {
00050 }
00051 
00052 photo_image::~photo_image( void )
00053 {
00054   delete[] data_; // delete on a NULL pointer has no effect, so this will work if data_ points to an image or not
00055 }
00056 
00057 
00058 int photo_image::getWidth( void )
00059 {
00060   return width_;
00061 }
00062 
00063 int photo_image::getHeight( void )
00064 {
00065   return height_;
00066 }
00067 
00068 size_t photo_image::getBytesPerPixel( void )
00069 {
00070   return bytes_per_pixel_;
00071 }
00072 
00073 size_t photo_image::getImageSize( void )
00074 {
00075   return image_size_;
00076 }
00077 
00078 char* photo_image::getDataAddress( void )
00079 {
00080   return data_;
00081 }
00082 
00083 //* sets size and allocates memory for image data
00084 void photo_image::photo_image_set_size( int image_width, int image_height, size_t image_bytes_per_pixel )
00085 {
00086   delete[] data_; // delete on a NULL pointer has no effect
00087 
00088   width_ = image_width;
00089   height_ = image_height;
00090   bytes_per_pixel_ = image_bytes_per_pixel;
00091   image_size_ = width_ * height_ * bytes_per_pixel_;
00092   
00093   data_ = new char[image_size_](); // create array and initialize to default value: 0
00094 }
00095 
00096 //* reads an image from filesystem
00097 bool photo_image::photo_image_read( std::string filename )
00098 {
00099   int r, c;
00100   // Read image from file using OpenCV
00101   cv::Mat img = cv::imread( filename.c_str() );
00102   if( img.empty() )
00103   {
00104     std::cerr << "img.empty() == true" << std::endl;
00105     return false;
00106   }
00107 
00108   int w = img.cols;
00109   int h = img.rows;
00110 
00111 
00112   //int chan = img.channels(); // number of data channels, ex: 3 for RGB
00113   int d = img.elemSize(); // bytes per element: 1 element has 'chan' channels of data
00114 
00115   // Store image in photo_image
00116   if( width_ != w || height_ != h )
00117   {
00118     //std::cout << "Setting size to " << w << " x " << h << " x " << d << ".";
00119     photo_image_set_size( w, h, d );
00120   }
00121 
00122   size_t n = 0; // counter for iterating over data_
00123   for( r = 0; r < height_; ++r )
00124   {
00125     for( c = 0; c < width_; ++c )
00126     {
00127       // This assumes the image is 24-bit RGB. Needs improvement to handle other image types.
00128       const cv::Vec3b& pixel = img.at<cv::Vec3b>(r, c);
00129 
00130       uint8_t R = pixel[2]; // Red
00131       uint8_t G = pixel[1]; // Green
00132       uint8_t B = pixel[0]; // Blue
00133 
00134       data_[n++] = R; // R
00135       data_[n++] = G; // G
00136       data_[n++] = B; // B
00137     }
00138   }
00139   return true;
00140 }
00141 
00142 //* writes an image to filesystem
00143 bool photo_image::photo_image_write( std::string filename )
00144 {
00145   int r, c;
00146 
00147   // Create OpenCV image for 24-bit RGB
00148   cv::Mat img (height_, width_, CV_8UC3);
00149 
00150   int n = 0;
00151   for( r = 0; r < height_; ++r )
00152   {
00153     for( c = 0; c < width_; ++c )
00154     {
00155       img.at<unsigned char> (r, 3*c+2) = data_[n++]; // Red
00156       img.at<unsigned char> (r, 3*c+1) = data_[n++]; // Green
00157       img.at<unsigned char> (r, 3*c+0) = data_[n++]; // Blue
00158     }
00159   }
00160   cv::imwrite( filename.c_str(), img );
00161   return true;
00162 }


photo
Author(s): Benjamin Pitzer
autogenerated on Mon Oct 6 2014 10:09:43