00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 #ifndef __DVBUFFER_H
00023 #define __DVBUFFER_H
00024
00025 #include <cvd/videobuffer.h>
00026 #include <cvd/byte.h>
00027 #include <cvd/rgb.h>
00028 #include <cvd/colourspaces.h>
00029 #include <cvd/exceptions.h>
00030 #include <libraw1394/raw1394.h>
00031 #include <libdc1394/dc1394_control.h>
00032 #include <vector>
00033 #include <string>
00034 #include <utility>
00035
00036 namespace CVD {
00037
00038 namespace Exceptions
00039 {
00042 namespace DVBuffer
00043 {
00046 struct All: public CVD::Exceptions::VideoBuffer::All{};
00047
00050 struct Raw1394Setup: public All {Raw1394Setup(std::string action);
00051 };
00052
00055 struct DC1394Setup: public All {DC1394Setup(std::string action);
00056 };
00057
00060 struct BadCameraSelection: public All { BadCameraSelection(int num_cameras, int camera_no);
00061 };
00062
00065 struct BusReset: public All {BusReset();
00066 };
00067
00070 struct DeviceOpen: public All {DeviceOpen(std::string dev);
00071 };
00074 struct DeviceSetup: public All {DeviceSetup(std::string action);
00075 };
00078 struct PutFrame: public All {PutFrame(std::string dev);
00079 };
00082 struct GetFrame: public All {GetFrame(std::string dev);
00083 };
00084 }
00085 }
00086
00087
00089 namespace DC
00090 {
00091 #ifndef DOXYGEN_IGNORE_INTERNAL
00092 template<class C> struct cam_type
00093 {
00094 static const int mode = C::Error__type_not_valid_for_camera___Use_byte_or_yuv411_or_rgb_of_byte;
00095
00096 static const double fps;
00097 };
00098
00099 template<> struct cam_type<yuv411>
00100 {
00101 static const int mode = MODE_640x480_YUV411;
00102 static const double fps;
00103 };
00104
00105 template<> struct cam_type<byte>
00106 {
00107 static const int mode = MODE_640x480_MONO;
00108 static const double fps;
00109 };
00110
00111 template<> struct cam_type<Rgb<byte> >
00112 {
00113 static const int mode = MODE_640x480_RGB;
00114 static const double fps;
00115 };
00116
00117 struct raw_frame
00118 {
00119 unsigned char* data;
00120 double timestamp;
00121 int buffer;
00122 };
00123 #endif
00124
00129 class RawDCVideo
00130 {
00131 public:
00139 RawDCVideo(int camera_no, int num_dma_buffers, int bright, int exposure, int mode, double frame_rate);
00140 ~RawDCVideo();
00141
00143 ImageRef size();
00145 VideoFrame<byte>* get_frame();
00148 void put_frame(VideoFrame<byte>* f);
00150 bool frame_pending();
00151
00154 void set_shutter(unsigned int s);
00156 unsigned int get_shutter();
00157
00160 void set_iris(unsigned int i );
00162 unsigned int get_iris();
00163
00166 void set_sharpness(unsigned int s );
00168 unsigned int get_sharpness();
00169
00172 void set_gain(unsigned int g);
00174 unsigned int get_gain();
00175
00178 void set_exposure(unsigned int e);
00180 unsigned int get_exposure();
00181
00184 void set_brightness(unsigned int b);
00186 unsigned int get_brightness();
00187
00188
00192 void set_feature_value(unsigned int feature, unsigned int value);
00193
00196 unsigned int get_feature_value(unsigned int feature);
00197
00200 std::pair<unsigned int, unsigned int> get_feature_min_max(unsigned int feature);
00201
00205 void auto_on_off(unsigned int feature, unsigned int auto_value);
00206
00208 double frame_rate();
00209
00210
00212 raw1394handle_t& handle();
00214 nodeid_t& node();
00215
00216 private:
00217
00218
00219 int my_channel;
00220 unsigned char* my_ring_buffer;
00221 int my_frame_size;
00222 int my_num_buffers;
00223
00224 int my_fd;
00225 raw1394handle_t my_handle;
00226 nodeid_t * my_camera_nodes;
00227 nodeid_t my_node;
00228 ImageRef my_size;
00229
00230 std::vector<int> my_frame_sequence;
00231 int my_next_frame;
00232 int my_last_in_sequence;
00233 double true_fps;
00234 };
00235
00236 }
00237
00244 template<class T> class DVBuffer2: public VideoBuffer<T>, public DC::RawDCVideo
00245 {
00246 public:
00253 DVBuffer2(int cam_no, int num_dma_buffers, int bright=-1, int exposure=-1, double fps=DC::cam_type<T>::fps)
00254 :VideoBuffer<T>(VideoBufferType::Live),RawDCVideo(cam_no, num_dma_buffers, bright, exposure, DC::cam_type<T>::mode, fps)
00255 {
00256
00257
00258 }
00259
00260 virtual ~DVBuffer2()
00261 {
00262 }
00263
00264 double frame_rate()
00265 {
00266 return RawDCVideo::frame_rate();
00267 }
00268
00269 virtual ImageRef size()
00270 {
00271 return RawDCVideo::size();
00272 }
00273
00274 virtual VideoFrame<T>* get_frame()
00275 {
00276 return reinterpret_cast<VideoFrame<T>*>(RawDCVideo::get_frame());
00277 }
00278
00279 virtual void put_frame(VideoFrame<T>* f)
00280 {
00281 RawDCVideo::put_frame(reinterpret_cast<VideoFrame<byte>*>(f));
00282 }
00283
00284 virtual bool frame_pending()
00285 {
00286 return RawDCVideo::frame_pending();
00287 }
00288
00289 virtual void seek_to(double){}
00290 };
00291
00295 typedef DVBuffer2<byte> DVBuffer;
00296
00297 }
00298
00299 #endif