diag.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 *********************************************************************/
00039 #include "libuvc.h"
00040 #include "libuvc_internal.h"
00041 
00043 typedef struct _uvc_error_msg {
00044   uvc_error_t err;
00045   const char *msg;
00046 } _uvc_error_msg_t;
00047 
00048 static const _uvc_error_msg_t uvc_error_msgs[] = {
00049   {UVC_SUCCESS, "Success"},
00050   {UVC_ERROR_IO, "I/O error"},
00051   {UVC_ERROR_INVALID_PARAM, "Invalid parameter"},
00052   {UVC_ERROR_ACCESS, "Access denied"},
00053   {UVC_ERROR_NO_DEVICE, "No such device"},
00054   {UVC_ERROR_NOT_FOUND, "Not found"},
00055   {UVC_ERROR_BUSY, "Busy"},
00056   {UVC_ERROR_TIMEOUT, "Timeout"},
00057   {UVC_ERROR_OVERFLOW, "Overflow"},
00058   {UVC_ERROR_PIPE, "Pipe"},
00059   {UVC_ERROR_INTERRUPTED, "Interrupted"},
00060   {UVC_ERROR_NO_MEM, "Out of memory"},
00061   {UVC_ERROR_NOT_SUPPORTED, "Not supported"},
00062   {UVC_ERROR_INVALID_DEVICE, "Invalid device"},
00063   {UVC_ERROR_INVALID_MODE, "Invalid mode"},
00064   {UVC_ERROR_CALLBACK_EXISTS, "Callback exists"}
00065 };
00066 
00073 void uvc_perror(uvc_error_t err, const char *msg) {
00074   if (msg && *msg) {
00075     fputs(msg, stderr);
00076     fputs(": ", stderr);
00077   }
00078 
00079   fprintf(stderr, "%s (%d)\n", uvc_strerror(err), err);
00080 }
00081 
00088 const char* uvc_strerror(uvc_error_t err) {
00089   size_t idx;
00090 
00091   for (idx = 0; idx < sizeof(uvc_error_msgs) / sizeof(*uvc_error_msgs); ++idx) {
00092     if (uvc_error_msgs[idx].err == err) {
00093       return uvc_error_msgs[idx].msg;
00094     }
00095   }
00096 
00097   return "Unknown error";
00098 }
00099 
00106 void uvc_print_stream_ctrl(uvc_stream_ctrl_t *ctrl, FILE *stream) {
00107   if (stream == NULL)
00108     stream = stderr;
00109 
00110   fprintf(stream, "bmHint: %04x\n", ctrl->bmHint);
00111   fprintf(stream, "bFormatIndex: %d\n", ctrl->bFormatIndex);
00112   fprintf(stream, "bFrameIndex: %d\n", ctrl->bFrameIndex);
00113   fprintf(stream, "dwFrameInterval: %u\n", ctrl->dwFrameInterval);
00114   fprintf(stream, "wKeyFrameRate: %d\n", ctrl->wKeyFrameRate);
00115   fprintf(stream, "wPFrameRate: %d\n", ctrl->wPFrameRate);
00116   fprintf(stream, "wCompQuality: %d\n", ctrl->wCompQuality);
00117   fprintf(stream, "wCompWindowSize: %d\n", ctrl->wCompWindowSize);
00118   fprintf(stream, "wDelay: %d\n", ctrl->wDelay);
00119   fprintf(stream, "dwMaxVideoFrameSize: %u\n", ctrl->dwMaxVideoFrameSize);
00120   fprintf(stream, "dwMaxPayloadTransferSize: %u\n", ctrl->dwMaxPayloadTransferSize);
00121   fprintf(stream, "bInterfaceNumber: %d\n", ctrl->bInterfaceNumber);
00122 }
00123 
00124 static const char *_uvc_name_for_format_subtype(uint8_t subtype) {
00125   switch (subtype) {
00126   case UVC_VS_FORMAT_UNCOMPRESSED:
00127     return "UncompressedFormat";
00128   case UVC_VS_FORMAT_MJPEG:
00129     return "MJPEGFormat";
00130   case UVC_VS_FORMAT_FRAME_BASED:
00131     return "FrameFormat";
00132   default:
00133     return "Unknown";
00134   }
00135 }
00136 
00143 void uvc_print_diag(uvc_device_handle_t *devh, FILE *stream) {
00144   if (stream == NULL)
00145     stream = stderr;
00146 
00147   if (devh->info->ctrl_if.bcdUVC) {
00148     uvc_streaming_interface_t *stream_if;
00149     int stream_idx = 0;
00150 
00151     uvc_device_descriptor_t *desc;
00152     uvc_get_device_descriptor(devh->dev, &desc);
00153 
00154     fprintf(stream, "DEVICE CONFIGURATION (%04x:%04x/%s) ---\n",
00155         desc->idVendor, desc->idProduct,
00156         desc->serialNumber ? desc->serialNumber : "[none]");
00157 
00158     uvc_free_device_descriptor(desc);
00159 
00160     fprintf(stream, "Status: %s\n", devh->streams ? "streaming" : "idle");
00161 
00162     fprintf(stream, "VideoControl:\n"
00163         "\tbcdUVC: 0x%04x\n",
00164         devh->info->ctrl_if.bcdUVC);
00165 
00166     DL_FOREACH(devh->info->stream_ifs, stream_if) {
00167       uvc_format_desc_t *fmt_desc;
00168 
00169       ++stream_idx;
00170 
00171       fprintf(stream, "VideoStreaming(%d):\n"
00172           "\tbEndpointAddress: %d\n\tFormats:\n",
00173           stream_idx, stream_if->bEndpointAddress);
00174 
00175       DL_FOREACH(stream_if->format_descs, fmt_desc) {
00176         uvc_frame_desc_t *frame_desc;
00177         int i;
00178 
00179         switch (fmt_desc->bDescriptorSubtype) {
00180           case UVC_VS_FORMAT_UNCOMPRESSED:
00181           case UVC_VS_FORMAT_MJPEG:
00182           case UVC_VS_FORMAT_FRAME_BASED:
00183             fprintf(stream,
00184                 "\t\t%s(%d)\n"
00185                 "\t\t  bits per pixel: %d\n"
00186                 "\t\t  GUID: ",
00187                 _uvc_name_for_format_subtype(fmt_desc->bDescriptorSubtype),
00188                 fmt_desc->bFormatIndex,
00189                 fmt_desc->bBitsPerPixel);
00190 
00191             for (i = 0; i < 16; ++i)
00192               fprintf(stream, "%02x", fmt_desc->guidFormat[i]);
00193 
00194             fprintf(stream, " (%4s)\n", fmt_desc->fourccFormat );
00195 
00196             fprintf(stream,
00197                 "\t\t  default frame: %d\n"
00198                 "\t\t  aspect ratio: %dx%d\n"
00199                 "\t\t  interlace flags: %02x\n"
00200                 "\t\t  copy protect: %02x\n",
00201                 fmt_desc->bDefaultFrameIndex,
00202                 fmt_desc->bAspectRatioX,
00203                 fmt_desc->bAspectRatioY,
00204                 fmt_desc->bmInterlaceFlags,
00205                 fmt_desc->bCopyProtect);
00206 
00207             DL_FOREACH(fmt_desc->frame_descs, frame_desc) {
00208               uint32_t *interval_ptr;
00209 
00210               fprintf(stream,
00211                   "\t\t\tFrameDescriptor(%d)\n"
00212                   "\t\t\t  capabilities: %02x\n"
00213                   "\t\t\t  size: %dx%d\n"
00214                   "\t\t\t  bit rate: %d-%d\n"
00215                   "\t\t\t  max frame size: %d\n"
00216                   "\t\t\t  default interval: 1/%d\n",
00217                   frame_desc->bFrameIndex,
00218                   frame_desc->bmCapabilities,
00219                   frame_desc->wWidth,
00220                   frame_desc->wHeight,
00221                   frame_desc->dwMinBitRate,
00222                   frame_desc->dwMaxBitRate,
00223                   frame_desc->dwMaxVideoFrameBufferSize,
00224                   10000000 / frame_desc->dwDefaultFrameInterval);
00225               if (frame_desc->intervals) {
00226                 for (interval_ptr = frame_desc->intervals;
00227                      *interval_ptr;
00228                      ++interval_ptr) {
00229                   fprintf(stream,
00230                       "\t\t\t  interval[%d]: 1/%d\n",
00231               (int) (interval_ptr - frame_desc->intervals),
00232               10000000 / *interval_ptr);
00233                 }
00234               } else {
00235                 fprintf(stream,
00236                     "\t\t\t  min interval[%d] = 1/%d\n"
00237                     "\t\t\t  max interval[%d] = 1/%d\n",
00238                     frame_desc->dwMinFrameInterval,
00239                     10000000 / frame_desc->dwMinFrameInterval,
00240                     frame_desc->dwMaxFrameInterval,
00241                     10000000 / frame_desc->dwMaxFrameInterval);
00242                 if (frame_desc->dwFrameIntervalStep)
00243                   fprintf(stream,
00244                       "\t\t\t  interval step[%d] = 1/%d\n",
00245                       frame_desc->dwFrameIntervalStep,
00246                       10000000 / frame_desc->dwFrameIntervalStep);
00247               }
00248             }
00249             break;
00250           default:
00251             fprintf(stream, "\t-UnknownFormat (%d)\n",
00252                 fmt_desc->bDescriptorSubtype );
00253         }
00254       }
00255     }
00256 
00257     fprintf(stream, "END DEVICE CONFIGURATION\n");
00258   } else {
00259     fprintf(stream, "uvc_print_diag: Device not configured!\n");
00260   }
00261 }
00262 


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