CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/cameras_gimbals/xacti-config/CX-GBXXXCtrl.cpp
Views: 1799
1
// =============================================================================
2
/**
3
* @file CX-GBXXXCtrl.cpp
4
* @brief CX-GBXXX用コントロールクラス ヘッダ
5
* @copyright (c) 2022 Xacti Corporation
6
*/
7
// =============================================================================
8
9
#include "CX-GBXXXCtrl.h"
10
#include <libusb-1.0/libusb.h>
11
#include <libuvc/libuvc.h>
12
#include <assert.h>
13
14
// -----------------------------------------------------------------------------
15
/*!
16
* @brief CX_GBXXXCtrlコンストラクタ
17
*/
18
// -----------------------------------------------------------------------------
19
CX_GBXXXCtrl::CX_GBXXXCtrl()
20
: m_ctx(NULL), m_dev(NULL), m_devh(NULL)
21
{
22
uvc_error_t res = uvc_init(&m_ctx, NULL);
23
if (res < 0)
24
{
25
uvc_perror(res, "uvc_init");
26
assert(res == 0);
27
}
28
}
29
30
// -----------------------------------------------------------------------------
31
/*!
32
* @brief CX_GBXXXCtrlデストラクタ
33
*/
34
// -----------------------------------------------------------------------------
35
CX_GBXXXCtrl::~CX_GBXXXCtrl()
36
{
37
uvc_exit(m_ctx);
38
}
39
40
// -----------------------------------------------------------------------------
41
/*!
42
* @brief カメラオープン
43
*
44
* @param [in] callback カメラシリアル番号(NULL: Don't Care)
45
*
46
* @return オープン成功可否
47
*/
48
// -----------------------------------------------------------------------------
49
bool CX_GBXXXCtrl::Open(const char *serial)
50
{
51
uvc_error_t res;
52
if ((res = uvc_find_device(
53
m_ctx, &m_dev,
54
0x296b, 0, serial)) < 0)
55
{
56
uvc_perror(res, "uvc_find_device"); // CX-GBXXX未接続
57
return false;
58
}
59
60
if ((res = uvc_open(m_dev, &m_devh)) < 0)
61
{
62
uvc_perror(res, "uvc_open");
63
return false;
64
}
65
66
return true;
67
}
68
69
// -----------------------------------------------------------------------------
70
/*!
71
* @brief カメラクローズ
72
*/
73
// -----------------------------------------------------------------------------
74
void CX_GBXXXCtrl::Close()
75
{
76
if (m_devh)
77
{
78
uvc_close(m_devh);
79
}
80
if (m_dev)
81
{
82
uvc_unref_device(m_dev);
83
}
84
}
85
86
// -----------------------------------------------------------------------------
87
/*!
88
* @brief カメラ情報設定
89
*
90
* @param [in] unit_id ユニットID
91
* @param [in] cotrol_id コントロールID
92
* @param [in] data データバッファ
93
* @param [in] length データサイズ(バイト)
94
*
95
* @return 成功可否
96
*/
97
// -----------------------------------------------------------------------------
98
bool CX_GBXXXCtrl::SetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length)
99
{
100
if (!m_devh)
101
{
102
uvc_perror(UVC_ERROR_INVALID_DEVICE, "SetCameraCtrl");
103
return false;
104
}
105
106
if (uvc_set_ctrl(m_devh, unit_id, cotrol_id, data, length) != length)
107
{
108
uvc_perror(UVC_ERROR_OTHER, "SetCameraCtrl");
109
return false;
110
}
111
112
return true;
113
}
114
115
// -----------------------------------------------------------------------------
116
/*!
117
* @brief カメラ情報取得
118
*
119
* @param [in] unit_id ユニットID
120
* @param [in] cotrol_id コントロールID
121
* @param [out] data データバッファ
122
* @param [in] length データサイズ(バイト)
123
*
124
* @return 成功可否
125
*/
126
// -----------------------------------------------------------------------------
127
bool CX_GBXXXCtrl::GetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length)
128
{
129
if (!m_devh)
130
{
131
uvc_perror(UVC_ERROR_INVALID_DEVICE, "GetCameraCtrl");
132
return false;
133
}
134
135
if (uvc_get_ctrl(m_devh, unit_id, cotrol_id, data, length, UVC_GET_CUR) != length)
136
{
137
uvc_perror(UVC_ERROR_OTHER, "GetCameraCtrl");
138
return false;
139
}
140
141
return true;
142
}
143
144