ros_image_texture.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef RVIZ_ROS_IMAGE_TEXTURE_H
31 #define RVIZ_ROS_IMAGE_TEXTURE_H
32 
33 #include <sensor_msgs/Image.h>
34 
35 #include <OgreTexture.h>
36 #include <OgreImage.h>
37 #include <OgreSharedPtr.h>
38 
39 #include <boost/shared_ptr.hpp>
40 #include <boost/thread/mutex.hpp>
41 
42 #include <ros/ros.h>
43 
44 #include <deque>
45 #include <stdexcept>
46 
47 namespace rviz
48 {
49 class UnsupportedImageEncoding : public std::runtime_error
50 {
51 public:
52  UnsupportedImageEncoding(const std::string& encoding)
53  : std::runtime_error("Unsupported image encoding [" + encoding + "]")
54  {
55  }
56 };
57 
59 {
60 public:
63 
64  void addMessage(const sensor_msgs::Image::ConstPtr& image);
65  bool update();
66  void clear();
67 
68  const Ogre::TexturePtr& getTexture()
69  {
70  return texture_;
71  }
72  const sensor_msgs::Image::ConstPtr& getImage();
73 
74  uint32_t getWidth()
75  {
76  return width_;
77  }
78  uint32_t getHeight()
79  {
80  return height_;
81  }
82 
83  // automatic range normalization
84  void setNormalizeFloatImage(bool normalize, double min = 0.0, double max = 1.0);
85  void setMedianFrames(unsigned median_frames);
86 
87 private:
88  double updateMedian(std::deque<double>& buffer, double new_value);
89 
90  template <typename T>
91  void normalize(T* image_data, size_t image_data_size, std::vector<uint8_t>& buffer);
92 
93  sensor_msgs::Image::ConstPtr current_image_;
94  boost::mutex mutex_;
95  bool new_image_;
96 
97  Ogre::TexturePtr texture_;
98  Ogre::Image empty_image_;
99 
100  uint32_t width_;
101  uint32_t height_;
102 
103  // fields for float image running median computation
105  double min_;
106  double max_;
107  unsigned median_frames_;
108  std::deque<double> min_buffer_;
109  std::deque<double> max_buffer_;
110 };
111 
112 } // namespace rviz
113 
114 #endif
rviz::ROSImageTexture::normalize_
bool normalize_
Definition: ros_image_texture.h:104
rviz::UnsupportedImageEncoding::UnsupportedImageEncoding
UnsupportedImageEncoding(const std::string &encoding)
Definition: ros_image_texture.h:52
rviz::ROSImageTexture::median_frames_
unsigned median_frames_
Definition: ros_image_texture.h:107
rviz::ROSImageTexture::mutex_
boost::mutex mutex_
Definition: ros_image_texture.h:94
rviz::ROSImageTexture
Definition: ros_image_texture.h:58
ros.h
rviz::ROSImageTexture::updateMedian
double updateMedian(std::deque< double > &buffer, double new_value)
Definition: ros_image_texture.cpp:92
rviz::ROSImageTexture::current_image_
sensor_msgs::Image::ConstPtr current_image_
Definition: ros_image_texture.h:93
rviz::ROSImageTexture::clear
void clear()
Definition: ros_image_texture.cpp:67
rviz::ROSImageTexture::texture_
Ogre::TexturePtr texture_
Definition: ros_image_texture.h:97
rviz::ROSImageTexture::setNormalizeFloatImage
void setNormalizeFloatImage(bool normalize, double min=0.0, double max=1.0)
Definition: ros_image_texture.cpp:106
rviz::ROSImageTexture::getWidth
uint32_t getWidth()
Definition: ros_image_texture.h:74
rviz::ROSImageTexture::getHeight
uint32_t getHeight()
Definition: ros_image_texture.h:78
rviz::ROSImageTexture::setMedianFrames
void setMedianFrames(unsigned median_frames)
Definition: ros_image_texture.cpp:87
rviz::ROSImageTexture::normalize
void normalize(T *image_data, size_t image_data_size, std::vector< uint8_t > &buffer)
Definition: ros_image_texture.cpp:115
rviz::ROSImageTexture::ROSImageTexture
ROSImageTexture()
Definition: ros_image_texture.cpp:46
rviz::ROSImageTexture::max_buffer_
std::deque< double > max_buffer_
Definition: ros_image_texture.h:109
rviz::ROSImageTexture::~ROSImageTexture
~ROSImageTexture()
Definition: ros_image_texture.cpp:62
rviz
Definition: add_display_dialog.cpp:54
rviz::ROSImageTexture::max_
double max_
Definition: ros_image_texture.h:106
rviz::ROSImageTexture::addMessage
void addMessage(const sensor_msgs::Image::ConstPtr &image)
Definition: ros_image_texture.cpp:285
rviz::ROSImageTexture::new_image_
bool new_image_
Definition: ros_image_texture.h:95
rviz::ROSImageTexture::min_buffer_
std::deque< double > min_buffer_
Definition: ros_image_texture.h:108
rviz::ROSImageTexture::getImage
const sensor_msgs::Image::ConstPtr & getImage()
Definition: ros_image_texture.cpp:80
rviz::ROSImageTexture::update
bool update()
Definition: ros_image_texture.cpp:179
rviz::ROSImageTexture::min_
double min_
Definition: ros_image_texture.h:105
std
rviz::ROSImageTexture::height_
uint32_t height_
Definition: ros_image_texture.h:101
rviz::ROSImageTexture::width_
uint32_t width_
Definition: ros_image_texture.h:100
rviz::UnsupportedImageEncoding
Definition: ros_image_texture.h:49
rviz::ROSImageTexture::empty_image_
Ogre::Image empty_image_
Definition: ros_image_texture.h:98
rviz::ROSImageTexture::getTexture
const Ogre::TexturePtr & getTexture()
Definition: ros_image_texture.h:68


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Sat Jun 1 2024 02:31:53