Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
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
00092
00093 current_image_.reset();
00094
00095 topic_ = topic;
00096 tf_filter_.reset();
00097
00098 if (!sub_)
00099 {
00100 sub_.reset(new image_transport::SubscriberFilter());
00101 }
00102
00103 if (!topic.empty())
00104 {
00105 sub_->subscribe(it_, topic, 1, image_transport::TransportHints(transport_type_));
00106
00107 if (frame_.empty())
00108 {
00109 sub_->registerCallback(boost::bind(&ROSImageTexture::callback, this, _1));
00110 }
00111 else
00112 {
00113 ROS_ASSERT(tf_client_);
00114 tf_filter_.reset(new tf::MessageFilter<sensor_msgs::Image>(*sub_, (tf::Transformer&)*tf_client_, frame_, 2, nh_));
00115 tf_filter_->registerCallback(boost::bind(&ROSImageTexture::callback, this, _1));
00116 }
00117 }
00118 }
00119
00120 void ROSImageTexture::setTransportType(const std::string& transport_type)
00121 {
00122 transport_type_ = transport_type;
00123 setTopic(topic_);
00124 }
00125
00126 void ROSImageTexture::getAvailableTransportTypes(V_string& types)
00127 {
00128 types.push_back("raw");
00129
00130 ros::master::V_TopicInfo topics;
00131 ros::master::getTopics(topics);
00132 ros::master::V_TopicInfo::iterator it = topics.begin();
00133 ros::master::V_TopicInfo::iterator end = topics.end();
00134 for (; it != end; ++it)
00135 {
00136 const ros::master::TopicInfo& ti = *it;
00137 if (ti.name.find(topic_) == 0 && ti.name != topic_)
00138 {
00139 std::string type = ti.name.substr(topic_.size() + 1);
00140 if (type.find('/') == std::string::npos)
00141 {
00142 types.push_back(type);
00143 }
00144 }
00145 }
00146 }
00147
00148 const sensor_msgs::Image::ConstPtr& ROSImageTexture::getImage()
00149 {
00150 boost::mutex::scoped_lock lock(mutex_);
00151
00152 return current_image_;
00153 }
00154
00155 bool ROSImageTexture::update()
00156 {
00157 sensor_msgs::Image::ConstPtr image;
00158 bool new_image = false;
00159 {
00160 boost::mutex::scoped_lock lock(mutex_);
00161
00162 image = current_image_;
00163 new_image = new_image_;
00164 }
00165
00166 if (!image || !new_image)
00167 {
00168 return false;
00169 }
00170
00171 new_image_ = false;
00172
00173 if (image->data.empty())
00174 {
00175 return false;
00176 }
00177
00178 Ogre::PixelFormat format = Ogre::PF_R8G8B8;
00179 Ogre::Image ogre_image;
00180 std::vector<uint8_t> buffer;
00181 void* data_ptr = (void*)&image->data[0];
00182 uint32_t data_size = image->data.size();
00183 if (image->encoding == sensor_msgs::image_encodings::RGB8)
00184 {
00185 format = Ogre::PF_BYTE_RGB;
00186 }
00187 else if (image->encoding == sensor_msgs::image_encodings::RGBA8)
00188 {
00189 format = Ogre::PF_BYTE_RGBA;
00190 }
00191 else if (image->encoding == sensor_msgs::image_encodings::TYPE_8UC4 ||
00192 image->encoding == sensor_msgs::image_encodings::TYPE_8SC4 ||
00193 image->encoding == sensor_msgs::image_encodings::BGRA8)
00194 {
00195 format = Ogre::PF_BYTE_BGRA;
00196 }
00197 else if (image->encoding == sensor_msgs::image_encodings::TYPE_8UC3 ||
00198 image->encoding == sensor_msgs::image_encodings::TYPE_8SC3 ||
00199 image->encoding == sensor_msgs::image_encodings::BGR8)
00200 {
00201 format = Ogre::PF_BYTE_BGR;
00202 }
00203 else if (image->encoding == sensor_msgs::image_encodings::TYPE_8UC1 ||
00204 image->encoding == sensor_msgs::image_encodings::TYPE_8SC1 ||
00205 image->encoding == sensor_msgs::image_encodings::MONO8)
00206 {
00207 format = Ogre::PF_BYTE_L;
00208 }
00209 else if (image->encoding == sensor_msgs::image_encodings::TYPE_16UC1 ||
00210 image->encoding == sensor_msgs::image_encodings::TYPE_16SC1 ||
00211 image->encoding == sensor_msgs::image_encodings::MONO16)
00212 {
00213 format = Ogre::PF_BYTE_L;
00214
00215
00216 buffer.resize(image->data.size() / 2);
00217 data_size = buffer.size();
00218 data_ptr = (void*)&buffer[0];
00219 for (size_t i = 0; i < data_size; ++i)
00220 {
00221 uint16_t s = image->data[2*i] << 8 | image->data[2*i + 1];
00222 float val = (float)s / std::numeric_limits<uint16_t>::max();
00223 buffer[i] = val * 255;
00224 }
00225 }
00226 else if (image->encoding.find("bayer") == 0)
00227 {
00228 format = Ogre::PF_BYTE_L;
00229 }
00230 else
00231 {
00232 throw UnsupportedImageEncoding(image->encoding);
00233 }
00234
00235 width_ = image->width;
00236 height_ = image->height;
00237
00238
00239
00240 Ogre::DataStreamPtr pixel_stream;
00241 pixel_stream.bind(new Ogre::MemoryDataStream(data_ptr, data_size));
00242
00243 try
00244 {
00245 ogre_image.loadRawData(pixel_stream, width_, height_, 1, format, 1, 0);
00246 }
00247 catch (Ogre::Exception& e)
00248 {
00249
00250 ROS_ERROR("Error loading image: %s", e.what());
00251 return false;
00252 }
00253
00254 texture_->unload();
00255 texture_->loadImage(ogre_image);
00256
00257 return true;
00258 }
00259
00260 void ROSImageTexture::callback(const sensor_msgs::Image::ConstPtr& msg)
00261 {
00262 boost::mutex::scoped_lock lock(mutex_);
00263 current_image_ = msg;
00264 new_image_ = true;
00265
00266 ++image_count_;
00267 }
00268
00269 }