processor.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 #include "image_proc/processor.h"
00035 #include <sensor_msgs/image_encodings.h>
00036 #include <ros/console.h>
00037 
00038 namespace image_proc {
00039 
00040 namespace enc = sensor_msgs::image_encodings;
00041 
00042 bool Processor::process(const sensor_msgs::ImageConstPtr& raw_image,
00043                         const image_geometry::PinholeCameraModel& model,
00044                         ImageSet& output, int flags) const
00045 {
00046   static const int MONO_EITHER = MONO | RECT;
00047   static const int COLOR_EITHER = COLOR | RECT_COLOR;
00048   if (!(flags & ALL)) return true;
00049   
00050   // Check if raw_image is color
00051   const std::string& raw_encoding = raw_image->encoding;
00052   int raw_type = CV_8UC1;
00053   if (raw_encoding == enc::BGR8 || raw_encoding == enc::RGB8) {
00054     raw_type = CV_8UC3;
00055     output.color_encoding = raw_encoding;
00056   }
00057   // Construct cv::Mat pointing to raw_image data
00058   const cv::Mat raw(raw_image->height, raw_image->width, raw_type,
00059                     const_cast<uint8_t*>(&raw_image->data[0]), raw_image->step);
00060 
00062   // Construct colorized (unrectified) images from raw //
00064   
00065   // Bayer case
00066   if (raw_encoding.find("bayer") != std::string::npos) {
00067     // Convert to color BGR
00069     int code = 0;
00070     if (raw_encoding == enc::BAYER_RGGB8)
00071       code = CV_BayerBG2BGR;
00072     else if (raw_encoding == enc::BAYER_BGGR8)
00073       code = CV_BayerRG2BGR;
00074     else if (raw_encoding == enc::BAYER_GBRG8)
00075       code = CV_BayerGR2BGR;
00076     else if (raw_encoding == enc::BAYER_GRBG8)
00077       code = CV_BayerGB2BGR;
00078     else {
00079       ROS_ERROR("[image_proc] Unsupported encoding '%s'", raw_encoding.c_str());
00080       return false;
00081     }
00082     cv::cvtColor(raw, output.color, code);
00083     output.color_encoding = enc::BGR8;
00084     
00085     if (flags & MONO_EITHER)
00086       cv::cvtColor(output.color, output.mono, CV_BGR2GRAY);
00087   }
00088   // Color case
00089   else if (raw_type == CV_8UC3) {
00090     output.color = raw;
00091     if (flags & MONO_EITHER) {
00092       int code = (raw_encoding == enc::BGR8) ? CV_BGR2GRAY : CV_RGB2GRAY;
00093       cv::cvtColor(output.color, output.mono, code);
00094     }
00095   }
00096   // Mono case
00097   else if (raw_encoding == enc::MONO8) {
00098     output.mono = raw;
00099     if (flags & COLOR_EITHER) {
00100       output.color_encoding = enc::MONO8;
00101       output.color = raw;
00102     }
00103   }
00104   // 8UC3 does not specify a color encoding. Is it BGR, RGB, HSV, XYZ, LUV...?
00105   else if (raw_encoding == enc::TYPE_8UC3) {
00106     ROS_ERROR("[image_proc] Ambiguous encoding '8UC3'. The camera driver "
00107               "should set the encoding to 'bgr8' or 'rgb8'.");
00108     return false;
00109   }
00110   // Something else we can't handle
00111   else {
00112     ROS_ERROR("[image_proc] Unsupported encoding '%s'", raw_encoding.c_str());
00113     return false;
00114   }
00115 
00117   // Construct rectified images from colorized images //
00119   
00122   if (flags & RECT)
00123     model.rectifyImage(output.mono, output.rect, interpolation_);
00124   if (flags & RECT_COLOR)
00125     model.rectifyImage(output.color, output.rect_color, interpolation_);
00126 
00127   return true;
00128 }
00129 
00130 } //namespace image_proc


image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Mon Oct 6 2014 00:45:02