openni_image.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011 Willow Garage, Inc.
5  * Suat Gedikli <gedikli@willowgarage.com>
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Willow Garage, Inc. nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  */
37 #ifndef __OPENNI_IMAGE__
38 #define __OPENNI_IMAGE__
39 
40 #include <XnCppWrapper.h>
41 #include "openni_exception.h"
42 #include <boost/shared_ptr.hpp>
43 
44 namespace openni_wrapper
45 {
46 
54 class Image
55 {
56 public:
59 
60  typedef enum
61  {
65  } Encoding;
66 
67  inline Image (boost::shared_ptr<xn::ImageMetaData> image_meta_data) throw ();
68  inline virtual ~Image () throw ();
69  virtual bool isResizingSupported (unsigned input_width, unsigned input_height,
70  unsigned output_width, unsigned output_height) const = 0;
71  virtual void fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer,
72  unsigned rgb_line_step = 0) const throw (OpenNIException) = 0;
73 
74  virtual Encoding getEncoding () const = 0;
75 
76  inline void
77  fillRaw (unsigned char* rgb_buffer) const throw (OpenNIException)
78  {
79  memcpy (rgb_buffer, image_md_->WritableData(), image_md_->DataSize ());
80  }
81 
82  virtual void fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer,
83  unsigned gray_line_step = 0) const throw (OpenNIException) = 0;
84 
85  inline unsigned getWidth () const throw ();
86  inline unsigned getHeight () const throw ();
87  inline unsigned getFrameID () const throw ();
88  inline unsigned long getTimeStamp () const throw ();
89  inline const xn::ImageMetaData& getMetaData () const throw ();
91 
92 protected:
94 };
95 
97 : image_md_ (image_meta_data)
98 {
99 }
100 
101 Image::~Image () throw ()
102 {
103 }
104 
105 unsigned Image::getWidth () const throw ()
106 {
107  return image_md_->XRes ();
108 }
109 
110 unsigned Image::getHeight () const throw ()
111 {
112  return image_md_->YRes ();
113 }
114 
115 unsigned Image::getFrameID () const throw ()
116 {
117  return image_md_->FrameID ();
118 }
119 
120 unsigned long Image::getTimeStamp () const throw ()
121 {
122  return (unsigned long) image_md_->Timestamp ();
123 }
124 
125 const xn::ImageMetaData& Image::getMetaData () const throw ()
126 {
127  return *image_md_;
128 }
129 
131 {
132  return image_md_;
133 }
134 } // namespace
135 #endif //__OPENNI_IMAGE__
virtual Encoding getEncoding() const =0
Image(boost::shared_ptr< xn::ImageMetaData > image_meta_data)
Definition: openni_image.h:96
const xn::ImageMetaData & getMetaData() const
Definition: openni_image.h:125
Image class containing just a reference to image meta data. Thus this class just provides an interfac...
Definition: openni_image.h:54
General exception class.
virtual void fillRGB(unsigned width, unsigned height, unsigned char *rgb_buffer, unsigned rgb_line_step=0) const =0
unsigned getWidth() const
Definition: openni_image.h:105
virtual bool isResizingSupported(unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const =0
virtual void fillGrayscale(unsigned width, unsigned height, unsigned char *gray_buffer, unsigned gray_line_step=0) const =0
unsigned getHeight() const
Definition: openni_image.h:110
boost::shared_ptr< xn::ImageMetaData > image_md_
Definition: openni_image.h:93
unsigned long getTimeStamp() const
Definition: openni_image.h:120
void fillRaw(unsigned char *rgb_buffer) const
Definition: openni_image.h:77
const boost::shared_ptr< xn::ImageMetaData > getMetaDataPtr() const
Definition: openni_image.h:130
unsigned getFrameID() const
Definition: openni_image.h:115
boost::shared_ptr< Image > Ptr
Definition: openni_image.h:57
boost::shared_ptr< const Image > ConstPtr
Definition: openni_image.h:58


openni_camera
Author(s): Patrick Mihelich, Suat Gedikli, Radu Bogdan Rusu
autogenerated on Mon Jun 10 2019 14:15:53