ctrl.c
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (C) 2010-2012 Ken Tossell
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 author nor other contributors may be
00018 *     used to endorse or promote products derived from this software
00019 *     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 *********************************************************************/
00042 #include "libuvc.h"
00043 #include "libuvc_internal.h"
00044 
00045 static const int REQ_TYPE_SET = 0x21;
00046 static const int REQ_TYPE_GET = 0xa1;
00047 
00048 /***** GENERIC CONTROLS *****/
00059 int uvc_get_ctrl_len(uvc_device_handle_t *devh, uint8_t unit, uint8_t ctrl) {
00060   unsigned char buf[2];
00061 
00062   int ret = libusb_control_transfer(
00063     devh->usb_devh,
00064     REQ_TYPE_GET, UVC_GET_LEN,
00065     ctrl << 8,
00066     unit << 8,
00067     buf,
00068     2,
00069     0 /* timeout */);
00070 
00071   if (ret < 0)
00072     return ret;
00073   else
00074     return (unsigned short)SW_TO_SHORT(buf);
00075 }
00076 
00090 int uvc_get_ctrl(uvc_device_handle_t *devh, uint8_t unit, uint8_t ctrl, void *data, int len, enum uvc_req_code req_code) {
00091   return libusb_control_transfer(
00092     devh->usb_devh,
00093     REQ_TYPE_GET, req_code,
00094     ctrl << 8,
00095     unit << 8,
00096     data,
00097     len,
00098     0 /* timeout */);
00099 }
00100 
00113 int uvc_set_ctrl(uvc_device_handle_t *devh, uint8_t unit, uint8_t ctrl, void *data, int len) {
00114   return libusb_control_transfer(
00115     devh->usb_devh,
00116     REQ_TYPE_SET, UVC_SET_CUR,
00117     ctrl << 8,
00118     unit << 8,
00119     data,
00120     len,
00121     0 /* timeout */);
00122 }
00123 
00124 /***** INTERFACE CONTROLS *****/
00125 uvc_error_t uvc_get_power_mode(uvc_device_handle_t *devh, enum uvc_device_power_mode *mode, enum uvc_req_code req_code) {
00126   uint8_t mode_char;
00127   uvc_error_t ret;
00128 
00129   ret = libusb_control_transfer(
00130     devh->usb_devh,
00131     REQ_TYPE_GET, req_code,
00132     UVC_VC_VIDEO_POWER_MODE_CONTROL << 8,
00133     0,
00134     &mode_char,
00135     sizeof(mode_char),
00136     0);
00137 
00138   if (ret == 1) {
00139     *mode = mode_char;
00140     return UVC_SUCCESS;
00141   } else {
00142     return ret;
00143   }
00144 }
00145 
00146 uvc_error_t uvc_set_power_mode(uvc_device_handle_t *devh, enum uvc_device_power_mode mode) {
00147   uint8_t mode_char = mode;
00148   uvc_error_t ret;
00149 
00150   ret = libusb_control_transfer(
00151     devh->usb_devh,
00152     REQ_TYPE_SET, UVC_SET_CUR,
00153     UVC_VC_VIDEO_POWER_MODE_CONTROL << 8,
00154     0,
00155     &mode_char,
00156     sizeof(mode_char),
00157     0);
00158 
00159   if (ret == 1)
00160     return UVC_SUCCESS;
00161   else
00162     return ret;
00163 }
00164 


librealsense
Author(s): Sergey Dorodnicov , Mark Horn , Reagan Lopez
autogenerated on Tue Jun 25 2019 19:54:38