Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/cameras_gimbals/xacti-config/CX-GBXXXCtrl.cpp
Views: 1799
// =============================================================================1/**2* @file CX-GBXXXCtrl.cpp3* @brief CX-GBXXX用コントロールクラス ヘッダ4* @copyright (c) 2022 Xacti Corporation5*/6// =============================================================================78#include "CX-GBXXXCtrl.h"9#include <libusb-1.0/libusb.h>10#include <libuvc/libuvc.h>11#include <assert.h>1213// -----------------------------------------------------------------------------14/*!15* @brief CX_GBXXXCtrlコンストラクタ16*/17// -----------------------------------------------------------------------------18CX_GBXXXCtrl::CX_GBXXXCtrl()19: m_ctx(NULL), m_dev(NULL), m_devh(NULL)20{21uvc_error_t res = uvc_init(&m_ctx, NULL);22if (res < 0)23{24uvc_perror(res, "uvc_init");25assert(res == 0);26}27}2829// -----------------------------------------------------------------------------30/*!31* @brief CX_GBXXXCtrlデストラクタ32*/33// -----------------------------------------------------------------------------34CX_GBXXXCtrl::~CX_GBXXXCtrl()35{36uvc_exit(m_ctx);37}3839// -----------------------------------------------------------------------------40/*!41* @brief カメラオープン42*43* @param [in] callback カメラシリアル番号(NULL: Don't Care)44*45* @return オープン成功可否46*/47// -----------------------------------------------------------------------------48bool CX_GBXXXCtrl::Open(const char *serial)49{50uvc_error_t res;51if ((res = uvc_find_device(52m_ctx, &m_dev,530x296b, 0, serial)) < 0)54{55uvc_perror(res, "uvc_find_device"); // CX-GBXXX未接続56return false;57}5859if ((res = uvc_open(m_dev, &m_devh)) < 0)60{61uvc_perror(res, "uvc_open");62return false;63}6465return true;66}6768// -----------------------------------------------------------------------------69/*!70* @brief カメラクローズ71*/72// -----------------------------------------------------------------------------73void CX_GBXXXCtrl::Close()74{75if (m_devh)76{77uvc_close(m_devh);78}79if (m_dev)80{81uvc_unref_device(m_dev);82}83}8485// -----------------------------------------------------------------------------86/*!87* @brief カメラ情報設定88*89* @param [in] unit_id ユニットID90* @param [in] cotrol_id コントロールID91* @param [in] data データバッファ92* @param [in] length データサイズ(バイト)93*94* @return 成功可否95*/96// -----------------------------------------------------------------------------97bool CX_GBXXXCtrl::SetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length)98{99if (!m_devh)100{101uvc_perror(UVC_ERROR_INVALID_DEVICE, "SetCameraCtrl");102return false;103}104105if (uvc_set_ctrl(m_devh, unit_id, cotrol_id, data, length) != length)106{107uvc_perror(UVC_ERROR_OTHER, "SetCameraCtrl");108return false;109}110111return true;112}113114// -----------------------------------------------------------------------------115/*!116* @brief カメラ情報取得117*118* @param [in] unit_id ユニットID119* @param [in] cotrol_id コントロールID120* @param [out] data データバッファ121* @param [in] length データサイズ(バイト)122*123* @return 成功可否124*/125// -----------------------------------------------------------------------------126bool CX_GBXXXCtrl::GetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length)127{128if (!m_devh)129{130uvc_perror(UVC_ERROR_INVALID_DEVICE, "GetCameraCtrl");131return false;132}133134if (uvc_get_ctrl(m_devh, unit_id, cotrol_id, data, length, UVC_GET_CUR) != length)135{136uvc_perror(UVC_ERROR_OTHER, "GetCameraCtrl");137return false;138}139140return true;141}142143144