mt9v.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2009, 2010 Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #ifndef __FOREARM_CAM__MT9V_H__
00036 #define __FOREARM_CAM__MT9V_H__
00037 
00038 #include <stdlib.h>
00039 #include <stdint.h>
00040 #include <boost/shared_ptr.hpp>
00041 #include <wge100_camera/wge100lib.h>
00042 
00043 #define MT9V_REG_WINDOW_WIDTH 0x04
00044 #define MT9V_REG_HORIZONTAL_BLANKING 0x05
00045 #define MT9V_REG_VERTICAL_BLANKING 0x06
00046 #define MT9V_REG_TOTAL_SHUTTER_WIDTH 0x0B
00047 #define MT9V_REG_ANALOG_GAIN 0x35
00048 #define MT9V_REG_AGC_AEC_ENABLE 0xAF
00049 #define MT9V_COMPANDING_MODE 0x1C
00050 
00051 #define MT9V_CK_FREQ 16e6
00052 
00053 /*
00054  * Imager Modes
00055  */
00056 #define MT9VMODE_752x480x15b1           0
00057 #define MT9VMODE_752x480x12_5b1         1
00058 #define MT9VMODE_640x480x30b1           2
00059 #define MT9VMODE_640x480x25b1           3
00060 #define MT9VMODE_640x480x15b1           4
00061 #define MT9VMODE_640x480x12_5b1         5
00062 #define MT9VMODE_320x240x60b2           6
00063 #define MT9VMODE_320x240x50b2           7
00064 #define MT9VMODE_320x240x30b2           8
00065 #define MT9VMODE_320x240x25b2           9
00066 #define MT9V_NUM_MODES 10
00067 
00068 struct MT9VMode {
00069   const char *name;
00070   size_t width;
00071   size_t height;
00072   double fps;
00073   uint16_t hblank;
00074   uint16_t vblank;
00075 };
00076 
00077 extern const struct MT9VMode MT9VModes[MT9V_NUM_MODES];
00078 
00079 class MT9VImager;
00080 typedef boost::shared_ptr<MT9VImager> MT9VImagerPtr;
00081 
00082 // Methods return true on failure.
00083 class MT9VImager 
00084 {
00085 public:
00086   virtual bool setBrightness(int brightness) = 0;
00087   virtual bool setAgcAec(bool agc_on, bool aec_on) = 0;
00088   virtual bool setGain(int gain) = 0;
00089   virtual bool setExposure(double exposure) = 0;
00090   virtual bool setMaxExposure(double exposure) = 0;
00091   virtual bool setMirror(bool mirrorx, bool mirrory) = 0;
00092   virtual bool setMode(int x, int y, int binx, int biny, double rate, int xoffset, int yoffset) = 0;
00093   virtual bool setCompanding(bool activated) = 0;
00094   virtual MT9VImagerPtr getAlternateContext() = 0;
00095   virtual bool setBlackLevel(bool manual_override, int calibration_value, int step_size, int filter_length) = 0;
00096   virtual std::string getModel() = 0;
00097   virtual uint16_t getVersion() = 0;
00098   
00099   static MT9VImagerPtr getInstance(IpCamList &cam);
00100 };
00101 
00102 #endif


wge100_camera
Author(s): Blaise Gassend, Patrick Mihelich, Eric MacIntosh, David Palchak
autogenerated on Fri Jan 3 2014 12:16:00