$search
00001 /* 00002 * but_rostexture.cpp 00003 * 00004 * Created on: 7.6.2012 00005 * Author: wik 00006 */ 00007 00008 /* 00009 * Copyright (c) 2009, Willow Garage, Inc. 00010 * All rights reserved. 00011 * 00012 * Redistribution and use in source and binary forms, with or without 00013 * modification, are permitted provided that the following conditions are met: 00014 * 00015 * * Redistributions of source code must retain the above copyright 00016 * notice, this list of conditions and the following disclaimer. 00017 * * Redistributions in binary form must reproduce the above copyright 00018 * notice, this list of conditions and the following disclaimer in the 00019 * documentation and/or other materials provided with the distribution. 00020 * * Neither the name of the Willow Garage, Inc. nor the names of its 00021 * contributors may be used to endorse or promote products derived from 00022 * this software without specific prior written permission. 00023 * 00024 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00025 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00026 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00027 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00028 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00029 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00030 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00031 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00032 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00033 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00034 * POSSIBILITY OF SUCH DAMAGE. 00035 */ 00036 00037 #include "but_rostexture.h" 00038 #include "sensor_msgs/image_encodings.h" 00039 00040 #include <tf/tf.h> 00041 00042 #include <OGRE/OgreTextureManager.h> 00043 #include <OGRE/OgreColourValue.h> 00044 00045 /******************************************************************************************* 00046 * CRosTextureConverter 00047 *******************************************************************************************/ 00048 00052 srs_ui_but::CRosTextureConverter::CRosTextureConverter( const std::string & encoding, bool bStaticTexture /*= false*/ ) 00053 : m_output_encoding( encoding ) 00054 , m_bStaticTexture( bStaticTexture ) 00055 { 00056 if( bStaticTexture ) 00057 { 00058 // Get pixel format 00059 try 00060 { 00061 m_static_format = getFormat(encoding); 00062 } 00063 catch (RTCException & e) 00064 { 00065 std::cerr << "CRosTextureConverter::CRosTextureConverter exception: " << e.what() << std::endl; 00066 ROS_ERROR( "CRosTextureConverter::CRosTextureConverter exception: %s", e.what() ); 00067 return; 00068 } 00069 00070 // Initialize static texture 00071 initOgreTexture( m_static_format, "RosTexture "); 00072 } 00073 00074 // std::cerr << "CRosTextureConverter::CRosTextureConverter done" << std::endl; 00075 00076 } 00077 00081 srs_ui_but::CRosTextureConverter::CRosTextureConverter( const std::string & name, const std::string & encoding, bool bStaticTexture /*= false*/ ) 00082 : m_output_encoding( encoding ) 00083 , m_texture_name( name ) 00084 , m_bStaticTexture( bStaticTexture ) 00085 { 00086 if( bStaticTexture ) 00087 { 00088 00089 // Get pixel format 00090 try 00091 { 00092 m_static_format = getFormat(encoding); 00093 } 00094 catch (RTCException & e) 00095 { 00096 std::cerr << "CRosTextureConverter::CRosTextureConverter exception: " << e.what() << std::endl; 00097 ROS_ERROR( "CRosTextureConverter::CRosTextureConverter exception: %s", e.what() ); 00098 return; 00099 } 00100 00101 00102 if( m_texture_name.size() == 0) 00103 { 00104 std::cerr << "CRosTextureConverter::CRosTextureConverter exception: Wrong texture name - zero length. " << std::endl; 00105 throw RTCException( "Wrong texture name - zero length." ); 00106 return; 00107 } 00108 00109 // Initialize static texture 00110 initOgreTexture( m_static_format, name ); 00111 } 00112 00113 // std::cerr << "CRosTextureConverter::CRosTextureConverter done" << std::endl; 00114 00115 } 00116 00120 srs_ui_but::CRosTextureConverter::~CRosTextureConverter( ) 00121 { 00122 00123 } 00124 00128 bool srs_ui_but::CRosTextureConverter::convert( const sensor_msgs::Image::ConstPtr& image, const std::string & texture_name, bool writeInfo ) 00129 { 00130 if( writeInfo) 00131 std::cerr << "CRosTextureConverter::convert. IE: " << image->encoding << " OE: " << m_output_encoding << std::endl; 00132 00133 try{ 00134 // Take input and convert it to the opencv image... 00135 m_cv_image = cv_bridge::toCvCopy( image, m_output_encoding ); 00136 } 00137 catch (cv_bridge::Exception& e) 00138 { 00139 std::cerr << "cv_bridge exception: " << e.what() << std::endl; 00140 ROS_ERROR("cv_bridge exception: %s", e.what()); 00141 return false; 00142 } 00143 00144 Ogre::PixelFormat format( Ogre::PF_UNKNOWN ); 00145 00146 if( !m_bStaticTexture ) 00147 { 00148 std::string encoding( m_output_encoding ); 00149 00150 // Output encoding not defined, so use input one 00151 if( encoding.length() == 0 ) 00152 { 00153 encoding = m_cv_image->encoding; 00154 } 00155 00156 // Initialize ogre texture 00157 try{ 00158 format = getFormat( encoding ); 00159 initOgreTexture( format, texture_name ); 00160 } 00161 catch( RTCException & e) 00162 { 00163 std::cerr << "Texture converter exception: " << e.what() << std::endl; 00164 ROS_ERROR( "Texture converter exception: %s", e.what() ); 00165 return false; 00166 } 00167 }else{ 00168 00169 format = m_static_format; 00170 } 00171 00172 // Convert texture 00173 00174 // Get data access and size 00175 uchar *data_ptr = m_cv_image->image.ptr(); 00176 cv::Size size = m_cv_image->image.size(); 00177 size_t data_size( size.area() * m_cv_image->image.elemSize() ); 00178 int width = size.width; 00179 int height = size.height; 00180 00181 // Buffer image 00182 Ogre::Image ogre_image; 00183 00184 // Create pixel stream 00185 Ogre::DataStreamPtr pixel_stream; 00186 pixel_stream.bind(new Ogre::MemoryDataStream(data_ptr, data_size)); 00187 00188 try 00189 { 00190 // Load data 00191 ogre_image.loadRawData(pixel_stream, width, height, 1, format, 1, 0); 00192 00193 // if( m_bFlip ) 00194 // ogre_image.flipAroundX(); 00195 } 00196 catch (Ogre::Exception& e) 00197 { 00198 // TODO: signal error better 00199 ROS_ERROR("Error loading image: %s", e.what()); 00200 return false; 00201 } 00202 00203 m_ogre_image->unload(); 00204 m_ogre_image->loadImage(ogre_image); 00205 00206 if( writeInfo ) 00207 writeStats( ogre_image ); 00208 00209 return true; 00210 } 00211 00215 Ogre::PixelFormat srs_ui_but::CRosTextureConverter::getFormat( const std::string & encoding) 00216 { 00217 if( encoding == "CV_8UC1" || encoding == "mono8" ) 00218 return Ogre::PF_BYTE_L; 00219 00220 if( encoding == "CV_8UC2" ) 00221 return Ogre::PF_BYTE_LA; 00222 00223 if( encoding == "bgr8" || encoding == "CV_8UC3" || encoding == "bgr8: CV_8UC3" || encoding == "CV_8SC3" || encoding == "bgr8: CV_8SC3" ) 00224 return Ogre::PF_BYTE_BGR; 00225 00226 if( encoding == "rgb8" || encoding == "rgb8: CV_8UC3" || encoding == "rgb8: CV_8SC3") 00227 return Ogre::PF_BYTE_RGB; 00228 00229 if( encoding == "rgba8" || encoding == "CV_8UC4" || encoding == "rgba8: CV_8UC4" || encoding == "CV_8SC4" || encoding == "rgba8: CV_8SC4") 00230 return Ogre::PF_BYTE_RGBA; 00231 00232 if( encoding == "bgra8" || encoding == "bgra8: CV_8UC4" || encoding == "bgra8: CV_8SC4") 00233 return Ogre::PF_BYTE_BGRA; 00234 00235 if( encoding == "CV_32FC1" || encoding == "32FC1" ) 00236 return Ogre::PF_FLOAT32_R; 00237 00238 if( encoding == "CV_32FC2" || encoding == "32FC2") 00239 return Ogre::PF_FLOAT32_GR; 00240 00241 if( encoding == "CV_32FC3" || encoding == "32FC3" ) 00242 return Ogre::PF_FLOAT32_RGB; 00243 00244 if( encoding == "CV_32FC4" || encoding == "32FC4") 00245 return Ogre::PF_FLOAT32_RGBA; 00246 00247 if( encoding == "mono16" ) 00248 { 00249 return Ogre::PF_FLOAT16_R; 00250 } 00251 00252 throw RTCException( "Unknown input format: " + encoding ); 00253 00254 return Ogre::PF_UNKNOWN; 00255 } 00256 00260 void srs_ui_but::CRosTextureConverter::initOgreTexture( Ogre::PixelFormat format, const std::string & name ) 00261 { 00262 if( m_ogre_image.get() != 0 && m_ogre_image->getFormat() == format ) 00263 { 00264 throw RTCException( "Cannot initialize ogre texture: " + name ); 00265 return; 00266 } 00267 00268 m_empty_image.load("no_image.png", Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME); 00269 00270 m_ogre_image = Ogre::TextureManager::getSingleton().createManual(name, 00271 Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, 00272 Ogre::TEX_TYPE_2D, // Type 00273 m_empty_image.getWidth(), // Width 00274 m_empty_image.getWidth(), // Height 00275 1, // Depth 00276 0, // Number of mipmaps 00277 format, // Pixel format 00278 Ogre::TU_DYNAMIC_WRITE_ONLY); // Usage 00279 } 00280 00284 void srs_ui_but::CRosTextureConverter::writeStats( Ogre::Image & image ) 00285 { 00286 size_t width( image.getWidth() ), height( image.getHeight() ), x, y; 00287 00288 Ogre::ColourValue c; 00289 00290 double rmin( 100000), gmin( 100000), bmin( 100000), amin( 100000); 00291 double rmax(-100000), gmax(-100000), bmax(-100000), amax(-100000); 00292 00293 for( y = 0; y < height; ++y ) 00294 { 00295 for( x = 0; x < width; ++x ) 00296 { 00297 c = image.getColourAt( x, y, 0 ); 00298 00299 if( rmin > c.r ) rmin = c.r; 00300 if( gmin > c.g ) gmin = c.g; 00301 if( bmin > c.b ) bmin = c.b; 00302 if( amin > c.a ) amin = c.a; 00303 00304 if( rmax < c.r ) rmax = c.r; 00305 if( gmax < c.g ) gmax = c.g; 00306 if( bmax < c.b ) bmax = c.b; 00307 if( amax < c.a ) amax = c.a; 00308 00309 } 00310 } 00311 00312 std::cerr << "Image size: " << width << " x " << height << std::endl; 00313 std::cerr << "Encoding: " << m_output_encoding << std::endl; 00314 std::cerr << "R: < " << rmin << ", " << rmax << " >" << std::endl; 00315 std::cerr << "G: < " << gmin << ", " << gmax << " >" << std::endl; 00316 std::cerr << "B: < " << bmin << ", " << bmax << " >" << std::endl; 00317 std::cerr << "A: < " << amin << ", " << amax << " >" << std::endl; 00318 } 00319 00320 /**************************************************************************************************** 00321 * CRosTopicTexture 00322 ****************************************************************************************************/ 00323 00324 00328 srs_ui_but::CRosTopicTexture::CRosTopicTexture( const ros::NodeHandle& nh, const std::string & texture_name, const std::string & encoding ) 00329 : m_nh( nh ) 00330 , m_texture_converter( texture_name, encoding, true ) // Create static texture converter 00331 , m_name( texture_name ) 00332 , m_it(nh) 00333 , m_transport_type("raw") 00334 , m_new_image(false) 00335 , m_tf_client(0) 00336 { 00337 // std::cerr << "CRosTopicTexture::CRosTopicTexture" << std::endl; 00338 } 00339 00343 srs_ui_but::CRosTopicTexture::~CRosTopicTexture() 00344 { 00345 m_sub->unsubscribe(); 00346 } 00347 00352 void srs_ui_but::CRosTopicTexture::setTopic(const std::string& topic) 00353 { 00354 boost::mutex::scoped_lock lock(m_mutex); 00355 // Must reset the current image here because image_transport will unload the plugin as soon as we unsubscribe, 00356 // which removes the code segment necessary for the shared_ptr's deleter to exist! 00357 m_current_image.reset(); 00358 00359 m_topic = topic; 00360 m_tf_filter.reset(); 00361 00362 if (!m_sub) 00363 { 00364 m_sub.reset(new image_transport::SubscriberFilter()); 00365 } 00366 00367 if (!topic.empty()) 00368 { 00369 m_sub->subscribe(m_it, topic, 1, image_transport::TransportHints(m_transport_type)); 00370 00371 if (m_frame.empty()) 00372 { 00373 m_sub->registerCallback(boost::bind(&CRosTopicTexture::callback, this, _1)); 00374 } 00375 else 00376 { 00377 ROS_ASSERT(m_tf_client); 00378 m_tf_filter.reset(new tf::MessageFilter<sensor_msgs::Image>(*m_sub, (tf::Transformer&)*m_tf_client, m_frame, 2, m_nh)); 00379 m_tf_filter->registerCallback(boost::bind(&CRosTopicTexture::callback, this, _1)); 00380 } 00381 } 00382 else 00383 { 00384 m_sub->unsubscribe(); 00385 } 00386 } 00387 00391 bool srs_ui_but::CRosTopicTexture::update() 00392 { 00393 // std::cerr << "CRosTopicTexture::update" << std::endl; 00394 00395 sensor_msgs::Image::ConstPtr image; 00396 00397 bool new_image = false; 00398 { 00399 boost::mutex::scoped_lock lock(m_mutex); 00400 00401 image = m_current_image; 00402 new_image = m_new_image; 00403 } 00404 00405 // std::cerr << "Image: " << image << ", new_image: " << new_image << std::endl; 00406 00407 if (!image || !new_image) 00408 { 00409 return false; 00410 } 00411 00412 // std::cerr << "Texture update. Topic: " << m_topic << std::endl; 00413 00414 m_new_image = false; 00415 00416 if (image->data.empty()) 00417 { 00418 return false; 00419 } 00420 00421 // Convert input data 00422 return m_texture_converter.convert( image ); 00423 } 00424 00428 void srs_ui_but::CRosTopicTexture::clear() 00429 { 00430 boost::mutex::scoped_lock lock(m_mutex); 00431 00432 // texture_->unload(); 00433 // texture_->loadImage(empty_image_); 00434 00435 m_new_image = false; 00436 m_current_image.reset(); 00437 00438 if (m_tf_filter) 00439 { 00440 m_tf_filter->clear(); 00441 } 00442 } 00443 00447 void srs_ui_but::CRosTopicTexture::callback(const sensor_msgs::Image::ConstPtr& image) 00448 { 00449 boost::mutex::scoped_lock lock(m_mutex); 00450 00451 m_current_image = image; 00452 m_new_image = true; 00453 00454 // std::cerr << "CB: Image: " << m_current_image << ", new_image: " << m_new_image << std::endl; 00455 00456 // std::cerr << "New image for: " << m_name << std::endl; 00457 } 00458 00459 00460 00461 00462 00463