$search
00001 /* 00002 * Copyright (c) 2009, Willow Garage, Inc. 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 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 #include "image_segmentation_demo/ros_image_texture.h" 00031 #include "sensor_msgs/image_encodings.h" 00032 00033 #include <tf/tf.h> 00034 00035 #include <OGRE/OgreTextureManager.h> 00036 00037 namespace image_segmentation_demo 00038 { 00039 00040 ROSImageTexture::ROSImageTexture() 00041 : width_(0) 00042 , height_(0) 00043 { 00044 00045 empty_image_.load("no_image.png", Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME); 00046 00047 static uint32_t count = 0; 00048 std::stringstream ss; 00049 ss << "ROSImageTexture" << count++; 00050 texture_ = Ogre::TextureManager::getSingleton().loadImage(ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, empty_image_, Ogre::TEX_TYPE_2D, 0); 00051 00052 } 00053 00054 ROSImageTexture::~ROSImageTexture() 00055 { 00056 current_image_.reset(); 00057 } 00058 00059 void ROSImageTexture::clear() 00060 { 00061 texture_->unload(); 00062 texture_->loadImage(empty_image_); 00063 00064 current_image_.reset(); 00065 00066 image_count_ = 0; 00067 } 00068 /* 00069 const sensor_msgs::Image::ConstPtr& ROSImageTexture::getImage() 00070 { 00071 boost::mutex::scoped_lock lock(mutex_); 00072 00073 return current_image_; 00074 }*/ 00075 void ROSImageTexture::setNewImage(sensor_msgs::Image::Ptr new_image_) 00076 { 00077 current_image_.reset(); 00078 current_image_ = new_image_; 00079 00080 ++image_count_; 00081 setSize(current_image_->width, current_image_->height); 00082 } 00083 00084 void ROSImageTexture::setSize(uint32_t width, uint32_t height) 00085 { 00086 width_ = width; 00087 height_ = height; 00088 00089 update(); 00090 } 00091 00092 bool ROSImageTexture::update() 00093 { 00094 sensor_msgs::Image::Ptr image; 00095 00096 image = current_image_; 00097 00098 00099 if (image->data.empty()) 00100 { 00101 return false; 00102 } 00103 00104 Ogre::PixelFormat format = Ogre::PF_R8G8B8; 00105 Ogre::Image ogre_image; 00106 std::vector<uint8_t> buffer; 00107 void* data_ptr = (void*)&image->data[0]; 00108 uint32_t data_size = image->data.size(); 00109 if (image->encoding == sensor_msgs::image_encodings::RGB8) 00110 { 00111 format = Ogre::PF_BYTE_RGB; 00112 } 00113 else if (image->encoding == sensor_msgs::image_encodings::RGBA8) 00114 { 00115 format = Ogre::PF_BYTE_RGBA; 00116 } 00117 else if (image->encoding == sensor_msgs::image_encodings::TYPE_8UC4 || 00118 image->encoding == sensor_msgs::image_encodings::TYPE_8SC4 || 00119 image->encoding == sensor_msgs::image_encodings::BGRA8) 00120 { 00121 format = Ogre::PF_BYTE_BGRA; 00122 } 00123 else if (image->encoding == sensor_msgs::image_encodings::TYPE_8UC3 || 00124 image->encoding == sensor_msgs::image_encodings::TYPE_8SC3 || 00125 image->encoding == sensor_msgs::image_encodings::BGR8) 00126 { 00127 format = Ogre::PF_BYTE_BGR; 00128 } 00129 else if (image->encoding == sensor_msgs::image_encodings::TYPE_8UC1 || 00130 image->encoding == sensor_msgs::image_encodings::TYPE_8SC1 || 00131 image->encoding == sensor_msgs::image_encodings::MONO8) 00132 { 00133 format = Ogre::PF_BYTE_L; 00134 } 00135 else if (image->encoding == sensor_msgs::image_encodings::TYPE_16UC1 || 00136 image->encoding == sensor_msgs::image_encodings::TYPE_16SC1 || 00137 image->encoding == sensor_msgs::image_encodings::MONO16) 00138 { 00139 format = Ogre::PF_BYTE_L; 00140 00141 // downsample manually to 8-bit, because otherwise the lower 8-bits are simply removed 00142 buffer.resize(image->data.size() / 2); 00143 data_size = buffer.size(); 00144 data_ptr = (void*)&buffer[0]; 00145 for (size_t i = 0; i < data_size; ++i) 00146 { 00147 uint16_t s = image->data[2*i] << 8 | image->data[2*i + 1]; 00148 float val = (float)s / std::numeric_limits<uint16_t>::max(); 00149 buffer[i] = val * 255; 00150 } 00151 } 00152 else if (image->encoding.find("bayer") == 0) 00153 { 00154 format = Ogre::PF_BYTE_L; 00155 } 00156 else 00157 { 00158 throw UnsupportedImageEncoding(image->encoding); 00159 } 00160 00161 00162 // TODO: Support different steps/strides 00163 00164 Ogre::DataStreamPtr pixel_stream; 00165 pixel_stream.bind(new Ogre::MemoryDataStream(data_ptr, data_size)); 00166 00167 try 00168 { 00169 ogre_image.loadRawData(pixel_stream, image->width, image->height, 1, format, 1, 0); 00170 //ogre_image.loadDynamicImage( (Ogre::uchar*)data_ptr, image->width, image->height, 1, format, false, 1, 0 ); 00171 ogre_image.resize( width_, height_ ); 00172 } 00173 catch (Ogre::Exception& e) 00174 { 00175 // TODO: signal error better 00176 ROS_ERROR("Error loading image: %s", e.what()); 00177 return false; 00178 } 00179 texture_->unload(); 00180 texture_->loadImage(ogre_image); 00181 00182 return true; 00183 } 00184 00185 00186 }