8 #include <linux/kernel.h> 9 #include <linux/videodev2.h> 10 #include <linux/usb/video.h> 11 #include <linux/uvcvideo.h> 41 #define V4L2_CID_PANTILT_RESET (V4L2_CID_PRIVATE_BASE+9) 42 #define V4L2_CID_WHITE_BALANCE_TEMPERATURE_AUTO V4L2_CID_AUTO_WHITE_BALANCE 43 #define V4L2_CID_ZOOM_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+14) 45 #define UVC_GUID_UVC_EXTENSION {0x4e, 0x4d, 0x33, 0x30, 0x01, 0x7a, 0xce, 0x41, \ 46 0x80, 0x53, 0x5b, 0x7f, 0x3f, 0xb7, 0x61, 0x99} 47 #define XU_UNDEFINED 0x00 49 #define XU_FIRMWARE_VERSION_CONTROL 0x01 50 #define XU_FLASH_PARAMETER_CONTROL 0x02 51 #define XU_FLIP_SCREEN_CONTROL 0x03 52 #define XU_SMALL_HEMISPHERE_CONTROL 0x04 53 #define XU_ANALOG_VIDEO_STANDARD_CONTROL 0x05 54 #define XU_MEDIAN_FILTER_CONTROL 0x07 55 #define XU_PUSH_BUTTON_CONTROL 0x08 56 #define XU_PENDING_PTZR_CONTROL 0x0B 57 #define XU_AUTO_PAN_SPEED_CONTROL 0x0C 58 #define XU_JPEG_QUALITY_CONTROL 0x0D 59 #define XU_SERIAL_ID_CONTROL 0x0E 60 #define XU_INFO_DISPLAY_CONTROL 0x0F 61 #define XU_CAPTURE_FPS_CONTROL 0x10 62 #define XU_ACTUAL_FPS_CONTROL 0x11 63 #define XU_LENS_TYPE_CONTROL 0x12 64 #define XU_PAN_ABSOLUTE_CONTROL 0x13 65 #define XU_TILT_ABSOLUTE_CONTROL 0x14 66 #define XU_ROLL_ABSOLUTE_CONTROL 0x15 67 #define XU_ZOOM_ABSOLUTE_CONTROL 0x16 68 #define XU_LOCATION_ABSOLUTE_CONTROL 0x17 69 #define XU_GAIN_ABSOLUTE_CONTROL 0x1E 72 #define UVC_CONTROL_SET_CUR (1 << 0) 73 #define UVC_CONTROL_GET_CUR (1 << 1) 81 #define SC_UNDEFINED 0x00 82 #define SC_VIDEOCONTROL 0x01 83 #define SC_VIDEOSTREAMING 0x02 84 #define SC_VIDEO_INTERFACE_COLLECTION 0x03 86 #define PC_PROTOCOL_UNDEFINED 0x00 88 #define CS_UNDEFINED 0x20 89 #define CS_DEVICE 0x21 90 #define CS_CONFIGURATION 0x22 91 #define CS_STRING 0x23 92 #define CS_INTERFACE 0x24 93 #define CS_ENDPOINT 0x25 96 #define VC_DESCRIPTOR_UNDEFINED 0x00 97 #define VC_HEADER 0x01 98 #define VC_INPUT_TERMINAL 0x02 99 #define VC_OUTPUT_TERMINAL 0x03 100 #define VC_SELECTOR_UNIT 0x04 101 #define VC_PROCESSING_UNIT 0x05 102 #define VC_EXTENSION_UNIT 0x06 105 #define VS_UNDEFINED 0x00 106 #define VS_INPUT_HEADER 0x01 107 #define VS_OUTPUT_HEADER 0x02 108 #define VS_STILL_IMAGE_FRAME 0x03 109 #define VS_FORMAT_UNCOMPRESSED 0x04 110 #define VS_FRAME_UNCOMPRESSED 0x05 111 #define VS_FORMAT_MJPEG 0x06 112 #define VS_FRAME_MJPEG 0x07 113 #define VS_FORMAT_MPEG2TS 0x0a 114 #define VS_FORMAT_DV 0x0c 115 #define VS_COLORFORMAT 0x0d 116 #define VS_FORMAT_FRAME_BASED 0x10 117 #define VS_FRAME_FRAME_BASED 0x11 118 #define VS_FORMAT_STREAM_BASED 0x12 121 #define EP_UNDEFINED 0x00 122 #define EP_GENERAL 0x01 123 #define EP_ENDPOINT 0x02 124 #define EP_INTERRUPT 0x03 127 #define RC_UNDEFINED 0x00 134 #define GET_INFO 0x86 138 #define VC_CONTROL_UNDEFINED 0x00 139 #define VC_VIDEO_POWER_MODE_CONTROL 0x01 140 #define VC_REQUEST_ERROR_CODE_CONTROL 0x02 143 #define TE_CONTROL_UNDEFINED 0x00 146 #define SU_CONTROL_UNDEFINED 0x00 147 #define SU_INPUT_SELECT_CONTROL 0x01 150 #define CT_CONTROL_UNDEFINED 0x00 151 #define CT_SCANNING_MODE_CONTROL 0x01 152 #define CT_AE_MODE_CONTROL 0x02 153 #define CT_AE_PRIORITY_CONTROL 0x03 154 #define CT_EXPOSURE_TIME_ABSOLUTE_CONTROL 0x04 155 #define CT_EXPOSURE_TIME_RELATIVE_CONTROL 0x05 156 #define CT_FOCUS_ABSOLUTE_CONTROL 0x06 157 #define CT_FOCUS_RELATIVE_CONTROL 0x07 158 #define CT_FOCUS_AUTO_CONTROL 0x08 159 #define CT_IRIS_ABSOLUTE_CONTROL 0x09 160 #define CT_IRIS_RELATIVE_CONTROL 0x0a 161 #define CT_ZOOM_ABSOLUTE_CONTROL 0x0b 162 #define CT_ZOOM_RELATIVE_CONTROL 0x0c 163 #define CT_PANTILT_ABSOLUTE_CONTROL 0x0d 164 #define CT_PANTILT_RELATIVE_CONTROL 0x0e 165 #define CT_ROLL_ABSOLUTE_CONTROL 0x0f 166 #define CT_ROLL_RELATIVE_CONTROL 0x10 167 #define CT_PRIVACY_CONTROL 0x11 170 #define PU_CONTROL_UNDEFINED 0x00 171 #define PU_BACKLIGHT_COMPENSATION_CONTROL 0x01 172 #define PU_BRIGHTNESS_CONTROL 0x02 173 #define PU_CONTRAST_CONTROL 0x03 174 #define PU_GAIN_CONTROL 0x04 175 #define PU_POWER_LINE_FREQUENCY_CONTROL 0x05 176 #define PU_HUE_CONTROL 0x06 177 #define PU_SATURATION_CONTROL 0x07 178 #define PU_SHARPNESS_CONTROL 0x08 179 #define PU_GAMMA_CONTROL 0x09 180 #define PU_WHITE_BALANCE_TEMPERATURE_CONTROL 0x0a 181 #define PU_WHITE_BALANCE_TEMPERATURE_AUTO_CONTROL 0x0b 182 #define PU_WHITE_BALANCE_COMPONENT_CONTROL 0x0c 183 #define PU_WHITE_BALANCE_COMPONENT_AUTO_CONTROL 0x0d 184 #define PU_DIGITAL_MULTIPLIER_CONTROL 0x0e 185 #define PU_DIGITAL_MULTIPLIER_LIMIT_CONTROL 0x0f 186 #define PU_HUE_AUTO_CONTROL 0x10 187 #define PU_ANALOG_VIDEO_STANDARD_CONTROL 0x11 188 #define PU_ANALOG_LOCK_STATUS_CONTROL 0x12 190 #define LXU_MOTOR_PANTILT_RELATIVE_CONTROL 0x01 191 #define LXU_MOTOR_PANTILT_RESET_CONTROL 0x02 194 #define VS_CONTROL_UNDEFINED 0x00 195 #define VS_PROBE_CONTROL 0x01 196 #define VS_COMMIT_CONTROL 0x02 197 #define VS_STILL_PROBE_CONTROL 0x03 198 #define VS_STILL_COMMIT_CONTROL 0x04 199 #define VS_STILL_IMAGE_TRIGGER_CONTROL 0x05 200 #define VS_STREAM_ERROR_CODE_CONTROL 0x06 201 #define VS_GENERATE_KEY_FRAME_CONTROL 0x07 202 #define VS_UPDATE_FRAME_SEGMENT_CONTROL 0x08 203 #define VS_SYNC_DELAY_CONTROL 0x09 205 #define TT_VENDOR_SPECIFIC 0x0100 206 #define TT_STREAMING 0x0101 209 #define ITT_VENDOR_SPECIFIC 0x0200 210 #define ITT_CAMERA 0x0201 211 #define ITT_MEDIA_TRANSPORT_INPUT 0x0202 214 #define OTT_VENDOR_SPECIFIC 0x0300 215 #define OTT_DISPLAY 0x0301 216 #define OTT_MEDIA_TRANSPORT_OUTPUT 0x0302 218 #define EXTERNAL_VENDOR_SPECIFIC 0x0400 219 #define COMPOSITE_CONNECTOR 0x0401 220 #define SVIDEO_CONNECTOR 0x0402 221 #define COMPONENT_CONNECTOR 0x0403 223 #define UVC_ENTITY_IS_UNIT(entity) ((entity->type & 0xff00) == 0) 224 #define UVC_ENTITY_IS_TERM(entity) ((entity->type & 0xff00) != 0) 225 #define UVC_ENTITY_IS_ITERM(entity) ((entity->type & 0xff00) == ITT_VENDOR_SPECIFIC) 226 #define UVC_ENTITY_IS_OTERM(entity) ((entity->type & 0xff00) == OTT_VENDOR_SPECIFIC) 231 #define UVC_GUID_UVC_CAMERA {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \ 232 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01} 233 #define UVC_GUID_UVC_OUTPUT {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \ 234 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02} 235 #define UVC_GUID_UVC_PROCESSING {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \ 236 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01} 237 #define UVC_GUID_UVC_SELECTOR {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \ 238 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02} 240 #define UVC_GUID_LOGITECH_XU1 {0x82, 0x06, 0x61, 0x63, 0x70, 0x50, 0xab, 0x49, \ 241 0xb8, 0xcc, 0xb3, 0x85, 0x5e, 0x8d, 0x22, 0x1d} 242 #define UVC_GUID_LOGITECH_XU2 {0x82, 0x06, 0x61, 0x63, 0x70, 0x50, 0xab, 0x49, \ 243 0xb8, 0xcc, 0xb3, 0x85, 0x5e, 0x8d, 0x22, 0x1e} 244 #define UVC_GUID_LOGITECH_XU3 {0x82, 0x06, 0x61, 0x63, 0x70, 0x50, 0xab, 0x49, \ 245 0xb8, 0xcc, 0xb3, 0x85, 0x5e, 0x8d, 0x22, 0x1f} 246 #define UVC_GUID_LOGITECH_MOTOR {0x82, 0x06, 0x61, 0x63, 0x70, 0x50, 0xab, 0x49, \ 247 0xb8, 0xcc, 0xb3, 0x85, 0x5e, 0x8d, 0x22, 0x56} 248 #define UVC_GUID_LOGITECH_DEV_INFO \ 249 {0x82, 0x06, 0x61, 0x63, 0x70, 0x50, 0xab, 0x49, \ 250 0xb8, 0xcc, 0xb3, 0x85, 0x5e, 0x8d, 0x22, 0x1e} 252 #define UVC_GUID_FORMAT_MJPEG {0x4d, 0x4a, 0x50, 0x47, 0x00, 0x00, 0x10, 0x00, \ 253 0x80, 0x00, 0x00, 0xaa, 0x00, 0x38, 0x9b, 0x71} 254 #define UVC_GUID_FORMAT_YUY2 {0x59, 0x55, 0x59, 0x32, 0x00, 0x00, 0x10, 0x00, \ 255 0x80, 0x00, 0x00, 0xaa, 0x00, 0x38, 0x9b, 0x71} 256 #define UVC_GUID_FORMAT_NV12 {0x4e, 0x56, 0x31, 0x32, 0x00, 0x00, 0x10, 0x00, \ 257 0x80, 0x00, 0x00, 0xaa, 0x00, 0x38, 0x9b, 0x71} 264 #define DRIVER_VERSION_NUMBER KERNEL_VERSION(0, 1, 0) 269 #define UVC_MAX_ISO_PACKETS 40 271 #define UVC_MAX_FRAME_SIZE (16*1024*1024) 273 #define UVC_MAX_VIDEO_BUFFERS 32 275 #define UVC_CTRL_TIMEOUT 300 278 #define UVC_QUIRK_STATUS_INTERVAL 0x00000001 289 struct uvc_streaming_control {
293 __u32 dwFrameInterval;
297 __u16 wCompWindowSize;
299 __u32 dwMaxVideoFrameSize;
300 __u32 dwMaxPayloadTransferSize;
301 __u32 dwClockFrequency;
303 __u8 bPreferedVersion;
308 struct uvc_menu_info {
313 struct uvc_control_info {
314 struct list_head list;
315 struct list_head mappings;
326 enum uvc_control_data_type {
327 UVC_CTRL_DATA_TYPE_RAW = 0,
328 UVC_CTRL_DATA_TYPE_SIGNED,
329 UVC_CTRL_DATA_TYPE_UNSIGNED,
330 UVC_CTRL_DATA_TYPE_BOOLEAN,
331 UVC_CTRL_DATA_TYPE_ENUM,
332 UVC_CTRL_DATA_TYPE_BITMASK,
335 struct uvc_control_mapping {
336 struct list_head list;
338 struct uvc_control_info *ctrl;
347 enum v4l2_ctrl_type v4l2_type;
348 enum uvc_control_data_type data_type;
350 struct uvc_menu_info *menu_info;
355 struct uvc_entity *entity;
356 struct uvc_control_info *info;
365 struct uvc_format_desc {
382 struct list_head list;
390 __u16 wObjectiveFocalLengthMin;
391 __u16 wObjectiveFocalLengthMax;
392 __u16 wOcularFocalLength;
403 __u16 wMaxMultiplier;
406 __u8 bmVideoStandards;
415 __u8 guidExtensionCode[16];
421 __u8 *bmControlsType;
425 unsigned int ncontrols;
426 struct uvc_control *controls;
436 __u32 dwMaxVideoFrameBufferSize;
437 __u8 bFrameIntervalType;
438 __u32 dwDefaultFrameInterval;
439 __u32 *dwFrameInterval;
452 unsigned int nframes;
453 struct uvc_frame *frame;
456 struct uvc_input_header {
458 __u8 bEndpointAddress;
461 __u8 bStillCaptureMethod;
462 __u8 bTriggerSupport;
468 struct uvc_output_header {
471 struct uvc_streaming {
472 struct list_head list;
474 struct usb_interface *intf;
479 struct uvc_input_header input;
480 struct uvc_output_header output;
483 unsigned int nformats;
484 struct uvc_format *format;
486 struct uvc_streaming_control ctrl;
487 struct uvc_format *cur_format;
488 struct uvc_frame *cur_frame;
493 enum uvc_stream_state {
495 UVC_STREAM_INTERRUPT = 1,
499 enum uvc_buffer_state {
500 UVC_BUF_STATE_IDLE = 0,
501 UVC_BUF_STATE_QUEUED = 1,
502 UVC_BUF_STATE_ACTIVE = 2,
503 UVC_BUF_STATE_DONE = 3,
504 UVC_BUF_STATE_ERROR = 4,
509 unsigned long vma_use_count;
510 struct list_head stream;
513 struct v4l2_buffer buf;
514 struct list_head queue;
515 wait_queue_head_t
wait;
516 enum uvc_buffer_state state;
519 struct uvc_video_queue {
521 unsigned int streaming;
526 struct uvc_buffer buffer[UVC_MAX_VIDEO_BUFFERS];
530 struct list_head mainqueue;
531 struct list_head irqqueue;
534 struct uvc_video_device {
535 struct uvc_device *dev;
536 struct video_device *vdev;
539 enum uvc_stream_state stream;
541 struct uvc_entity *iterm;
542 struct uvc_entity *oterm;
543 struct uvc_entity *processing;
544 struct uvc_entity *extension[8];
545 struct mutex ctrl_mutex;
547 struct uvc_video_queue queue;
549 struct uvc_streaming *streaming;
551 struct urb *urb[UVC_URBS];
552 char *urb_buffer[UVC_URBS];
555 enum uvc_device_state {
556 UVC_DEV_DISCONNECTED = 1,
560 struct usb_device *udev;
561 struct usb_interface *intf;
565 enum uvc_device_state state;
567 struct list_head list;
571 __u32 clock_frequency;
573 struct list_head entities;
575 struct uvc_video_device video;
578 struct usb_host_endpoint *int_ep;
583 struct list_head streaming;
586 enum uvc_handle_state {
587 UVC_HANDLE_PASSIVE = 0,
588 UVC_HANDLE_ACTIVE = 1,
592 struct uvc_video_device *device;
593 enum uvc_handle_state state;
597 struct usb_driver driver;
599 struct mutex open_mutex;
601 struct list_head devices;
602 struct list_head controls;
603 struct mutex ctrl_mutex;
610 #define UVC_TRACE_PROBE (1 << 0) 611 #define UVC_TRACE_DESCR (1 << 1) 612 #define UVC_TRACE_CONTROL (1 << 2) 613 #define UVC_TRACE_FORMAT (1 << 3) 614 #define UVC_TRACE_CAPTURE (1 << 4) 615 #define UVC_TRACE_CALLS (1 << 5) 616 #define UVC_TRACE_IOCTL (1 << 6) 617 #define UVC_TRACE_FRAME (1 << 7) 619 extern unsigned int uvc_trace_param;
621 #define uvc_trace(flag, msg...) \ 623 if (uvc_trace_param & flag) \ 624 printk(KERN_DEBUG "uvcvideo: " msg); \ 627 #define uvc_printk(level, msg...) \ 628 printk(level "uvcvideo: " msg) 630 #define UVC_GUID_FORMAT "%02x%02x%02x%02x-%02x%02x-%02x%02x-%02x%02x-%02x%02x%02x%02x%02x%02x" 631 #define UVC_GUID_ARGS(guid) \ 632 (guid)[3], (guid)[2], (guid)[1], (guid)[0], \ 633 (guid)[5], (guid)[4], \ 634 (guid)[7], (guid)[6], \ 635 (guid)[8], (guid)[9], \ 636 (guid)[10], (guid)[11], (guid)[12], \ 637 (guid)[13], (guid)[14], (guid)[15] 644 extern struct uvc_driver uvc_driver;
645 extern void uvc_delete(
struct kref *kref);
648 extern void uvc_queue_init(
struct uvc_video_queue *queue);
649 extern int uvc_alloc_buffers(
struct uvc_video_queue *queue,
650 unsigned int nbuffers,
unsigned int buflength);
651 extern int uvc_free_buffers(
struct uvc_video_queue *queue);
652 extern void uvc_query_buffer(
struct uvc_buffer *buf,
653 struct v4l2_buffer *v4l2_buf);
654 extern int uvc_queue_buffer(
struct uvc_video_queue *queue,
655 struct v4l2_buffer *v4l2_buf);
656 extern int uvc_dequeue_buffer(
struct uvc_video_queue *queue,
657 struct v4l2_buffer *v4l2_buf,
int nonblocking);
658 extern int uvc_queue_enable(
struct uvc_video_queue *queue,
int enable);
659 extern void uvc_queue_cancel(
struct uvc_video_queue *queue);
660 extern struct uvc_buffer *uvc_queue_next_buffer(
struct uvc_video_queue *queue,
661 struct uvc_buffer *buf);
664 extern struct file_operations uvc_fops;
667 extern int uvc_video_init(
struct uvc_video_device *video);
668 extern int uvc_video_enable(
struct uvc_video_device *video,
int enable);
669 extern int uvc_probe_video(
struct uvc_video_device *video,
670 struct uvc_streaming_control *probe);
671 extern int uvc_query_ctrl(
struct uvc_device *dev, __u8 query, __u8 unit,
672 __u8 intfnum, __u8 cs,
void *data, __u16 size);
673 extern int uvc_set_video_ctrl(
struct uvc_video_device *video,
674 struct uvc_streaming_control *ctrl,
int probe);
675 extern int uvc_init_status(
struct uvc_device *dev);
678 extern struct uvc_control *uvc_find_control(
struct uvc_video_device *video,
679 __u32 v4l2_id,
struct uvc_control_mapping **mapping);
680 extern int uvc_query_v4l2_ctrl(
struct uvc_video_device *video,
681 struct v4l2_queryctrl *v4l2_ctrl);
683 extern void uvc_ctrl_add_info(
struct uvc_control_info *info);
684 extern int uvc_ctrl_init_device(
struct uvc_device *dev);
685 extern void uvc_ctrl_cleanup_device(
struct uvc_device *dev);
686 extern void uvc_ctrl_init(
void);
688 extern int uvc_ctrl_begin(
struct uvc_video_device *video);
689 extern int __uvc_ctrl_commit(
struct uvc_video_device *video,
int rollback);
690 static inline int uvc_ctrl_commit(
struct uvc_video_device *video)
692 return __uvc_ctrl_commit(video, 0);
694 static inline int uvc_ctrl_rollback(
struct uvc_video_device *video)
696 return __uvc_ctrl_commit(video, 1);
699 extern int uvc_ctrl_get(
struct uvc_video_device *video,
700 struct v4l2_ext_control *xctrl);
701 extern int uvc_ctrl_set(
struct uvc_video_device *video,
702 struct v4l2_ext_control *xctrl);
705 extern void uvc_simplify_fraction(uint32_t *numerator, uint32_t *denominator,
706 unsigned int n_terms,
unsigned int threshold);
707 extern uint32_t uvc_fraction_to_interval(uint32_t numerator,
708 uint32_t denominator);
709 extern struct usb_host_endpoint *uvc_find_endpoint(
710 struct usb_host_interface *alts, __u8 epaddr);