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