35 #include <boost/algorithm/string/erase.hpp> 36 #include <boost/foreach.hpp> 38 #include <OgreTextureManager.h> 53 empty_image_.load(
"no_image.png", Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
55 static uint32_t count = 0;
57 ss <<
"ROSImageTexture" << count++;
58 texture_ = Ogre::TextureManager::getSingleton().loadImage(ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
empty_image_, Ogre::TEX_TYPE_2D, 0);
70 boost::mutex::scoped_lock lock(
mutex_);
81 boost::mutex::scoped_lock lock(
mutex_);
98 buffer.push_front(value);
100 std::deque<double> buffer2 = buffer;
101 std::nth_element( buffer2.begin(), buffer2.begin()+buffer2.size()/2, buffer2.end() );
102 return *( buffer2.begin()+buffer2.size()/2 );
117 buffer.resize(image_data_size, 0);
124 T* input_ptr = image_data;
126 minValue = std::numeric_limits<T>::max();
127 maxValue = std::numeric_limits<T>::min();
128 for(
unsigned i = 0; i < image_data_size; ++i )
130 minValue = std::min( minValue, *input_ptr );
131 maxValue = std::max( maxValue, *input_ptr );
149 double range = maxValue - minValue;
152 T* input_ptr = image_data;
155 uint8_t* output_ptr = &buffer[0];
158 for(
size_t i = 0; i < image_data_size; ++i, ++output_ptr, ++input_ptr )
160 double val = (double(*input_ptr - minValue) / range);
161 if ( val < 0 ) val = 0;
162 if ( val > 1 ) val = 1;
163 *output_ptr = val * 255u;
170 sensor_msgs::Image::ConstPtr image;
171 bool new_image =
false;
173 boost::mutex::scoped_lock lock(
mutex_);
179 if (!image || !new_image)
186 if (image->data.empty())
191 Ogre::PixelFormat format = Ogre::PF_R8G8B8;
192 Ogre::Image ogre_image;
193 std::vector<uint8_t> buffer;
195 uint8_t* imageDataPtr = (uint8_t*)&image->data[0];
196 size_t imageDataSize = image->data.size();
200 format = Ogre::PF_BYTE_RGB;
204 format = Ogre::PF_BYTE_RGBA;
210 format = Ogre::PF_BYTE_BGRA;
216 format = Ogre::PF_BYTE_BGR;
222 format = Ogre::PF_BYTE_L;
228 imageDataSize /=
sizeof(uint16_t);
229 normalize<uint16_t>( (uint16_t*)&image->data[0], imageDataSize, buffer );
230 format = Ogre::PF_BYTE_L;
231 imageDataPtr = &buffer[0];
233 else if (image->encoding.find(
"bayer") == 0)
235 format = Ogre::PF_BYTE_L;
239 imageDataSize /=
sizeof(float);
240 normalize<float>( (
float*)&image->data[0], imageDataSize, buffer );
241 format = Ogre::PF_BYTE_L;
242 imageDataPtr = &buffer[0];
254 Ogre::DataStreamPtr pixel_stream;
255 pixel_stream.bind(
new Ogre::MemoryDataStream(imageDataPtr, imageDataSize));
259 ogre_image.loadRawData(pixel_stream,
width_,
height_, 1, format, 1, 0);
261 catch (Ogre::Exception& e)
264 ROS_ERROR(
"Error loading image: %s", e.what());
276 boost::mutex::scoped_lock lock(
mutex_);
const std::string TYPE_8SC4
const std::string TYPE_8UC4
Ogre::TexturePtr texture_
double updateMedian(std::deque< double > &buffer, double new_value)
const std::string TYPE_8UC1
std::deque< double > max_buffer_
sensor_msgs::Image::ConstPtr current_image_
void setNormalizeFloatImage(bool normalize, double min=0.0, double max=1.0)
void setMedianFrames(unsigned median_frames)
void normalize(T *image_data, size_t image_data_size, std::vector< uint8_t > &buffer)
const std::string TYPE_8SC3
void addMessage(const sensor_msgs::Image::ConstPtr &image)
const std::string TYPE_32FC1
const std::string TYPE_16UC1
const std::string TYPE_8SC1
std::deque< double > min_buffer_
const std::string TYPE_8UC3
const sensor_msgs::Image::ConstPtr & getImage()
const std::string TYPE_16SC1