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 <stdexcept>
45 
46 namespace rviz
47 {
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 
58 {
59 public:
61  ~ROSImageTexture();
62 
63  void addMessage(const sensor_msgs::Image::ConstPtr& image);
64  bool update();
65  void clear();
66 
67  const Ogre::TexturePtr& getTexture() { return texture_; }
68  const sensor_msgs::Image::ConstPtr& getImage();
69 
70  uint32_t getWidth() { return width_; }
71  uint32_t getHeight() { return height_; }
72 
73  // automatic range normalization
74  void setNormalizeFloatImage( bool normalize, double min=0.0, double max=1.0 );
75  void setMedianFrames( unsigned median_frames );
76 
77 private:
78 
79  double updateMedian( std::deque<double>& buffer, double new_value );
80 
81  template<typename T>
82  void normalize( T* image_data, size_t image_data_size, std::vector<uint8_t> &buffer );
83 
84  sensor_msgs::Image::ConstPtr current_image_;
85  boost::mutex mutex_;
86  bool new_image_;
87 
88  Ogre::TexturePtr texture_;
89  Ogre::Image empty_image_;
90 
91  uint32_t width_;
92  uint32_t height_;
93 
94  // fields for float image running median computation
95  bool normalize_;
96  double min_;
97  double max_;
98  unsigned median_frames_;
99  std::deque<double> min_buffer_;
100  std::deque<double> max_buffer_;
101 };
102 
103 }
104 
105 #endif
const Ogre::TexturePtr & getTexture()
Ogre::TexturePtr texture_
std::deque< double > max_buffer_
sensor_msgs::Image::ConstPtr current_image_
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
TFSIMD_FORCE_INLINE Vector3 & normalize()
int min(int a, int b)
UnsupportedImageEncoding(const std::string &encoding)
std::deque< double > min_buffer_


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:51