image_buffer.hpp
Go to the documentation of this file.
00001 #ifndef IMAGE_BUFFER_6RYGHM2V
00002 #define IMAGE_BUFFER_6RYGHM2V
00003 
00004 #include <stdexcept>
00005 #include <boost/thread/mutex.hpp>
00006 #include <boost/shared_ptr.hpp>
00007 #include <boost/lexical_cast.hpp>
00008 
00009 #include <libfreenect/libfreenect.h>
00010 
00011 namespace freenect_camera {
00012 
00013   const float RGB_FOCAL_LENGTH_SXGA = 1050;
00014   const float WIDTH_SXGA = 1280;
00015 
00022   struct ImageBuffer {
00023     boost::mutex mutex;
00024     boost::shared_array<unsigned char> image_buffer;
00025     int valid;
00026     freenect_frame_mode metadata;
00027     float focal_length;
00028     bool is_registered;
00029   };
00030 
00031   
00035   float getRGBFocalLength(int width) {
00036     float scale = width / WIDTH_SXGA;
00037     return RGB_FOCAL_LENGTH_SXGA * scale;
00038   }
00039 
00043   float getDepthFocalLength(
00044       const freenect_registration& registration, int width) {
00045 
00046     float depth_focal_length_sxga = 
00047       registration.zero_plane_info.reference_distance /
00048       registration.zero_plane_info.reference_pixel_size;
00049     float scale = width / WIDTH_SXGA;
00050     return depth_focal_length_sxga * scale;
00051   }
00052 
00056   void allocateBufferVideo(
00057       ImageBuffer& buffer,
00058       const freenect_video_format& format,
00059       const freenect_resolution& resolution,
00060       const freenect_registration& registration) {
00061 
00062     // Obtain a lock on the buffer. This is mostly for debugging, as allocate
00063     // buffer should only be called when the buffer is not being used by the
00064     // freenect thread
00065     boost::lock_guard<boost::mutex> buffer_lock(buffer.mutex);
00066 
00067     // Deallocate the buffer incase an exception happens (the buffer should no
00068     // longer be valid)
00069     buffer.image_buffer.reset();
00070 
00071     switch (format) {
00072       case FREENECT_VIDEO_RGB:
00073       case FREENECT_VIDEO_BAYER:
00074       case FREENECT_VIDEO_YUV_RGB:
00075       case FREENECT_VIDEO_IR_8BIT:
00076       case FREENECT_VIDEO_IR_10BIT:
00077       case FREENECT_VIDEO_IR_10BIT_PACKED:
00078         switch (resolution) {
00079           case FREENECT_RESOLUTION_HIGH:
00080           case FREENECT_RESOLUTION_MEDIUM:
00081             buffer.metadata = 
00082               freenect_find_video_mode(resolution, format);
00083             if (!buffer.metadata.is_valid) {
00084               throw std::runtime_error("libfreenect: Invalid video fmt, res: " + 
00085                   boost::lexical_cast<std::string>(format) + "," +
00086                   boost::lexical_cast<std::string>(resolution));
00087             }
00088             break;
00089           default:
00090             throw std::runtime_error("libfreenect: Invalid video resolution: " +
00091                 boost::lexical_cast<std::string>(resolution));
00092         }
00093         break;
00094       default:
00095         throw std::runtime_error("libfreenect: Invalid video format: " +
00096             boost::lexical_cast<std::string>(format));
00097     }
00098 
00099     // All is good, reallocate the buffer and calculate other pieces of info
00100     buffer.image_buffer.reset(new unsigned char[buffer.metadata.bytes]);
00101     switch(format) {
00102       case FREENECT_VIDEO_RGB:
00103       case FREENECT_VIDEO_BAYER:
00104       case FREENECT_VIDEO_YUV_RGB:
00105         buffer.focal_length = getRGBFocalLength(buffer.metadata.width);
00106         break;
00107       case FREENECT_VIDEO_IR_8BIT:
00108       case FREENECT_VIDEO_IR_10BIT:
00109       case FREENECT_VIDEO_IR_10BIT_PACKED:
00110         buffer.focal_length = getDepthFocalLength(registration, 
00111             buffer.metadata.width);
00112         break;
00113       default:
00114         throw std::runtime_error("libfreenect: shouldn't reach here");
00115     }
00116     buffer.is_registered = false;
00117   }
00118 
00122   void allocateBufferDepth(
00123       ImageBuffer& buffer,
00124       const freenect_depth_format& format,
00125       const freenect_resolution& resolution,
00126       const freenect_registration& registration) {
00127 
00128     // Obtain a lock on the buffer. This is mostly for debugging, as allocate
00129     // buffer should only be called when the buffer is not being used by the
00130     // freenect thread
00131     boost::lock_guard<boost::mutex> buffer_lock(buffer.mutex);
00132 
00133     // Deallocate the buffer incase an exception happens (the buffer should no
00134     // longer be valid)
00135     buffer.image_buffer.reset();
00136 
00137     switch (format) {
00138       case FREENECT_DEPTH_11BIT:
00139       case FREENECT_DEPTH_10BIT:
00140       case FREENECT_DEPTH_11BIT_PACKED:
00141       case FREENECT_DEPTH_10BIT_PACKED:
00142       case FREENECT_DEPTH_REGISTERED:
00143       case FREENECT_DEPTH_MM:
00144         switch (resolution) {
00145           case FREENECT_RESOLUTION_MEDIUM:
00146             buffer.metadata = 
00147               freenect_find_depth_mode(resolution, format);
00148             if (!buffer.metadata.is_valid) {
00149               throw std::runtime_error("libfreenect: Invalid depth fmt, res: " + 
00150                   boost::lexical_cast<std::string>(format) + "," +
00151                   boost::lexical_cast<std::string>(resolution));
00152             }
00153             break;
00154           default:
00155             throw std::runtime_error("libfreenect: Invalid depth resolution: " +
00156                 boost::lexical_cast<std::string>(resolution));
00157         }
00158         break;
00159       default:
00160         throw std::runtime_error("libfreenect: Invalid depth format: " +
00161             boost::lexical_cast<std::string>(format));
00162     }
00163 
00164     // All is good, reallocate the buffer and calculate other pieces of info
00165     buffer.image_buffer.reset(new unsigned char[buffer.metadata.bytes]);
00166     switch(format) {
00167       case FREENECT_DEPTH_11BIT:
00168       case FREENECT_DEPTH_10BIT:
00169       case FREENECT_DEPTH_11BIT_PACKED:
00170       case FREENECT_DEPTH_10BIT_PACKED:
00171       case FREENECT_DEPTH_MM:
00172         buffer.focal_length = 
00173           getDepthFocalLength(registration, buffer.metadata.width);
00174         buffer.is_registered = false;
00175         break;
00176       case FREENECT_DEPTH_REGISTERED:
00177         buffer.focal_length = getRGBFocalLength(buffer.metadata.width);
00178         buffer.is_registered = true;
00179         break;
00180       default:
00181         throw std::runtime_error("libfreenect: shouldn't reach here");
00182     }
00183   }
00184 
00185   void fillImage(const ImageBuffer& buffer, void* data) {
00186     memcpy(data, buffer.image_buffer.get(), buffer.metadata.bytes);
00187   }
00188 
00189 } /* end namespace freenect_camera */
00190 
00191 #endif /* end of include guard: IMAGE_BUFFER_6RYGHM2V */


freenect_camera
Author(s): Patrick Mihelich, Suat Gedikli, Radu Bogdan Rusu (original openni_camera driver)., Piyush Khandelwal (libfreenect port).
autogenerated on Sat Jun 8 2019 18:26:45