uvcvideo.h
Go to the documentation of this file.
00001 // 2009/7/1 Opt Corporation
00002 //   change Private V4L2 control identifiers.
00003 //   add XU_COMMAND definition.
00004 
00005 #ifndef _USB_VIDEO_H_
00006 #define _USB_VIDEO_H_
00007 
00008 #include <linux/kernel.h>
00009 #include <linux/videodev2.h>
00010 
00011 /* Compatibility */
00012 #include "uvc_compat.h"
00013 
00014 /*
00015  * Private V4L2 control identifiers.
00016  */
00017 /*
00018 #define V4L2_CID_BACKLIGHT_COMPENSATION         (V4L2_CID_PRIVATE_BASE+0)
00019 #define V4L2_CID_POWER_LINE_FREQUENCY           (V4L2_CID_PRIVATE_BASE+1)
00020 #define V4L2_CID_SHARPNESS                      (V4L2_CID_PRIVATE_BASE+2)
00021 #define V4L2_CID_HUE_AUTO                       (V4L2_CID_PRIVATE_BASE+3)
00022 
00023 #define V4L2_CID_FOCUS_AUTO                     (V4L2_CID_PRIVATE_BASE+4)
00024 #define V4L2_CID_FOCUS_ABSOLUTE                 (V4L2_CID_PRIVATE_BASE+5)
00025 #define V4L2_CID_FOCUS_RELATIVE                 (V4L2_CID_PRIVATE_BASE+6)
00026 
00027 #define V4L2_CID_PAN_RELATIVE                   (V4L2_CID_PRIVATE_BASE+7)
00028 #define V4L2_CID_TILT_RELATIVE                  (V4L2_CID_PRIVATE_BASE+8)
00029 #define V4L2_CID_PANTILT_RESET                  (V4L2_CID_PRIVATE_BASE+9)
00030 
00031 #define V4L2_CID_EXPOSURE_AUTO                  (V4L2_CID_PRIVATE_BASE+10)
00032 #define V4L2_CID_EXPOSURE_ABSOLUTE              (V4L2_CID_PRIVATE_BASE+11)
00033 
00034 #define V4L2_CID_WHITE_BALANCE_TEMPERATURE_AUTO (V4L2_CID_PRIVATE_BASE+12)
00035 #define V4L2_CID_WHITE_BALANCE_TEMPERATURE      (V4L2_CID_PRIVATE_BASE+13)
00036 
00037 #define V4L2_CID_PRIVATE_LAST                   V4L2_CID_WHITE_BALANCE_TEMPERATURE
00038 */
00039 #define V4L2_CID_PANTILT_RESET                  (V4L2_CID_PRIVATE_BASE+9)
00040 #define V4L2_CID_WHITE_BALANCE_TEMPERATURE_AUTO V4L2_CID_AUTO_WHITE_BALANCE
00041 #define V4L2_CID_ZOOM_RELATIVE                  (V4L2_CID_CAMERA_CLASS_BASE+14)
00042 
00043 #define UVC_GUID_UVC_EXTENSION  {0x4e, 0x4d, 0x33, 0x30, 0x01, 0x7a, 0xce, 0x41, \
00044                                  0x80, 0x53, 0x5b, 0x7f, 0x3f, 0xb7, 0x61, 0x99}
00045 
00046 #define XU_UNDEFINED                       0x00
00047 #define XU_FIRMWARE_VERSION_CONTROL        0x01
00048 #define XU_FLASH_PARAMETER_CONTROL         0x02
00049 #define XU_FLIP_SCREEN_CONTROL             0x03
00050 #define XU_SMALL_HEMISPHERE_CONTROL        0x04
00051 #define XU_ANALOG_VIDEO_STANDARD_CONTROL   0x05
00052 #define XU_MEDIAN_FILTER_CONTROL           0x07
00053 #define XU_PUSH_BUTTON_CONTROL             0x08
00054 #define XU_PENDING_PTZR_CONTROL            0x0B
00055 #define XU_AUTO_PAN_SPEED_CONTROL          0x0C
00056 #define XU_JPEG_QUALITY_CONTROL            0x0D
00057 #define XU_SERIAL_ID_CONTROL               0x0E
00058 #define XU_INFO_DISPLAY_CONTROL            0x0F
00059 #define XU_CAPTURE_FPS_CONTROL             0x10
00060 #define XU_ACTUAL_FPS_CONTROL              0x11
00061 #define XU_LENS_TYPE_CONTROL               0x12
00062 #define XU_PAN_ABSOLUTE_CONTROL            0x13
00063 #define XU_TILT_ABSOLUTE_CONTROL           0x14
00064 #define XU_ROLL_ABSOLUTE_CONTROL           0x15
00065 #define XU_ZOOM_ABSOLUTE_CONTROL           0x16
00066 #define XU_LOCATION_ABSOLUTE_CONTROL       0x17
00067 #define XU_GAIN_ABSOLUTE_CONTROL           0x1E
00068 
00069 /* Data types for UVC control data */
00070 #define UVC_CTRL_DATA_TYPE_RAW          0
00071 #define UVC_CTRL_DATA_TYPE_SIGNED       1
00072 #define UVC_CTRL_DATA_TYPE_UNSIGNED     2
00073 #define UVC_CTRL_DATA_TYPE_BOOLEAN      3
00074 #define UVC_CTRL_DATA_TYPE_ENUM         4
00075 #define UVC_CTRL_DATA_TYPE_BITMASK      5
00076 
00077 /* Control flags */
00078 #define UVC_CONTROL_SET_CUR     (1 << 0)
00079 #define UVC_CONTROL_GET_CUR     (1 << 1)
00080 
00081 struct uvc_xu_control_info {
00082         __u8 entity[16];
00083         __u8 index;
00084         __u8 selector;
00085         __u16 size;
00086         __u32 flags;
00087 };
00088 
00089 struct uvc_xu_control_mapping {
00090         __u32 id;
00091         __u8 name[32];
00092         __u8 entity[16];
00093         __u8 selector;
00094 
00095         __u8 size;
00096         __u8 offset;
00097         enum v4l2_ctrl_type v4l2_type;
00098         __u32 data_type;
00099 };
00100 
00101 struct uvc_xu_control {
00102         __u8 unit;
00103         __u8 selector;
00104         __u16 size;
00105         __u8 __user *data;
00106 };
00107 
00108 #define UVCIOC_CTRL_ADD         _IOW('U', 1, struct uvc_xu_control_info)
00109 #define UVCIOC_CTRL_MAP         _IOWR('U', 2, struct uvc_xu_control_mapping)
00110 #define UVCIOC_CTRL_GET         _IOWR('U', 3, struct uvc_xu_control)
00111 #define UVCIOC_CTRL_SET         _IOW('U', 4, struct uvc_xu_control)
00112 
00113 #ifdef __KERNEL__
00114 
00115 /* --------------------------------------------------------------------------
00116  * UVC constants
00117  */
00118 
00119 #define SC_UNDEFINED                    0x00
00120 #define SC_VIDEOCONTROL                 0x01
00121 #define SC_VIDEOSTREAMING               0x02
00122 #define SC_VIDEO_INTERFACE_COLLECTION   0x03
00123 
00124 #define PC_PROTOCOL_UNDEFINED           0x00
00125 
00126 #define CS_UNDEFINED                    0x20
00127 #define CS_DEVICE                       0x21
00128 #define CS_CONFIGURATION                0x22
00129 #define CS_STRING                       0x23
00130 #define CS_INTERFACE                    0x24
00131 #define CS_ENDPOINT                     0x25
00132 
00133 /* VideoControl class specific interface descriptor */
00134 #define VC_DESCRIPTOR_UNDEFINED         0x00
00135 #define VC_HEADER                       0x01
00136 #define VC_INPUT_TERMINAL               0x02
00137 #define VC_OUTPUT_TERMINAL              0x03
00138 #define VC_SELECTOR_UNIT                0x04
00139 #define VC_PROCESSING_UNIT              0x05
00140 #define VC_EXTENSION_UNIT               0x06
00141 
00142 /* VideoStreaming class specific interface descriptor */
00143 #define VS_UNDEFINED                    0x00
00144 #define VS_INPUT_HEADER                 0x01
00145 #define VS_OUTPUT_HEADER                0x02
00146 #define VS_STILL_IMAGE_FRAME            0x03
00147 #define VS_FORMAT_UNCOMPRESSED          0x04
00148 #define VS_FRAME_UNCOMPRESSED           0x05
00149 #define VS_FORMAT_MJPEG                 0x06
00150 #define VS_FRAME_MJPEG                  0x07
00151 #define VS_FORMAT_MPEG2TS               0x0a
00152 #define VS_FORMAT_DV                    0x0c
00153 #define VS_COLORFORMAT                  0x0d
00154 #define VS_FORMAT_FRAME_BASED           0x10
00155 #define VS_FRAME_FRAME_BASED            0x11
00156 #define VS_FORMAT_STREAM_BASED          0x12
00157 
00158 /* Endpoint type */
00159 #define EP_UNDEFINED                    0x00
00160 #define EP_GENERAL                      0x01
00161 #define EP_ENDPOINT                     0x02
00162 #define EP_INTERRUPT                    0x03
00163 
00164 /* Request codes */
00165 #define RC_UNDEFINED                    0x00
00166 #define SET_CUR                         0x01
00167 #define GET_CUR                         0x81
00168 #define GET_MIN                         0x82
00169 #define GET_MAX                         0x83
00170 #define GET_RES                         0x84
00171 #define GET_LEN                         0x85
00172 #define GET_INFO                        0x86
00173 #define GET_DEF                         0x87
00174 
00175 /* VideoControl interface controls */
00176 #define VC_CONTROL_UNDEFINED            0x00
00177 #define VC_VIDEO_POWER_MODE_CONTROL     0x01
00178 #define VC_REQUEST_ERROR_CODE_CONTROL   0x02
00179 
00180 /* Terminal controls */
00181 #define TE_CONTROL_UNDEFINED            0x00
00182 
00183 /* Selector Unit controls */
00184 #define SU_CONTROL_UNDEFINED            0x00
00185 #define SU_INPUT_SELECT_CONTROL         0x01
00186 
00187 /* Camera Terminal controls */
00188 #define CT_CONTROL_UNDEFINED                            0x00
00189 #define CT_SCANNING_MODE_CONTROL                        0x01
00190 #define CT_AE_MODE_CONTROL                              0x02
00191 #define CT_AE_PRIORITY_CONTROL                          0x03
00192 #define CT_EXPOSURE_TIME_ABSOLUTE_CONTROL               0x04
00193 #define CT_EXPOSURE_TIME_RELATIVE_CONTROL               0x05
00194 #define CT_FOCUS_ABSOLUTE_CONTROL                       0x06
00195 #define CT_FOCUS_RELATIVE_CONTROL                       0x07
00196 #define CT_FOCUS_AUTO_CONTROL                           0x08
00197 #define CT_IRIS_ABSOLUTE_CONTROL                        0x09
00198 #define CT_IRIS_RELATIVE_CONTROL                        0x0a
00199 #define CT_ZOOM_ABSOLUTE_CONTROL                        0x0b
00200 #define CT_ZOOM_RELATIVE_CONTROL                        0x0c
00201 #define CT_PANTILT_ABSOLUTE_CONTROL                     0x0d
00202 #define CT_PANTILT_RELATIVE_CONTROL                     0x0e
00203 #define CT_ROLL_ABSOLUTE_CONTROL                        0x0f
00204 #define CT_ROLL_RELATIVE_CONTROL                        0x10
00205 #define CT_PRIVACY_CONTROL                              0x11
00206 
00207 /* Processing Unit controls */
00208 #define PU_CONTROL_UNDEFINED                            0x00
00209 #define PU_BACKLIGHT_COMPENSATION_CONTROL               0x01
00210 #define PU_BRIGHTNESS_CONTROL                           0x02
00211 #define PU_CONTRAST_CONTROL                             0x03
00212 #define PU_GAIN_CONTROL                                 0x04
00213 #define PU_POWER_LINE_FREQUENCY_CONTROL                 0x05
00214 #define PU_HUE_CONTROL                                  0x06
00215 #define PU_SATURATION_CONTROL                           0x07
00216 #define PU_SHARPNESS_CONTROL                            0x08
00217 #define PU_GAMMA_CONTROL                                0x09
00218 #define PU_WHITE_BALANCE_TEMPERATURE_CONTROL            0x0a
00219 #define PU_WHITE_BALANCE_TEMPERATURE_AUTO_CONTROL       0x0b
00220 #define PU_WHITE_BALANCE_COMPONENT_CONTROL              0x0c
00221 #define PU_WHITE_BALANCE_COMPONENT_AUTO_CONTROL         0x0d
00222 #define PU_DIGITAL_MULTIPLIER_CONTROL                   0x0e
00223 #define PU_DIGITAL_MULTIPLIER_LIMIT_CONTROL             0x0f
00224 #define PU_HUE_AUTO_CONTROL                             0x10
00225 #define PU_ANALOG_VIDEO_STANDARD_CONTROL                0x11
00226 #define PU_ANALOG_LOCK_STATUS_CONTROL                   0x12
00227 
00228 #define LXU_MOTOR_PANTILT_RELATIVE_CONTROL              0x01
00229 #define LXU_MOTOR_PANTILT_RESET_CONTROL                 0x02
00230 
00231 /* VideoStreaming interface controls */
00232 #define VS_CONTROL_UNDEFINED            0x00
00233 #define VS_PROBE_CONTROL                0x01
00234 #define VS_COMMIT_CONTROL               0x02
00235 #define VS_STILL_PROBE_CONTROL          0x03
00236 #define VS_STILL_COMMIT_CONTROL         0x04
00237 #define VS_STILL_IMAGE_TRIGGER_CONTROL  0x05
00238 #define VS_STREAM_ERROR_CODE_CONTROL    0x06
00239 #define VS_GENERATE_KEY_FRAME_CONTROL   0x07
00240 #define VS_UPDATE_FRAME_SEGMENT_CONTROL 0x08
00241 #define VS_SYNC_DELAY_CONTROL           0x09
00242 
00243 #define TT_VENDOR_SPECIFIC              0x0100
00244 #define TT_STREAMING                    0x0101
00245 
00246 /* Input Terminal types */
00247 #define ITT_VENDOR_SPECIFIC             0x0200
00248 #define ITT_CAMERA                      0x0201
00249 #define ITT_MEDIA_TRANSPORT_INPUT       0x0202
00250 
00251 /* Output Terminal types */
00252 #define OTT_VENDOR_SPECIFIC             0x0300
00253 #define OTT_DISPLAY                     0x0301
00254 #define OTT_MEDIA_TRANSPORT_OUTPUT      0x0302
00255 
00256 #define EXTERNAL_VENDOR_SPECIFIC        0x0400
00257 #define COMPOSITE_CONNECTOR             0x0401
00258 #define SVIDEO_CONNECTOR                0x0402
00259 #define COMPONENT_CONNECTOR             0x0403
00260 
00261 #define UVC_ENTITY_IS_UNIT(entity)      ((entity->type & 0xff00) == 0)
00262 #define UVC_ENTITY_IS_TERM(entity)      ((entity->type & 0xff00) != 0)
00263 #define UVC_ENTITY_IS_ITERM(entity)     ((entity->type & 0xff00) == ITT_VENDOR_SPECIFIC)
00264 #define UVC_ENTITY_IS_OTERM(entity)     ((entity->type & 0xff00) == OTT_VENDOR_SPECIFIC)
00265 
00266 /* ------------------------------------------------------------------------
00267  * GUIDs
00268  */
00269 #define UVC_GUID_UVC_CAMERA     {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
00270                                  0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01}
00271 #define UVC_GUID_UVC_OUTPUT     {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
00272                                  0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02}
00273 #define UVC_GUID_UVC_PROCESSING {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
00274                                  0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01}
00275 #define UVC_GUID_UVC_SELECTOR   {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
00276                                  0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02}
00277 
00278 #define UVC_GUID_LOGITECH_XU1   {0x82, 0x06, 0x61, 0x63, 0x70, 0x50, 0xab, 0x49, \
00279                                  0xb8, 0xcc, 0xb3, 0x85, 0x5e, 0x8d, 0x22, 0x1d}
00280 #define UVC_GUID_LOGITECH_XU2   {0x82, 0x06, 0x61, 0x63, 0x70, 0x50, 0xab, 0x49, \
00281                                  0xb8, 0xcc, 0xb3, 0x85, 0x5e, 0x8d, 0x22, 0x1e}
00282 #define UVC_GUID_LOGITECH_XU3   {0x82, 0x06, 0x61, 0x63, 0x70, 0x50, 0xab, 0x49, \
00283                                  0xb8, 0xcc, 0xb3, 0x85, 0x5e, 0x8d, 0x22, 0x1f}
00284 #define UVC_GUID_LOGITECH_MOTOR {0x82, 0x06, 0x61, 0x63, 0x70, 0x50, 0xab, 0x49, \
00285                                  0xb8, 0xcc, 0xb3, 0x85, 0x5e, 0x8d, 0x22, 0x56}
00286 #define UVC_GUID_LOGITECH_DEV_INFO \
00287                                 {0x82, 0x06, 0x61, 0x63, 0x70, 0x50, 0xab, 0x49, \
00288                                  0xb8, 0xcc, 0xb3, 0x85, 0x5e, 0x8d, 0x22, 0x1e}
00289 
00290 #define UVC_GUID_FORMAT_MJPEG   {0x4d, 0x4a, 0x50, 0x47, 0x00, 0x00, 0x10, 0x00, \
00291                                  0x80, 0x00, 0x00, 0xaa, 0x00, 0x38, 0x9b, 0x71}
00292 #define UVC_GUID_FORMAT_YUY2    {0x59, 0x55, 0x59, 0x32, 0x00, 0x00, 0x10, 0x00, \
00293                                  0x80, 0x00, 0x00, 0xaa, 0x00, 0x38, 0x9b, 0x71}
00294 #define UVC_GUID_FORMAT_NV12    {0x4e, 0x56, 0x31, 0x32, 0x00, 0x00, 0x10, 0x00, \
00295                                  0x80, 0x00, 0x00, 0xaa, 0x00, 0x38, 0x9b, 0x71}
00296 
00297 
00298 /* ------------------------------------------------------------------------
00299  * Driver specific constants.
00300  */
00301 
00302 #define DRIVER_VERSION_NUMBER   KERNEL_VERSION(0, 1, 0)
00303 
00304 /* Number of isochronous URBs. */
00305 #define UVC_URBS                5
00306 /* Maximum number of packets per isochronous URB. */
00307 #define UVC_MAX_ISO_PACKETS     40
00308 /* Maximum frame size in bytes, for sanity checking. */
00309 #define UVC_MAX_FRAME_SIZE      (16*1024*1024)
00310 /* Maximum number of video buffers. */
00311 #define UVC_MAX_VIDEO_BUFFERS   32
00312 
00313 #define UVC_CTRL_TIMEOUT        300
00314 
00315 /* Devices quirks */
00316 #define UVC_QUIRK_STATUS_INTERVAL       0x00000001
00317 
00318 /* ------------------------------------------------------------------------
00319  * Structures.
00320  */
00321 
00322 struct uvc_device;
00323 
00324 /* TODO: Put the most frequently accessed fields at the beginning of
00325  * structures to maximize cache efficiency.
00326  */
00327 struct uvc_streaming_control {
00328         __u16 bmHint;
00329         __u8  bFormatIndex;
00330         __u8  bFrameIndex;
00331         __u32 dwFrameInterval;
00332         __u16 wKeyFrameRate;
00333         __u16 wPFrameRate;
00334         __u16 wCompQuality;
00335         __u16 wCompWindowSize;
00336         __u16 wDelay;
00337         __u32 dwMaxVideoFrameSize;
00338         __u32 dwMaxPayloadTransferSize;
00339         __u32 dwClockFrequency;
00340         __u8  bmFramingInfo;
00341         __u8  bPreferedVersion;
00342         __u8  bMinVersion;
00343         __u8  bMaxVersion;
00344 };
00345 
00346 struct uvc_menu_info {
00347         __u32 index;
00348         __u8 name[32];
00349 };
00350 
00351 struct uvc_control_info {
00352         struct list_head list;
00353         struct list_head mappings;
00354 
00355         __u8 entity[16];
00356         __u8 index;
00357         __u8 selector;
00358 
00359         __u8 size;
00360         __u8 flags;
00361 };
00362 
00363 /* Data types for UVC control data */
00364 enum uvc_control_data_type {
00365         UVC_CTRL_DATA_TYPE_RAW = 0,
00366         UVC_CTRL_DATA_TYPE_SIGNED,
00367         UVC_CTRL_DATA_TYPE_UNSIGNED,
00368         UVC_CTRL_DATA_TYPE_BOOLEAN,
00369         UVC_CTRL_DATA_TYPE_ENUM,
00370         UVC_CTRL_DATA_TYPE_BITMASK,
00371 };
00372 
00373 struct uvc_control_mapping {
00374         struct list_head list;
00375 
00376         struct uvc_control_info *ctrl;
00377 
00378         __u32 id;
00379         __u8 name[32];
00380         __u8 entity[16];
00381         __u8 selector;
00382 
00383         __u8 size;
00384         __u8 offset;
00385         enum v4l2_ctrl_type v4l2_type;
00386         enum uvc_control_data_type data_type;
00387 
00388         struct uvc_menu_info *menu_info;
00389         __u32 menu_count;
00390 };
00391 
00392 struct uvc_control {
00393         struct uvc_entity *entity;
00394         struct uvc_control_info *info;
00395 
00396         __u8 index;     /* Used to match the uvc_control entry with a uvc_control_info. */
00397         __u8 dirty : 1,
00398              loaded : 1;
00399 
00400         __u8 *data;
00401 };
00402 
00403 struct uvc_format_desc {
00404         __u8 guid[16];
00405         __u32 fcc;
00406 };
00407 
00408 /* The term 'entity' refers to both UVC units and UVC terminals.
00409  *
00410  * The type field is either the terminal type (wTerminalType in the terminal
00411  * descriptor), or the unit type (bDescriptorSubtype in the unit descriptor).
00412  * As the bDescriptorSubtype field is one byte long, the type value will
00413  * always have a null MSB for units. All terminal types defined by the UVC
00414  * specification have a non-null MSB, so it is safe to use the MSB to
00415  * differentiate between units and terminals as long as the descriptor parsing
00416  * code makes sur terminal types have a non-null MSB.
00417  */
00418 
00419 struct uvc_entity {
00420         struct list_head list;
00421 
00422         __u8 id;
00423         __u16 type;
00424         char name[64];
00425 
00426         union {
00427                 struct {
00428                         __u16 wObjectiveFocalLengthMin;
00429                         __u16 wObjectiveFocalLengthMax;
00430                         __u16 wOcularFocalLength;
00431                         __u8  bControlSize;
00432                         __u8  *bmControls;
00433                 } camera;
00434 
00435                 struct {
00436                         __u8  bSourceID;
00437                 } output;
00438 
00439                 struct {
00440                         __u8  bSourceID;
00441                         __u16 wMaxMultiplier;
00442                         __u8  bControlSize;
00443                         __u8  *bmControls;
00444                         __u8  bmVideoStandards;
00445                 } processing;
00446 
00447                 struct {
00448                         __u8  bNrInPins;
00449                         __u8  *baSourceID;
00450                 } selector;
00451 
00452                 struct {
00453                         __u8  guidExtensionCode[16];
00454                         __u8  bNumControls;
00455                         __u8  bNrInPins;
00456                         __u8  *baSourceID;
00457                         __u8  bControlSize;
00458                         __u8  *bmControls;
00459                         __u8  *bmControlsType;
00460                 } extension;
00461         };
00462 
00463         unsigned int ncontrols;
00464         struct uvc_control *controls;
00465 };
00466 
00467 struct uvc_frame {
00468         __u8  bFrameIndex;
00469         __u8  bmCapabilities;
00470         __u16 wWidth;
00471         __u16 wHeight;
00472         __u32 dwMinBitRate;
00473         __u32 dwMaxBitRate;
00474         __u32 dwMaxVideoFrameBufferSize;
00475         __u8  bFrameIntervalType;
00476         __u32 dwDefaultFrameInterval;
00477         __u32 *dwFrameInterval;
00478 };
00479 
00480 struct uvc_format {
00481         __u8 type;
00482         __u8 index;
00483         __u8 bpp;
00484         __u8 colorspace;
00485         __u32 fcc;
00486         __u32 flags;
00487 
00488         char name[32];
00489 
00490         unsigned int nframes;
00491         struct uvc_frame *frame;
00492 };
00493 
00494 struct uvc_input_header {
00495         __u8 bNumFormats;
00496         __u8 bEndpointAddress;
00497         __u8 bmInfo;
00498         __u8 bTerminalLink;
00499         __u8 bStillCaptureMethod;
00500         __u8 bTriggerSupport;
00501         __u8 bTriggerUsage;
00502         __u8 bControlSize;
00503         __u8 *bmaControls;
00504 };
00505 
00506 struct uvc_output_header {
00507 };
00508 
00509 struct uvc_streaming {
00510         struct list_head list;
00511 
00512         struct usb_interface *intf;
00513         int intfnum;
00514         __u16 maxpsize;
00515 
00516         union {
00517                 struct uvc_input_header input;
00518                 struct uvc_output_header output;
00519         };
00520 
00521         unsigned int nformats;
00522         struct uvc_format *format;
00523 
00524         struct uvc_streaming_control ctrl;
00525         struct uvc_format *cur_format;
00526         struct uvc_frame *cur_frame;
00527 
00528         struct mutex mutex;
00529 };
00530 
00531 enum uvc_stream_state {
00532         UVC_STREAM_OFF = 0,
00533         UVC_STREAM_INTERRUPT = 1,
00534         UVC_STREAM_ON = 2,
00535 };
00536 
00537 enum uvc_buffer_state {
00538         UVC_BUF_STATE_IDLE       = 0,
00539         UVC_BUF_STATE_QUEUED     = 1,
00540         UVC_BUF_STATE_ACTIVE     = 2,
00541         UVC_BUF_STATE_DONE       = 3,
00542         UVC_BUF_STATE_ERROR      = 4,
00543 };
00544 
00545 struct uvc_buffer {
00546         unsigned int size;
00547         unsigned long vma_use_count;
00548         struct list_head stream;
00549 
00550         /* Touched by interrupt handler. */
00551         struct v4l2_buffer buf;
00552         struct list_head queue;
00553         wait_queue_head_t wait;
00554         enum uvc_buffer_state state;
00555 };
00556 
00557 struct uvc_video_queue {
00558         void *mem;
00559         unsigned int streaming;
00560         __u32 sequence;
00561         __u8 last_fid;
00562 
00563         unsigned int count;
00564         struct uvc_buffer buffer[UVC_MAX_VIDEO_BUFFERS];
00565         struct mutex mutex;
00566         spinlock_t irqlock;
00567 
00568         struct list_head mainqueue;
00569         struct list_head irqqueue;
00570 };
00571 
00572 struct uvc_video_device {
00573         struct uvc_device *dev;
00574         struct video_device *vdev;
00575         atomic_t active;
00576 
00577         enum uvc_stream_state stream;
00578 
00579         struct uvc_entity *iterm;
00580         struct uvc_entity *oterm;
00581         struct uvc_entity *processing;
00582         struct uvc_entity *extension[8];
00583         struct mutex ctrl_mutex;
00584 
00585         struct uvc_video_queue queue;
00586 
00587         struct uvc_streaming *streaming;
00588 
00589         struct urb *urb[UVC_URBS];
00590         char *urb_buffer[UVC_URBS];
00591 };
00592 
00593 enum uvc_device_state {
00594         UVC_DEV_DISCONNECTED = 1,
00595 };
00596 
00597 struct uvc_device {
00598         struct usb_device *udev;
00599         struct usb_interface *intf;
00600         __u32 quirks;
00601         int intfnum;
00602 
00603         enum uvc_device_state state;
00604         struct kref kref;
00605         struct list_head list;
00606 
00607         /* Video control interface */
00608         __u16 uvc_version;
00609         __u32 clock_frequency;
00610 
00611         struct list_head entities;
00612 
00613         struct uvc_video_device video;
00614 
00615         /* Status Interrupt Endpoint */
00616         struct usb_host_endpoint *int_ep;
00617         struct urb *int_urb;
00618         __u8 status[16];
00619 
00620         /* Video Streaming interfaces */
00621         struct list_head streaming;
00622 };
00623 
00624 enum uvc_handle_state {
00625         UVC_HANDLE_PASSIVE      = 0,
00626         UVC_HANDLE_ACTIVE       = 1,
00627 };
00628 
00629 struct uvc_fh {
00630         struct uvc_video_device *device;
00631         enum uvc_handle_state state;
00632 };
00633 
00634 struct uvc_driver {
00635         struct usb_driver driver;
00636 
00637         struct mutex open_mutex;        /* protects from open/disconnect race */
00638 
00639         struct list_head devices;       /* struct uvc_device list */
00640         struct list_head controls;      /* struct uvc_control_info list */
00641         struct mutex ctrl_mutex;        /* protects controls and devices lists */
00642 };
00643 
00644 /* ------------------------------------------------------------------------
00645  * Debugging, printing and logging
00646  */
00647 
00648 #define UVC_TRACE_PROBE         (1 << 0)
00649 #define UVC_TRACE_DESCR         (1 << 1)
00650 #define UVC_TRACE_CONTROL       (1 << 2)
00651 #define UVC_TRACE_FORMAT        (1 << 3)
00652 #define UVC_TRACE_CAPTURE       (1 << 4)
00653 #define UVC_TRACE_CALLS         (1 << 5)
00654 #define UVC_TRACE_IOCTL         (1 << 6)
00655 #define UVC_TRACE_FRAME         (1 << 7)
00656 
00657 extern unsigned int uvc_trace_param;
00658 
00659 #define uvc_trace(flag, msg...) \
00660         do { \
00661                 if (uvc_trace_param & flag) \
00662                         printk(KERN_DEBUG "uvcvideo: " msg); \
00663         } while(0)
00664 
00665 #define uvc_printk(level, msg...) \
00666         printk(level "uvcvideo: " msg)
00667 
00668 #define UVC_GUID_FORMAT "%02x%02x%02x%02x-%02x%02x-%02x%02x-%02x%02x-%02x%02x%02x%02x%02x%02x"
00669 #define UVC_GUID_ARGS(guid) \
00670         (guid)[3],  (guid)[2],  (guid)[1],  (guid)[0], \
00671         (guid)[5],  (guid)[4], \
00672         (guid)[7],  (guid)[6], \
00673         (guid)[8],  (guid)[9], \
00674         (guid)[10], (guid)[11], (guid)[12], \
00675         (guid)[13], (guid)[14], (guid)[15]
00676 
00677 /* --------------------------------------------------------------------------
00678  * Internal functions.
00679  */
00680 
00681 /* Core driver */
00682 extern struct uvc_driver uvc_driver;
00683 extern void uvc_delete(struct kref *kref);
00684 
00685 /* Video buffers queue management. */
00686 extern void uvc_queue_init(struct uvc_video_queue *queue);
00687 extern int uvc_alloc_buffers(struct uvc_video_queue *queue,
00688                 unsigned int nbuffers, unsigned int buflength);
00689 extern int uvc_free_buffers(struct uvc_video_queue *queue);
00690 extern void uvc_query_buffer(struct uvc_buffer *buf,
00691                 struct v4l2_buffer *v4l2_buf);
00692 extern int uvc_queue_buffer(struct uvc_video_queue *queue,
00693                 struct v4l2_buffer *v4l2_buf);
00694 extern int uvc_dequeue_buffer(struct uvc_video_queue *queue,
00695                 struct v4l2_buffer *v4l2_buf, int nonblocking);
00696 extern int uvc_queue_enable(struct uvc_video_queue *queue, int enable);
00697 extern void uvc_queue_cancel(struct uvc_video_queue *queue);
00698 extern struct uvc_buffer *uvc_queue_next_buffer(struct uvc_video_queue *queue,
00699                 struct uvc_buffer *buf);
00700 
00701 /* V4L2 interface */
00702 extern struct file_operations uvc_fops;
00703 
00704 /* Video */
00705 extern int uvc_video_init(struct uvc_video_device *video);
00706 extern int uvc_video_enable(struct uvc_video_device *video, int enable);
00707 extern int uvc_probe_video(struct uvc_video_device *video,
00708                 struct uvc_streaming_control *probe);
00709 extern int uvc_query_ctrl(struct uvc_device *dev, __u8 query, __u8 unit,
00710                 __u8 intfnum, __u8 cs, void *data, __u16 size);
00711 extern int uvc_set_video_ctrl(struct uvc_video_device *video,
00712                 struct uvc_streaming_control *ctrl, int probe);
00713 extern int uvc_init_status(struct uvc_device *dev);
00714 
00715 /* Controls */
00716 extern struct uvc_control *uvc_find_control(struct uvc_video_device *video,
00717                 __u32 v4l2_id, struct uvc_control_mapping **mapping);
00718 extern int uvc_query_v4l2_ctrl(struct uvc_video_device *video,
00719                 struct v4l2_queryctrl *v4l2_ctrl);
00720 
00721 extern void uvc_ctrl_add_info(struct uvc_control_info *info);
00722 extern int uvc_ctrl_init_device(struct uvc_device *dev);
00723 extern void uvc_ctrl_cleanup_device(struct uvc_device *dev);
00724 extern void uvc_ctrl_init(void);
00725 
00726 extern int uvc_ctrl_begin(struct uvc_video_device *video);
00727 extern int __uvc_ctrl_commit(struct uvc_video_device *video, int rollback);
00728 static inline int uvc_ctrl_commit(struct uvc_video_device *video)
00729 {
00730         return __uvc_ctrl_commit(video, 0);
00731 }
00732 static inline int uvc_ctrl_rollback(struct uvc_video_device *video)
00733 {
00734         return __uvc_ctrl_commit(video, 1);
00735 }
00736 
00737 extern int uvc_ctrl_get(struct uvc_video_device *video,
00738                 struct v4l2_ext_control *xctrl);
00739 extern int uvc_ctrl_set(struct uvc_video_device *video,
00740                 struct v4l2_ext_control *xctrl);
00741 
00742 /* Utility functions */
00743 extern void uvc_simplify_fraction(uint32_t *numerator, uint32_t *denominator,
00744                 unsigned int n_terms, unsigned int threshold);
00745 extern uint32_t uvc_fraction_to_interval(uint32_t numerator,
00746                 uint32_t denominator);
00747 extern struct usb_host_endpoint *uvc_find_endpoint(
00748                 struct usb_host_interface *alts, __u8 epaddr);
00749 
00750 #endif /* __KERNEL__ */
00751 
00752 #endif
00753 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


opt_camera
Author(s): Kei Okada
autogenerated on Sat Mar 23 2013 21:00:15