$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 "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 rviz 00038 { 00039 00040 ROSImageTexture::ROSImageTexture(const ros::NodeHandle& nh) 00041 : nh_(nh) 00042 , it_(nh_) 00043 , transport_type_("raw") 00044 , new_image_(false) 00045 , width_(0) 00046 , height_(0) 00047 , tf_client_(0) 00048 , image_count_(0) 00049 { 00050 empty_image_.load("no_image.png", Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME); 00051 00052 static uint32_t count = 0; 00053 std::stringstream ss; 00054 ss << "ROSImageTexture" << count++; 00055 texture_ = Ogre::TextureManager::getSingleton().loadImage(ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, empty_image_, Ogre::TEX_TYPE_2D, 0); 00056 } 00057 00058 ROSImageTexture::~ROSImageTexture() 00059 { 00060 current_image_.reset(); 00061 } 00062 00063 void ROSImageTexture::clear() 00064 { 00065 boost::mutex::scoped_lock lock(mutex_); 00066 00067 texture_->unload(); 00068 texture_->loadImage(empty_image_); 00069 00070 new_image_ = false; 00071 current_image_.reset(); 00072 00073 if (tf_filter_) 00074 { 00075 tf_filter_->clear(); 00076 } 00077 00078 image_count_ = 0; 00079 } 00080 00081 void ROSImageTexture::setFrame(const std::string& frame, tf::TransformListener* tf_client) 00082 { 00083 tf_client_ = tf_client; 00084 frame_ = frame; 00085 setTopic(topic_); 00086 } 00087 00088 void ROSImageTexture::setTopic(const std::string& topic) 00089 { 00090 boost::mutex::scoped_lock lock(mutex_); 00091 // Must reset the current image here because image_transport will unload the plugin as soon as we unsubscribe, 00092 // which removes the code segment necessary for the shared_ptr's deleter to exist! 00093 current_image_.reset(); 00094 00095 topic_ = topic; 00096 tf_filter_.reset(); 00097 00098 sub_.reset(new image_transport::SubscriberFilter()); 00099 00100 if (!topic.empty()) 00101 { 00102 sub_->subscribe(it_, topic, 1, image_transport::TransportHints(transport_type_)); 00103 00104 if (frame_.empty()) 00105 { 00106 sub_->registerCallback(boost::bind(&ROSImageTexture::callback, this, _1)); 00107 } 00108 else 00109 { 00110 ROS_ASSERT(tf_client_); 00111 tf_filter_.reset(new tf::MessageFilter<sensor_msgs::Image>(*sub_, (tf::Transformer&)*tf_client_, frame_, 2, nh_)); 00112 tf_filter_->registerCallback(boost::bind(&ROSImageTexture::callback, this, _1)); 00113 } 00114 } 00115 else 00116 { 00117 sub_->unsubscribe(); 00118 } 00119 } 00120 00121 void ROSImageTexture::setTransportType(const std::string& transport_type) 00122 { 00123 transport_type_ = transport_type; 00124 setTopic(topic_); 00125 } 00126 00127 void ROSImageTexture::getAvailableTransportTypes(V_string& types) 00128 { 00129 types.push_back("raw"); 00130 00131 ros::master::V_TopicInfo topics; 00132 ros::master::getTopics(topics); 00133 ros::master::V_TopicInfo::iterator it = topics.begin(); 00134 ros::master::V_TopicInfo::iterator end = topics.end(); 00135 for (; it != end; ++it) 00136 { 00137 const ros::master::TopicInfo& ti = *it; 00138 if (ti.name.find(topic_) == 0 && ti.name != topic_) 00139 { 00140 std::string type = ti.name.substr(topic_.size() + 1); 00141 if (type.find('/') == std::string::npos) 00142 { 00143 types.push_back(type); 00144 } 00145 } 00146 } 00147 } 00148 00149 const sensor_msgs::Image::ConstPtr& ROSImageTexture::getImage() 00150 { 00151 boost::mutex::scoped_lock lock(mutex_); 00152 00153 return current_image_; 00154 } 00155 00156 bool ROSImageTexture::update() 00157 { 00158 sensor_msgs::Image::ConstPtr image; 00159 bool new_image = false; 00160 { 00161 boost::mutex::scoped_lock lock(mutex_); 00162 00163 image = current_image_; 00164 new_image = new_image_; 00165 } 00166 00167 if (!image || !new_image) 00168 { 00169 return false; 00170 } 00171 00172 new_image_ = false; 00173 00174 if (image->data.empty()) 00175 { 00176 return false; 00177 } 00178 00179 Ogre::PixelFormat format = Ogre::PF_R8G8B8; 00180 Ogre::Image ogre_image; 00181 std::vector<uint8_t> buffer; 00182 void* data_ptr = (void*)&image->data[0]; 00183 uint32_t data_size = image->data.size(); 00184 if (image->encoding == sensor_msgs::image_encodings::RGB8) 00185 { 00186 format = Ogre::PF_BYTE_RGB; 00187 } 00188 else if (image->encoding == sensor_msgs::image_encodings::RGBA8) 00189 { 00190 format = Ogre::PF_BYTE_RGBA; 00191 } 00192 else if (image->encoding == sensor_msgs::image_encodings::TYPE_8UC4 || 00193 image->encoding == sensor_msgs::image_encodings::TYPE_8SC4 || 00194 image->encoding == sensor_msgs::image_encodings::BGRA8) 00195 { 00196 format = Ogre::PF_BYTE_BGRA; 00197 } 00198 else if (image->encoding == sensor_msgs::image_encodings::TYPE_8UC3 || 00199 image->encoding == sensor_msgs::image_encodings::TYPE_8SC3 || 00200 image->encoding == sensor_msgs::image_encodings::BGR8) 00201 { 00202 format = Ogre::PF_BYTE_BGR; 00203 } 00204 else if (image->encoding == sensor_msgs::image_encodings::TYPE_8UC1 || 00205 image->encoding == sensor_msgs::image_encodings::TYPE_8SC1 || 00206 image->encoding == sensor_msgs::image_encodings::MONO8) 00207 { 00208 format = Ogre::PF_BYTE_L; 00209 } 00210 else if (image->encoding == sensor_msgs::image_encodings::TYPE_16UC1 || 00211 image->encoding == sensor_msgs::image_encodings::TYPE_16SC1 || 00212 image->encoding == sensor_msgs::image_encodings::MONO16) 00213 { 00214 format = Ogre::PF_BYTE_L; 00215 00216 // downsample manually to 8-bit, because otherwise the lower 8-bits are simply removed 00217 buffer.resize(image->data.size() / 2); 00218 data_size = buffer.size(); 00219 data_ptr = (void*)&buffer[0]; 00220 for (size_t i = 0; i < data_size; ++i) 00221 { 00222 uint16_t s = image->data[2*i] << 8 | image->data[2*i + 1]; 00223 float val = (float)s / std::numeric_limits<uint16_t>::max(); 00224 buffer[i] = val * 255; 00225 } 00226 } 00227 else if (image->encoding.find("bayer") == 0) 00228 { 00229 format = Ogre::PF_BYTE_L; 00230 } 00231 else 00232 { 00233 throw UnsupportedImageEncoding(image->encoding); 00234 } 00235 00236 width_ = image->width; 00237 height_ = image->height; 00238 00239 // TODO: Support different steps/strides 00240 00241 Ogre::DataStreamPtr pixel_stream; 00242 pixel_stream.bind(new Ogre::MemoryDataStream(data_ptr, data_size)); 00243 00244 try 00245 { 00246 ogre_image.loadRawData(pixel_stream, width_, height_, 1, format, 1, 0); 00247 } 00248 catch (Ogre::Exception& e) 00249 { 00250 // TODO: signal error better 00251 ROS_ERROR("Error loading image: %s", e.what()); 00252 return false; 00253 } 00254 00255 texture_->unload(); 00256 texture_->loadImage(ogre_image); 00257 00258 return true; 00259 } 00260 00261 void ROSImageTexture::callback(const sensor_msgs::Image::ConstPtr& msg) 00262 { 00263 boost::mutex::scoped_lock lock(mutex_); 00264 current_image_ = msg; 00265 new_image_ = true; 00266 00267 ++image_count_; 00268 } 00269 00270 }