$search
00001 /**************************************************************************** 00002 * 00003 * $Id: image.cpp 3496 2011-11-22 15:14:32Z fnovotny $ 00004 * 00005 * This file is part of the ViSP software. 00006 * Copyright (C) 2005 - 2012 by INRIA. All rights reserved. 00007 * 00008 * This software is free software; you can redistribute it and/or 00009 * modify it under the terms of the GNU General Public License 00010 * ("GPL") version 2 as published by the Free Software Foundation. 00011 * See the file LICENSE.txt at the root directory of this source 00012 * distribution for additional information about the GNU GPL. 00013 * 00014 * For using ViSP with software that can not be combined with the GNU 00015 * GPL, please contact INRIA about acquiring a ViSP Professional 00016 * Edition License. 00017 * 00018 * See http://www.irisa.fr/lagadic/visp/visp.html for more information. 00019 * 00020 * This software was developed at: 00021 * INRIA Rennes - Bretagne Atlantique 00022 * Campus Universitaire de Beaulieu 00023 * 35042 Rennes Cedex 00024 * France 00025 * http://www.irisa.fr/lagadic 00026 * 00027 * If you have questions regarding the use of this file, please contact 00028 * INRIA at visp@inria.fr 00029 * 00030 * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE 00031 * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. 00032 * 00033 * Contact visp@irisa.fr if any conditions of this licensing are 00034 * not clear to you. 00035 * 00036 * Description: 00037 * 00038 * 00039 * Authors: 00040 * Filip Novotny 00041 * 00042 * 00043 *****************************************************************************/ 00044 00050 #include "image.h" 00051 #include <sensor_msgs/Image.h> 00052 #include <sensor_msgs/image_encodings.h> 00053 #include <boost/format.hpp> 00054 #include <stdexcept> 00055 00056 namespace visp_bridge 00057 { 00058 00059 sensor_msgs::Image toSensorMsgsImage(const vpImage<unsigned char>& src) 00060 { 00061 sensor_msgs::Image dst; 00062 dst.width = src.getWidth(); 00063 dst.height = src.getHeight(); 00064 dst.encoding = sensor_msgs::image_encodings::MONO8; 00065 dst.step = src.getWidth(); 00066 dst.data.resize(dst.height * dst.step); 00067 memcpy(&dst.data[0], src.bitmap, dst.height * dst.step * sizeof(unsigned char)); 00068 00069 return dst; 00070 } 00071 00072 vpImage<unsigned char> toVispImage(const sensor_msgs::Image& src) 00073 { 00074 using sensor_msgs::image_encodings::MONO8; 00075 using sensor_msgs::image_encodings::RGB8; 00076 using sensor_msgs::image_encodings::RGBA8; 00077 using sensor_msgs::image_encodings::BGR8; 00078 using sensor_msgs::image_encodings::BGRA8; 00079 00080 00081 vpImage<unsigned char> dst(src.height, src.width); 00082 00083 if (src.encoding == MONO8) 00084 memcpy(dst.bitmap, &(src.data[0]), dst.getHeight() * src.step * sizeof(unsigned char)); 00085 else if (src.encoding == RGB8 || src.encoding == RGBA8 || src.encoding == BGR8 || src.encoding == BGRA8){ 00086 unsigned nc = sensor_msgs::image_encodings::numChannels(src.encoding); 00087 unsigned cEnd = (src.encoding == RGBA8 || src.encoding == BGRA8) ? nc - 1 : nc; 00088 00089 for (unsigned i = 0; i < dst.getWidth(); ++i){ 00090 for (unsigned j = 0; j < dst.getHeight(); ++j){ 00091 int acc = 0; 00092 for (unsigned c = 0; c < cEnd; ++c) 00093 acc += src.data[j * src.step + i * nc + c]; 00094 dst[j][i] = acc / nc; 00095 } 00096 } 00097 } 00098 return dst; 00099 } 00100 00101 vpImage<vpRGBa> toVispImageRGBa(const sensor_msgs::Image& src) 00102 { 00103 using sensor_msgs::image_encodings::MONO8; 00104 using sensor_msgs::image_encodings::RGB8; 00105 using sensor_msgs::image_encodings::RGBA8; 00106 using sensor_msgs::image_encodings::BGR8; 00107 using sensor_msgs::image_encodings::BGRA8; 00108 00109 00110 vpImage<vpRGBa> dst(src.height, src.width); 00111 00112 if (src.encoding == MONO8) 00113 for (unsigned i = 0; i < dst.getWidth(); ++i){ 00114 for (unsigned j = 0; j < dst.getHeight(); ++j){ 00115 int acc = 0; 00116 00117 dst[j][i] = vpRGBa(src.data[j * src.step + i],src.data[j * src.step + i],src.data[j * src.step + i]); 00118 } 00119 } 00120 else{ 00121 unsigned nc = sensor_msgs::image_encodings::numChannels(src.encoding); 00122 00123 for (unsigned i = 0; i < dst.getWidth(); ++i){ 00124 for (unsigned j = 0; j < dst.getHeight(); ++j){ 00125 dst[j][i] = vpRGBa(src.data[j * src.step + i * nc + 0],src.data[j * src.step + i * nc + 1],src.data[j * src.step + i * nc + 2]); 00126 } 00127 } 00128 } 00129 return dst; 00130 } 00131 00132 sensor_msgs::Image toSensorMsgsImage(const vpImage<vpRGBa>& src){ 00133 sensor_msgs::Image dst; 00134 dst.width = src.getWidth(); 00135 dst.height = src.getHeight(); 00136 dst.encoding = sensor_msgs::image_encodings::RGB8; 00137 unsigned nc = sensor_msgs::image_encodings::numChannels(dst.encoding); 00138 dst.step = src.getWidth()*nc; 00139 00140 dst.data.resize(dst.height * dst.step); 00141 for (unsigned i = 0; i < src.getWidth(); ++i){ 00142 for (unsigned j = 0; j < src.getHeight(); ++j){ 00143 dst.data[j * dst.step + i * nc + 0] = src.bitmap[j * src.getWidth() + i].R; 00144 dst.data[j * dst.step + i * nc + 1] = src.bitmap[j * src.getWidth() + i].G; 00145 dst.data[j * dst.step + i * nc + 2] = src.bitmap[j * src.getWidth() + i].B; 00146 //dst.data[j * dst.step + i * nc + 3] = src.bitmap[j * dst.step + i].A; 00147 } 00148 } 00149 return dst; 00150 } 00151 }