Merge win support into develop
This commit is contained in:
commit
e4fddf2b8d
4
.gitignore
vendored
4
.gitignore
vendored
|
@ -1,5 +1,7 @@
|
||||||
.DS_Store
|
.DS_Store
|
||||||
/.vscode/
|
|
||||||
|
.vs/
|
||||||
|
.vscode/
|
||||||
|
|
||||||
_build/
|
_build/
|
||||||
_install/
|
_install/
|
||||||
|
|
|
@ -171,23 +171,32 @@ ifeq ($(HOST_OS),Win)
|
||||||
ifeq ($(HOST_NAME),MinGW)
|
ifeq ($(HOST_NAME),MinGW)
|
||||||
CMAKE += -G "MinGW Makefiles"
|
CMAKE += -G "MinGW Makefiles"
|
||||||
else ifeq ($(HOST_ARCH),x64)
|
else ifeq ($(HOST_ARCH),x64)
|
||||||
VS_VERSION := $(shell echo "$(shell which cl)" | sed "s/.*Visual\sStudio\s\([0-9]\+\).*/\1/g")
|
ifeq ($(VS_CODE),)
|
||||||
ifeq (15,$(VS_VERSION))
|
WHICH_CL := $(shell which cl)
|
||||||
|
ifeq ($(WHICH_CL),)
|
||||||
|
$(error "Visual Studio version is unknown. Could set VS_CODE to specify it, e.g. make [TARGET] VS_CODE=2017")
|
||||||
|
endif
|
||||||
|
# C:\Program Files (x86)\Microsoft Visual Studio 14.0\VC\...
|
||||||
|
# C:\Program Files (x86)\Microsoft Visual Studio\2017\Community\VC\...
|
||||||
|
VS_CODE := $(shell echo "$(WHICH_CL)" | grep -Po "(?<=Visual Studio[ /])[0-9]+")
|
||||||
|
endif
|
||||||
|
# $(call mkinfo,"VS_CODE: $(VS_CODE)")
|
||||||
|
ifeq ($(filter $(VS_CODE),15 2017),$(VS_CODE))
|
||||||
CMAKE += -G "Visual Studio 15 2017 Win64"
|
CMAKE += -G "Visual Studio 15 2017 Win64"
|
||||||
else ifeq (14,$(VS_VERSION))
|
else ifeq ($(filter $(VS_CODE),14 2015),$(VS_CODE))
|
||||||
CMAKE += -G "Visual Studio 14 2015 Win64"
|
CMAKE += -G "Visual Studio 14 2015 Win64"
|
||||||
else ifeq (12,$(VS_VERSION))
|
else ifeq ($(filter $(VS_CODE),12 2013),$(VS_CODE))
|
||||||
CMAKE += -G "Visual Studio 12 2013 Win64"
|
CMAKE += -G "Visual Studio 12 2013 Win64"
|
||||||
else ifeq (11,$(VS_VERSION))
|
else ifeq ($(filter $(VS_CODE),11 2012),$(VS_CODE))
|
||||||
CMAKE += -G "Visual Studio 11 2012 Win64"
|
CMAKE += -G "Visual Studio 11 2012 Win64"
|
||||||
else ifeq (10,$(VS_VERSION))
|
else ifeq ($(filter $(VS_CODE),10 2010),$(VS_CODE))
|
||||||
CMAKE += -G "Visual Studio 10 2010 Win64"
|
CMAKE += -G "Visual Studio 10 2010 Win64"
|
||||||
else ifeq (9,$(VS_VERSION))
|
else ifeq ($(filter $(VS_CODE),9 2008),$(VS_CODE))
|
||||||
CMAKE += -G "Visual Studio 9 2008 Win64"
|
CMAKE += -G "Visual Studio 9 2008 Win64"
|
||||||
else ifeq (8,$(VS_VERSION))
|
else ifeq ($(filter $(VS_CODE),8 2005),$(VS_CODE))
|
||||||
CMAKE += -G "Visual Studio 8 2005 Win64"
|
CMAKE += -G "Visual Studio 8 2005 Win64"
|
||||||
else
|
else
|
||||||
$(call mkinfo,"Connot specify Visual Studio Win64")
|
$(error "Visual Studio version is not proper, VS_CODE: $(VS_CODE)")
|
||||||
endif
|
endif
|
||||||
endif
|
endif
|
||||||
|
|
||||||
|
|
|
@ -27,8 +27,17 @@
|
||||||
|
|
||||||
struct frame {
|
struct frame {
|
||||||
const void *data = nullptr;
|
const void *data = nullptr;
|
||||||
|
std::function<void()> continuation = nullptr;
|
||||||
|
frame() {
|
||||||
|
// VLOG(2) << __func__;
|
||||||
|
}
|
||||||
~frame() {
|
~frame() {
|
||||||
|
// VLOG(2) << __func__;
|
||||||
data = nullptr;
|
data = nullptr;
|
||||||
|
if (continuation) {
|
||||||
|
continuation();
|
||||||
|
continuation = nullptr;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -41,7 +50,11 @@ int main(int argc, char *argv[]) {
|
||||||
|
|
||||||
auto context = uvc::create_context();
|
auto context = uvc::create_context();
|
||||||
auto devices = uvc::query_devices(context);
|
auto devices = uvc::query_devices(context);
|
||||||
LOG_IF(FATAL, devices.size() <= 0) << "No devices :(";
|
if (devices.size() <= 0) {
|
||||||
|
LOG(ERROR) << "No devices :(";
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
for (auto &&device : devices) {
|
for (auto &&device : devices) {
|
||||||
auto vid = uvc::get_vendor_id(*device);
|
auto vid = uvc::get_vendor_id(*device);
|
||||||
// auto pid = uvc::get_product_id(*device);
|
// auto pid = uvc::get_product_id(*device);
|
||||||
|
@ -54,7 +67,10 @@ int main(int argc, char *argv[]) {
|
||||||
// std::string dashes(80, '-');
|
// std::string dashes(80, '-');
|
||||||
|
|
||||||
size_t n = mynteye_devices.size();
|
size_t n = mynteye_devices.size();
|
||||||
LOG_IF(FATAL, n <= 0) << "No MYNT EYE devices :(";
|
if (n <= 0) {
|
||||||
|
LOG(ERROR) << "No MYNT EYE devices :(";
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
LOG(INFO) << "MYNT EYE devices: ";
|
LOG(INFO) << "MYNT EYE devices: ";
|
||||||
for (size_t i = 0; i < n; i++) {
|
for (size_t i = 0; i < n; i++) {
|
||||||
|
@ -87,18 +103,21 @@ int main(int argc, char *argv[]) {
|
||||||
std::mutex mtx;
|
std::mutex mtx;
|
||||||
std::condition_variable cv;
|
std::condition_variable cv;
|
||||||
|
|
||||||
std::vector<frame> frames;
|
std::shared_ptr<frame> frame = nullptr;
|
||||||
const auto frame_ready = [&frames]() { return !frames.empty(); };
|
const auto frame_ready = [&frame]() { return frame != nullptr; };
|
||||||
const auto frame_empty = [&frames]() { return frames.empty(); };
|
const auto frame_empty = [&frame]() { return frame == nullptr; };
|
||||||
|
|
||||||
uvc::set_device_mode(
|
uvc::set_device_mode(
|
||||||
*device, 752, 480, static_cast<int>(Format::YUYV), 25,
|
*device, 752, 480, static_cast<int>(Format::YUYV), 25,
|
||||||
[&mtx, &cv, &frames, &frame_ready](const void *data) {
|
[&mtx, &cv, &frame, &frame_ready](
|
||||||
|
const void *data, std::function<void()> continuation) {
|
||||||
// reinterpret_cast<const std::uint8_t *>(data);
|
// reinterpret_cast<const std::uint8_t *>(data);
|
||||||
std::unique_lock<std::mutex> lock(mtx);
|
std::unique_lock<std::mutex> lock(mtx);
|
||||||
frame frame;
|
if (frame == nullptr) {
|
||||||
frame.data = data; // not copy
|
frame = std::make_shared<struct frame>();
|
||||||
frames.push_back(frame);
|
}
|
||||||
|
frame->data = data; // not copy here
|
||||||
|
frame->continuation = continuation;
|
||||||
if (frame_ready())
|
if (frame_ready())
|
||||||
cv.notify_one();
|
cv.notify_one();
|
||||||
});
|
});
|
||||||
|
@ -119,13 +138,12 @@ int main(int argc, char *argv[]) {
|
||||||
throw std::runtime_error("Timeout waiting for frame.");
|
throw std::runtime_error("Timeout waiting for frame.");
|
||||||
}
|
}
|
||||||
|
|
||||||
auto frame = frames.back(); // only last one is valid
|
// only lastest frame is valid
|
||||||
|
cv::Mat img(480, 752, CV_8UC2, const_cast<void *>(frame->data));
|
||||||
cv::Mat img(480, 752, CV_8UC2, const_cast<void *>(frame.data));
|
|
||||||
cv::cvtColor(img, img, cv::COLOR_YUV2BGR_YUY2);
|
cv::cvtColor(img, img, cv::COLOR_YUV2BGR_YUY2);
|
||||||
cv::imshow("frame", img);
|
cv::imshow("frame", img);
|
||||||
|
|
||||||
frames.clear();
|
frame = nullptr;
|
||||||
|
|
||||||
char key = static_cast<char>(cv::waitKey(1));
|
char key = static_cast<char>(cv::waitKey(1));
|
||||||
if (key == 27 || key == 'q' || key == 'Q') { // ESC/Q
|
if (key == 27 || key == 'q' || key == 'Q') { // ESC/Q
|
||||||
|
|
|
@ -25,10 +25,11 @@
|
||||||
MYNTEYE_BEGIN_NAMESPACE
|
MYNTEYE_BEGIN_NAMESPACE
|
||||||
|
|
||||||
class API;
|
class API;
|
||||||
class Object;
|
|
||||||
class Plugin;
|
class Plugin;
|
||||||
class Processor;
|
class Processor;
|
||||||
|
|
||||||
|
struct Object;
|
||||||
|
|
||||||
class Synthetic {
|
class Synthetic {
|
||||||
public:
|
public:
|
||||||
using stream_callback_t = API::stream_callback_t;
|
using stream_callback_t = API::stream_callback_t;
|
||||||
|
|
|
@ -414,7 +414,7 @@ void Device::StartVideoStreaming() {
|
||||||
uvc::set_device_mode(
|
uvc::set_device_mode(
|
||||||
*device_, stream_request.width, stream_request.height,
|
*device_, stream_request.width, stream_request.height,
|
||||||
static_cast<int>(stream_request.format), stream_request.fps,
|
static_cast<int>(stream_request.format), stream_request.fps,
|
||||||
[this](const void *data) {
|
[this](const void *data, std::function<void()> continuation) {
|
||||||
// drop the first stereo stream data
|
// drop the first stereo stream data
|
||||||
static std::uint8_t drop_count = 1;
|
static std::uint8_t drop_count = 1;
|
||||||
if (drop_count > 0) {
|
if (drop_count > 0) {
|
||||||
|
@ -425,6 +425,7 @@ void Device::StartVideoStreaming() {
|
||||||
CallbackPushedStreamData(Stream::LEFT);
|
CallbackPushedStreamData(Stream::LEFT);
|
||||||
CallbackPushedStreamData(Stream::RIGHT);
|
CallbackPushedStreamData(Stream::RIGHT);
|
||||||
}
|
}
|
||||||
|
continuation();
|
||||||
});
|
});
|
||||||
} else {
|
} else {
|
||||||
LOG(FATAL) << "Not any stream capabilities are supported by this device";
|
LOG(FATAL) << "Not any stream capabilities are supported by this device";
|
||||||
|
|
|
@ -31,6 +31,8 @@ MYNTEYE_BEGIN_NAMESPACE
|
||||||
|
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
|
const uvc::xu mynteye_xu = {3, 2, {0x947a6d9f, 0x8a2f, 0x418d, {0x85, 0x9e, 0x6c, 0x9a, 0xa0, 0x38, 0x10, 0x14}}};
|
||||||
|
|
||||||
int XuCamCtrlId(Option option) {
|
int XuCamCtrlId(Option option) {
|
||||||
switch (option) {
|
switch (option) {
|
||||||
case Option::EXPOSURE_MODE:
|
case Option::EXPOSURE_MODE:
|
||||||
|
@ -867,10 +869,22 @@ bool Channels::PuControlQuery(
|
||||||
return uvc::pu_control_query(*device_, option, query, value);
|
return uvc::pu_control_query(*device_, option, query, value);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool Channels::XuControlRange(
|
||||||
|
channel_t channel, uint8_t id, int32_t *min, int32_t *max, int32_t *def) const {
|
||||||
|
return XuControlRange(mynteye_xu, channel, id, min, max, def);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Channels::XuControlRange(
|
||||||
|
const uvc::xu &xu, uint8_t selector, uint8_t id, int32_t *min, int32_t *max,
|
||||||
|
int32_t *def) const {
|
||||||
|
CHECK_NOTNULL(device_);
|
||||||
|
return uvc::xu_control_range(*device_, xu, selector, id, min, max, def);
|
||||||
|
}
|
||||||
|
|
||||||
bool Channels::XuControlQuery(
|
bool Channels::XuControlQuery(
|
||||||
channel_t channel, uvc::xu_query query, uint16_t size,
|
channel_t channel, uvc::xu_query query, uint16_t size,
|
||||||
uint8_t *data) const {
|
uint8_t *data) const {
|
||||||
return XuControlQuery({3}, channel >> 8, query, size, data);
|
return XuControlQuery(mynteye_xu, channel, query, size, data);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Channels::XuControlQuery(
|
bool Channels::XuControlQuery(
|
||||||
|
@ -1001,32 +1015,11 @@ Channels::control_info_t Channels::PuControlInfo(Option option) const {
|
||||||
Channels::control_info_t Channels::XuControlInfo(Option option) const {
|
Channels::control_info_t Channels::XuControlInfo(Option option) const {
|
||||||
int id = XuCamCtrlId(option);
|
int id = XuCamCtrlId(option);
|
||||||
|
|
||||||
std::uint8_t data[3] = {static_cast<std::uint8_t>((id | 0x80) & 0xFF), 0, 0};
|
int32_t min = 0, max = 0, def = 0;
|
||||||
if (!XuCamCtrlQuery(uvc::XU_QUERY_SET, 3, data)) {
|
if (!XuControlRange(CHANNEL_CAM_CTRL, static_cast<std::uint8_t>(id), &min, &max, &def)) {
|
||||||
LOG(WARNING) << "Get XuControlInfo of " << option << " failed";
|
LOG(WARNING) << "Get XuControlInfo of " << option << " failed";
|
||||||
return {0, 0, 0};
|
|
||||||
}
|
}
|
||||||
|
return {min, max, def};
|
||||||
control_info_t info{0, 0, 0};
|
|
||||||
|
|
||||||
data[0] = id & 0xFF;
|
|
||||||
if (XuCamCtrlQuery(uvc::XU_QUERY_MIN, 3, data)) {
|
|
||||||
info.min = (data[1] << 8) | (data[2]);
|
|
||||||
} else {
|
|
||||||
LOG(WARNING) << "Get XuControlInfo.min of " << option << " failed";
|
|
||||||
}
|
|
||||||
if (XuCamCtrlQuery(uvc::XU_QUERY_MAX, 3, data)) {
|
|
||||||
info.max = (data[1] << 8) | (data[2]);
|
|
||||||
} else {
|
|
||||||
LOG(WARNING) << "Get XuControlInfo.max of " << option << " failed";
|
|
||||||
}
|
|
||||||
if (XuCamCtrlQuery(uvc::XU_QUERY_DEF, 3, data)) {
|
|
||||||
info.def = (data[1] << 8) | (data[2]);
|
|
||||||
} else {
|
|
||||||
LOG(WARNING) << "Get XuControlInfo.def of " << option << " failed";
|
|
||||||
}
|
|
||||||
|
|
||||||
return info;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
MYNTEYE_END_NAMESPACE
|
MYNTEYE_END_NAMESPACE
|
||||||
|
|
|
@ -37,11 +37,11 @@ struct xu;
|
||||||
class MYNTEYE_API Channels {
|
class MYNTEYE_API Channels {
|
||||||
public:
|
public:
|
||||||
typedef enum Channel {
|
typedef enum Channel {
|
||||||
CHANNEL_CAM_CTRL = 0x0100,
|
CHANNEL_CAM_CTRL = 1,
|
||||||
CHANNEL_HALF_DUPLEX = 0x0200,
|
CHANNEL_HALF_DUPLEX = 2,
|
||||||
CHANNEL_IMU_WRITE = 0x0300,
|
CHANNEL_IMU_WRITE = 3,
|
||||||
CHANNEL_IMU_READ = 0x0400,
|
CHANNEL_IMU_READ = 4,
|
||||||
CHANNEL_FILE = 0x0500,
|
CHANNEL_FILE = 5,
|
||||||
CHANNEL_LAST
|
CHANNEL_LAST
|
||||||
} channel_t;
|
} channel_t;
|
||||||
|
|
||||||
|
@ -110,6 +110,12 @@ class MYNTEYE_API Channels {
|
||||||
Option option, int32_t *min, int32_t *max, int32_t *def) const;
|
Option option, int32_t *min, int32_t *max, int32_t *def) const;
|
||||||
bool PuControlQuery(Option option, uvc::pu_query query, int32_t *value) const;
|
bool PuControlQuery(Option option, uvc::pu_query query, int32_t *value) const;
|
||||||
|
|
||||||
|
bool XuControlRange(
|
||||||
|
channel_t channel, uint8_t id, int32_t *min, int32_t *max, int32_t *def) const;
|
||||||
|
bool XuControlRange(
|
||||||
|
const uvc::xu &xu, uint8_t selector, uint8_t id, int32_t *min, int32_t *max,
|
||||||
|
int32_t *def) const;
|
||||||
|
|
||||||
bool XuControlQuery(
|
bool XuControlQuery(
|
||||||
channel_t channel, uvc::xu_query query, uint16_t size,
|
channel_t channel, uvc::xu_query query, uint16_t size,
|
||||||
uint8_t *data) const;
|
uint8_t *data) const;
|
||||||
|
|
10
src/uvc/README.md
Normal file
10
src/uvc/README.md
Normal file
|
@ -0,0 +1,10 @@
|
||||||
|
|
||||||
|
## `uvc-v4l2.cc`
|
||||||
|
|
||||||
|
* [Linux Media Subsystem Documentation](https://www.kernel.org/doc/html/latest/media/index.html)
|
||||||
|
* [The Linux USB Video Class (UVC) driver](https://www.kernel.org/doc/html/latest/media/v4l-drivers/uvcvideo.html)
|
||||||
|
|
||||||
|
## `uvc-wmf.cc`
|
||||||
|
|
||||||
|
* [Media Foundation](https://msdn.microsoft.com/en-us/library/ms694197(VS.85).aspx)
|
||||||
|
* [USB Video Class Driver](https://docs.microsoft.com/en-us/windows-hardware/drivers/stream/usb-video-class-driver)
|
|
@ -144,6 +144,20 @@ bool pu_control_query(
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool xu_control_range(
|
||||||
|
const device &device, const xu &xu, uint8_t selector, uint8_t id, int32_t *min,
|
||||||
|
int32_t *max, int32_t *def) {
|
||||||
|
// TODO(JohnZhao)
|
||||||
|
UNUSED(device)
|
||||||
|
UNUSED(xu)
|
||||||
|
UNUSED(selector)
|
||||||
|
UNUSED(id)
|
||||||
|
UNUSED(min)
|
||||||
|
UNUSED(max)
|
||||||
|
UNUSED(def)
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
bool xu_control_query(
|
bool xu_control_query(
|
||||||
const device &device, const xu &xu, uint8_t selector, xu_query query,
|
const device &device, const xu &xu, uint8_t selector, xu_query query,
|
||||||
uint16_t size, uint8_t *data) {
|
uint16_t size, uint8_t *data) {
|
||||||
|
|
|
@ -381,11 +381,11 @@ struct device {
|
||||||
}
|
}
|
||||||
|
|
||||||
if (callback) {
|
if (callback) {
|
||||||
callback(buffers[buf.index].start);
|
callback(buffers[buf.index].start, [buf, this]() mutable {
|
||||||
}
|
|
||||||
|
|
||||||
if (xioctl(fd, VIDIOC_QBUF, &buf) < 0)
|
if (xioctl(fd, VIDIOC_QBUF, &buf) < 0)
|
||||||
LOG_ERROR(FATAL, "VIDIOC_QBUF");
|
throw_error("VIDIOC_QBUF");
|
||||||
|
});
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -504,6 +504,39 @@ bool pu_control_query(
|
||||||
return device.pu_control_query(get_cid(option), code, value);
|
return device.pu_control_query(get_cid(option), code, value);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool xu_control_range(
|
||||||
|
const device &device, const xu &xu, uint8_t selector, uint8_t id,
|
||||||
|
int32_t *min, int32_t *max, int32_t *def) {
|
||||||
|
bool ret = true;
|
||||||
|
|
||||||
|
std::uint8_t data[3]{static_cast<uint8_t>(id | 0x80), 0, 0};
|
||||||
|
|
||||||
|
if (!xu_control_query(device, xu, selector, XU_QUERY_SET, 3, data)) {
|
||||||
|
LOG(WARNING) << "xu_control_range query failed";
|
||||||
|
ret = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (xu_control_query(device, xu, selector, XU_QUERY_MIN, 3, data)) {
|
||||||
|
*min = (data[1] << 8) | (data[2]);
|
||||||
|
} else {
|
||||||
|
LOG(WARNING) << "xu_control_range query min failed";
|
||||||
|
ret = false;
|
||||||
|
}
|
||||||
|
if (xu_control_query(device, xu, selector, XU_QUERY_MAX, 3, data)) {
|
||||||
|
*max = (data[1] << 8) | (data[2]);
|
||||||
|
} else {
|
||||||
|
LOG(WARNING) << "xu_control_range query max failed";
|
||||||
|
ret = false;
|
||||||
|
}
|
||||||
|
if (xu_control_query(device, xu, selector, XU_QUERY_DEF, 3, data)) {
|
||||||
|
*def = (data[1] << 8) | (data[2]);
|
||||||
|
} else {
|
||||||
|
LOG(WARNING) << "xu_control_range query def failed";
|
||||||
|
ret = false;
|
||||||
|
}
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
bool xu_control_query(
|
bool xu_control_query(
|
||||||
const device &device, const xu &xu, uint8_t selector, xu_query query,
|
const device &device, const xu &xu, uint8_t selector, xu_query query,
|
||||||
uint16_t size, uint8_t *data) {
|
uint16_t size, uint8_t *data) {
|
||||||
|
|
|
@ -13,44 +13,476 @@
|
||||||
// limitations under the License.
|
// limitations under the License.
|
||||||
#include "uvc/uvc.h" // NOLINT
|
#include "uvc/uvc.h" // NOLINT
|
||||||
|
|
||||||
|
#include <windows.h>
|
||||||
|
#include <usbioctl.h>
|
||||||
|
|
||||||
|
#include <Shlwapi.h> // For QISearch, etc.
|
||||||
|
#include <mfapi.h> // For MFStartup, etc.
|
||||||
|
#include <mfidl.h> // For MF_DEVSOURCE_*, etc.
|
||||||
|
#include <mfreadwrite.h> // MFCreateSourceReaderFromMediaSource
|
||||||
|
#include <mferror.h>
|
||||||
|
|
||||||
|
#pragma comment(lib, "Shlwapi.lib")
|
||||||
|
#pragma comment(lib, "mf.lib")
|
||||||
|
#pragma comment(lib, "mfplat.lib")
|
||||||
|
#pragma comment(lib, "mfreadwrite.lib")
|
||||||
|
#pragma comment(lib, "mfuuid.lib")
|
||||||
|
|
||||||
|
#pragma comment(lib, "setupapi.lib")
|
||||||
|
#pragma comment(lib, "winusb.lib")
|
||||||
|
|
||||||
|
#include <uuids.h>
|
||||||
|
#include <vidcap.h>
|
||||||
|
#include <ksmedia.h>
|
||||||
|
#include <ksproxy.h>
|
||||||
|
|
||||||
|
#include <Cfgmgr32.h>
|
||||||
|
|
||||||
|
#pragma comment(lib, "cfgmgr32.lib")
|
||||||
|
|
||||||
|
#include <SetupAPI.h>
|
||||||
|
#include <WinUsb.h>
|
||||||
|
|
||||||
|
#include <algorithm>
|
||||||
|
#include <chrono>
|
||||||
|
#include <functional>
|
||||||
|
#include <map>
|
||||||
|
#include <regex>
|
||||||
|
#include <sstream>
|
||||||
|
#include <thread>
|
||||||
|
|
||||||
|
#include <strsafe.h>
|
||||||
|
|
||||||
#include <glog/logging.h>
|
#include <glog/logging.h>
|
||||||
|
|
||||||
|
#define VLOG_INFO VLOG(2)
|
||||||
|
// #define VLOG_INFO LOG(INFO)
|
||||||
|
|
||||||
MYNTEYE_BEGIN_NAMESPACE
|
MYNTEYE_BEGIN_NAMESPACE
|
||||||
|
|
||||||
namespace uvc {
|
namespace uvc {
|
||||||
|
|
||||||
struct context {
|
const std::map<uint32_t, uint32_t> fourcc_map = {
|
||||||
context() {
|
{ 0x56595559, 0x32595559 }, // 'VYUY' => '2YUY'
|
||||||
VLOG(2) << __func__;
|
{ 0x59555956, 0x59555932 } // 'YUYV' => 'YUY2'
|
||||||
|
};
|
||||||
|
|
||||||
|
struct throw_error {
|
||||||
|
throw_error() = default;
|
||||||
|
|
||||||
|
explicit throw_error(const std::string &s) {
|
||||||
|
ss << s;
|
||||||
}
|
}
|
||||||
|
|
||||||
~context() {
|
~throw_error() noexcept(false) {
|
||||||
VLOG(2) << __func__;
|
throw std::runtime_error(ss.str());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
template<class T>
|
||||||
|
throw_error &operator<<(const T &val) {
|
||||||
|
ss << val;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::ostringstream ss;
|
||||||
|
};
|
||||||
|
|
||||||
|
static void check(const char *call, HRESULT hr) {
|
||||||
|
if (FAILED(hr)) {
|
||||||
|
throw_error() << call << "(...) returned 0x" << std::hex
|
||||||
|
<< static_cast<uint32_t>(hr);
|
||||||
|
} else {
|
||||||
|
// VLOG_INFO << call << " SUCCESSED";
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
template<class T> class com_ptr {
|
||||||
|
T *p;
|
||||||
|
void ref(T *new_p) {
|
||||||
|
if (p == new_p) return;
|
||||||
|
unref();
|
||||||
|
p = new_p;
|
||||||
|
if (p) p->AddRef();
|
||||||
|
}
|
||||||
|
|
||||||
|
void unref() {
|
||||||
|
if (p) {
|
||||||
|
p->Release();
|
||||||
|
p = nullptr;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
public:
|
||||||
|
com_ptr() : p() {}
|
||||||
|
com_ptr(T *p) : com_ptr() {
|
||||||
|
ref(p);
|
||||||
|
}
|
||||||
|
com_ptr(const com_ptr &r) : com_ptr(r.p) {}
|
||||||
|
~com_ptr() {
|
||||||
|
unref();
|
||||||
|
}
|
||||||
|
|
||||||
|
operator T *() const {
|
||||||
|
return p;
|
||||||
|
}
|
||||||
|
T &operator*() const {
|
||||||
|
return *p;
|
||||||
|
}
|
||||||
|
T *operator->() const {
|
||||||
|
return p;
|
||||||
|
}
|
||||||
|
|
||||||
|
T **operator&() {
|
||||||
|
unref();
|
||||||
|
return &p;
|
||||||
|
}
|
||||||
|
com_ptr &operator=(const com_ptr &r) {
|
||||||
|
ref(r.p);
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
static std::string win_to_utf(const WCHAR *s) {
|
||||||
|
int len = WideCharToMultiByte(CP_UTF8, 0, s, -1, nullptr, 0, NULL, NULL);
|
||||||
|
if (len == 0) throw_error() << "WideCharToMultiByte(...) returned 0 and GetLastError() is " << GetLastError();
|
||||||
|
std::string buffer(len - 1, ' ');
|
||||||
|
len = WideCharToMultiByte(CP_UTF8, 0, s, -1, &buffer[0], (int)buffer.size()+1, NULL, NULL);
|
||||||
|
if (len == 0) throw_error() << "WideCharToMultiByte(...) returned 0 and GetLastError() is " << GetLastError();
|
||||||
|
return buffer;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<std::string> tokenize(std::string string, char separator) {
|
||||||
|
std::vector<std::string> tokens;
|
||||||
|
std::string::size_type i1 = 0;
|
||||||
|
while (true) {
|
||||||
|
auto i2 = string.find(separator, i1);
|
||||||
|
if (i2 == std::string::npos) {
|
||||||
|
tokens.push_back(string.substr(i1));
|
||||||
|
return tokens;
|
||||||
|
}
|
||||||
|
tokens.push_back(string.substr(i1, i2-i1));
|
||||||
|
i1 = i2 + 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
static void print_guid(const char *call, int i, GUID guid) {
|
||||||
|
std::ostringstream ss;
|
||||||
|
ss << call << "(" << i << ") = ";
|
||||||
|
ss << "Data1: " << std::hex << guid.Data1 << ", ";
|
||||||
|
ss << "Data2: " << std::hex << guid.Data2 << ", ";
|
||||||
|
ss << "Data3: " << std::hex << guid.Data3 << ", ";
|
||||||
|
ss << "Data4: [ ";
|
||||||
|
for (int j = 0; j < 8; j++) {
|
||||||
|
ss << std::hex << (int)guid.Data4[j] << " ";
|
||||||
|
}
|
||||||
|
ss << "]";
|
||||||
|
LOG(INFO) << ss.str();
|
||||||
|
}
|
||||||
|
*/
|
||||||
|
|
||||||
|
bool parse_usb_path(int &vid, int &pid, int &mi, std::string &unique_id, const std::string &path) {
|
||||||
|
auto name = path;
|
||||||
|
std::transform(begin(name), end(name), begin(name), ::tolower);
|
||||||
|
auto tokens = tokenize(name, '#');
|
||||||
|
if (tokens.size() < 1 || tokens[0] != R"(\\?\usb)") return false; // Not a USB device
|
||||||
|
if (tokens.size() < 3) {
|
||||||
|
LOG(ERROR) << "malformed usb device path: " << name;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
auto ids = tokenize(tokens[1], '&');
|
||||||
|
if (ids[0].size() != 8 || ids[0].substr(0,4) != "vid_" || !(std::istringstream(ids[0].substr(4,4)) >> std::hex >> vid)) {
|
||||||
|
LOG(ERROR) << "malformed vid string: " << tokens[1];
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ids[1].size() != 8 || ids[1].substr(0,4) != "pid_" || !(std::istringstream(ids[1].substr(4,4)) >> std::hex >> pid)) {
|
||||||
|
LOG(ERROR) << "malformed pid string: " << tokens[1];
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ids[2].size() != 5 || ids[2].substr(0,3) != "mi_" || !(std::istringstream(ids[2].substr(3,2)) >> mi)) {
|
||||||
|
LOG(ERROR) << "malformed mi string: " << tokens[1];
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
ids = tokenize(tokens[2], '&');
|
||||||
|
if (ids.size() < 2) {
|
||||||
|
LOG(ERROR) << "malformed id string: " << tokens[2];
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
unique_id = ids[1];
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool parse_usb_path_from_device_id(int &vid, int &pid, int &mi, std::string &unique_id, const std::string &device_id) {
|
||||||
|
auto name = device_id;
|
||||||
|
std::transform(begin(name), end(name), begin(name), ::tolower);
|
||||||
|
auto tokens = tokenize(name, '\\');
|
||||||
|
if (tokens.size() < 1 || tokens[0] != R"(usb)") return false; // Not a USB device
|
||||||
|
|
||||||
|
auto ids = tokenize(tokens[1], '&');
|
||||||
|
if (ids[0].size() != 8 || ids[0].substr(0, 4) != "vid_" || !(std::istringstream(ids[0].substr(4, 4)) >> std::hex >> vid)) {
|
||||||
|
LOG(ERROR) << "malformed vid string: " << tokens[1];
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ids[1].size() != 8 || ids[1].substr(0, 4) != "pid_" || !(std::istringstream(ids[1].substr(4, 4)) >> std::hex >> pid)) {
|
||||||
|
LOG(ERROR) << "malformed pid string: " << tokens[1];
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ids[2].size() != 5 || ids[2].substr(0, 3) != "mi_" || !(std::istringstream(ids[2].substr(3, 2)) >> mi)) {
|
||||||
|
LOG(ERROR) << "malformed mi string: " << tokens[1];
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
ids = tokenize(tokens[2], '&');
|
||||||
|
if (ids.size() < 2) {
|
||||||
|
LOG(ERROR) << "malformed id string: " + tokens[2];
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
unique_id = ids[1];
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
struct context {
|
||||||
|
context() {
|
||||||
|
CoInitializeEx(NULL, COINIT_APARTMENTTHREADED);
|
||||||
|
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
||||||
|
MFStartup(MF_VERSION, MFSTARTUP_NOSOCKET);
|
||||||
|
}
|
||||||
|
~context() {
|
||||||
|
MFShutdown();
|
||||||
|
CoUninitialize();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
class reader_callback : public IMFSourceReaderCallback {
|
||||||
|
std::weak_ptr<device> owner; // The device holds a reference to us, so use
|
||||||
|
// weak_ptr to prevent a cycle
|
||||||
|
ULONG ref_count;
|
||||||
|
volatile bool streaming = false;
|
||||||
|
public:
|
||||||
|
reader_callback(std::weak_ptr<device> owner) : owner(owner), ref_count() {}
|
||||||
|
|
||||||
|
bool is_streaming() const {
|
||||||
|
return streaming;
|
||||||
|
}
|
||||||
|
void on_start() {
|
||||||
|
streaming = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
#pragma warning( push )
|
||||||
|
#pragma warning( disable: 4838 )
|
||||||
|
// Implement IUnknown
|
||||||
|
HRESULT STDMETHODCALLTYPE QueryInterface(REFIID riid, void **ppvObject) override {
|
||||||
|
static const QITAB table[] = {QITABENT(reader_callback, IUnknown), QITABENT(reader_callback, IMFSourceReaderCallback), {0}};
|
||||||
|
return QISearch(this, table, riid, ppvObject);
|
||||||
|
}
|
||||||
|
#pragma warning( pop )
|
||||||
|
|
||||||
|
ULONG STDMETHODCALLTYPE AddRef() override { return InterlockedIncrement(&ref_count); }
|
||||||
|
ULONG STDMETHODCALLTYPE Release() override {
|
||||||
|
ULONG count = InterlockedDecrement(&ref_count);
|
||||||
|
if (count == 0) delete this;
|
||||||
|
return count;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Implement IMFSourceReaderCallback
|
||||||
|
HRESULT STDMETHODCALLTYPE OnReadSample(HRESULT hrStatus, DWORD dwStreamIndex, DWORD dwStreamFlags, LONGLONG llTimestamp, IMFSample *sample) override;
|
||||||
|
HRESULT STDMETHODCALLTYPE OnFlush(DWORD dwStreamIndex) override { streaming = false; return S_OK; }
|
||||||
|
HRESULT STDMETHODCALLTYPE OnEvent(DWORD dwStreamIndex, IMFMediaEvent *pEvent) override { return S_OK; }
|
||||||
};
|
};
|
||||||
|
|
||||||
struct device {
|
struct device {
|
||||||
const std::shared_ptr<context> parent;
|
const std::shared_ptr<context> parent;
|
||||||
|
|
||||||
int vid, pid;
|
int vid, pid;
|
||||||
|
std::string unique_id;
|
||||||
|
std::string name;
|
||||||
|
|
||||||
explicit device(std::shared_ptr<context> parent) : parent(parent) {
|
com_ptr<reader_callback> reader_callback;
|
||||||
VLOG(2) << __func__;
|
com_ptr<IMFActivate> mf_activate;
|
||||||
|
com_ptr<IMFMediaSource> mf_media_source;
|
||||||
|
com_ptr<IAMCameraControl> am_camera_control;
|
||||||
|
com_ptr<IAMVideoProcAmp> am_video_proc_amp;
|
||||||
|
std::map<int, com_ptr<IKsControl>> ks_controls;
|
||||||
|
com_ptr<IMFSourceReader> mf_source_reader;
|
||||||
|
video_channel_callback callback = nullptr;
|
||||||
|
|
||||||
|
device(std::shared_ptr<context> parent, int vid, int pid, std::string unique_id, std::string name)
|
||||||
|
: parent(move(parent)), vid(vid), pid(pid), unique_id(move(unique_id)), name(name) {
|
||||||
}
|
}
|
||||||
|
|
||||||
~device() {
|
~device() {
|
||||||
VLOG(2) << __func__;
|
stop_streaming();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
IKsControl *get_ks_control(const uvc::xu &xu) {
|
||||||
|
auto it = ks_controls.find(xu.node);
|
||||||
|
if (it != end(ks_controls)) return it->second;
|
||||||
|
|
||||||
|
get_media_source();
|
||||||
|
|
||||||
|
// Attempt to retrieve IKsControl
|
||||||
|
com_ptr<IKsTopologyInfo> ks_topology_info = NULL;
|
||||||
|
check("QueryInterface", mf_media_source->QueryInterface(__uuidof(IKsTopologyInfo), (void **)&ks_topology_info));
|
||||||
|
|
||||||
|
GUID node_type;
|
||||||
|
/*
|
||||||
|
DWORD numberOfNodes;
|
||||||
|
check("get_NumNodes", ks_topology_info->get_NumNodes(&numberOfNodes));
|
||||||
|
for (int i = 0; i < numberOfNodes; i++) {
|
||||||
|
check("get_NodeType", ks_topology_info->get_NodeType(i, &node_type));
|
||||||
|
print_guid("node_type", i, node_type);
|
||||||
|
}
|
||||||
|
*/
|
||||||
|
check("get_NodeType", ks_topology_info->get_NodeType(xu.node, &node_type));
|
||||||
|
const GUID KSNODETYPE_DEV_SPECIFIC_LOCAL{0x941C7AC0L, 0xC559, 0x11D0, {0x8A, 0x2B, 0x00, 0xA0, 0xC9, 0x25, 0x5A, 0xC1}};
|
||||||
|
if (node_type != KSNODETYPE_DEV_SPECIFIC_LOCAL) throw_error() << "Invalid extension unit node ID: " << xu.node;
|
||||||
|
|
||||||
|
com_ptr<IUnknown> unknown;
|
||||||
|
check("CreateNodeInstance", ks_topology_info->CreateNodeInstance(xu.node, IID_IUnknown, (LPVOID *)&unknown));
|
||||||
|
|
||||||
|
com_ptr<IKsControl> ks_control;
|
||||||
|
check("QueryInterface", unknown->QueryInterface(__uuidof(IKsControl), (void **)&ks_control));
|
||||||
|
VLOG_INFO << "Obtained KS control node : " << xu.node;
|
||||||
|
return ks_controls[xu.node] = ks_control;
|
||||||
|
}
|
||||||
|
|
||||||
|
void start_streaming() {
|
||||||
|
if (mf_source_reader) {
|
||||||
|
reader_callback->on_start();
|
||||||
|
check("IMFSourceReader::ReadSample", mf_source_reader->ReadSample(MF_SOURCE_READER_FIRST_VIDEO_STREAM, 0, NULL, NULL, NULL, NULL));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void stop_streaming() {
|
||||||
|
if (mf_source_reader) mf_source_reader->Flush(MF_SOURCE_READER_FIRST_VIDEO_STREAM);
|
||||||
|
|
||||||
|
while (true) {
|
||||||
|
bool is_streaming = reader_callback->is_streaming();
|
||||||
|
if (is_streaming) std::this_thread::sleep_for(std::chrono::milliseconds(10));
|
||||||
|
else break;
|
||||||
|
}
|
||||||
|
|
||||||
|
mf_source_reader = nullptr;
|
||||||
|
am_camera_control = nullptr;
|
||||||
|
am_video_proc_amp = nullptr;
|
||||||
|
ks_controls.clear();
|
||||||
|
if (mf_media_source) {
|
||||||
|
mf_media_source = nullptr;
|
||||||
|
check("IMFActivate::ShutdownObject", mf_activate->ShutdownObject());
|
||||||
|
}
|
||||||
|
callback = {};
|
||||||
|
}
|
||||||
|
|
||||||
|
com_ptr<IMFMediaSource> get_media_source() {
|
||||||
|
if (!mf_media_source) {
|
||||||
|
check("IMFActivate::ActivateObject", mf_activate->ActivateObject(__uuidof(IMFMediaSource), (void **)&mf_media_source));
|
||||||
|
if (mf_media_source) {
|
||||||
|
check("IMFMediaSource::QueryInterface", mf_media_source->QueryInterface(__uuidof(IAMCameraControl), (void **)&am_camera_control));
|
||||||
|
if (SUCCEEDED(mf_media_source->QueryInterface(__uuidof(IAMVideoProcAmp), (void **)&am_video_proc_amp)));
|
||||||
|
} else throw_error() << "Invalid media source";
|
||||||
|
}
|
||||||
|
return mf_media_source;
|
||||||
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
HRESULT reader_callback::OnReadSample(HRESULT hrStatus, DWORD dwStreamIndex, DWORD dwStreamFlags, LONGLONG llTimestamp, IMFSample *sample) {
|
||||||
|
if (auto owner_ptr = owner.lock()) {
|
||||||
|
if (sample) {
|
||||||
|
com_ptr<IMFMediaBuffer> buffer = NULL;
|
||||||
|
if (SUCCEEDED(sample->GetBufferByIndex(0, &buffer))) {
|
||||||
|
BYTE *byte_buffer;
|
||||||
|
DWORD max_length, current_length;
|
||||||
|
if (SUCCEEDED(buffer->Lock(&byte_buffer, &max_length, ¤t_length))) {
|
||||||
|
auto continuation = [buffer, this]() {
|
||||||
|
buffer->Unlock();
|
||||||
|
};
|
||||||
|
owner_ptr->callback(byte_buffer, continuation);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (auto owner_ptr_new = owner.lock()) {
|
||||||
|
auto hr = owner_ptr_new->mf_source_reader->ReadSample(MF_SOURCE_READER_FIRST_VIDEO_STREAM, 0, NULL, NULL, NULL, NULL);
|
||||||
|
switch (hr) {
|
||||||
|
case S_OK: break;
|
||||||
|
case MF_E_INVALIDREQUEST: LOG(ERROR) << "ReadSample returned MF_E_INVALIDREQUEST"; break;
|
||||||
|
case MF_E_INVALIDSTREAMNUMBER: LOG(ERROR) << "ReadSample returned MF_E_INVALIDSTREAMNUMBER"; break;
|
||||||
|
case MF_E_NOTACCEPTING: LOG(ERROR) << "ReadSample returned MF_E_NOTACCEPTING"; break;
|
||||||
|
case E_INVALIDARG: LOG(ERROR) << "ReadSample returned E_INVALIDARG"; break;
|
||||||
|
case MF_E_VIDEO_RECORDING_DEVICE_INVALIDATED: LOG(ERROR) << "ReadSample returned MF_E_VIDEO_RECORDING_DEVICE_INVALIDATED"; break;
|
||||||
|
default: LOG(ERROR) << "ReadSample returned HRESULT " << std::hex << (uint32_t)hr; break;
|
||||||
|
}
|
||||||
|
if (hr != S_OK) streaming = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return S_OK;
|
||||||
|
}
|
||||||
|
|
||||||
std::shared_ptr<context> create_context() {
|
std::shared_ptr<context> create_context() {
|
||||||
return std::make_shared<context>();
|
return std::make_shared<context>();
|
||||||
}
|
}
|
||||||
|
|
||||||
std::vector<std::shared_ptr<device>> query_devices(
|
std::vector<std::shared_ptr<device>> query_devices(std::shared_ptr<context> context) {
|
||||||
std::shared_ptr<context> context) {
|
IMFAttributes *pAttributes = NULL;
|
||||||
|
check("MFCreateAttributes", MFCreateAttributes(&pAttributes, 1));
|
||||||
|
check("IMFAttributes::SetGUID", pAttributes->SetGUID(
|
||||||
|
MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE, MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE_VIDCAP_GUID));
|
||||||
|
|
||||||
|
IMFActivate **ppDevices;
|
||||||
|
UINT32 numDevices;
|
||||||
|
check("MFEnumDeviceSources", MFEnumDeviceSources(pAttributes, &ppDevices, &numDevices));
|
||||||
|
|
||||||
std::vector<std::shared_ptr<device>> devices;
|
std::vector<std::shared_ptr<device>> devices;
|
||||||
UNUSED(context)
|
for (UINT32 i = 0; i < numDevices; ++i) {
|
||||||
|
com_ptr<IMFActivate> pDevice;
|
||||||
|
*&pDevice = ppDevices[i];
|
||||||
|
|
||||||
|
WCHAR *wchar_dev_name = NULL;
|
||||||
|
WCHAR *wchar_name = NULL;
|
||||||
|
UINT32 length;
|
||||||
|
|
||||||
|
pDevice->GetAllocatedString(
|
||||||
|
MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE_VIDCAP_SYMBOLIC_LINK, &wchar_dev_name,
|
||||||
|
&length);
|
||||||
|
auto dev_name = win_to_utf(wchar_dev_name);
|
||||||
|
CoTaskMemFree(wchar_dev_name);
|
||||||
|
|
||||||
|
pDevice->GetAllocatedString(MF_DEVSOURCE_ATTRIBUTE_FRIENDLY_NAME, &wchar_name, &length);
|
||||||
|
auto name = win_to_utf(wchar_name); // Device description name
|
||||||
|
CoTaskMemFree(wchar_name);
|
||||||
|
|
||||||
|
int vid, pid, mi;
|
||||||
|
std::string unique_id;
|
||||||
|
|
||||||
|
if (!parse_usb_path(vid, pid, mi, unique_id, dev_name)) continue;
|
||||||
|
|
||||||
|
std::shared_ptr<device> dev;
|
||||||
|
for (auto & d : devices) {
|
||||||
|
if (d->vid == vid && d->pid == pid && d->unique_id == unique_id)
|
||||||
|
dev = d;
|
||||||
|
}
|
||||||
|
if (!dev) {
|
||||||
|
try {
|
||||||
|
dev = std::make_shared<device>(context, vid, pid, unique_id, name);
|
||||||
|
devices.push_back(dev);
|
||||||
|
} catch (const std::exception &e) {
|
||||||
|
VLOG_INFO << "Not a USB video device: " << e.what();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
dev->reader_callback = new reader_callback(dev);
|
||||||
|
dev->mf_activate = pDevice;
|
||||||
|
dev->vid = vid;
|
||||||
|
dev->pid = pid;
|
||||||
|
}
|
||||||
|
|
||||||
|
CoTaskMemFree(ppDevices);
|
||||||
return devices;
|
return devices;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -63,65 +495,286 @@ int get_product_id(const device &device) {
|
||||||
}
|
}
|
||||||
|
|
||||||
std::string get_name(const device &device) {
|
std::string get_name(const device &device) {
|
||||||
UNUSED(device)
|
return device.name;
|
||||||
return "";
|
|
||||||
}
|
}
|
||||||
|
|
||||||
std::string get_video_name(const device &device) {
|
std::string get_video_name(const device &device) {
|
||||||
UNUSED(device)
|
return device.name;
|
||||||
return "";
|
}
|
||||||
|
|
||||||
|
static long get_cid(Option option) {
|
||||||
|
switch (option) {
|
||||||
|
case Option::GAIN:
|
||||||
|
return VideoProcAmp_Gain;
|
||||||
|
case Option::BRIGHTNESS:
|
||||||
|
return VideoProcAmp_Brightness;
|
||||||
|
case Option::CONTRAST:
|
||||||
|
return VideoProcAmp_Contrast;
|
||||||
|
default:
|
||||||
|
LOG(FATAL) << "No VideoProcAmp cid for " << option;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool pu_control_range(
|
bool pu_control_range(
|
||||||
const device &device, Option option, int32_t *min, int32_t *max,
|
const device &device, Option option, int32_t *min, int32_t *max,
|
||||||
int32_t *def) {
|
int32_t *def) {
|
||||||
UNUSED(device)
|
VLOG_INFO << __func__ << " " << option;
|
||||||
UNUSED(option)
|
const_cast<uvc::device &>(device).get_media_source();
|
||||||
UNUSED(min)
|
long minVal = 0, maxVal = 0, steppingDelta = 0, defVal = 0, capsFlag = 0;
|
||||||
UNUSED(max)
|
check("IAMVideoProcAmp::GetRange",
|
||||||
UNUSED(def)
|
const_cast<uvc::device &>(device).am_video_proc_amp->GetRange(
|
||||||
return false;
|
get_cid(option), &minVal, &maxVal, &steppingDelta, &defVal, &capsFlag));
|
||||||
|
if (min) *min = static_cast<int>(minVal);
|
||||||
|
if (max) *max = static_cast<int>(maxVal);
|
||||||
|
if (def) *def = static_cast<int>(defVal);
|
||||||
|
VLOG_INFO << __func__ << " " << option <<
|
||||||
|
": min=" << *min << ", max=" << *max << ", def=" << *def;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void pu_control_get(const device &device, long property, int32_t *value) {
|
||||||
|
long data, flags = 0;
|
||||||
|
check("IAMVideoProcAmp::Get",
|
||||||
|
const_cast<uvc::device &>(device).am_video_proc_amp->Get(
|
||||||
|
property, &data, &flags));
|
||||||
|
*value = data;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void pu_control_set(const device &device, long property, int32_t *value) {
|
||||||
|
long data = *value;
|
||||||
|
check("IAMVideoProcAmp::Set",
|
||||||
|
const_cast<uvc::device &>(device).am_video_proc_amp->Set(
|
||||||
|
property, data, VideoProcAmp_Flags_Auto));
|
||||||
}
|
}
|
||||||
|
|
||||||
bool pu_control_query(
|
bool pu_control_query(
|
||||||
const device &device, Option option, pu_query query, int32_t *value) {
|
const device &device, Option option, pu_query query, int32_t *value) {
|
||||||
UNUSED(device)
|
CHECK_NOTNULL(value);
|
||||||
UNUSED(option)
|
const_cast<uvc::device &>(device).get_media_source();
|
||||||
UNUSED(query)
|
switch (query) {
|
||||||
UNUSED(value)
|
case PU_QUERY_SET:
|
||||||
|
VLOG_INFO << "pu_control_set " << option << ": " << *value;
|
||||||
|
pu_control_set(device, get_cid(option), value);
|
||||||
|
VLOG_INFO << "pu_control_set " << option << " done";
|
||||||
|
return true;
|
||||||
|
case PU_QUERY_GET:
|
||||||
|
VLOG_INFO << "pu_control_get " << option;
|
||||||
|
pu_control_get(device, get_cid(option), value);
|
||||||
|
VLOG_INFO << "pu_control_get " << option << ": " << *value;
|
||||||
|
return true;
|
||||||
|
default:
|
||||||
|
LOG(ERROR) << "pu_control_query request code is unaccepted";
|
||||||
return false;
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static std::string to_string(uint16_t size, uint8_t *data) {
|
||||||
|
std::ostringstream ss;
|
||||||
|
for (uint8_t *beg = data, *end = data + size; beg != end; beg++) {
|
||||||
|
ss << "0x" << std::hex << static_cast<int>(*beg) << ",";
|
||||||
|
}
|
||||||
|
return ss.str();
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
static std::vector<BYTE> xu_control_desc(const device &device, const xu &xu, ULONG id, ULONG flags) {
|
||||||
|
auto ks_control = const_cast<uvc::device &>(device).get_ks_control(xu);
|
||||||
|
|
||||||
|
KSP_NODE node;
|
||||||
|
memset(&node, 0, sizeof(KSP_NODE));
|
||||||
|
node.Property.Set = reinterpret_cast<const GUID &>(xu.id);
|
||||||
|
node.Property.Id = id;
|
||||||
|
node.Property.Flags = flags;
|
||||||
|
node.NodeId = xu.node;
|
||||||
|
|
||||||
|
KSPROPERTY_DESCRIPTION description;
|
||||||
|
ULONG bytes_received = 0;
|
||||||
|
check("IKsControl::KsProperty", ks_control->KsProperty(
|
||||||
|
(PKSPROPERTY)&node,
|
||||||
|
sizeof(node),
|
||||||
|
&description,
|
||||||
|
sizeof(KSPROPERTY_DESCRIPTION),
|
||||||
|
&bytes_received));
|
||||||
|
|
||||||
|
ULONG size = description.DescriptionSize;
|
||||||
|
std::vector<BYTE> buffer(size);
|
||||||
|
|
||||||
|
check("IKsControl::KsProperty", ks_control->KsProperty(
|
||||||
|
(PKSPROPERTY)&node,
|
||||||
|
sizeof(node),
|
||||||
|
buffer.data(),
|
||||||
|
size,
|
||||||
|
&bytes_received));
|
||||||
|
|
||||||
|
if (bytes_received != size) { throw_error() << "wrong data"; }
|
||||||
|
|
||||||
|
// VLOG_INFO << "buffer size=" << size << ", data=["
|
||||||
|
// << to_string(size, buffer.data()) << "]";
|
||||||
|
return buffer;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool xu_control_range(
|
||||||
|
const device &device, const xu &xu, uint8_t selector, int32_t *min,
|
||||||
|
int32_t *max, int32_t *def) {
|
||||||
|
VLOG_INFO << __func__ << " " << static_cast<int>(selector);
|
||||||
|
size_t prop_header_size = sizeof(KSPROPERTY_MEMBERSHEADER) + sizeof(KSPROPERTY_DESCRIPTION);
|
||||||
|
// get step, min and max values
|
||||||
|
{
|
||||||
|
auto &&buffer = xu_control_desc(device, xu, selector,
|
||||||
|
KSPROPERTY_TYPE_BASICSUPPORT | KSPROPERTY_TYPE_TOPOLOGY);
|
||||||
|
|
||||||
|
BYTE *values = buffer.data() + prop_header_size;
|
||||||
|
|
||||||
|
// size_t size = buffer.size() - prop_header_size;
|
||||||
|
// VLOG_INFO << "values size: " << size << ", data=["
|
||||||
|
// << to_string(size, values) << "]";
|
||||||
|
|
||||||
|
*min = (values[1] << 8) | (values[2]);
|
||||||
|
values += 3;
|
||||||
|
*max = (values[1] << 8) | (values[2]);
|
||||||
|
// values += 3;
|
||||||
|
// *step = (values[1] << 8) | (values[2]);
|
||||||
|
}
|
||||||
|
// get def value
|
||||||
|
{
|
||||||
|
auto &&buffer = xu_control_desc(device, xu, selector,
|
||||||
|
KSPROPERTY_TYPE_DEFAULTVALUES | KSPROPERTY_TYPE_TOPOLOGY);
|
||||||
|
|
||||||
|
BYTE *values = buffer.data() + prop_header_size;
|
||||||
|
|
||||||
|
// size_t size = buffer.size() - prop_header_size;
|
||||||
|
// VLOG_INFO << "values size: " << size << ", data=["
|
||||||
|
// << to_string(size, values) << "]";
|
||||||
|
|
||||||
|
*def = (values[1] << 8) | (values[2]);
|
||||||
|
}
|
||||||
|
VLOG_INFO << __func__ << " " << static_cast<int>(selector)
|
||||||
|
<< ": min=" << *min << ", max=" << *max << ", def=" << *def;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
*/
|
||||||
|
|
||||||
|
static void xu_control_get(const device &device, const xu &xu, uint8_t selector,
|
||||||
|
uint16_t size, uint8_t *data) {
|
||||||
|
VLOG_INFO << __func__ << " " << static_cast<int>(selector);
|
||||||
|
auto &&ks_control = const_cast<uvc::device &>(device).get_ks_control(xu);
|
||||||
|
|
||||||
|
KSP_NODE node;
|
||||||
|
memset(&node, 0, sizeof(KSP_NODE));
|
||||||
|
node.Property.Set = reinterpret_cast<const GUID &>(xu.id);
|
||||||
|
node.Property.Id = selector;
|
||||||
|
node.Property.Flags = KSPROPERTY_TYPE_GET | KSPROPERTY_TYPE_TOPOLOGY;
|
||||||
|
node.NodeId = xu.node;
|
||||||
|
|
||||||
|
ULONG bytes_received = 0;
|
||||||
|
check("IKsControl::KsProperty", ks_control->KsProperty(
|
||||||
|
(PKSPROPERTY)&node, sizeof(node), data, size, &bytes_received));
|
||||||
|
|
||||||
|
if (bytes_received != size)
|
||||||
|
throw_error() << "xu_control_get did not return enough data";
|
||||||
|
VLOG_INFO << __func__ << " " << static_cast<int>(selector)
|
||||||
|
<< ": size=" << size << ", data=[" << to_string(size, data) << "]";
|
||||||
|
}
|
||||||
|
|
||||||
|
static void xu_control_set(const device &device, const xu &xu, uint8_t selector,
|
||||||
|
uint16_t size, uint8_t *data) {
|
||||||
|
VLOG_INFO << __func__ << " " << static_cast<int>(selector)
|
||||||
|
<< ": size=" << size << ", data=[" << to_string(size, data) << "]";
|
||||||
|
auto &&ks_control = const_cast<uvc::device &>(device).get_ks_control(xu);
|
||||||
|
|
||||||
|
KSP_NODE node;
|
||||||
|
memset(&node, 0, sizeof(KSP_NODE));
|
||||||
|
node.Property.Set = reinterpret_cast<const GUID &>(xu.id);
|
||||||
|
node.Property.Id = selector;
|
||||||
|
node.Property.Flags = KSPROPERTY_TYPE_SET | KSPROPERTY_TYPE_TOPOLOGY;
|
||||||
|
node.NodeId = xu.node;
|
||||||
|
|
||||||
|
ULONG bytes_received = 0;
|
||||||
|
check("IKsControl::KsProperty", ks_control->KsProperty(
|
||||||
|
(PKSPROPERTY)&node, sizeof(node), data, size, &bytes_received));
|
||||||
|
VLOG_INFO << __func__ << " " << static_cast<int>(selector) << " done";
|
||||||
|
}
|
||||||
|
|
||||||
|
static int32_t xu_control_range_basic(const device &device, const xu &xu, uint8_t selector, uint8_t id) {
|
||||||
|
std::uint8_t data[3]{id, 0, 0};
|
||||||
|
xu_control_set(device, xu, selector, 3, data);
|
||||||
|
xu_control_get(device, xu, selector, 3, data);
|
||||||
|
return (data[1] << 8) | (data[2]);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool xu_control_range(
|
||||||
|
const device &device, const xu &xu, uint8_t selector, uint8_t id,
|
||||||
|
int32_t *min, int32_t *max, int32_t *def) {
|
||||||
|
VLOG_INFO << __func__ << " " << static_cast<int>(selector);
|
||||||
|
*min = xu_control_range_basic(
|
||||||
|
device, xu, selector, static_cast<uint8_t>(id | 0x90));
|
||||||
|
*max = xu_control_range_basic(
|
||||||
|
device, xu, selector, static_cast<uint8_t>(id | 0xa0));
|
||||||
|
*def = xu_control_range_basic(
|
||||||
|
device, xu, selector, static_cast<uint8_t>(id | 0xc0));
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool xu_control_query(
|
bool xu_control_query(
|
||||||
const device &device, const xu &xu, uint8_t selector, xu_query query,
|
const device &device, const xu &xu, uint8_t selector, xu_query query,
|
||||||
uint16_t size, uint8_t *data) {
|
uint16_t size, uint8_t *data) {
|
||||||
UNUSED(device)
|
CHECK_NOTNULL(data);
|
||||||
UNUSED(xu)
|
switch (query) {
|
||||||
UNUSED(selector)
|
case XU_QUERY_SET:
|
||||||
UNUSED(query)
|
xu_control_set(device, xu, selector, size, data);
|
||||||
UNUSED(size)
|
return true;
|
||||||
UNUSED(data)
|
case XU_QUERY_GET:
|
||||||
|
xu_control_get(device, xu, selector, size, data);
|
||||||
|
return true;
|
||||||
|
default:
|
||||||
|
LOG(ERROR) << "xu_control_query request code is unaccepted";
|
||||||
return false;
|
return false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void set_device_mode(
|
void set_device_mode(device &device, int width, int height, int fourcc, int fps, video_channel_callback callback) {
|
||||||
device &device, int width, int height, int fourcc, int fps, // NOLINT
|
if (!device.mf_source_reader) {
|
||||||
video_channel_callback callback) {
|
com_ptr<IMFAttributes> pAttributes;
|
||||||
UNUSED(device)
|
check("MFCreateAttributes", MFCreateAttributes(&pAttributes, 1));
|
||||||
UNUSED(width)
|
check("IMFAttributes::SetUnknown", pAttributes->SetUnknown(MF_SOURCE_READER_ASYNC_CALLBACK, static_cast<IUnknown *>(device.reader_callback)));
|
||||||
UNUSED(height)
|
check("MFCreateSourceReaderFromMediaSource", MFCreateSourceReaderFromMediaSource(device.get_media_source(), pAttributes, &device.mf_source_reader));
|
||||||
UNUSED(fourcc)
|
}
|
||||||
UNUSED(fps)
|
|
||||||
UNUSED(callback)
|
if (fourcc_map.count(fourcc)) fourcc = fourcc_map.at(fourcc);
|
||||||
|
|
||||||
|
for (DWORD j = 0; ; j++) {
|
||||||
|
com_ptr<IMFMediaType> media_type;
|
||||||
|
HRESULT hr = device.mf_source_reader->GetNativeMediaType((DWORD)MF_SOURCE_READER_FIRST_VIDEO_STREAM, j, &media_type);
|
||||||
|
if (hr == MF_E_NO_MORE_TYPES) break;
|
||||||
|
check("IMFSourceReader::GetNativeMediaType", hr);
|
||||||
|
|
||||||
|
UINT32 uvc_width, uvc_height, uvc_fps_num, uvc_fps_denom;
|
||||||
|
GUID subtype;
|
||||||
|
check("MFGetAttributeSize", MFGetAttributeSize(media_type, MF_MT_FRAME_SIZE, &uvc_width, &uvc_height));
|
||||||
|
if (uvc_width != width || uvc_height != height) continue;
|
||||||
|
|
||||||
|
check("IMFMediaType::GetGUID", media_type->GetGUID(MF_MT_SUBTYPE, &subtype));
|
||||||
|
if (subtype.Data1 != fourcc) continue;
|
||||||
|
|
||||||
|
check("MFGetAttributeRatio", MFGetAttributeRatio(media_type, MF_MT_FRAME_RATE, &uvc_fps_num, &uvc_fps_denom));
|
||||||
|
if (uvc_fps_denom == 0) continue;
|
||||||
|
//int uvc_fps = uvc_fps_num / uvc_fps_denom;
|
||||||
|
//LOG(INFO) << "uvc_fps: " << uvc_fps;
|
||||||
|
|
||||||
|
check("IMFSourceReader::SetCurrentMediaType", device.mf_source_reader->SetCurrentMediaType((DWORD)MF_SOURCE_READER_FIRST_VIDEO_STREAM, NULL, media_type));
|
||||||
|
|
||||||
|
device.callback = callback;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
throw_error() << "no matching media type for pixel format " << std::hex << fourcc;
|
||||||
}
|
}
|
||||||
|
|
||||||
void start_streaming(device &device, int num_transfer_bufs) { // NOLINT
|
void start_streaming(device &device, int num_transfer_bufs) {
|
||||||
UNUSED(device)
|
device.start_streaming();
|
||||||
UNUSED(num_transfer_bufs)
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void stop_streaming(device &device) { // NOLINT
|
void stop_streaming(device &device) {
|
||||||
UNUSED(device)
|
device.stop_streaming();
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace uvc
|
} // namespace uvc
|
||||||
|
|
|
@ -36,9 +36,17 @@ typedef enum pu_query {
|
||||||
PU_QUERY_LAST
|
PU_QUERY_LAST
|
||||||
} pu_query;
|
} pu_query;
|
||||||
|
|
||||||
|
struct MYNTEYE_API guid {
|
||||||
|
uint32_t data1;
|
||||||
|
uint16_t data2, data3;
|
||||||
|
uint8_t data4[8];
|
||||||
|
};
|
||||||
|
|
||||||
// Extension Unit
|
// Extension Unit
|
||||||
struct MYNTEYE_API xu {
|
struct MYNTEYE_API xu {
|
||||||
uint8_t unit;
|
uint8_t unit;
|
||||||
|
int node;
|
||||||
|
guid id;
|
||||||
};
|
};
|
||||||
|
|
||||||
typedef enum xu_query {
|
typedef enum xu_query {
|
||||||
|
@ -77,12 +85,16 @@ MYNTEYE_API bool pu_control_query(
|
||||||
const device &device, Option option, pu_query query, int32_t *value);
|
const device &device, Option option, pu_query query, int32_t *value);
|
||||||
|
|
||||||
// Access XU (Extension Unit) controls
|
// Access XU (Extension Unit) controls
|
||||||
MYNTEYE_API bool xu_control_query(
|
MYNTEYE_API bool xu_control_range(
|
||||||
|
const device &device, const xu &xu, uint8_t selector, uint8_t id,
|
||||||
|
int32_t *min, int32_t *max, int32_t *def);
|
||||||
|
MYNTEYE_API bool xu_control_query( // XU_QUERY_SET, XU_QUERY_GET
|
||||||
const device &device, const xu &xu, uint8_t selector, xu_query query,
|
const device &device, const xu &xu, uint8_t selector, xu_query query,
|
||||||
uint16_t size, uint8_t *data);
|
uint16_t size, uint8_t *data);
|
||||||
|
|
||||||
// Control streaming
|
// Control streaming
|
||||||
typedef std::function<void(const void *frame)> video_channel_callback;
|
typedef std::function<void(const void *frame,
|
||||||
|
std::function<void()> continuation)> video_channel_callback;
|
||||||
|
|
||||||
MYNTEYE_API void set_device_mode(
|
MYNTEYE_API void set_device_mode(
|
||||||
device &device, int width, int height, int fourcc, int fps, // NOLINT
|
device &device, int width, int height, int fourcc, int fps, // NOLINT
|
||||||
|
|
Loading…
Reference in New Issue
Block a user