Compare commits
18 Commits
devel-s210
...
2.2.4
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
203c5ce18b | ||
|
|
27ab088acd | ||
|
|
2a2ea0b370 | ||
|
|
6172f4c1b8 | ||
|
|
a3206e5be5 | ||
|
|
e34e6e1466 | ||
|
|
87c3c81a93 | ||
|
|
ceec4f492a | ||
|
|
812638b7dc | ||
|
|
6e638813f2 | ||
|
|
18258fe7c9 | ||
|
|
0bcaa0801e | ||
|
|
b10415515e | ||
|
|
aa19d65272 | ||
|
|
1f6acd3c98 | ||
|
|
28e539e277 | ||
|
|
2e97266516 | ||
|
|
9eea427d59 |
@@ -14,7 +14,7 @@
|
||||
|
||||
cmake_minimum_required(VERSION 3.0)
|
||||
|
||||
project(mynteye VERSION 2.2.2 LANGUAGES C CXX)
|
||||
project(mynteye VERSION 2.2.4 LANGUAGES C CXX)
|
||||
|
||||
include(cmake/Common.cmake)
|
||||
|
||||
@@ -106,6 +106,7 @@ set_outdir(
|
||||
)
|
||||
|
||||
## main
|
||||
|
||||
if(WITH_GLOG)
|
||||
add_executable(main src/main.cc)
|
||||
target_link_libraries(main glog::glog)
|
||||
@@ -123,11 +124,6 @@ if(NOT WITH_GLOG AND NOT OS_WIN)
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${__MINIGLOG_FLAGS}")
|
||||
unset(__MINIGLOG_FLAGS)
|
||||
endif()
|
||||
if(NOT WITH_GLOG)
|
||||
list(APPEND MYNTEYE_PUBLIC_H
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/miniglog.h
|
||||
)
|
||||
endif()
|
||||
|
||||
if(OS_WIN)
|
||||
set(UVC_SRC src/mynteye/uvc/win/uvc-wmf.cc)
|
||||
|
||||
12
README.md
12
README.md
@@ -1,6 +1,6 @@
|
||||
# MYNT® EYE S SDK
|
||||
|
||||
[](https://github.com/slightech/MYNT-EYE-S-SDK)
|
||||
[](https://github.com/slightech/MYNT-EYE-S-SDK)
|
||||
|
||||
## Overview
|
||||
|
||||
@@ -17,11 +17,11 @@ Please follow the guide doc to install the SDK on different platforms.
|
||||
## Documentations
|
||||
|
||||
* [API Doc](https://github.com/slightech/MYNT-EYE-S-SDK/releases): API reference, some guides and data spec.
|
||||
* en: [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2683636/mynt-eye-s-sdk-apidoc-2.2.2-en.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2683637/mynt-eye-s-sdk-apidoc-2.2.2-en.zip) [](https://slightech.github.io/MYNT-EYE-S-SDK/)
|
||||
* zh-Hans: [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2683638/mynt-eye-s-sdk-apidoc-2.2.2-zh-Hans.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2683639/mynt-eye-s-sdk-apidoc-2.2.2-zh-Hans.zip) [](http://doc.myntai.com/resource/api/mynt-eye-s-sdk-apidoc-2.2.2-zh-Hans/mynt-eye-s-sdk-apidoc-2.2.2-zh-Hans/index.html)
|
||||
* en: [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2717670/mynt-eye-s-sdk-apidoc-2.2.4-en.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2717671/mynt-eye-s-sdk-apidoc-2.2.4-en.zip) [](https://slightech.github.io/MYNT-EYE-S-SDK/)
|
||||
* zh-Hans: [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2717672/mynt-eye-s-sdk-apidoc-2.2.4-zh-Hans.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2717673/mynt-eye-s-sdk-apidoc-2.2.4-zh-Hans.zip) [](http://doc.myntai.com/resource/api/mynt-eye-s-sdk-apidoc-2.2.4-zh-Hans/mynt-eye-s-sdk-apidoc-2.2.4-zh-Hans/index.html)
|
||||
* [Guide Doc](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/releases): How to install and start using the SDK.
|
||||
* en: [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2683625/mynt-eye-s-sdk-guide-2.2.2-en.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2683626/mynt-eye-s-sdk-guide-2.2.2-en.zip) [](https://slightech.github.io/MYNT-EYE-S-SDK-Guide/)
|
||||
* zh-Hans: [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2683627/mynt-eye-s-sdk-guide-2.2.2-zh-Hans.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2683628/mynt-eye-s-sdk-guide-2.2.2-zh-Hans.zip) [](http://doc.myntai.com/resource/sdk/mynt-eye-s-sdk-guide-2.2.2-zh-Hans/mynt-eye-s-sdk-guide-2.2.2-zh-Hans/index.html)
|
||||
* en: [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2717663/mynt-eye-s-sdk-guide-2.2.4-en.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2717664/mynt-eye-s-sdk-guide-2.2.4-en.zip) [](https://slightech.github.io/MYNT-EYE-S-SDK-Guide/)
|
||||
* zh-Hans: [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2717665/mynt-eye-s-sdk-guide-2.2.4-zh-Hans.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2717666/mynt-eye-s-sdk-guide-2.2.4-zh-Hans.zip) [](http://doc.myntai.com/resource/sdk/mynt-eye-s-sdk-guide-2.2.4-zh-Hans/mynt-eye-s-sdk-guide-2.2.4-zh-Hans/index.html)
|
||||
|
||||
> Supported languages: `en`, `zh-Hans`.
|
||||
|
||||
@@ -29,7 +29,7 @@ Please follow the guide doc to install the SDK on different platforms.
|
||||
|
||||
[MYNTEYE_BOX]: http://doc.myntai.com/mynteye/s/download
|
||||
|
||||
Get firmwares from our online disks: [MYNTEYE_BOX][]. The latest version is `2.2.2`.
|
||||
Get firmwares from our online disks: [MYNTEYE_BOX][].
|
||||
|
||||
## Usage
|
||||
|
||||
|
||||
@@ -21,6 +21,7 @@ include(${CMAKE_CURRENT_LIST_DIR}/Utils.cmake)
|
||||
# build components
|
||||
|
||||
option(WITH_API "Build with API layer, need OpenCV" ON)
|
||||
|
||||
option(WITH_DEVICE_INFO_REQUIRED "Build with device info required" ON)
|
||||
|
||||
# 3rdparty components
|
||||
@@ -31,6 +32,7 @@ option(WITH_BOOST "Include Boost support" ON)
|
||||
# Ubuntu: `sudo apt-get install libgoogle-glog-dev`
|
||||
option(WITH_GLOG "Include glog support" OFF)
|
||||
|
||||
|
||||
# packages
|
||||
|
||||
if(WITH_API)
|
||||
|
||||
@@ -38,7 +38,7 @@ PROJECT_NAME = "MYNT EYE S SDK"
|
||||
# could be handy for archiving the generated documentation or if some version
|
||||
# control system is used.
|
||||
|
||||
PROJECT_NUMBER = 2.2.2
|
||||
PROJECT_NUMBER = 2.2.4
|
||||
|
||||
# Using the PROJECT_BRIEF tag one can provide an optional one line description
|
||||
# for a project that appears at the top of each page and should give viewer a
|
||||
|
||||
@@ -38,7 +38,7 @@ PROJECT_NAME = "MYNT EYE S SDK"
|
||||
# could be handy for archiving the generated documentation or if some version
|
||||
# control system is used.
|
||||
|
||||
PROJECT_NUMBER = 2.2.2
|
||||
PROJECT_NUMBER = 2.2.4
|
||||
|
||||
# Using the PROJECT_BRIEF tag one can provide an optional one line description
|
||||
# for a project that appears at the top of each page and should give viewer a
|
||||
|
||||
@@ -6,22 +6,25 @@
|
||||
|
||||
| 名称 | 字段 | 字节数 | 默认值 | 最小值 | 最大值 | 是否储存 | Flash 地址 | 说明 |
|
||||
| :----- | :----- | :-------- | :-------- | :-------- | :-------- | :----------- | :----------- | :----- |
|
||||
| 亮度 | brightness | 2 | 192 | 0 | 255 | √ | 0x14 | 关闭自动曝光,手动设定的参数 |
|
||||
| 增益 | gain | 2 | 24 | 0 | 48 | √ | 0x12 | 关闭自动曝光,手动设定的参数 |
|
||||
| 亮度 | brightness/exposure_time | 2 | 120 | 0 | 240 | √ | 0x14 | 关闭自动曝光,手动设定的参数 |
|
||||
| 对比度 | contrast/black_level_calibration | 2 | 127 | 0 | 255 | √ | 0x10 | 关闭自动曝光,手动设定的参数 |
|
||||
|
||||
> UVC 标准协议实现的控制,有现成的 API 进行 Get & Set ,包括 Min, Max, Default 。
|
||||
|
||||
## 自定义协议
|
||||
|
||||
| 名称 | 字段 | 字节数 | 默认值 | 最小值 | 最大值 | 是否储存 | Flash 地址 | 所属通道 | 通道地址 | 说明 |
|
||||
| :----- | :----- | :-------- | :-------- | :-------- | :-------- | :----------- | :----------- | :----------- | :----------- | :----- |
|
||||
| 曝光模式 | exposure_mode | 1 | 0 | 0 | 1 | √ | 0x0F | XU_CAM_CTRL | 0x0100 | 0:开启自动曝光; 1:关闭 |
|
||||
| 最大增益 | max_gain | 2 | 8 | 0 | 255 | √ | 0x1D | XU_CAM_CTRL | 0x0100 | 开始自动曝光,可设定的阈值 |
|
||||
| 最大曝光时间 | max_exposure_time | 2 | 333 | 0 | 1000 | √ | 0x1B | XU_CAM_CTRL | 0x0100 | 开始自动曝光,可设定的阈值 |
|
||||
| 期望亮度 | desired_brightness | 2 | 122 | 1 | 255 | √ | 0x19 | XU_CAM_CTRL | 0x0100 | |
|
||||
| 擦除芯片 | erase_chip | | - | - | - | × | - | XU_HALF_DUPLEX | 0x0200 | |
|
||||
| 最小曝光时间 | min_exposure_time | 2 | 0 | 0 | 1000 | √ | - | XU_CAM_CTRL | 0x0100 | 开始自动曝光,可设定的阈值 |
|
||||
| 名称 | 字段 | 字节数 | 默认值 | 最小值 | 最大值 | 是否储存 | Flash 地址 | 所属通道 | 说明 |
|
||||
| :----- | :----- | :-------- | :-------- | :-------- | :-------- | :----------- | :----------- | :----------- | :----- |
|
||||
| 图像帧率 | frame_rate | 2 | 25 | 10 | 60 | √ | 0x21 | XU_CAM_CTRL | 步进为5,即有效值为{10,15,20,25,30,35,40,45,50,55,60} |
|
||||
| IMU 频率 | imu_frequency | 2 | 200 | 100 | 500 | √ | 0x23 | XU_CAM_CTRL | 有效值为{100,200,250,333,500} |
|
||||
| 曝光模式 | exposure_mode | 1 | 0 | 0 | 1 | √ | 0x0F | XU_CAM_CTRL | 0:开启自动曝光; 1:关闭 |
|
||||
| 最大增益 | max_gain | 2 | 48 | 0 | 48 | √ | 0x1D | XU_CAM_CTRL | 开始自动曝光,可设定的阈值 |
|
||||
| 最大曝光时间 | max_exposure_time | 2 | 240 | 0 | 240 | √ | 0x1B | XU_CAM_CTRL | 开始自动曝光,可设定的阈值 |
|
||||
| 期望亮度 | desired_brightness | 2 | 192 | 0 | 255 | √ | 0x19 | XU_CAM_CTRL | 开始自动曝光,可设定的阈值 |
|
||||
| IR 控制 | ir_control | 1 | 0 | 0 | 160 | × | - | XU_CAM_CTRL | |
|
||||
| HDR 模式 | hdr_mode | 1 | 0 | 0 | 1 | √ | 0x1F | XU_CAM_CTRL | 0:10-bit;1:12-bit |
|
||||
| 零漂标定 | zero_drift_calibration | | - | - | - | × | - | XU_HALF_DUPLEX | |
|
||||
| 擦除芯片 | erase_chip | | - | - | - | × | - | XU_HALF_DUPLEX | |
|
||||
| 加速度计量程 | accelerometer_range | 2 | 12 | 6 | 48 | √ | - | XU_CAM_CTRL | 0x0100 | |
|
||||
| 陀螺仪量程 | gyroscope_range | 2 | 1000 | 250 | 4000 | √ | - | XU_CAM_CTRL | 0x0100 | |
|
||||
| 加速度计低通滤波 | accelerometer_low_pass_filter | 2 | 2 | 0 | 2 | √ | - | XU_CAM_CTRL | 0x0100 | |
|
||||
| 陀螺仪低通滤波 | gyroscope__low_pass_filter | 2 | 64 | 23 | 64 | √ | - | XU_CAM_CTRL | 0x0100 | |
|
||||
|
||||
|
||||
@@ -49,5 +49,5 @@
|
||||
| File | ID | Max Size |
|
||||
| :--- | :- | :------- |
|
||||
| 硬件信息 | 1 | 250 |
|
||||
| 图像参数 | 2 | 404 |
|
||||
| 图像参数 | 2 | 250 |
|
||||
| IMU 参数 | 4 | 500 |
|
||||
|
||||
@@ -3,19 +3,20 @@
|
||||
| 名称 | 字段 | 单位 | 字节数 | 说明 |
|
||||
| :----- | :----- | :----- | :-------- | :----- |
|
||||
| 帧 ID | frame_id | - | 2 | uint16_t; [0,65535] |
|
||||
| 时间戳 | timestamp | 1 us | 8 | uint64_t |
|
||||
| 曝光时间 | exposure_time | 1 us | 2 | uint16_t |
|
||||
| 时间戳 | timestamp | 10 us | 4 | uint32_t |
|
||||
| 曝光时间 | exposure_time | 10 us | 2 | uint16_t |
|
||||
|
||||
> 图像数据传输方式:倒序排在图像尾部。
|
||||
|
||||
## 图像数据包
|
||||
|
||||
| Name | Header | Size | FrameID | Timestamp | ExposureTime | Checksum |
|
||||
| :--- | :----- | :--- | :------ | :-------- | :----------- | :------- |
|
||||
| 字节数 | 1 | 1 | 2 | 8 | 2 | 1 |
|
||||
| 类型 | uint8_t | uint8_t | uint16_t | uint64_t | uint16_t | uint8_t |
|
||||
| 描述 | 0x3B | 0x10 (数据内容大小) | 帧 ID | 时间戳 | 曝光时间 | 校验码(数据内容所有字节异或) |
|
||||
| Name | Header | Size | Frame ID | Timestamp | Exposure Time | Checksum |
|
||||
| :--- | :----- | :--- | :------- | :-------- | :------------ | :------- |
|
||||
| 字节数 | 1 | 1 | 2 | 4 | 2 | 1 |
|
||||
| 类型 | uint8_t | uint8_t | uint16_t | uint32_t | uint16_t | uint8_t |
|
||||
| 描述 | 0x3B | 0x08 (数据内容大小) | 帧 ID | 时间戳 | 曝光时间 | 校验码(数据内容所有字节异或) |
|
||||
|
||||
* 数据包校验不过,会丢弃该帧。
|
||||
* 时间的单位精度为: 1 us 。
|
||||
* 时间单位的精度为: 0.01 ms / 10 us 。
|
||||
* 4 字节能表示的最大时间约是 11.9 小时,溢出后将重累计。
|
||||
* 时间累计是从上电时从开始,而不是从打开时开始。
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
|
||||
## IMU 响应数据包
|
||||
|
||||
IMU 响应数据包里会包含1个 IMU 包,而每个 IMU 包又带有多个 IMU 段。
|
||||
IMU 响应数据包里会包含多个 IMU 包,而每个 IMU 包又带有多个 IMU 段。
|
||||
|
||||
| Name | Header | State | Size | IMU Packets | Checksum |
|
||||
| :--- | :----- | :---- | :--- | :---------- | :------- |
|
||||
@@ -22,21 +22,21 @@ IMU 响应数据包里会包含1个 IMU 包,而每个 IMU 包又带有多个 I
|
||||
|
||||
IMU 包/小包,是一组 IMU 数据。
|
||||
|
||||
| Name | Count | IMU Datas |
|
||||
| :--- | :-----| :-------- |
|
||||
| 字节数 | 2 | ... |
|
||||
| 类型 | uint16_t | - |
|
||||
| 描述 | IMU 段数量 | 所包含的 IMU 段 |
|
||||
| Name | Serial Number | Timestamp | Count | IMU Datas |
|
||||
| :--- | :------------ | :-------- | :---- | :-------- |
|
||||
| 字节数 | 4 | 4 | 1 | ... |
|
||||
| 类型 | uint32_t | uint32_t | uint8_t | - |
|
||||
| 描述 | 序列号 | IMU 基准时间戳 | IMU 段数量 | 所包含的 IMU 段 |
|
||||
|
||||
### IMU 段
|
||||
|
||||
| Name | Serial Number | Timestamp | flag | Temperature | Accelerometer or Gyroscope |
|
||||
| :--- | :------------ | :-------- | :----| :----------- | :------------------------- |
|
||||
| 字节数 | 4 | 8 | 1 | 2 | 6 |
|
||||
| 类型 | uint32_t | uint64_t | int8_t | int16_t | int16_t * 3 |
|
||||
| Description | 序列号 | 时间戳 | 指定传感器类型 | IMU 的温度 | 陀螺仪或陀螺仪 x y z 三轴的值 |
|
||||
| Name | Offset | Frame ID | Accelerometer | Temperature | Gyroscope |
|
||||
| :--- | :----- | :------- | :------------ | :---------- | :-------- |
|
||||
| 字节数 | 2 | 2 | 6 | 2 | 6 |
|
||||
| 类型 | int16_t | uint16_t | int16_t * 3 | int16_t | int16_t * 3 |
|
||||
| 描述 | 相对基准时间戳的偏移量 | 图像帧 ID | 加速度计 x y z 三轴的值 | IMU 的温度 | 陀螺仪 x y z 三轴的值 |
|
||||
|
||||
* 加速度计和陀螺仪的计量值换算成物理值公式: **real = data * range / 0x10000** 。
|
||||
* 加速度计量程默认值为 **12 g** ,陀螺仪量程默认值为 **1000 deg/s** 。
|
||||
* 加速度计量程默认值为 **8 g** ,陀螺仪量程默认值为 **1000 deg/s** 。
|
||||
* 温度计量值换算成物理值公式: **real = data / ratio + offset** 。
|
||||
* ``ratio`` 默认值为 **326.8** , ``offset`` 默认值为 **25℃** 。
|
||||
|
||||
@@ -72,7 +72,8 @@ struct MYNTEYE_API MotionData {
|
||||
|
||||
bool operator==(const MotionData &other) const {
|
||||
if (imu && other.imu) {
|
||||
return imu->timestamp == other.imu->timestamp;
|
||||
return imu->frame_id == other.imu->frame_id &&
|
||||
imu->timestamp == other.imu->timestamp;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
@@ -98,14 +99,7 @@ class MYNTEYE_API API {
|
||||
* @return the API instance.
|
||||
* @note This will call device::select() to select a device.
|
||||
*/
|
||||
static std::shared_ptr<API> Create(Resolution res);
|
||||
/**
|
||||
* Create the API instance.
|
||||
* @param device the selected device.
|
||||
* @return the API instance.
|
||||
*/
|
||||
static std::shared_ptr<API> Create(
|
||||
std::shared_ptr<Device> device, Resolution res);
|
||||
static std::shared_ptr<API> Create();
|
||||
/**
|
||||
* Create the API instance.
|
||||
* @param device the selected device.
|
||||
@@ -154,10 +148,6 @@ class MYNTEYE_API API {
|
||||
*/
|
||||
bool Supports(const AddOns &addon) const;
|
||||
|
||||
/**
|
||||
* set the stream request.
|
||||
*/
|
||||
void SetStreamRequest(const Format &format, const FrameRate &rate);
|
||||
/**
|
||||
* Get all stream requests of the capability.
|
||||
*/
|
||||
@@ -214,11 +204,6 @@ class MYNTEYE_API API {
|
||||
*/
|
||||
bool RunOptionAction(const Option &option) const;
|
||||
|
||||
/**
|
||||
* Init device resolution.
|
||||
*/
|
||||
void InitResolution(const Resolution &res);
|
||||
|
||||
/**
|
||||
* Set the callback of stream.
|
||||
*/
|
||||
@@ -294,8 +279,6 @@ class MYNTEYE_API API {
|
||||
std::shared_ptr<Device> device_;
|
||||
|
||||
std::unique_ptr<Synthetic> synthetic_;
|
||||
|
||||
void CheckImageParams();
|
||||
};
|
||||
|
||||
MYNTEYE_END_NAMESPACE
|
||||
|
||||
@@ -19,7 +19,6 @@
|
||||
|
||||
#include <algorithm>
|
||||
#include <functional>
|
||||
#include <map>
|
||||
#include <memory>
|
||||
#include <vector>
|
||||
|
||||
@@ -30,20 +29,6 @@ MYNTEYE_BEGIN_NAMESPACE
|
||||
|
||||
namespace device {
|
||||
|
||||
typedef struct ImgParams {
|
||||
bool ok;
|
||||
std::map<Resolution, Intrinsics> in_left_map;
|
||||
std::map<Resolution, Intrinsics> in_right_map;
|
||||
Extrinsics ex_right_to_left;
|
||||
} img_params_t;
|
||||
|
||||
typedef struct ImuParams {
|
||||
bool ok;
|
||||
ImuIntrinsics in_accel;
|
||||
ImuIntrinsics in_gyro;
|
||||
Extrinsics ex_left_to_imu;
|
||||
} imu_params_t;
|
||||
|
||||
/**
|
||||
* @ingroup datatypes
|
||||
* Frame with raw data.
|
||||
|
||||
@@ -66,9 +66,6 @@ class MYNTEYE_API Device {
|
||||
using stream_async_callback_ptr_t = std::shared_ptr<stream_async_callback_t>;
|
||||
using motion_async_callback_ptr_t = std::shared_ptr<motion_async_callback_t>;
|
||||
|
||||
using img_params_t = device::img_params_t;
|
||||
using imu_params_t = device::imu_params_t;
|
||||
|
||||
Device(const Model &model, std::shared_ptr<uvc::device> device);
|
||||
virtual ~Device();
|
||||
|
||||
@@ -104,14 +101,7 @@ class MYNTEYE_API Device {
|
||||
* Supports the addon or not.
|
||||
*/
|
||||
bool Supports(const AddOns &addon) const;
|
||||
/**
|
||||
* Init device resolution.
|
||||
*/
|
||||
void InitResolution(const Resolution &res);
|
||||
/**
|
||||
* set the stream request.
|
||||
*/
|
||||
void SetStreamRequest(const Format &format, const FrameRate &rate);
|
||||
|
||||
/**
|
||||
* Get all stream requests of the capability.
|
||||
*/
|
||||
@@ -263,10 +253,6 @@ class MYNTEYE_API Device {
|
||||
* Get the motion datas.
|
||||
*/
|
||||
std::vector<device::MotionData> GetMotionDatas();
|
||||
/**
|
||||
* Get the device img params
|
||||
*/
|
||||
img_params_t GetImgParams();
|
||||
|
||||
protected:
|
||||
std::shared_ptr<uvc::device> device() const {
|
||||
@@ -302,8 +288,6 @@ class MYNTEYE_API Device {
|
||||
|
||||
private:
|
||||
Model model_;
|
||||
Resolution res_ = Resolution::RES_752x480;
|
||||
StreamRequest request_;
|
||||
std::shared_ptr<uvc::device> device_;
|
||||
std::shared_ptr<DeviceInfo> device_info_;
|
||||
|
||||
@@ -313,7 +297,6 @@ class MYNTEYE_API Device {
|
||||
std::shared_ptr<MotionIntrinsics> motion_intrinsics_;
|
||||
std::map<Stream, Extrinsics> motion_from_extrinsics_;
|
||||
|
||||
img_params_t img_params_;
|
||||
stream_callbacks_t stream_callbacks_;
|
||||
motion_callback_t motion_callback_;
|
||||
|
||||
@@ -332,8 +315,6 @@ class MYNTEYE_API Device {
|
||||
|
||||
void ReadAllInfos();
|
||||
|
||||
void ConfigIntrinsics(const Resolution &res);
|
||||
|
||||
void CallbackPushedStreamData(const Stream &stream);
|
||||
void CallbackMotionData(const device::MotionData &data);
|
||||
|
||||
|
||||
@@ -76,8 +76,6 @@ enum class Capabilities : std::uint8_t {
|
||||
STEREO,
|
||||
/** Provides color stream */
|
||||
COLOR,
|
||||
/** Provide stereo color stream */
|
||||
STEREO_COLOR,
|
||||
/** Provides depth stream */
|
||||
DEPTH,
|
||||
/** Provides point cloud stream */
|
||||
@@ -165,19 +163,19 @@ enum class Option : std::uint8_t {
|
||||
/**
|
||||
* Max gain, valid if auto-exposure
|
||||
*
|
||||
* range: [0,255], default: 8
|
||||
* range: [0,48], default: 48
|
||||
*/
|
||||
MAX_GAIN,
|
||||
/**
|
||||
* Max exposure time, valid if auto-exposure
|
||||
*
|
||||
* range: [0,1000], default: 333
|
||||
* range: [0,240], default: 240
|
||||
*/
|
||||
MAX_EXPOSURE_TIME,
|
||||
/**
|
||||
* Desired brightness, valid if auto-exposure
|
||||
*
|
||||
* range: [1,255], default: 122
|
||||
* range: [0,255], default: 192
|
||||
*/
|
||||
DESIRED_BRIGHTNESS,
|
||||
/**
|
||||
@@ -197,36 +195,18 @@ enum class Option : std::uint8_t {
|
||||
ZERO_DRIFT_CALIBRATION,
|
||||
/** Erase chip */
|
||||
ERASE_CHIP,
|
||||
/**
|
||||
* min exposure time, valid if auto-exposure
|
||||
*
|
||||
* range: [0,1000], default: 0
|
||||
*/
|
||||
MIN_EXPOSURE_TIME,
|
||||
/**
|
||||
* The range of accelerometer
|
||||
*
|
||||
* values: {6,12,24,48}, default: 6
|
||||
* values: {4,8,16,32}, default: 8
|
||||
*/
|
||||
ACCELEROMETER_RANGE,
|
||||
/**
|
||||
* The range of gyroscope
|
||||
*
|
||||
* values: {250,500,1000,2000,4000}, default: 1000
|
||||
* values: {500,1000,2000,4000}, default: 1000
|
||||
*/
|
||||
GYROSCOPE_RANGE,
|
||||
/**
|
||||
* The parameter of accelerometer low pass filter
|
||||
*
|
||||
* values: {0,1,2}, default: 2
|
||||
*/
|
||||
ACCELEROMETER_LOW_PASS_FILTER,
|
||||
/**
|
||||
* The parameter of gyroscope low pass filter
|
||||
*
|
||||
* values: {23,64}, default: 64
|
||||
*/
|
||||
GYROSCOPE_LOW_PASS_FILTER,
|
||||
/** Last guard */
|
||||
LAST
|
||||
};
|
||||
@@ -259,40 +239,6 @@ enum class AddOns : std::uint8_t {
|
||||
LAST
|
||||
};
|
||||
|
||||
/**
|
||||
* @ingroup enumerations
|
||||
* @brief Camera supported resolution.
|
||||
*/
|
||||
enum class Resolution : std::uint8_t {
|
||||
/** 752x480 */
|
||||
RES_752x480,
|
||||
/** 1280x400 */
|
||||
RES_1280x400,
|
||||
/** 2560x800 */
|
||||
RES_2560x800,
|
||||
/** Last guard */
|
||||
LAST
|
||||
};
|
||||
|
||||
/**
|
||||
* @ingroup enumerations
|
||||
* @brief Camera supported frame rate.
|
||||
*/
|
||||
enum class FrameRate : std::uint8_t {
|
||||
/** 10 fps */
|
||||
RATE_10_FPS = 10,
|
||||
/** 20 fps */
|
||||
RATE_20_FPS = 20,
|
||||
/** 20 fps */
|
||||
RATE_25_FPS = 25,
|
||||
/** 30 fps */
|
||||
RATE_30_FPS = 30,
|
||||
/** 60 fps */
|
||||
RATE_60_FPS = 60,
|
||||
/** Last guard */
|
||||
LAST
|
||||
};
|
||||
|
||||
#define MYNTEYE_ENUM_HELPERS(TYPE) \
|
||||
MYNTEYE_API const char *to_string(const TYPE &value); \
|
||||
inline bool is_valid(const TYPE &value) { \
|
||||
@@ -316,8 +262,6 @@ MYNTEYE_ENUM_HELPERS(Info)
|
||||
MYNTEYE_ENUM_HELPERS(Option)
|
||||
MYNTEYE_ENUM_HELPERS(Source)
|
||||
MYNTEYE_ENUM_HELPERS(AddOns)
|
||||
MYNTEYE_ENUM_HELPERS(Resolution)
|
||||
MYNTEYE_ENUM_HELPERS(FrameRate)
|
||||
|
||||
#undef MYNTEYE_ENUM_HELPERS
|
||||
|
||||
@@ -334,8 +278,6 @@ enum class Format : std::uint32_t {
|
||||
GREY = MYNTEYE_FOURCC('G', 'R', 'E', 'Y'),
|
||||
/** YUV 4:2:2, 16 bits per pixel */
|
||||
YUYV = MYNTEYE_FOURCC('Y', 'U', 'Y', 'V'),
|
||||
/** BGR 8:8:8, 24 bits per pixel */
|
||||
BGR888 = MYNTEYE_FOURCC('B', 'G', 'R', '3'),
|
||||
/** Last guard */
|
||||
LAST
|
||||
};
|
||||
@@ -363,33 +305,6 @@ struct MYNTEYE_API StreamRequest {
|
||||
/** Stream frames per second (unused) */
|
||||
std::uint16_t fps;
|
||||
|
||||
StreamRequest() {}
|
||||
|
||||
StreamRequest(
|
||||
std::uint16_t width, std::uint16_t height, Format format,
|
||||
std::uint16_t fps)
|
||||
: width(width), height(height), format(format), fps(fps) {}
|
||||
|
||||
StreamRequest(Resolution res, Format format, FrameRate rate)
|
||||
: format(format) {
|
||||
fps = static_cast<uint16_t>(rate);
|
||||
|
||||
switch (res) {
|
||||
case Resolution::RES_752x480:
|
||||
width = 480, height = 752;
|
||||
break;
|
||||
case Resolution::RES_1280x400:
|
||||
width = 1280, height = 400;
|
||||
break;
|
||||
case Resolution::RES_2560x800:
|
||||
width = 2560, height = 800;
|
||||
break;
|
||||
default:
|
||||
width = 480, height = 752;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
bool operator==(const StreamRequest &other) const {
|
||||
return width == other.width && height == other.height &&
|
||||
format == other.format && fps == other.fps;
|
||||
@@ -506,8 +421,8 @@ std::ostream &operator<<(std::ostream &os, const Extrinsics &ex);
|
||||
struct MYNTEYE_API ImgData {
|
||||
/** Image frame id */
|
||||
std::uint16_t frame_id;
|
||||
/** Image timestamp in 1us */
|
||||
std::uint64_t timestamp;
|
||||
/** Image timestamp in 0.01ms */
|
||||
std::uint32_t timestamp;
|
||||
/** Image exposure time, virtual value in [1, 480] */
|
||||
std::uint16_t exposure_time;
|
||||
|
||||
@@ -538,12 +453,10 @@ struct MYNTEYE_API ImgData {
|
||||
* IMU data.
|
||||
*/
|
||||
struct MYNTEYE_API ImuData {
|
||||
/** Imu serial number */
|
||||
std::uint32_t serial_number;
|
||||
/** accel or gyro flag:1 for accel,2 for gyro,3 for both */
|
||||
std::uint8_t flag;
|
||||
/** IMU timestamp in 1us */
|
||||
std::uint64_t timestamp;
|
||||
/** Image frame id */
|
||||
std::uint16_t frame_id;
|
||||
/** IMU timestamp in 0.01ms */
|
||||
std::uint32_t timestamp;
|
||||
/** IMU accelerometer data for 3-axis: X, Y, Z. */
|
||||
double accel[3];
|
||||
/** IMU gyroscope data for 3-axis: X, Y, Z. */
|
||||
@@ -552,7 +465,7 @@ struct MYNTEYE_API ImuData {
|
||||
double temperature;
|
||||
|
||||
void Reset() {
|
||||
flag = 0;
|
||||
frame_id = 0;
|
||||
timestamp = 0;
|
||||
std::fill(accel, accel + 3, 0);
|
||||
std::fill(gyro, gyro + 3, 0);
|
||||
|
||||
@@ -13,8 +13,6 @@
|
||||
# limitations under the License.
|
||||
|
||||
@PACKAGE_INIT@
|
||||
set(mynteye_WITH_API @WITH_API@)
|
||||
set(mynteye_WITH_GLOG @WITH_GLOG@)
|
||||
|
||||
set(mynteye_WITH_API @WITH_API@)
|
||||
set(mynteye_WITH_GLOG @WITH_GLOG@)
|
||||
|
||||
@@ -53,10 +53,6 @@ message(STATUS "Found mynteye: ${mynteye_VERSION}")
|
||||
|
||||
include(${PRO_DIR}/cmake/DetectOpenCV.cmake)
|
||||
|
||||
if(mynteye_WITH_GLOG)
|
||||
include(${PRO_DIR}/cmake/DetectGLog.cmake)
|
||||
endif()
|
||||
|
||||
#LIST(APPEND CMAKE_MODULE_PATH ${PRO_DIR}/cmake)
|
||||
|
||||
# targets
|
||||
|
||||
@@ -23,7 +23,10 @@ int main(int argc, char *argv[]) {
|
||||
auto &&api = API::Create(argc, argv);
|
||||
if (!api)
|
||||
return 1;
|
||||
api->SetStreamRequest(Format::BGR888, FrameRate::RATE_30_FPS);
|
||||
|
||||
// api->SetOptionValue(Option::FRAME_RATE, 25);
|
||||
// api->SetOptionValue(Option::IMU_FREQUENCY, 500);
|
||||
api->SetOptionValue(Option::IR_CONTROL, 80);
|
||||
api->LogOptionInfos();
|
||||
|
||||
std::size_t left_count = 0;
|
||||
@@ -52,7 +55,8 @@ int main(int argc, char *argv[]) {
|
||||
CHECK_NOTNULL(data.imu);
|
||||
++imu_count;
|
||||
VLOG(2) << "Imu count: " << imu_count;
|
||||
VLOG(2) << ", timestamp: " << data.imu->timestamp
|
||||
VLOG(2) << " frame_id: " << data.imu->frame_id
|
||||
<< ", timestamp: " << data.imu->timestamp
|
||||
<< ", accel_x: " << data.imu->accel[0]
|
||||
<< ", accel_y: " << data.imu->accel[1]
|
||||
<< ", accel_z: " << data.imu->accel[2]
|
||||
@@ -102,7 +106,8 @@ int main(int argc, char *argv[]) {
|
||||
auto &&motion_datas = api->GetMotionDatas();
|
||||
motion_count += motion_datas.size();
|
||||
for (auto &&data : motion_datas) {
|
||||
LOG(INFO) << ", timestamp: " << data.imu->timestamp
|
||||
LOG(INFO) << "Imu frame_id: " << data.imu->frame_id
|
||||
<< ", timestamp: " << data.imu->timestamp
|
||||
<< ", accel_x: " << data.imu->accel[0]
|
||||
<< ", accel_y: " << data.imu->accel[1]
|
||||
<< ", accel_z: " << data.imu->accel[2]
|
||||
|
||||
@@ -14,10 +14,6 @@
|
||||
|
||||
get_filename_component(DIR_NAME ${CMAKE_CURRENT_LIST_DIR} NAME)
|
||||
|
||||
include_directories(
|
||||
${PRO_DIR}/src
|
||||
)
|
||||
|
||||
set_outdir(
|
||||
"${OUT_DIR}/lib/${DIR_NAME}"
|
||||
"${OUT_DIR}/lib/${DIR_NAME}"
|
||||
|
||||
@@ -27,15 +27,33 @@ int main(int argc, char *argv[]) {
|
||||
auto &&device = device::select();
|
||||
if (!device)
|
||||
return 1;
|
||||
/*
|
||||
{ // auto-exposure
|
||||
device->SetOptionValue(Option::EXPOSURE_MODE, 0);
|
||||
device->SetOptionValue(Option::MAX_GAIN, 40); // [0.48]
|
||||
device->SetOptionValue(Option::MAX_EXPOSURE_TIME, 120); // [0,240]
|
||||
device->SetOptionValue(Option::DESIRED_BRIGHTNESS, 200); // [0,255]
|
||||
}
|
||||
{ // manual-exposure
|
||||
device->SetOptionValue(Option::EXPOSURE_MODE, 1);
|
||||
device->SetOptionValue(Option::GAIN, 20); // [0.48]
|
||||
device->SetOptionValue(Option::BRIGHTNESS, 20); // [0,240]
|
||||
device->SetOptionValue(Option::CONTRAST, 20); // [0,255]
|
||||
}
|
||||
device->SetOptionValue(Option::IR_CONTROL, 80);
|
||||
device->SetOptionValue(Option::FRAME_RATE, 25);
|
||||
device->SetOptionValue(Option::IMU_FREQUENCY, 500);
|
||||
*/
|
||||
device->LogOptionInfos();
|
||||
|
||||
// device->RunOptionAction(Option::ZERO_DRIFT_CALIBRATION);
|
||||
|
||||
std::size_t left_count = 0;
|
||||
device->InitResolution(Resolution::RES_1280x400);
|
||||
device->SetStreamRequest(Format::BGR888, FrameRate::RATE_30_FPS);
|
||||
device->SetStreamCallback(
|
||||
Stream::LEFT, [&left_count](const device::StreamData &data) {
|
||||
CHECK_NOTNULL(data.img);
|
||||
++left_count;
|
||||
VLOG(2) << Stream::LEFT << "count: " << left_count;
|
||||
VLOG(2) << Stream::LEFT << ", count: " << left_count;
|
||||
VLOG(2) << " frame_id: " << data.img->frame_id
|
||||
<< ", timestamp: " << data.img->timestamp
|
||||
<< ", exposure_time: " << data.img->exposure_time;
|
||||
@@ -45,19 +63,19 @@ int main(int argc, char *argv[]) {
|
||||
Stream::RIGHT, [&right_count](const device::StreamData &data) {
|
||||
CHECK_NOTNULL(data.img);
|
||||
++right_count;
|
||||
VLOG(2) << Stream::RIGHT << "count: " << right_count;
|
||||
VLOG(2) << Stream::RIGHT << ", count: " << right_count;
|
||||
VLOG(2) << " frame_id: " << data.img->frame_id
|
||||
<< ", timestamp: " << data.img->timestamp
|
||||
<< ", exposure_time: " << data.img->exposure_time;
|
||||
});
|
||||
|
||||
std::size_t imu_count = 0;
|
||||
|
||||
device->SetMotionCallback([&imu_count](const device::MotionData &data) {
|
||||
CHECK_NOTNULL(data.imu);
|
||||
++imu_count;
|
||||
VLOG(2) << "Imu count: " << imu_count;
|
||||
VLOG(2) << ", timestamp: " << data.imu->timestamp
|
||||
VLOG(2) << " frame_id: " << data.imu->frame_id
|
||||
<< ", timestamp: " << data.imu->timestamp
|
||||
<< ", accel_x: " << data.imu->accel[0]
|
||||
<< ", accel_y: " << data.imu->accel[1]
|
||||
<< ", accel_z: " << data.imu->accel[2]
|
||||
@@ -70,6 +88,7 @@ int main(int argc, char *argv[]) {
|
||||
// Enable this will cache the motion datas until you get them.
|
||||
device->EnableMotionDatas();
|
||||
device->Start(Source::ALL);
|
||||
|
||||
cv::namedWindow("frame");
|
||||
|
||||
std::size_t motion_count = 0;
|
||||
@@ -83,7 +102,8 @@ int main(int argc, char *argv[]) {
|
||||
auto &&motion_datas = device->GetMotionDatas();
|
||||
motion_count += motion_datas.size();
|
||||
for (auto &&data : motion_datas) {
|
||||
LOG(INFO) << "timestamp: " << data.imu->timestamp
|
||||
LOG(INFO) << "Imu frame_id: " << data.imu->frame_id
|
||||
<< ", timestamp: " << data.imu->timestamp
|
||||
<< ", accel_x: " << data.imu->accel[0]
|
||||
<< ", accel_y: " << data.imu->accel[1]
|
||||
<< ", accel_z: " << data.imu->accel[2]
|
||||
@@ -93,41 +113,15 @@ int main(int argc, char *argv[]) {
|
||||
<< ", temperature: " << data.imu->temperature;
|
||||
}
|
||||
|
||||
cv::Mat img;
|
||||
|
||||
// TODO(Kalman): Extract into public or internal method
|
||||
if (left_data.frame->format() == Format::GREY) {
|
||||
cv::Mat left_img(
|
||||
left_data.frame->height(), left_data.frame->width(), CV_8UC1,
|
||||
left_data.frame->data());
|
||||
cv::Mat right_img(
|
||||
right_data.frame->height(), right_data.frame->width(), CV_8UC1,
|
||||
right_data.frame->data());
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else if (left_data.frame->format() == Format::YUYV) {
|
||||
cv::Mat left_img(
|
||||
left_data.frame->height(), left_data.frame->width(), CV_8UC2,
|
||||
left_data.frame->data());
|
||||
cv::Mat right_img(
|
||||
right_data.frame->height(), right_data.frame->width(), CV_8UC2,
|
||||
right_data.frame->data());
|
||||
cv::cvtColor(left_img, left_img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::cvtColor(right_img, right_img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else if (left_data.frame->format() == Format::BGR888) {
|
||||
cv::Mat left_img(
|
||||
left_data.frame->height(), left_data.frame->width(), CV_8UC3,
|
||||
left_data.frame->data());
|
||||
cv::Mat right_img(
|
||||
right_data.frame->height(), right_data.frame->width(), CV_8UC3,
|
||||
right_data.frame->data());
|
||||
cv::cvtColor(left_img, left_img, CV_BGR2RGB);
|
||||
cv::cvtColor(right_img, right_img, CV_BGR2RGB);
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else {
|
||||
return -1;
|
||||
}
|
||||
|
||||
cv::Mat img;
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
cv::imshow("frame", img);
|
||||
|
||||
char key = static_cast<char>(cv::waitKey(1));
|
||||
@@ -150,7 +144,7 @@ int main(int argc, char *argv[]) {
|
||||
<< ", fps: " << (1000.f * right_count / elapsed_ms);
|
||||
LOG(INFO) << "Imu count: " << imu_count
|
||||
<< ", hz: " << (1000.f * imu_count / elapsed_ms);
|
||||
LOG(INFO) << "Motion count: " << motion_count
|
||||
<< ", hz: " << (1000.f * motion_count / elapsed_ms);
|
||||
// LOG(INFO) << "Motion count: " << motion_count
|
||||
// << ", hz: " << (1000.f * motion_count / elapsed_ms);
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -16,7 +16,6 @@ get_filename_component(DIR_NAME ${CMAKE_CURRENT_LIST_DIR} NAME)
|
||||
|
||||
include_directories(
|
||||
${CMAKE_CURRENT_SOURCE_DIR}
|
||||
${PRO_DIR}/src
|
||||
)
|
||||
|
||||
set_outdir(
|
||||
@@ -124,6 +123,7 @@ make_executable2(ctrl_manual_exposure
|
||||
SRCS control/manual_exposure.cc util/cv_painter.cc
|
||||
WITH_OPENCV
|
||||
)
|
||||
make_executable2(ctrl_infrared SRCS control/infrared.cc WITH_OPENCV)
|
||||
|
||||
# intermediate level
|
||||
|
||||
|
||||
@@ -24,19 +24,16 @@ int main(int argc, char *argv[]) {
|
||||
auto &&api = API::Create(argc, argv);
|
||||
if (!api)
|
||||
return 1;
|
||||
api->SetStreamRequest(Format::BGR888, FrameRate::RATE_30_FPS);
|
||||
|
||||
// auto-exposure: 0
|
||||
api->SetOptionValue(Option::EXPOSURE_MODE, 0);
|
||||
|
||||
// max_gain: range [0,255], default 8
|
||||
api->SetOptionValue(Option::MAX_GAIN, 8);
|
||||
// max_exposure_time: range [0,1000], default 333
|
||||
api->SetOptionValue(Option::MAX_EXPOSURE_TIME, 333);
|
||||
// desired_brightness: range [1,255], default 122
|
||||
api->SetOptionValue(Option::DESIRED_BRIGHTNESS, 122);
|
||||
// min_exposure_time: range [0,1000], default 0
|
||||
api->SetOptionValue(Option::MIN_EXPOSURE_TIME, 0);
|
||||
// max_gain: range [0,48], default 48
|
||||
api->SetOptionValue(Option::MAX_GAIN, 48);
|
||||
// max_exposure_time: range [0,240], default 240
|
||||
api->SetOptionValue(Option::MAX_EXPOSURE_TIME, 240);
|
||||
// desired_brightness: range [0,255], default 192
|
||||
api->SetOptionValue(Option::DESIRED_BRIGHTNESS, 192);
|
||||
|
||||
LOG(INFO) << "Enable auto-exposure";
|
||||
LOG(INFO) << "Set MAX_GAIN to " << api->GetOptionValue(Option::MAX_GAIN);
|
||||
@@ -44,12 +41,10 @@ int main(int argc, char *argv[]) {
|
||||
<< api->GetOptionValue(Option::MAX_EXPOSURE_TIME);
|
||||
LOG(INFO) << "Set DESIRED_BRIGHTNESS to "
|
||||
<< api->GetOptionValue(Option::DESIRED_BRIGHTNESS);
|
||||
LOG(INFO) << "Set MIN_EXPOSURE_TIME to "
|
||||
<< api->GetOptionValue(Option::MIN_EXPOSURE_TIME);
|
||||
|
||||
api->Start(Source::VIDEO_STREAMING);
|
||||
|
||||
CVPainter painter(30);
|
||||
CVPainter painter(api->GetOptionValue(Option::FRAME_RATE));
|
||||
|
||||
cv::namedWindow("frame");
|
||||
|
||||
|
||||
@@ -22,11 +22,22 @@
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
int main(int argc, char *argv[]) {
|
||||
auto &&api = API::Create(Resolution::RES_1280x400);
|
||||
// auto &&api = API::Create(argc, argv);
|
||||
auto &&api = API::Create(argc, argv);
|
||||
if (!api)
|
||||
return 1;
|
||||
api->SetStreamRequest(Format::BGR888, FrameRate::RATE_30_FPS);
|
||||
|
||||
// Attention: must set FRAME_RATE and IMU_FREQUENCY together, otherwise won't
|
||||
// succeed.
|
||||
|
||||
// FRAME_RATE values: 10, 15, 20, 25, 30, 35, 40, 45, 50, 55, 60
|
||||
api->SetOptionValue(Option::FRAME_RATE, 25);
|
||||
// IMU_FREQUENCY values: 100, 200, 250, 333, 500
|
||||
api->SetOptionValue(Option::IMU_FREQUENCY, 500);
|
||||
|
||||
LOG(INFO) << "Set FRAME_RATE to " << api->GetOptionValue(Option::FRAME_RATE);
|
||||
LOG(INFO) << "Set IMU_FREQUENCY to "
|
||||
<< api->GetOptionValue(Option::IMU_FREQUENCY);
|
||||
|
||||
// Count img
|
||||
std::atomic_uint img_count(0);
|
||||
api->SetStreamCallback(
|
||||
@@ -35,6 +46,13 @@ int main(int argc, char *argv[]) {
|
||||
++img_count;
|
||||
});
|
||||
|
||||
// Count imu
|
||||
std::atomic_uint imu_count(0);
|
||||
api->SetMotionCallback([&imu_count](const api::MotionData &data) {
|
||||
CHECK_NOTNULL(data.imu);
|
||||
++imu_count;
|
||||
});
|
||||
|
||||
api->Start(Source::ALL);
|
||||
|
||||
cv::namedWindow("frame");
|
||||
@@ -67,5 +85,7 @@ int main(int argc, char *argv[]) {
|
||||
<< ", cost: " << elapsed_ms << "ms";
|
||||
LOG(INFO) << "Img count: " << img_count
|
||||
<< ", fps: " << (1000.f * img_count / elapsed_ms);
|
||||
LOG(INFO) << "Imu count: " << imu_count
|
||||
<< ", hz: " << (1000.f * imu_count / elapsed_ms);
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -26,9 +26,9 @@ int main(int argc, char *argv[]) {
|
||||
if (!api)
|
||||
return 1;
|
||||
|
||||
// ACCELEROMETER_RANGE values: 6, 12, 24, 32
|
||||
api->SetOptionValue(Option::ACCELEROMETER_RANGE, 6);
|
||||
// GYROSCOPE_RANGE values: 250, 500, 1000, 2000, 4000
|
||||
// ACCELEROMETER_RANGE values: 4, 8, 16, 32
|
||||
api->SetOptionValue(Option::ACCELEROMETER_RANGE, 8);
|
||||
// GYROSCOPE_RANGE values: 500, 1000, 2000, 4000
|
||||
api->SetOptionValue(Option::GYROSCOPE_RANGE, 1000);
|
||||
|
||||
LOG(INFO) << "Set ACCELEROMETER_RANGE to "
|
||||
|
||||
61
samples/tutorials/control/infrared.cc
Normal file
61
samples/tutorials/control/infrared.cc
Normal file
@@ -0,0 +1,61 @@
|
||||
// Copyright 2018 Slightech Co., Ltd. All rights reserved.
|
||||
//
|
||||
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||
// you may not use this file except in compliance with the License.
|
||||
// You may obtain a copy of the License at
|
||||
//
|
||||
// http://www.apache.org/licenses/LICENSE-2.0
|
||||
//
|
||||
// Unless required by applicable law or agreed to in writing, software
|
||||
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
// See the License for the specific language governing permissions and
|
||||
// limitations under the License.
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/api/api.h"
|
||||
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
int main(int argc, char *argv[]) {
|
||||
auto &&api = API::Create(argc, argv);
|
||||
if (!api)
|
||||
return 1;
|
||||
|
||||
// Detect infrared add-ons
|
||||
LOG(INFO) << "Support infrared: " << std::boolalpha
|
||||
<< api->Supports(AddOns::INFRARED);
|
||||
LOG(INFO) << "Support infrared2: " << std::boolalpha
|
||||
<< api->Supports(AddOns::INFRARED2);
|
||||
|
||||
// Get infrared intensity range
|
||||
auto &&info = api->GetOptionInfo(Option::IR_CONTROL);
|
||||
LOG(INFO) << Option::IR_CONTROL << ": {" << info << "}";
|
||||
|
||||
// Set infrared intensity value
|
||||
api->SetOptionValue(Option::IR_CONTROL, 80);
|
||||
|
||||
api->Start(Source::VIDEO_STREAMING);
|
||||
|
||||
cv::namedWindow("frame");
|
||||
|
||||
while (true) {
|
||||
api->WaitForStreams();
|
||||
|
||||
auto &&left_data = api->GetStreamData(Stream::LEFT);
|
||||
auto &&right_data = api->GetStreamData(Stream::RIGHT);
|
||||
|
||||
cv::Mat img;
|
||||
cv::hconcat(left_data.frame, right_data.frame, img);
|
||||
cv::imshow("frame", img);
|
||||
|
||||
char key = static_cast<char>(cv::waitKey(1));
|
||||
if (key == 27 || key == 'q' || key == 'Q') { // ESC/Q
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
api->Stop(Source::VIDEO_STREAMING);
|
||||
return 0;
|
||||
}
|
||||
@@ -24,20 +24,25 @@ int main(int argc, char *argv[]) {
|
||||
auto &&api = API::Create(argc, argv);
|
||||
if (!api)
|
||||
return 1;
|
||||
api->SetStreamRequest(Format::BGR888, FrameRate::RATE_30_FPS);
|
||||
|
||||
// manual-exposure: 1
|
||||
api->SetOptionValue(Option::EXPOSURE_MODE, 1);
|
||||
|
||||
// gain: range [0,48], default 24
|
||||
api->SetOptionValue(Option::GAIN, 24);
|
||||
// brightness/exposure_time: range [0,240], default 120
|
||||
api->SetOptionValue(Option::BRIGHTNESS, 120);
|
||||
// contrast/black_level_calibration: range [0,255], default 127
|
||||
api->SetOptionValue(Option::CONTRAST, 127);
|
||||
|
||||
LOG(INFO) << "Enable manual-exposure";
|
||||
LOG(INFO) << "Set GAIN to " << api->GetOptionValue(Option::GAIN);
|
||||
LOG(INFO) << "Set BRIGHTNESS to " << api->GetOptionValue(Option::BRIGHTNESS);
|
||||
LOG(INFO) << "Set CONTRAST to " << api->GetOptionValue(Option::CONTRAST);
|
||||
|
||||
api->Start(Source::VIDEO_STREAMING);
|
||||
|
||||
CVPainter painter(30);
|
||||
CVPainter painter(api->GetOptionValue(Option::FRAME_RATE));
|
||||
|
||||
cv::namedWindow("frame");
|
||||
|
||||
|
||||
@@ -20,7 +20,7 @@ int main(int argc, char *argv[]) {
|
||||
auto &&api = API::Create(argc, argv);
|
||||
if (!api)
|
||||
return 1;
|
||||
api->SetStreamRequest(Format::BGR888, FrameRate::RATE_30_FPS);
|
||||
|
||||
LOG(INFO) << "Intrinsics left: {" << api->GetIntrinsics(Stream::LEFT) << "}";
|
||||
LOG(INFO) << "Intrinsics right: {" << api->GetIntrinsics(Stream::RIGHT)
|
||||
<< "}";
|
||||
|
||||
@@ -117,7 +117,7 @@ cv::Rect CVPainter::DrawImuData(
|
||||
if (gravity == BOTTOM_LEFT || gravity == BOTTOM_RIGHT)
|
||||
sign = -1;
|
||||
|
||||
Clear(ss) << "stamp: " << data.timestamp
|
||||
Clear(ss) << "frame_id: " << data.frame_id << ", stamp: " << data.timestamp
|
||||
<< ", temp: " << fmt_temp << data.temperature;
|
||||
cv::Rect rect_i = DrawText(img, ss.str(), gravity, 5);
|
||||
|
||||
|
||||
@@ -108,7 +108,7 @@ int main(int argc, char *argv[]) {
|
||||
const auto frame_empty = [&frame]() { return frame == nullptr; };
|
||||
|
||||
uvc::set_device_mode(
|
||||
*device, 1280, 400, static_cast<int>(Format::BGR888), 20,
|
||||
*device, 752, 480, static_cast<int>(Format::YUYV), 25,
|
||||
[&mtx, &cv, &frame, &frame_ready](
|
||||
const void *data, std::function<void()> continuation) {
|
||||
// reinterpret_cast<const std::uint8_t *>(data);
|
||||
@@ -143,8 +143,8 @@ int main(int argc, char *argv[]) {
|
||||
}
|
||||
|
||||
// only lastest frame is valid
|
||||
cv::Mat img(400, 1280, CV_8UC3, const_cast<void *>(frame->data));
|
||||
cv::cvtColor(img, img, CV_BGR2RGB);
|
||||
cv::Mat img(480, 752, CV_8UC2, const_cast<void *>(frame->data));
|
||||
cv::cvtColor(img, img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::imshow("frame", img);
|
||||
|
||||
frame = nullptr;
|
||||
|
||||
@@ -16,12 +16,12 @@
|
||||
#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__)
|
||||
#define GLOG_NO_ABBREVIATED_SEVERITIES
|
||||
#endif
|
||||
#include <glog/logging.h>
|
||||
|
||||
#ifdef HAVE_LIB_GFLAGS
|
||||
#include <gflags/gflags.h>
|
||||
#endif
|
||||
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/mynteye.h"
|
||||
|
||||
int main(int /*argc*/, char *argv[]) {
|
||||
|
||||
@@ -210,7 +210,26 @@ std::vector<std::string> get_plugin_paths() {
|
||||
|
||||
API::API(std::shared_ptr<Device> device) : device_(device) {
|
||||
VLOG(2) << __func__;
|
||||
std::dynamic_pointer_cast<StandardDevice>(device_);
|
||||
if (std::dynamic_pointer_cast<StandardDevice>(device_) != nullptr) {
|
||||
bool in_l_ok, in_r_ok, ex_r2l_ok;
|
||||
device_->GetIntrinsics(Stream::LEFT, &in_l_ok);
|
||||
device_->GetIntrinsics(Stream::RIGHT, &in_r_ok);
|
||||
device_->GetExtrinsics(Stream::RIGHT, Stream::LEFT, &ex_r2l_ok);
|
||||
if (!in_l_ok || !in_r_ok || !ex_r2l_ok) {
|
||||
#if defined(WITH_DEVICE_INFO_REQUIRED)
|
||||
LOG(FATAL)
|
||||
#else
|
||||
LOG(WARNING)
|
||||
#endif
|
||||
<< "Image params not found, but we need it to process the "
|
||||
"images. Please `make tools` and use `img_params_writer` "
|
||||
"to write the image params. If you update the SDK from "
|
||||
"1.x, the `SN*.conf` is the file contains them. Besides, "
|
||||
"you could also calibrate them by yourself. Read the guide "
|
||||
"doc (https://github.com/slightech/MYNT-EYE-S-SDK-Guide) "
|
||||
"to learn more.";
|
||||
}
|
||||
}
|
||||
synthetic_.reset(new Synthetic(this));
|
||||
}
|
||||
|
||||
@@ -218,52 +237,29 @@ API::~API() {
|
||||
VLOG(2) << __func__;
|
||||
}
|
||||
|
||||
std::shared_ptr<API> API::Create(Resolution res) {
|
||||
auto &&device = device::select();
|
||||
if (!device)
|
||||
return nullptr;
|
||||
device->InitResolution(res);
|
||||
return std::make_shared<API>(device);
|
||||
std::shared_ptr<API> API::Create() {
|
||||
return Create(device::select());
|
||||
}
|
||||
|
||||
std::shared_ptr<API> API::Create(
|
||||
std::shared_ptr<Device> device, Resolution res) {
|
||||
if (!device)
|
||||
return nullptr;
|
||||
device->InitResolution(res);
|
||||
return std::make_shared<API>(device);
|
||||
}
|
||||
|
||||
// TODO(Kalman): Compatible with two generation
|
||||
std::shared_ptr<API> API::Create(std::shared_ptr<Device> device) {
|
||||
return Create(device, Resolution::RES_2560x800);
|
||||
if (!device)
|
||||
return nullptr;
|
||||
return std::make_shared<API>(device);
|
||||
}
|
||||
|
||||
std::shared_ptr<API> API::Create(int argc, char *argv[]) {
|
||||
static glog_init _(argc, argv);
|
||||
auto &&device = device::select();
|
||||
return Create(argc, argv, device);
|
||||
if (!device)
|
||||
return nullptr;
|
||||
return std::make_shared<API>(device);
|
||||
}
|
||||
|
||||
// TODO(Kalman): Compatible with two generation
|
||||
std::shared_ptr<API> API::Create(
|
||||
int argc, char *argv[], std::shared_ptr<Device> device) {
|
||||
static glog_init _(argc, argv);
|
||||
int index = 0;
|
||||
if (argc >= 2) {
|
||||
try {
|
||||
index = std::stoi(argv[1]);
|
||||
} catch (...) {
|
||||
LOG(WARNING) << "Unexpected index.";
|
||||
}
|
||||
}
|
||||
if (!device)
|
||||
return nullptr;
|
||||
if (index == 0)
|
||||
device->InitResolution(Resolution::RES_1280x400);
|
||||
else if (index == 1)
|
||||
device->InitResolution(Resolution::RES_2560x800);
|
||||
else
|
||||
device->InitResolution(Resolution::RES_1280x400);
|
||||
return std::make_shared<API>(device);
|
||||
}
|
||||
|
||||
@@ -287,14 +283,6 @@ bool API::Supports(const AddOns &addon) const {
|
||||
return device_->Supports(addon);
|
||||
}
|
||||
|
||||
void API::InitResolution(const Resolution &res) {
|
||||
return device_->InitResolution(res);
|
||||
}
|
||||
|
||||
void API::SetStreamRequest(const Format &format, const FrameRate &rate) {
|
||||
device_->SetStreamRequest(format, rate);
|
||||
}
|
||||
|
||||
const std::vector<StreamRequest> &API::GetStreamRequests(
|
||||
const Capabilities &capability) const {
|
||||
return device_->GetStreamRequests(capability);
|
||||
@@ -462,23 +450,4 @@ std::shared_ptr<Device> API::device() {
|
||||
return device_;
|
||||
}
|
||||
|
||||
// TODO(Kalman): Call this function in the appropriate place
|
||||
void API::CheckImageParams() {
|
||||
if (device_ != nullptr) {
|
||||
bool in_l_ok, in_r_ok, ex_l2r_ok;
|
||||
device_->GetIntrinsics(Stream::LEFT, &in_l_ok);
|
||||
device_->GetIntrinsics(Stream::RIGHT, &in_r_ok);
|
||||
device_->GetExtrinsics(Stream::LEFT, Stream::RIGHT, &ex_l2r_ok);
|
||||
if (!in_l_ok || !in_r_ok || !ex_l2r_ok) {
|
||||
LOG(FATAL) << "Image params not found, but we need it to process the "
|
||||
"images. Please `make tools` and use `img_params_writer` "
|
||||
"to write the image params. If you update the SDK from "
|
||||
"1.x, the `SN*.conf` is the file contains them. Besides, "
|
||||
"you could also calibrate them by yourself. Read the guide "
|
||||
"doc (https://github.com/slightech/MYNT-EYE-SDK-2-Guide) "
|
||||
"to learn more.";
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
MYNTEYE_END_NAMESPACE
|
||||
|
||||
@@ -17,8 +17,6 @@
|
||||
#include <functional>
|
||||
#include <stdexcept>
|
||||
|
||||
#include <opencv2/imgproc/imgproc.hpp>
|
||||
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/api/object.h"
|
||||
#include "mynteye/api/plugin.h"
|
||||
@@ -41,17 +39,9 @@ MYNTEYE_BEGIN_NAMESPACE
|
||||
namespace {
|
||||
|
||||
cv::Mat frame2mat(const std::shared_ptr<device::Frame> &frame) {
|
||||
if (frame->format() == Format::YUYV) {
|
||||
cv::Mat img(frame->height(), frame->width(), CV_8UC2, frame->data());
|
||||
cv::cvtColor(img, img, cv::COLOR_YUV2BGR_YUY2);
|
||||
return img;
|
||||
} else if (frame->format() == Format::BGR888) {
|
||||
cv::Mat img(frame->height(), frame->width(), CV_8UC3, frame->data());
|
||||
cv::cvtColor(img, img, CV_BGR2RGB);
|
||||
return img;
|
||||
} else {
|
||||
// TODO(JohnZhao) Support different format frame to cv::Mat
|
||||
CHECK_EQ(frame->format(), Format::GREY);
|
||||
return cv::Mat(frame->height(), frame->width(), CV_8UC1, frame->data());
|
||||
}
|
||||
}
|
||||
|
||||
api::StreamData data2api(const device::StreamData &data) {
|
||||
|
||||
@@ -24,8 +24,6 @@
|
||||
#include "mynteye/util/strings.h"
|
||||
#include "mynteye/util/times.h"
|
||||
|
||||
#include "mynteye/logger.h"
|
||||
|
||||
#define IMU_TRACK_PERIOD 25 // ms
|
||||
|
||||
MYNTEYE_BEGIN_NAMESPACE
|
||||
@@ -65,21 +63,12 @@ int XuCamCtrlId(Option option) {
|
||||
case Option::FRAME_RATE:
|
||||
return 7;
|
||||
break;
|
||||
case Option::MIN_EXPOSURE_TIME:
|
||||
return 8;
|
||||
break;
|
||||
case Option::ACCELEROMETER_RANGE:
|
||||
return 9;
|
||||
break;
|
||||
case Option::GYROSCOPE_RANGE:
|
||||
return 10;
|
||||
break;
|
||||
case Option::ACCELEROMETER_LOW_PASS_FILTER:
|
||||
return 11;
|
||||
break;
|
||||
case Option::GYROSCOPE_LOW_PASS_FILTER:
|
||||
return 12;
|
||||
break;
|
||||
default:
|
||||
LOG(FATAL) << "No cam ctrl id for " << option;
|
||||
}
|
||||
@@ -103,7 +92,7 @@ void CheckSpecVersion(const Version *spec_version) {
|
||||
LOG(FATAL) << "Spec version must be specified";
|
||||
}
|
||||
|
||||
std::vector<std::string> spec_versions{"1.0", "1.1"};
|
||||
std::vector<std::string> spec_versions{"1.0"};
|
||||
for (auto &&spec_ver : spec_versions) {
|
||||
if (*spec_version == Version(spec_ver)) {
|
||||
return; // supported
|
||||
@@ -143,24 +132,22 @@ void Channels::LogControlInfos() const {
|
||||
}
|
||||
}
|
||||
|
||||
// TODO(Kalman): Compatible with two generation
|
||||
void Channels::UpdateControlInfos() {
|
||||
for (auto &&option : std::vector<Option>{Option::BRIGHTNESS}) {
|
||||
for (auto &&option : std::vector<Option>{Option::GAIN, Option::BRIGHTNESS,
|
||||
Option::CONTRAST}) {
|
||||
control_infos_[option] = PuControlInfo(option);
|
||||
}
|
||||
|
||||
for (auto &&option : std::vector<Option>{
|
||||
Option::EXPOSURE_MODE, Option::DESIRED_BRIGHTNESS,
|
||||
Option::FRAME_RATE, Option::IMU_FREQUENCY, Option::EXPOSURE_MODE,
|
||||
Option::MAX_GAIN, Option::MAX_EXPOSURE_TIME,
|
||||
Option::MIN_EXPOSURE_TIME, Option::ACCELEROMETER_RANGE,
|
||||
Option::GYROSCOPE_RANGE, Option::ACCELEROMETER_LOW_PASS_FILTER,
|
||||
Option::GYROSCOPE_LOW_PASS_FILTER}) {
|
||||
Option::DESIRED_BRIGHTNESS, Option::IR_CONTROL, Option::HDR_MODE,
|
||||
Option::ACCELEROMETER_RANGE, Option::GYROSCOPE_RANGE}) {
|
||||
control_infos_[option] = XuControlInfo(option);
|
||||
}
|
||||
|
||||
if (VLOG_IS_ON(2)) {
|
||||
for (auto &&it = control_infos_.begin(); it != control_infos_.end();
|
||||
it++) {
|
||||
for (auto &&it = control_infos_.begin(); it != control_infos_.end(); it++) {
|
||||
VLOG(2) << it->first << ": min=" << it->second.min
|
||||
<< ", max=" << it->second.max << ", def=" << it->second.def
|
||||
<< ", cur=" << GetControlValue(it->first);
|
||||
@@ -197,11 +184,8 @@ std::int32_t Channels::GetControlValue(const Option &option) const {
|
||||
case Option::DESIRED_BRIGHTNESS:
|
||||
case Option::IR_CONTROL:
|
||||
case Option::HDR_MODE:
|
||||
case Option::MIN_EXPOSURE_TIME:
|
||||
case Option::ACCELEROMETER_RANGE:
|
||||
case Option::GYROSCOPE_RANGE:
|
||||
case Option::ACCELEROMETER_LOW_PASS_FILTER:
|
||||
case Option::GYROSCOPE_LOW_PASS_FILTER:
|
||||
return XuCamCtrlGet(option);
|
||||
case Option::ZERO_DRIFT_CALIBRATION:
|
||||
case Option::ERASE_CHIP:
|
||||
@@ -258,22 +242,12 @@ void Channels::SetControlValue(const Option &option, std::int32_t value) {
|
||||
XuCamCtrlSet(option, value);
|
||||
} break;
|
||||
case Option::ACCELEROMETER_RANGE: {
|
||||
if (!in_range() || !in_values({6, 12, 24, 48}))
|
||||
if (!in_range() || !in_values({4, 8, 16, 32}))
|
||||
break;
|
||||
XuCamCtrlSet(option, value);
|
||||
} break;
|
||||
case Option::GYROSCOPE_RANGE: {
|
||||
if (!in_range() || !in_values({250, 500, 1000, 2000, 4000}))
|
||||
break;
|
||||
XuCamCtrlSet(option, value);
|
||||
} break;
|
||||
case Option::ACCELEROMETER_LOW_PASS_FILTER: {
|
||||
if (!in_range() || !in_values({0, 1, 2}))
|
||||
break;
|
||||
XuCamCtrlSet(option, value);
|
||||
} break;
|
||||
case Option::GYROSCOPE_LOW_PASS_FILTER: {
|
||||
if (!in_range() || !in_values({23, 64}))
|
||||
if (!in_range() || !in_values({500, 1000, 2000, 4000}))
|
||||
break;
|
||||
XuCamCtrlSet(option, value);
|
||||
} break;
|
||||
@@ -282,8 +256,7 @@ void Channels::SetControlValue(const Option &option, std::int32_t value) {
|
||||
case Option::MAX_EXPOSURE_TIME:
|
||||
case Option::DESIRED_BRIGHTNESS:
|
||||
case Option::IR_CONTROL:
|
||||
case Option::HDR_MODE:
|
||||
case Option::MIN_EXPOSURE_TIME: {
|
||||
case Option::HDR_MODE: {
|
||||
if (!in_range())
|
||||
break;
|
||||
XuCamCtrlSet(option, value);
|
||||
@@ -314,11 +287,8 @@ bool Channels::RunControlAction(const Option &option) const {
|
||||
case Option::DESIRED_BRIGHTNESS:
|
||||
case Option::IR_CONTROL:
|
||||
case Option::HDR_MODE:
|
||||
case Option::MIN_EXPOSURE_TIME:
|
||||
case Option::ACCELEROMETER_RANGE:
|
||||
case Option::GYROSCOPE_RANGE:
|
||||
case Option::ACCELEROMETER_LOW_PASS_FILTER:
|
||||
case Option::GYROSCOPE_LOW_PASS_FILTER:
|
||||
LOG(WARNING) << option << " run action useless";
|
||||
return false;
|
||||
default:
|
||||
@@ -348,10 +318,6 @@ void Channels::DoImuTrack() {
|
||||
return;
|
||||
}
|
||||
|
||||
if (res_packet.packets.back().count == 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
VLOG(2) << "Imu req sn: " << imu_sn_ << ", res count: " << []() {
|
||||
std::size_t n = 0;
|
||||
for (auto &&packet : res_packet.packets) {
|
||||
@@ -360,7 +326,7 @@ void Channels::DoImuTrack() {
|
||||
return n;
|
||||
}();
|
||||
|
||||
auto &&sn = res_packet.packets.back().segments.back().serial_number;
|
||||
auto &&sn = res_packet.packets.back().serial_number;
|
||||
if (imu_sn_ == sn) {
|
||||
VLOG(2) << "New imu not ready, dropped";
|
||||
return;
|
||||
@@ -563,44 +529,18 @@ std::size_t from_data(
|
||||
return i;
|
||||
}
|
||||
|
||||
// TODO(Kalman): Is there a more elegant way?
|
||||
std::size_t from_data(
|
||||
device::img_params_t *img_params, const std::uint8_t *data,
|
||||
Channels::img_params_t *img_params, const std::uint8_t *data,
|
||||
const Version *spec_version) {
|
||||
std::size_t i = 0;
|
||||
|
||||
if (spec_version->major() == 1) {
|
||||
if (spec_version->minor() == 0) {
|
||||
i += from_data(
|
||||
&img_params->in_left_map[Resolution::RES_752x480], data + i,
|
||||
spec_version);
|
||||
i += from_data(
|
||||
&img_params->in_right_map[Resolution::RES_752x480], data + i,
|
||||
spec_version);
|
||||
}
|
||||
|
||||
if (spec_version->minor() == 1) {
|
||||
i += from_data(
|
||||
&img_params->in_left_map[Resolution::RES_1280x400], data + i,
|
||||
spec_version);
|
||||
i += from_data(
|
||||
&img_params->in_right_map[Resolution::RES_1280x400], data + i,
|
||||
spec_version);
|
||||
i += from_data(
|
||||
&img_params->in_left_map[Resolution::RES_2560x800], data + i,
|
||||
spec_version);
|
||||
i += from_data(
|
||||
&img_params->in_right_map[Resolution::RES_2560x800], data + i,
|
||||
spec_version);
|
||||
}
|
||||
}
|
||||
|
||||
i += from_data(&img_params->in_left, data + i, spec_version);
|
||||
i += from_data(&img_params->in_right, data + i, spec_version);
|
||||
i += from_data(&img_params->ex_right_to_left, data + i, spec_version);
|
||||
return i;
|
||||
}
|
||||
|
||||
std::size_t from_data(
|
||||
device::imu_params_t *imu_params, const std::uint8_t *data,
|
||||
Channels::imu_params_t *imu_params, const std::uint8_t *data,
|
||||
const Version *spec_version) {
|
||||
std::size_t i = 0;
|
||||
i += from_data(&imu_params->in_accel, data + i, spec_version);
|
||||
@@ -677,9 +617,7 @@ bool Channels::GetFiles(
|
||||
img_params->ok = file_size > 0;
|
||||
if (img_params->ok) {
|
||||
CheckSpecVersion(spec_ver);
|
||||
from_data(img_params, data + i, spec_ver);
|
||||
// Considering the upgrade, comment this
|
||||
// CHECK_EQ(from_data(img_params, data + i, spec_ver), file_size);
|
||||
CHECK_EQ(from_data(img_params, data + i, spec_ver), file_size);
|
||||
}
|
||||
} break;
|
||||
case FID_IMU_PARAMS: {
|
||||
@@ -864,37 +802,11 @@ std::size_t to_data(
|
||||
}
|
||||
|
||||
std::size_t to_data(
|
||||
const device::img_params_t *img_params, std::uint8_t *data,
|
||||
const Channels::img_params_t *img_params, std::uint8_t *data,
|
||||
const Version *spec_version) {
|
||||
std::size_t i = 3; // skip id, size
|
||||
|
||||
if (spec_version->major() == 1) {
|
||||
if (spec_version->minor() == 0) {
|
||||
i += to_data(
|
||||
&img_params->in_left_map.at(Resolution::RES_752x480), data + i,
|
||||
spec_version);
|
||||
i += to_data(
|
||||
&img_params->in_right_map.at(Resolution::RES_752x480), data + i,
|
||||
spec_version);
|
||||
}
|
||||
|
||||
if (spec_version->minor() == 1) {
|
||||
i += to_data(
|
||||
&img_params->in_left_map.at(Resolution::RES_1280x400), data + i,
|
||||
spec_version);
|
||||
i += to_data(
|
||||
&img_params->in_right_map.at(Resolution::RES_1280x400), data + i,
|
||||
spec_version);
|
||||
|
||||
i += to_data(
|
||||
&img_params->in_left_map.at(Resolution::RES_2560x800), data + i,
|
||||
spec_version);
|
||||
i += to_data(
|
||||
&img_params->in_right_map.at(Resolution::RES_2560x800), data + i,
|
||||
spec_version);
|
||||
}
|
||||
}
|
||||
|
||||
i += to_data(&img_params->in_left, data + i, spec_version);
|
||||
i += to_data(&img_params->in_right, data + i, spec_version);
|
||||
i += to_data(&img_params->ex_right_to_left, data + i, spec_version);
|
||||
// others
|
||||
std::size_t size = i - 3;
|
||||
|
||||
@@ -21,7 +21,6 @@
|
||||
|
||||
#include "mynteye/mynteye.h"
|
||||
#include "mynteye/types.h"
|
||||
#include "mynteye/device/device.h"
|
||||
#include "mynteye/device/types.h"
|
||||
#include "mynteye/uvc/uvc.h"
|
||||
|
||||
@@ -68,13 +67,10 @@ class MYNTEYE_API Channels {
|
||||
|
||||
using device_info_t = DeviceInfo;
|
||||
|
||||
using imu_params_t = device::imu_params_t;
|
||||
using img_params_t = device::img_params_t;
|
||||
/*
|
||||
typedef struct ImgParams {
|
||||
bool ok;
|
||||
std::map<Resolution, Intrinsics> in_left_map;
|
||||
std::map<Resolution, Intrinsics> in_right_map;
|
||||
Intrinsics in_left;
|
||||
Intrinsics in_right;
|
||||
Extrinsics ex_right_to_left;
|
||||
} img_params_t;
|
||||
|
||||
@@ -84,7 +80,7 @@ class MYNTEYE_API Channels {
|
||||
ImuIntrinsics in_gyro;
|
||||
Extrinsics ex_left_to_imu;
|
||||
} imu_params_t;
|
||||
*/
|
||||
|
||||
explicit Channels(std::shared_ptr<uvc::device> device);
|
||||
~Channels();
|
||||
|
||||
|
||||
@@ -19,36 +19,19 @@ const std::map<Model, StreamSupports> stream_supports_map = {
|
||||
{Model::STANDARD, {Stream::LEFT, Stream::RIGHT}}};
|
||||
|
||||
const std::map<Model, CapabilitiesSupports> capabilities_supports_map = {
|
||||
{Model::STANDARD, {Capabilities::STEREO_COLOR, Capabilities::IMU}}};
|
||||
{Model::STANDARD, {Capabilities::STEREO, Capabilities::IMU}}};
|
||||
|
||||
// TODO(Kalman): Compatible with two generation
|
||||
const std::map<Model, OptionSupports> option_supports_map = {
|
||||
{Model::STANDARD,
|
||||
{Option::BRIGHTNESS, Option::EXPOSURE_MODE, Option::MAX_GAIN,
|
||||
Option::MAX_EXPOSURE_TIME, Option::DESIRED_BRIGHTNESS,
|
||||
Option::MIN_EXPOSURE_TIME, Option::ERASE_CHIP,
|
||||
Option::ACCELEROMETER_RANGE, Option::GYROSCOPE_RANGE,
|
||||
Option::ACCELEROMETER_LOW_PASS_FILTER,
|
||||
Option::GYROSCOPE_LOW_PASS_FILTER}}};
|
||||
{Option::GAIN, Option::BRIGHTNESS, Option::CONTRAST, Option::FRAME_RATE,
|
||||
Option::IMU_FREQUENCY, Option::EXPOSURE_MODE, Option::MAX_GAIN,
|
||||
Option::MAX_EXPOSURE_TIME, Option::DESIRED_BRIGHTNESS, Option::IR_CONTROL,
|
||||
Option::HDR_MODE, Option::ZERO_DRIFT_CALIBRATION, Option::ERASE_CHIP,
|
||||
Option::ACCELEROMETER_RANGE, Option::GYROSCOPE_RANGE}}};
|
||||
|
||||
const std::map<Model, std::map<Capabilities, StreamRequests>>
|
||||
stream_requests_map = {
|
||||
{Model::STANDARD,
|
||||
{{Capabilities::STEREO, {{480, 752, Format::YUYV, 25}}},
|
||||
{Capabilities::STEREO_COLOR,
|
||||
{// {1280, 400, Format::YUYV, 10},
|
||||
// {1280, 400, Format::YUYV, 20},
|
||||
// {1280, 400, Format::YUYV, 30},
|
||||
// {1280, 400, Format::YUYV, 60},
|
||||
// {2560, 800, Format::YUYV, 10},
|
||||
// {2560, 800, Format::YUYV, 20},
|
||||
// {2560, 800, Format::YUYV, 30},
|
||||
{1280, 400, Format::BGR888, 10},
|
||||
{1280, 400, Format::BGR888, 20},
|
||||
{1280, 400, Format::BGR888, 30},
|
||||
{1280, 400, Format::BGR888, 60},
|
||||
{2560, 800, Format::BGR888, 10},
|
||||
{2560, 800, Format::BGR888, 20},
|
||||
{2560, 800, Format::BGR888, 30}}}}}};
|
||||
{{Capabilities::STEREO, {{752, 480, Format::YUYV, 25}}}}}};
|
||||
|
||||
MYNTEYE_END_NAMESPACE
|
||||
|
||||
@@ -27,18 +27,13 @@ MYNTEYE_BEGIN_NAMESPACE
|
||||
using StreamSupports = std::set<Stream>;
|
||||
using CapabilitiesSupports = std::set<Capabilities>;
|
||||
using OptionSupports = std::set<Option>;
|
||||
using ResolutionSupports = std::set<Resolution>;
|
||||
using FrameRateSupports = std::set<FrameRate>;
|
||||
|
||||
extern const std::map<Model, StreamSupports> stream_supports_map;
|
||||
extern const std::map<Model, CapabilitiesSupports> capabilities_supports_map;
|
||||
extern const std::map<Model, OptionSupports> option_supports_map;
|
||||
extern const std::map<Model, ResolutionSupports> resolution_supports_map;
|
||||
|
||||
using StreamRequests = std::vector<StreamRequest>;
|
||||
|
||||
extern const std::map<Model, std::map<Resolution, FrameRateSupports>>
|
||||
framerate_Supports_supports_map;
|
||||
|
||||
extern const std::map<Model, std::map<Capabilities, StreamRequests>>
|
||||
stream_requests_map;
|
||||
|
||||
|
||||
@@ -100,19 +100,13 @@ std::shared_ptr<Device> Device::Create(
|
||||
return std::make_shared<StandardDevice>(device);
|
||||
} else if (strings::starts_with(name, "MYNT-EYE-")) {
|
||||
// TODO(JohnZhao): Create different device by name, such as MYNT-EYE-S1000
|
||||
std::string model_s = name.substr(9, 5);
|
||||
std::string model_s = name.substr(9);
|
||||
VLOG(2) << "MYNE EYE Model: " << model_s;
|
||||
DeviceModel model(model_s);
|
||||
if (model.type == 'S') {
|
||||
switch (model.generation) {
|
||||
case '1':
|
||||
return std::make_shared<StandardDevice>(device);
|
||||
case '2':
|
||||
switch (model.type) {
|
||||
case 'S':
|
||||
return std::make_shared<StandardDevice>(device);
|
||||
default:
|
||||
LOG(FATAL) << "No such generation now";
|
||||
}
|
||||
} else {
|
||||
LOG(FATAL) << "MYNT EYE model is not supported now";
|
||||
}
|
||||
}
|
||||
@@ -437,26 +431,13 @@ std::vector<device::MotionData> Device::GetMotionDatas() {
|
||||
return motions_->GetMotionDatas();
|
||||
}
|
||||
|
||||
void Device::InitResolution(const Resolution &res) {
|
||||
res_ = res;
|
||||
ConfigIntrinsics(res_);
|
||||
}
|
||||
|
||||
void Device::SetStreamRequest(const Format &format, const FrameRate &rate) {
|
||||
StreamRequest request(res_, format, rate);
|
||||
request_ = request;
|
||||
}
|
||||
|
||||
const StreamRequest &Device::GetStreamRequest(const Capabilities &capability) {
|
||||
try {
|
||||
return stream_config_requests_.at(capability);
|
||||
} catch (const std::out_of_range &e) {
|
||||
auto &&requests = GetStreamRequests(capability);
|
||||
if (requests.size() >= 1) {
|
||||
for (auto &&request : requests) {
|
||||
if (request == request_)
|
||||
return request;
|
||||
}
|
||||
VLOG(2) << "Select the first one stream request of " << capability;
|
||||
return requests[0];
|
||||
} else {
|
||||
LOG(FATAL) << "Please config the stream request of " << capability;
|
||||
@@ -473,22 +454,28 @@ void Device::StartVideoStreaming() {
|
||||
streams_ = std::make_shared<Streams>(GetKeyStreams());
|
||||
|
||||
// if stream capabilities are supported with subdevices of device_
|
||||
/*
|
||||
Capabilities stream_capabilities[] = {
|
||||
Capabilities::STEREO, Capabilities::COLOR,
|
||||
Capabilities::STEREO_COLOR, Capabilities::DEPTH,
|
||||
Capabilities::POINTS, Capabilities::FISHEYE,
|
||||
Capabilities::INFRARED, Capabilities::INFRARED2};
|
||||
Capabilities::STEREO,
|
||||
Capabilities::COLOR,
|
||||
Capabilities::DEPTH,
|
||||
Capabilities::POINTS,
|
||||
Capabilities::FISHEYE,
|
||||
Capabilities::INFRARED,
|
||||
Capabilities::INFRARED2
|
||||
};
|
||||
for (auto &&capability : stream_capabilities) {
|
||||
if (Supports(capability)) {
|
||||
}
|
||||
*/
|
||||
if (Supports(Capabilities::STEREO)) {
|
||||
// do stream request selection if more than one request of each stream
|
||||
auto &&stream_request = GetStreamRequest(capability);
|
||||
auto &&stream_request = GetStreamRequest(Capabilities::STEREO);
|
||||
|
||||
streams_->ConfigStream(capability, stream_request);
|
||||
streams_->ConfigStream(Capabilities::STEREO, stream_request);
|
||||
uvc::set_device_mode(
|
||||
*device_, stream_request.width, stream_request.height,
|
||||
static_cast<int>(stream_request.format), stream_request.fps,
|
||||
[this, capability](
|
||||
const void *data, std::function<void()> continuation) {
|
||||
[this](const void *data, std::function<void()> continuation) {
|
||||
// drop the first stereo stream data
|
||||
static std::uint8_t drop_count = 1;
|
||||
if (drop_count > 0) {
|
||||
@@ -499,7 +486,7 @@ void Device::StartVideoStreaming() {
|
||||
// auto &&time_beg = times::now();
|
||||
{
|
||||
std::lock_guard<std::mutex> _(mtx_streams_);
|
||||
if (streams_->PushStream(capability, data)) {
|
||||
if (streams_->PushStream(Capabilities::STEREO, data)) {
|
||||
CallbackPushedStreamData(Stream::LEFT);
|
||||
CallbackPushedStreamData(Stream::RIGHT);
|
||||
}
|
||||
@@ -511,10 +498,9 @@ void Device::StartVideoStreaming() {
|
||||
// << " ms";
|
||||
});
|
||||
} else {
|
||||
// LOG(FATAL) << "Not any stream capabilities are supported by this
|
||||
// device";
|
||||
}
|
||||
LOG(FATAL) << "Not any stream capabilities are supported by this device";
|
||||
}
|
||||
|
||||
uvc::start_streaming(*device_, 0);
|
||||
video_streaming_ = true;
|
||||
}
|
||||
@@ -557,8 +543,9 @@ void Device::ReadAllInfos() {
|
||||
device_info_ = std::make_shared<DeviceInfo>();
|
||||
|
||||
CHECK_NOTNULL(channels_);
|
||||
Device::imu_params_t imu_params;
|
||||
if (!channels_->GetFiles(device_info_.get(), &img_params_, &imu_params)) {
|
||||
Channels::img_params_t img_params;
|
||||
Channels::imu_params_t imu_params;
|
||||
if (!channels_->GetFiles(device_info_.get(), &img_params, &imu_params)) {
|
||||
#if defined(WITH_DEVICE_INFO_REQUIRED)
|
||||
LOG(FATAL)
|
||||
#else
|
||||
@@ -579,10 +566,14 @@ void Device::ReadAllInfos() {
|
||||
<< ", nominal_baseline: " << device_info_->nominal_baseline << "}";
|
||||
|
||||
device_info_->name = uvc::get_name(*device_);
|
||||
if (img_params_.ok) {
|
||||
SetExtrinsics(Stream::LEFT, Stream::RIGHT, img_params_.ex_right_to_left);
|
||||
VLOG(2) << "Extrinsics left to right: {"
|
||||
<< GetExtrinsics(Stream::LEFT, Stream::RIGHT) << "}";
|
||||
if (img_params.ok) {
|
||||
SetIntrinsics(Stream::LEFT, img_params.in_left);
|
||||
SetIntrinsics(Stream::RIGHT, img_params.in_right);
|
||||
SetExtrinsics(Stream::RIGHT, Stream::LEFT, img_params.ex_right_to_left);
|
||||
VLOG(2) << "Intrinsics left: {" << GetIntrinsics(Stream::LEFT) << "}";
|
||||
VLOG(2) << "Intrinsics right: {" << GetIntrinsics(Stream::RIGHT) << "}";
|
||||
VLOG(2) << "Extrinsics right to left: {"
|
||||
<< GetExtrinsics(Stream::RIGHT, Stream::LEFT) << "}";
|
||||
} else {
|
||||
LOG(WARNING) << "Intrinsics & extrinsics not exist";
|
||||
}
|
||||
@@ -597,15 +588,6 @@ void Device::ReadAllInfos() {
|
||||
}
|
||||
}
|
||||
|
||||
void Device::ConfigIntrinsics(const Resolution &res) {
|
||||
if (img_params_.ok) {
|
||||
SetIntrinsics(Stream::LEFT, img_params_.in_left_map[res]);
|
||||
SetIntrinsics(Stream::RIGHT, img_params_.in_right_map[res]);
|
||||
VLOG(2) << "Intrinsics left: {" << GetIntrinsics(Stream::LEFT) << "}";
|
||||
VLOG(2) << "Intrinsics right: {" << GetIntrinsics(Stream::RIGHT) << "}";
|
||||
}
|
||||
}
|
||||
|
||||
void Device::CallbackPushedStreamData(const Stream &stream) {
|
||||
if (HasStreamCallback(stream)) {
|
||||
auto &&datas = streams_->stream_datas(stream);
|
||||
@@ -629,8 +611,4 @@ void Device::CallbackMotionData(const device::MotionData &data) {
|
||||
}
|
||||
}
|
||||
|
||||
Device::img_params_t Device::GetImgParams() {
|
||||
return img_params_;
|
||||
}
|
||||
|
||||
MYNTEYE_END_NAMESPACE
|
||||
|
||||
@@ -36,7 +36,7 @@ void Motions::SetMotionCallback(motion_callback_t callback) {
|
||||
if (motion_callback_) {
|
||||
accel_range = channels_->GetControlValue(Option::ACCELEROMETER_RANGE);
|
||||
if (accel_range == -1)
|
||||
accel_range = 12;
|
||||
accel_range = 8;
|
||||
|
||||
gyro_range = channels_->GetControlValue(Option::GYROSCOPE_RANGE);
|
||||
if (gyro_range == -1)
|
||||
@@ -48,34 +48,20 @@ void Motions::SetMotionCallback(motion_callback_t callback) {
|
||||
}
|
||||
for (auto &&seg : packet.segments) {
|
||||
auto &&imu = std::make_shared<ImuData>();
|
||||
// imu->frame_id = seg.frame_id;
|
||||
imu->frame_id = seg.frame_id;
|
||||
// if (seg.offset < 0 &&
|
||||
// static_cast<uint32_t>(-seg.offset) > packet.timestamp) {
|
||||
// LOG(WARNING) << "Imu timestamp offset is incorrect";
|
||||
// }
|
||||
imu->serial_number = seg.serial_number;
|
||||
imu->timestamp = seg.timestamp;
|
||||
imu->flag = seg.flag;
|
||||
imu->timestamp = packet.timestamp + seg.offset;
|
||||
imu->accel[0] = seg.accel[0] * 1.f * accel_range / 0x10000;
|
||||
imu->accel[1] = seg.accel[1] * 1.f * accel_range / 0x10000;
|
||||
imu->accel[2] = seg.accel[2] * 1.f * accel_range / 0x10000;
|
||||
imu->gyro[0] = seg.gyro[0] * 1.f * gyro_range / 0x10000;
|
||||
imu->gyro[1] = seg.gyro[1] * 1.f * gyro_range / 0x10000;
|
||||
imu->gyro[2] = seg.gyro[2] * 1.f * gyro_range / 0x10000;
|
||||
imu->temperature = seg.temperature / 326.8f + 25;
|
||||
|
||||
if (imu->flag == 1) {
|
||||
imu->accel[0] = seg.accel_or_gyro[0] * 1.f * accel_range / 0x10000;
|
||||
imu->accel[1] = seg.accel_or_gyro[1] * 1.f * accel_range / 0x10000;
|
||||
imu->accel[2] = seg.accel_or_gyro[2] * 1.f * accel_range / 0x10000;
|
||||
imu->gyro[0] = 0;
|
||||
imu->gyro[1] = 0;
|
||||
imu->gyro[2] = 0;
|
||||
} else if (imu->flag == 2) {
|
||||
imu->accel[0] = 0;
|
||||
imu->accel[1] = 0;
|
||||
imu->accel[2] = 0;
|
||||
imu->gyro[0] = seg.accel_or_gyro[0] * 1.f * gyro_range / 0x10000;
|
||||
imu->gyro[1] = seg.accel_or_gyro[1] * 1.f * gyro_range / 0x10000;
|
||||
imu->gyro[2] = seg.accel_or_gyro[2] * 1.f * gyro_range / 0x10000;
|
||||
} else {
|
||||
imu->Reset();
|
||||
}
|
||||
|
||||
std::lock_guard<std::mutex> _(mtx_datas_);
|
||||
motion_data_t data = {imu};
|
||||
if (motion_datas_enabled_) {
|
||||
|
||||
@@ -58,7 +58,7 @@ class Motions {
|
||||
|
||||
std::mutex mtx_datas_;
|
||||
|
||||
int accel_range = 12;
|
||||
int accel_range = 8;
|
||||
int gyro_range = 1000;
|
||||
};
|
||||
|
||||
|
||||
@@ -28,6 +28,8 @@ namespace {
|
||||
bool unpack_stereo_img_data(
|
||||
const void *data, const StreamRequest &request, ImgData *img) {
|
||||
CHECK_NOTNULL(img);
|
||||
CHECK_EQ(request.format, Format::YUYV);
|
||||
|
||||
auto data_new = reinterpret_cast<const std::uint8_t *>(data);
|
||||
std::size_t data_n =
|
||||
request.width * request.height * bytes_per_pixel(request.format);
|
||||
@@ -57,7 +59,6 @@ bool unpack_stereo_img_data(
|
||||
for (std::size_t i = 2, n = packet_n - 2; i <= n; i++) { // content: [2,9]
|
||||
checksum = (checksum ^ packet[i]);
|
||||
}
|
||||
|
||||
if (img_packet.checksum != checksum) {
|
||||
VLOG(2) << "Image packet checksum should be 0x" << std::hex
|
||||
<< std::uppercase << std::setw(2) << std::setfill('0')
|
||||
@@ -76,53 +77,26 @@ bool unpack_stereo_img_data(
|
||||
bool unpack_left_img_pixels(
|
||||
const void *data, const StreamRequest &request, Streams::frame_t *frame) {
|
||||
CHECK_NOTNULL(frame);
|
||||
CHECK_EQ(request.format, frame->format());
|
||||
CHECK_EQ(request.format, Format::YUYV);
|
||||
CHECK_EQ(frame->format(), Format::GREY);
|
||||
auto data_new = reinterpret_cast<const std::uint8_t *>(data);
|
||||
if (request.format == Format::YUYV || request.format == Format::BGR888) {
|
||||
std::size_t n = request.format == Format::YUYV ? 2 : 3;
|
||||
std::size_t w = frame->width() * n;
|
||||
std::size_t h = frame->height();
|
||||
for (std::size_t i = 0; i < h; i++) {
|
||||
for (std::size_t j = 0; j < w; j++) {
|
||||
frame->data()[i * w + j] = *(data_new + 2 * i * w + j);
|
||||
}
|
||||
}
|
||||
} else if (request.format == Format::GREY) {
|
||||
std::size_t n = frame->width() * frame->height();
|
||||
for (std::size_t i = 0; i < n; i++) {
|
||||
frame->data()[i] = *(data_new + (i * 2));
|
||||
}
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// TODO(Kalman): Too similar to 'unpack_left_img_pixels'
|
||||
bool unpack_right_img_pixels(
|
||||
const void *data, const StreamRequest &request, Streams::frame_t *frame) {
|
||||
CHECK_NOTNULL(frame);
|
||||
CHECK_EQ(request.format, frame->format());
|
||||
CHECK_EQ(request.format, Format::YUYV);
|
||||
CHECK_EQ(frame->format(), Format::GREY);
|
||||
auto data_new = reinterpret_cast<const std::uint8_t *>(data);
|
||||
if (request.format == Format::YUYV || request.format == Format::BGR888) {
|
||||
std::size_t n = request.format == Format::YUYV ? 2 : 3;
|
||||
std::size_t w = frame->width() * n;
|
||||
std::size_t h = frame->height();
|
||||
for (std::size_t i = 0; i < h; i++) {
|
||||
for (std::size_t j = 0; j < w; j++) {
|
||||
frame->data()[i * w + j] = *(data_new + (2 * i + 1) * w + j);
|
||||
}
|
||||
}
|
||||
} else if (request.format == Format::GREY) {
|
||||
std::size_t n = frame->width() * frame->height();
|
||||
for (std::size_t i = 0; i < n; i++) {
|
||||
frame->data()[i] = *(data_new + (i * 2 + 1));
|
||||
}
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
@@ -133,7 +107,7 @@ Streams::Streams(const std::vector<Stream> key_streams)
|
||||
stream_capabilities_(
|
||||
{Capabilities::STEREO, Capabilities::COLOR, Capabilities::DEPTH,
|
||||
Capabilities::POINTS, Capabilities::FISHEYE, Capabilities::INFRARED,
|
||||
Capabilities::INFRARED2, Capabilities::STEREO_COLOR}),
|
||||
Capabilities::INFRARED2}),
|
||||
unpack_img_data_map_(
|
||||
{{Stream::LEFT, unpack_stereo_img_data},
|
||||
{Stream::RIGHT, unpack_stereo_img_data}}),
|
||||
@@ -165,16 +139,16 @@ bool Streams::PushStream(const Capabilities &capability, const void *data) {
|
||||
auto &&request = GetStreamConfigRequest(capability);
|
||||
bool pushed = false;
|
||||
switch (capability) {
|
||||
case Capabilities::STEREO_COLOR: {
|
||||
case Capabilities::STEREO: {
|
||||
// alloc left
|
||||
AllocStreamData(Stream::LEFT, request);
|
||||
AllocStreamData(Stream::LEFT, request, Format::GREY);
|
||||
auto &&left_data = stream_datas_map_[Stream::LEFT].back();
|
||||
// unpack img data
|
||||
if (unpack_img_data_map_[Stream::LEFT](
|
||||
data, request, left_data.img.get())) {
|
||||
left_data.frame_id = left_data.img->frame_id;
|
||||
// alloc right
|
||||
AllocStreamData(Stream::RIGHT, request);
|
||||
AllocStreamData(Stream::RIGHT, request, Format::GREY);
|
||||
auto &&right_data = stream_datas_map_[Stream::RIGHT].back();
|
||||
*right_data.img = *left_data.img;
|
||||
right_data.frame_id = left_data.img->frame_id;
|
||||
@@ -308,11 +282,8 @@ void Streams::AllocStreamData(
|
||||
data.img = nullptr;
|
||||
}
|
||||
if (!data.frame) {
|
||||
int width = request.width;
|
||||
if (format != Format::GREY)
|
||||
width /= 2;
|
||||
data.frame =
|
||||
std::make_shared<frame_t>(width, request.height, format, nullptr);
|
||||
data.frame = std::make_shared<frame_t>(
|
||||
request.width, request.height, format, nullptr);
|
||||
}
|
||||
data.frame_id = 0;
|
||||
stream_datas_map_[stream].push_back(data);
|
||||
|
||||
@@ -16,6 +16,7 @@
|
||||
#pragma once
|
||||
|
||||
#include <cstdint>
|
||||
|
||||
#include <array>
|
||||
#include <bitset>
|
||||
#include <string>
|
||||
@@ -147,7 +148,7 @@ struct ImagePacket {
|
||||
std::uint8_t header;
|
||||
std::uint8_t size;
|
||||
std::uint16_t frame_id;
|
||||
std::uint64_t timestamp;
|
||||
std::uint32_t timestamp;
|
||||
std::uint16_t exposure_time;
|
||||
std::uint8_t checksum;
|
||||
|
||||
@@ -157,19 +158,13 @@ struct ImagePacket {
|
||||
}
|
||||
|
||||
void from_data(std::uint8_t *data) {
|
||||
std::uint32_t timestamp_l;
|
||||
std::uint32_t timestamp_h;
|
||||
|
||||
header = *data;
|
||||
size = *(data + 1);
|
||||
frame_id = (*(data + 2) << 8) | *(data + 3);
|
||||
timestamp_h = (*(data + 4) << 24) | (*(data + 5) << 16) |
|
||||
(*(data + 6) << 8) | *(data + 7);
|
||||
timestamp_l = (*(data + 8) << 24) | (*(data + 9) << 16) |
|
||||
(*(data + 10) << 8) | *(data + 11);
|
||||
timestamp = (static_cast<std::uint64_t>(timestamp_h) << 32) | timestamp_l;
|
||||
exposure_time = (*(data + 12) << 8) | *(data + 13);
|
||||
checksum = *(data + 14);
|
||||
timestamp = (*(data + 4) << 24) | (*(data + 5) << 16) | (*(data + 6) << 8) |
|
||||
*(data + 7);
|
||||
exposure_time = (*(data + 8) << 8) | *(data + 9);
|
||||
checksum = *(data + 10);
|
||||
}
|
||||
};
|
||||
#pragma pack(pop)
|
||||
@@ -204,11 +199,11 @@ struct ImuReqPacket {
|
||||
*/
|
||||
#pragma pack(push, 1)
|
||||
struct ImuSegment {
|
||||
std::uint32_t serial_number;
|
||||
std::uint64_t timestamp;
|
||||
std::uint8_t flag;
|
||||
std::int16_t offset;
|
||||
std::uint16_t frame_id;
|
||||
std::int16_t accel[3];
|
||||
std::int16_t temperature;
|
||||
std::int16_t accel_or_gyro[3];
|
||||
std::int16_t gyro[3];
|
||||
|
||||
ImuSegment() = default;
|
||||
explicit ImuSegment(std::uint8_t *data) {
|
||||
@@ -216,21 +211,15 @@ struct ImuSegment {
|
||||
}
|
||||
|
||||
void from_data(std::uint8_t *data) {
|
||||
std::uint32_t timestamp_l;
|
||||
std::uint32_t timestamp_h;
|
||||
|
||||
serial_number = (*(data) << 24) | (*(data + 1) << 16) | (*(data + 2) << 8) |
|
||||
*(data + 3);
|
||||
timestamp_h = (*(data + 4) << 24) | (*(data + 5) << 16) |
|
||||
(*(data + 6) << 8) | *(data + 7);
|
||||
timestamp_l = (*(data + 8) << 24) | (*(data + 9) << 16) |
|
||||
(*(data + 10) << 8) | *(data + 11);
|
||||
timestamp = (static_cast<std::uint64_t>(timestamp_h) << 32) | timestamp_l;
|
||||
flag = *(data + 12);
|
||||
temperature = (*(data + 13) << 8) | *(data + 14);
|
||||
accel_or_gyro[0] = (*(data + 15) << 8) | *(data + 16);
|
||||
accel_or_gyro[1] = (*(data + 17) << 8) | *(data + 18);
|
||||
accel_or_gyro[2] = (*(data + 19) << 8) | *(data + 20);
|
||||
offset = (*(data) << 8) | *(data + 1);
|
||||
frame_id = (*(data + 2) << 8) | *(data + 3);
|
||||
accel[0] = (*(data + 4) << 8) | *(data + 5);
|
||||
accel[1] = (*(data + 6) << 8) | *(data + 7);
|
||||
accel[2] = (*(data + 8) << 8) | *(data + 9);
|
||||
temperature = (*(data + 10) << 8) | *(data + 11);
|
||||
gyro[0] = (*(data + 12) << 8) | *(data + 13);
|
||||
gyro[1] = (*(data + 14) << 8) | *(data + 15);
|
||||
gyro[2] = (*(data + 16) << 8) | *(data + 17);
|
||||
}
|
||||
};
|
||||
#pragma pack(pop)
|
||||
@@ -241,18 +230,26 @@ struct ImuSegment {
|
||||
*/
|
||||
#pragma pack(push, 1)
|
||||
struct ImuPacket {
|
||||
std::uint32_t serial_number;
|
||||
std::uint32_t timestamp;
|
||||
std::uint8_t count;
|
||||
std::vector<ImuSegment> segments;
|
||||
|
||||
ImuPacket() = default;
|
||||
explicit ImuPacket(std::uint8_t seg_count, std::uint8_t *data) {
|
||||
count = seg_count;
|
||||
explicit ImuPacket(std::uint8_t *data) {
|
||||
from_data(data);
|
||||
}
|
||||
|
||||
void from_data(std::uint8_t *data) {
|
||||
std::size_t seg_n = sizeof(ImuSegment); // 21
|
||||
serial_number = (*(data) << 24) | (*(data + 1) << 16) | (*(data + 2) << 8) |
|
||||
*(data + 3);
|
||||
timestamp = (*(data + 4) << 24) | (*(data + 5) << 16) | (*(data + 6) << 8) |
|
||||
*(data + 7);
|
||||
count = *(data + 8);
|
||||
|
||||
std::size_t seg_n = sizeof(ImuSegment); // 18
|
||||
for (std::size_t i = 0; i < count; i++) {
|
||||
segments.push_back(ImuSegment(data + seg_n * i));
|
||||
segments.push_back(ImuSegment(data + 9 + (seg_n * i)));
|
||||
}
|
||||
}
|
||||
};
|
||||
@@ -280,11 +277,13 @@ struct ImuResPacket {
|
||||
state = *(data + 1);
|
||||
size = (*(data + 2) << 8) | *(data + 3);
|
||||
|
||||
std::size_t seg_n = sizeof(ImuSegment); // 21
|
||||
std::uint8_t seg_count = size / seg_n;
|
||||
ImuPacket packet(seg_count, data + 4);
|
||||
std::size_t seg_n = sizeof(ImuSegment); // 18
|
||||
for (std::size_t i = 4; i < size;) {
|
||||
ImuPacket packet(data + i);
|
||||
packets.push_back(packet);
|
||||
// packet(2);
|
||||
i += 9 + (packet.count * seg_n);
|
||||
}
|
||||
|
||||
checksum = *(data + 4 + size);
|
||||
}
|
||||
};
|
||||
|
||||
@@ -20,8 +20,6 @@
|
||||
#include "mynteye/device/context.h"
|
||||
#include "mynteye/device/device.h"
|
||||
|
||||
#include "mynteye/logger.h"
|
||||
|
||||
MYNTEYE_BEGIN_NAMESPACE
|
||||
|
||||
namespace device {
|
||||
|
||||
@@ -114,11 +114,8 @@ const char *to_string(const Option &value) {
|
||||
CASE(HDR_MODE)
|
||||
CASE(ZERO_DRIFT_CALIBRATION)
|
||||
CASE(ERASE_CHIP)
|
||||
CASE(MIN_EXPOSURE_TIME)
|
||||
CASE(ACCELEROMETER_RANGE)
|
||||
CASE(GYROSCOPE_RANGE)
|
||||
CASE(ACCELEROMETER_LOW_PASS_FILTER)
|
||||
CASE(GYROSCOPE_LOW_PASS_FILTER)
|
||||
default:
|
||||
CHECK(is_valid(value));
|
||||
return "Option::UNKNOWN";
|
||||
@@ -172,8 +169,6 @@ std::size_t bytes_per_pixel(const Format &value) {
|
||||
return 1;
|
||||
case Format::YUYV:
|
||||
return 2;
|
||||
case Format::BGR888:
|
||||
return 3;
|
||||
default:
|
||||
LOG(FATAL) << "Unknown format";
|
||||
}
|
||||
|
||||
@@ -46,10 +46,9 @@ namespace uvc {
|
||||
} while (0)
|
||||
|
||||
#define NO_DATA_MAX_COUNT 200
|
||||
#define LIVING_MAX_COUNT 9000
|
||||
|
||||
int no_data_count = 0;
|
||||
int living_count = 0;
|
||||
|
||||
/*
|
||||
class device_error : public std::exception {
|
||||
public:
|
||||
@@ -395,12 +394,6 @@ struct device {
|
||||
if (xioctl(fd, VIDIOC_QBUF, &buf) < 0)
|
||||
throw_error("VIDIOC_QBUF");
|
||||
});
|
||||
if (living_count < LIVING_MAX_COUNT) {
|
||||
living_count++;
|
||||
} else {
|
||||
living_count = 0;
|
||||
// LOG(INFO) << "UVC pulse detection,Please ignore.";
|
||||
}
|
||||
}
|
||||
|
||||
no_data_count = 0;
|
||||
@@ -409,12 +402,7 @@ struct device {
|
||||
}
|
||||
|
||||
if (no_data_count > NO_DATA_MAX_COUNT) {
|
||||
no_data_count = 0;
|
||||
living_count = 0;
|
||||
LOG(WARNING) << __func__
|
||||
<< " failed: v4l2 get stream time out,Try to reboot!";
|
||||
stop_capture();
|
||||
start_capture();
|
||||
throw_error("v4l2 get stream time out!");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -64,8 +64,7 @@ namespace uvc {
|
||||
|
||||
const std::map<uint32_t, uint32_t> fourcc_map = {
|
||||
{ 0x56595559, 0x32595559 }, // 'VYUY' => '2YUY'
|
||||
{ 0x59555956, 0x59555932 }, // 'YUYV' => 'YUY2'
|
||||
{ 0x33524742, 0x14 }
|
||||
{ 0x59555956, 0x59555932 } // 'YUYV' => 'YUY2'
|
||||
};
|
||||
|
||||
struct throw_error {
|
||||
@@ -757,7 +756,6 @@ void set_device_mode(device &device, int width, int height, int fourcc, int fps,
|
||||
check("IMFMediaType::GetGUID", media_type->GetGUID(MF_MT_SUBTYPE, &subtype));
|
||||
if (subtype.Data1 != fourcc) continue;
|
||||
|
||||
check("MFSetAttributeRatio", MFSetAttributeRatio(media_type, MF_MT_FRAME_RATE, fps, 1));
|
||||
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;
|
||||
|
||||
@@ -1,41 +0,0 @@
|
||||
// Ceres Solver - A fast non-linear least squares minimizer
|
||||
// Copyright 2012 Google Inc. All rights reserved.
|
||||
// http://code.google.com/p/ceres-solver/
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions are met:
|
||||
//
|
||||
// * Redistributions of source code must retain the above copyright notice,
|
||||
// this list of conditions and the following disclaimer.
|
||||
// * Redistributions in binary form must reproduce the above copyright notice,
|
||||
// this list of conditions and the following disclaimer in the documentation
|
||||
// and/or other materials provided with the distribution.
|
||||
// * Neither the name of Google Inc. nor the names of its contributors may be
|
||||
// used to endorse or promote products derived from this software without
|
||||
// specific prior written permission.
|
||||
//
|
||||
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
|
||||
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
||||
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
||||
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
// POSSIBILITY OF SUCH DAMAGE.
|
||||
//
|
||||
// Author: keir@google.com (Keir Mierle)
|
||||
|
||||
#include "mynteye/miniglog.h"
|
||||
|
||||
namespace google {
|
||||
|
||||
// This is the set of log sinks. This must be in a separate library to ensure
|
||||
// that there is only one instance of this across the entire program.
|
||||
std::set<google::LogSink *> log_sinks_global;
|
||||
|
||||
int log_severity_global(INFO);
|
||||
|
||||
} // namespace google
|
||||
@@ -1,3 +0,0 @@
|
||||
miniglog:
|
||||
* https://github.com/arpg/miniglog
|
||||
* https://github.com/tzutalin/miniglog
|
||||
@@ -1,199 +0,0 @@
|
||||
// Copyright 2018 Slightech Co., Ltd. All rights reserved.
|
||||
//
|
||||
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||
// you may not use this file except in compliance with the License.
|
||||
// You may obtain a copy of the License at
|
||||
//
|
||||
// http://www.apache.org/licenses/LICENSE-2.0
|
||||
//
|
||||
// Unless required by applicable law or agreed to in writing, software
|
||||
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
// See the License for the specific language governing permissions and
|
||||
// limitations under the License.
|
||||
#include "uvc/uvc.h" // NOLINT
|
||||
|
||||
#include <libuvc/libuvc.h>
|
||||
|
||||
#include "mynteye/logger.h"
|
||||
// #define ENABLE_DEBUG_SPAM
|
||||
|
||||
MYNTEYE_BEGIN_NAMESPACE
|
||||
|
||||
namespace uvc {
|
||||
|
||||
static void check(const char *call, uvc_error_t status) {
|
||||
LOG_IF(FATAL, status < 0)
|
||||
<< call << "(...) returned " << uvc_strerror(status);
|
||||
}
|
||||
#define CALL_UVC(name, ...) check(#name, name(__VA_ARGS__))
|
||||
|
||||
struct context {
|
||||
uvc_context_t *ctx;
|
||||
|
||||
context() : ctx(nullptr) {
|
||||
VLOG(2) << __func__;
|
||||
CALL_UVC(uvc_init, &ctx, nullptr);
|
||||
}
|
||||
|
||||
~context() {
|
||||
VLOG(2) << __func__;
|
||||
if (ctx)
|
||||
uvc_exit(ctx);
|
||||
}
|
||||
};
|
||||
|
||||
struct device {
|
||||
const std::shared_ptr<context> parent;
|
||||
|
||||
uvc_device_t *uvcdevice = nullptr;
|
||||
uvc_device_handle_t *handle = nullptr;
|
||||
|
||||
int vid, pid;
|
||||
|
||||
device(std::shared_ptr<context> parent, uvc_device_t *uvcdevice)
|
||||
: parent(parent), uvcdevice(uvcdevice) {
|
||||
VLOG(2) << __func__;
|
||||
open();
|
||||
|
||||
uvc_device_descriptor_t *desc;
|
||||
CALL_UVC(uvc_get_device_descriptor, uvcdevice, &desc);
|
||||
vid = desc->idVendor;
|
||||
pid = desc->idProduct;
|
||||
uvc_free_device_descriptor(desc);
|
||||
}
|
||||
|
||||
~device() {
|
||||
VLOG(2) << __func__;
|
||||
if (handle)
|
||||
uvc_close(handle);
|
||||
if (uvcdevice)
|
||||
uvc_unref_device(uvcdevice);
|
||||
}
|
||||
|
||||
void open() {
|
||||
if (!handle)
|
||||
CALL_UVC(uvc_open, uvcdevice, &handle);
|
||||
}
|
||||
};
|
||||
|
||||
std::shared_ptr<context> create_context() {
|
||||
return std::make_shared<context>();
|
||||
}
|
||||
|
||||
std::vector<std::shared_ptr<device>> query_devices(
|
||||
std::shared_ptr<context> context) {
|
||||
std::vector<std::shared_ptr<device>> devices;
|
||||
|
||||
uvc_device_t **list;
|
||||
CALL_UVC(uvc_get_device_list, context->ctx, &list);
|
||||
for (auto it = list; *it; ++it) {
|
||||
try {
|
||||
auto dev = std::make_shared<device>(context, *it);
|
||||
devices.push_back(dev);
|
||||
} catch (std::runtime_error &e) {
|
||||
LOG(WARNING) << "usb:" << static_cast<int>(uvc_get_bus_number(*it)) << ':'
|
||||
<< static_cast<int>(uvc_get_device_address(*it)) << ": "
|
||||
<< e.what();
|
||||
}
|
||||
}
|
||||
uvc_free_device_list(list, 1);
|
||||
|
||||
return devices;
|
||||
}
|
||||
|
||||
int get_vendor_id(const device &device) {
|
||||
return device.vid;
|
||||
}
|
||||
|
||||
int get_product_id(const device &device) {
|
||||
return device.pid;
|
||||
}
|
||||
|
||||
std::string get_name(const device &device) {
|
||||
// TODO(JohnZhao)
|
||||
UNUSED(device)
|
||||
return "";
|
||||
}
|
||||
|
||||
std::string get_video_name(const device &device) {
|
||||
// TODO(JohnZhao)
|
||||
UNUSED(device)
|
||||
return "";
|
||||
}
|
||||
|
||||
bool pu_control_range(
|
||||
const device &device, Option option, int32_t *min, int32_t *max,
|
||||
int32_t *def) {
|
||||
// TODO(JohnZhao)
|
||||
UNUSED(device)
|
||||
UNUSED(option)
|
||||
UNUSED(min)
|
||||
UNUSED(max)
|
||||
UNUSED(def)
|
||||
return false;
|
||||
}
|
||||
|
||||
bool pu_control_query(
|
||||
const device &device, Option option, pu_query query, int32_t *value) {
|
||||
// TODO(JohnZhao)
|
||||
UNUSED(device)
|
||||
UNUSED(option)
|
||||
UNUSED(query)
|
||||
UNUSED(value)
|
||||
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(
|
||||
const device &device, const xu &xu, uint8_t selector, xu_query query,
|
||||
uint16_t size, uint8_t *data) {
|
||||
// TODO(JohnZhao)
|
||||
UNUSED(device)
|
||||
UNUSED(xu)
|
||||
UNUSED(selector)
|
||||
UNUSED(query)
|
||||
UNUSED(size)
|
||||
UNUSED(data)
|
||||
return false;
|
||||
}
|
||||
|
||||
void set_device_mode(
|
||||
device &device, int width, int height, int fourcc, int fps, // NOLINT
|
||||
video_channel_callback callback) {
|
||||
// TODO(JohnZhao)
|
||||
UNUSED(device)
|
||||
UNUSED(width)
|
||||
UNUSED(height)
|
||||
UNUSED(fourcc)
|
||||
UNUSED(fps)
|
||||
UNUSED(callback)
|
||||
}
|
||||
|
||||
void start_streaming(device &device, int num_transfer_bufs) { // NOLINT
|
||||
// TODO(JohnZhao)
|
||||
UNUSED(device)
|
||||
UNUSED(num_transfer_bufs)
|
||||
}
|
||||
|
||||
void stop_streaming(device &device) { // NOLINT
|
||||
// TODO(JohnZhao)
|
||||
UNUSED(device)
|
||||
}
|
||||
|
||||
} // namespace uvc
|
||||
|
||||
MYNTEYE_END_NAMESPACE
|
||||
@@ -97,10 +97,10 @@ class BinDataset(object):
|
||||
if What.imu in result:
|
||||
imu = result[What.imu]
|
||||
np.array([(
|
||||
imu.timestamp, imu.flag,
|
||||
imu.timestamp,
|
||||
imu.accel_x, imu.accel_y, imu.accel_z,
|
||||
imu.gyro_x, imu.gyro_y, imu.gyro_z
|
||||
)], dtype="f8, i4, f8, f8, f8, f8, f8, f8").tofile(f_imu)
|
||||
)], dtype="f8, f8, f8, f8, f8, f8, f8").tofile(f_imu)
|
||||
imu_count = imu_count + 1
|
||||
has_imu = True
|
||||
sys.stdout.write('\r img: {}, imu: {}'.format(img_count, imu_count))
|
||||
@@ -130,7 +130,7 @@ class BinDataset(object):
|
||||
|
||||
if self.has_imu:
|
||||
imus = np.memmap(self._binimu, dtype=[
|
||||
('t', 'f8'), ('flag', 'i4'),
|
||||
('t', 'f8'),
|
||||
('accel_x', 'f8'), ('accel_y', 'f8'), ('accel_z', 'f8'),
|
||||
('gyro_x', 'f8'), ('gyro_y', 'f8'), ('gyro_z', 'f8'),
|
||||
], mode='r')
|
||||
@@ -145,111 +145,92 @@ class BinDataset(object):
|
||||
print(' img: {}, imu: {}'.format(period_img, period_imu))
|
||||
|
||||
imgs_t_diff = np.diff(imgs['t'])
|
||||
# imus_t_diff = np.diff(imus['t'])
|
||||
imus_t_diff = np.diff(imus['t'])
|
||||
|
||||
accel = imus[imus['flag'] == 1]
|
||||
accel_t_diff = np.diff(accel['t'])
|
||||
gyro = imus[imus['flag'] == 2]
|
||||
gyro_t_diff = np.diff(gyro['t'])
|
||||
|
||||
print('\ncount')
|
||||
print(' imgs: {}, imus: {}, accel: {}, gyro: {}'.format(
|
||||
imgs.size, imus.size, accel.size, gyro.size))
|
||||
print('\ndiff count')
|
||||
print(' imgs_t_diff: {}, accel_t_diff: {}, gyro_t_diff: {}'.format(
|
||||
imgs_t_diff.size, accel_t_diff.size, gyro_t_diff.size))
|
||||
print(' imgs: {}, imus: {}'.format(imgs['t'].size, imus['t'].size))
|
||||
print(' imgs_t_diff: {}, imus_t_diff: {}'
|
||||
.format(imgs_t_diff.size, imus_t_diff.size))
|
||||
|
||||
print('\ndiff where (factor={})'.format(args.factor))
|
||||
self._print_t_diff_where('imgs', imgs_t_diff, period_img, args.factor)
|
||||
# self._print_t_diff_where('imus', imus_t_diff, period_imu, args.factor)
|
||||
self._print_t_diff_where('accel', accel_t_diff, period_imu, args.factor)
|
||||
self._print_t_diff_where('gyro', gyro_t_diff, period_imu, args.factor)
|
||||
|
||||
where = np.argwhere(imgs_t_diff > period_img * (1 + args.factor))
|
||||
print(' imgs where diff > {}*{} ({})'.format(period_img,
|
||||
1 + args.factor, where.size))
|
||||
for x in where:
|
||||
print(' {:8d}: {:.16f}'.format(x[0], imgs_t_diff[x][0]))
|
||||
|
||||
where = np.argwhere(imgs_t_diff < period_img * (1 - args.factor))
|
||||
print(' imgs where diff < {}*{} ({})'.format(period_img,
|
||||
1 - args.factor, where.size))
|
||||
for x in where:
|
||||
print(' {:8d}: {:.16f}'.format(x[0], imgs_t_diff[x][0]))
|
||||
|
||||
where = np.argwhere(imus_t_diff > period_imu * (1 + args.factor))
|
||||
print(' imus where diff > {}*{} ({})'.format(period_imu,
|
||||
1 + args.factor, where.size))
|
||||
for x in where:
|
||||
print(' {:8d}: {:.16f}'.format(x[0], imus_t_diff[x][0]))
|
||||
|
||||
where = np.argwhere(imus_t_diff < period_imu * (1 - args.factor))
|
||||
print(' imus where diff < {}*{} ({})'.format(period_imu,
|
||||
1 - args.factor, where.size))
|
||||
for x in where:
|
||||
print(' {:8d}: {:.16f}'.format(x[0], imus_t_diff[x][0]))
|
||||
|
||||
import pandas as pd
|
||||
bins = imgs['t']
|
||||
bins_n = imgs['t'].size
|
||||
bins = pd.Series(data=bins).drop_duplicates(keep='first')
|
||||
cats = pd.cut(imus['t'], bins)
|
||||
|
||||
print('\nimage timestamp duplicates: {}'.format(bins_n - bins.size))
|
||||
|
||||
def _cut_by_imgs_t(imus_t):
|
||||
cats = pd.cut(imus_t, bins)
|
||||
return cats.value_counts()
|
||||
self._plot(outdir, imgs_t_diff, imus_t_diff, cats.value_counts())
|
||||
|
||||
self._plot(
|
||||
outdir,
|
||||
imgs_t_diff,
|
||||
accel_t_diff,
|
||||
_cut_by_imgs_t(
|
||||
accel['t']),
|
||||
gyro_t_diff,
|
||||
_cut_by_imgs_t(
|
||||
gyro['t']))
|
||||
|
||||
def _print_t_diff_where(self, name, t_diff, period, factor):
|
||||
import numpy as np
|
||||
|
||||
where = np.argwhere(t_diff > period * (1 + factor))
|
||||
print(' {} where diff > {}*{} ({})'.format(
|
||||
name, period, 1 + factor, where.size))
|
||||
for x in where:
|
||||
print(' {:8d}: {:.16f}'.format(x[0], t_diff[x][0]))
|
||||
|
||||
where = np.argwhere(t_diff < period * (1 - factor))
|
||||
print(' {} where diff < {}*{} ({})'.format(
|
||||
name, period, 1 - factor, where.size))
|
||||
for x in where:
|
||||
print(' {:8d}: {:.16f}'.format(x[0], t_diff[x][0]))
|
||||
|
||||
def _plot(self, outdir, imgs_t_diff,
|
||||
accel_t_diff, accel_counts, gyro_t_diff, gyro_counts):
|
||||
def _plot(self, outdir, imgs_t_diff, imus_t_diff, imgs_t_imus):
|
||||
import matplotlib.pyplot as plt
|
||||
import numpy as np
|
||||
|
||||
fig_1 = plt.figure(1, [16, 12])
|
||||
fig_1 = plt.figure(1, [16, 6])
|
||||
fig_1.suptitle('Stamp Analytics')
|
||||
fig_1.subplots_adjust(
|
||||
left=0.1,
|
||||
right=0.95,
|
||||
top=0.85,
|
||||
bottom=0.15,
|
||||
wspace=0.4,
|
||||
hspace=0.4)
|
||||
wspace=0.4)
|
||||
|
||||
ax_imgs_t_diff = fig_1.add_subplot(231)
|
||||
ax_imgs_t_diff = fig_1.add_subplot(131)
|
||||
ax_imgs_t_diff.set_title('Image Timestamp Diff')
|
||||
ax_imgs_t_diff.set_xlabel('diff index')
|
||||
ax_imgs_t_diff.set_ylabel('diff (s)')
|
||||
ax_imgs_t_diff.axis('auto')
|
||||
|
||||
ax_imgs_t_diff.set_xlim([0, imgs_t_diff.size])
|
||||
ax_imgs_t_diff.plot(imgs_t_diff)
|
||||
|
||||
def _plot_imus(name, t_diff, counts, pos_offset=0):
|
||||
ax_imus_t_diff = fig_1.add_subplot(232 + pos_offset)
|
||||
ax_imus_t_diff.set_title('{} Timestamp Diff'.format(name))
|
||||
ax_imus_t_diff = fig_1.add_subplot(132)
|
||||
ax_imus_t_diff.set_title('Imu Timestamp Diff')
|
||||
ax_imus_t_diff.set_xlabel('diff index')
|
||||
ax_imus_t_diff.set_ylabel('diff (s)')
|
||||
ax_imus_t_diff.axis('auto')
|
||||
|
||||
ax_imus_t_diff.set_xlim([0, t_diff.size - 1])
|
||||
ax_imus_t_diff.plot(t_diff)
|
||||
ax_imgs_t_imus = fig_1.add_subplot(133)
|
||||
ax_imgs_t_imus.set_title('Imu Count Per Image Intervel')
|
||||
ax_imgs_t_imus.set_xlabel('intervel index')
|
||||
ax_imgs_t_imus.set_ylabel('imu count')
|
||||
ax_imgs_t_imus.axis('auto')
|
||||
|
||||
ax_imus_counts = fig_1.add_subplot(233 + pos_offset)
|
||||
ax_imus_counts.set_title('{} Count Per Image Intervel'.format(name))
|
||||
ax_imus_counts.set_xlabel('intervel index')
|
||||
ax_imus_counts.set_ylabel('imu count')
|
||||
ax_imus_counts.axis('auto')
|
||||
ax_imgs_t_diff.set_xlim([0, imgs_t_diff.size])
|
||||
ax_imgs_t_diff.plot(imgs_t_diff)
|
||||
|
||||
# print(counts.values)
|
||||
# counts.plot(kind='line', ax=ax_imus_counts)
|
||||
data = counts.values
|
||||
ax_imus_counts.set_xlim([0, data.size])
|
||||
ax_imus_counts.set_ylim([np.min(data) - 1, np.max(data) + 1])
|
||||
ax_imus_counts.plot(data)
|
||||
ax_imus_t_diff.set_xlim([0, imus_t_diff.size])
|
||||
ax_imus_t_diff.plot(imus_t_diff)
|
||||
|
||||
_plot_imus('Accel', accel_t_diff, accel_counts)
|
||||
_plot_imus('Gyro', gyro_t_diff, gyro_counts, 3)
|
||||
# print(imgs_t_imus.values)
|
||||
# imgs_t_imus.plot(kind='line', ax=ax_imgs_t_imus)
|
||||
data = imgs_t_imus.values
|
||||
ax_imgs_t_imus.set_xlim([0, data.size])
|
||||
ax_imgs_t_imus.set_ylim([np.min(data) - 1, np.max(data) + 1])
|
||||
ax_imgs_t_imus.plot(data)
|
||||
|
||||
if outdir:
|
||||
figpath = os.path.join(outdir, RESULT_FIGURE)
|
||||
@@ -307,14 +288,14 @@ def _parse_args():
|
||||
'--rate-img',
|
||||
dest='rate_img',
|
||||
metavar='RATE',
|
||||
default=60,
|
||||
default=25,
|
||||
type=int,
|
||||
help='the img rate (default: %(default)s)')
|
||||
parser.add_argument(
|
||||
'--rate-imu',
|
||||
dest='rate_imu',
|
||||
metavar='RATE',
|
||||
default=200,
|
||||
default=500,
|
||||
type=int,
|
||||
help='the imu rate (default: %(default)s)')
|
||||
return parser.parse_args()
|
||||
|
||||
@@ -20,17 +20,13 @@ set_outdir(
|
||||
"${OUT_DIR}/bin/${DIR_NAME}"
|
||||
)
|
||||
|
||||
include_directories(
|
||||
${PRO_DIR}/src
|
||||
)
|
||||
|
||||
## record
|
||||
|
||||
# make_executable(record
|
||||
# SRCS record.cc dataset.cc
|
||||
# LINK_LIBS mynteye ${OpenCV_LIBS}
|
||||
# DLL_SEARCH_PATHS ${PRO_DIR}/_install/bin ${OpenCV_LIB_SEARCH_PATH}
|
||||
#)
|
||||
make_executable(record
|
||||
SRCS record.cc dataset.cc
|
||||
LINK_LIBS mynteye ${OpenCV_LIBS}
|
||||
DLL_SEARCH_PATHS ${PRO_DIR}/_install/bin ${OpenCV_LIB_SEARCH_PATH}
|
||||
)
|
||||
|
||||
make_executable(record2
|
||||
SRCS record2.cc dataset.cc
|
||||
|
||||
@@ -13,8 +13,11 @@
|
||||
// limitations under the License.
|
||||
#include "dataset/dataset.h"
|
||||
|
||||
#ifdef WITH_OPENCV2
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
#include <opencv2/imgproc/imgproc.hpp>
|
||||
#else
|
||||
#include <opencv2/imgcodecs/imgcodecs.hpp>
|
||||
#endif
|
||||
|
||||
#include <iomanip>
|
||||
#include <limits>
|
||||
@@ -65,53 +68,23 @@ void Dataset::SaveStreamData(
|
||||
std::stringstream ss;
|
||||
ss << writer->outdir << MYNTEYE_OS_SEP << std::dec
|
||||
<< std::setw(IMAGE_FILENAME_WIDTH) << std::setfill('0') << seq << ".png";
|
||||
if (data.frame->format() == Format::GREY) {
|
||||
cv::Mat img(
|
||||
data.frame->height(), data.frame->width(), CV_8UC1,
|
||||
data.frame->data());
|
||||
data.frame->height(), data.frame->width(), CV_8UC1, data.frame->data());
|
||||
cv::imwrite(ss.str(), img);
|
||||
} else if (data.frame->format() == Format::YUYV) {
|
||||
cv::Mat img(
|
||||
data.frame->height(), data.frame->width(), CV_8UC2,
|
||||
data.frame->data());
|
||||
cv::cvtColor(img, img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::imwrite(ss.str(), img);
|
||||
} else if (data.frame->format() == Format::BGR888) {
|
||||
cv::Mat img(
|
||||
data.frame->height(), data.frame->width(), CV_8UC3,
|
||||
data.frame->data());
|
||||
// cv::cvtColor(img, img, CV_BGR2RGB);
|
||||
cv::imwrite(ss.str(), img);
|
||||
} else {
|
||||
cv::Mat img(
|
||||
data.frame->height(), data.frame->width(), CV_8UC1,
|
||||
data.frame->data());
|
||||
cv::imwrite(ss.str(), img);
|
||||
}
|
||||
}
|
||||
++stream_counts_[stream];
|
||||
}
|
||||
|
||||
void Dataset::SaveMotionData(const device::MotionData &data) {
|
||||
auto &&writer = GetMotionWriter();
|
||||
// auto seq = data.imu->serial_number;
|
||||
auto seq = motion_count_;
|
||||
if (data.imu->flag == 1 || data.imu->flag == 2) {
|
||||
writer->ofs << seq << ", " << static_cast<int>(data.imu->flag) << ", "
|
||||
writer->ofs << seq << ", " << data.imu->frame_id << ", "
|
||||
<< data.imu->timestamp << ", " << data.imu->accel[0] << ", "
|
||||
<< data.imu->accel[1] << ", " << data.imu->accel[2] << ", "
|
||||
<< data.imu->gyro[0] << ", " << data.imu->gyro[1] << ", "
|
||||
<< data.imu->gyro[2] << ", " << data.imu->temperature
|
||||
<< std::endl;
|
||||
++motion_count_;
|
||||
}
|
||||
/*
|
||||
if(motion_count_ != seq) {
|
||||
LOG(INFO) << "motion_count_ != seq !" << " motion_count_: " << motion_count_
|
||||
<< " seq: " << seq;
|
||||
motion_count_ = seq;
|
||||
}
|
||||
*/
|
||||
}
|
||||
|
||||
void Dataset::SaveStreamData(
|
||||
@@ -132,24 +105,14 @@ void Dataset::SaveStreamData(
|
||||
|
||||
void Dataset::SaveMotionData(const api::MotionData &data) {
|
||||
auto &&writer = GetMotionWriter();
|
||||
// auto seq = data.imu->serial_number;
|
||||
auto seq = motion_count_;
|
||||
if (data.imu->flag == 1 || data.imu->flag == 2) {
|
||||
writer->ofs << seq << ", " << static_cast<int>(data.imu->flag) << ", "
|
||||
writer->ofs << seq << ", " << data.imu->frame_id << ", "
|
||||
<< data.imu->timestamp << ", " << data.imu->accel[0] << ", "
|
||||
<< data.imu->accel[1] << ", " << data.imu->accel[2] << ", "
|
||||
<< data.imu->gyro[0] << ", " << data.imu->gyro[1] << ", "
|
||||
<< data.imu->gyro[2] << ", " << data.imu->temperature
|
||||
<< std::endl;
|
||||
++motion_count_;
|
||||
}
|
||||
/*
|
||||
if(motion_count_ != seq) {
|
||||
LOG(INFO) << "motion_count_ != seq !" << " motion_count_: " << motion_count_
|
||||
<< " seq: " << seq;
|
||||
motion_count_ = seq;
|
||||
}
|
||||
*/
|
||||
}
|
||||
|
||||
Dataset::writer_t Dataset::GetStreamWriter(const Stream &stream) {
|
||||
@@ -188,15 +151,13 @@ Dataset::writer_t Dataset::GetMotionWriter() {
|
||||
|
||||
files::mkdir(writer->outdir);
|
||||
writer->ofs.open(writer->outfile, std::ofstream::out);
|
||||
writer->ofs << "seq, flag, timestamp, accel_x, accel_y, accel_z, "
|
||||
writer->ofs << "seq, frame_id, timestamp, accel_x, accel_y, accel_z, "
|
||||
"gyro_x, gyro_y, gyro_z, temperature"
|
||||
<< std::endl;
|
||||
writer->ofs << FULL_PRECISION;
|
||||
|
||||
motion_writer_ = writer;
|
||||
motion_count_ = 0;
|
||||
accel_count_ = 0;
|
||||
gyro_count_ = 0;
|
||||
}
|
||||
return motion_writer_;
|
||||
}
|
||||
|
||||
@@ -58,8 +58,6 @@ class Dataset {
|
||||
|
||||
std::map<Stream, std::size_t> stream_counts_;
|
||||
std::size_t motion_count_;
|
||||
std::size_t accel_count_;
|
||||
std::size_t gyro_count_;
|
||||
};
|
||||
|
||||
} // namespace tools
|
||||
|
||||
@@ -26,8 +26,23 @@ int main(int argc, char *argv[]) {
|
||||
auto &&api = API::Create(argc, argv);
|
||||
if (!api)
|
||||
return 1;
|
||||
api->InitResolution(Resolution::RES_1280x400);
|
||||
api->SetStreamRequest(Format::BGR888, FrameRate::RATE_30_FPS);
|
||||
/*
|
||||
{ // auto-exposure
|
||||
api->SetOptionValue(Option::EXPOSURE_MODE, 0);
|
||||
api->SetOptionValue(Option::MAX_GAIN, 40); // [0.48]
|
||||
api->SetOptionValue(Option::MAX_EXPOSURE_TIME, 120); // [0,240]
|
||||
api->SetOptionValue(Option::DESIRED_BRIGHTNESS, 200); // [0,255]
|
||||
}
|
||||
{ // manual-exposure
|
||||
api->SetOptionValue(Option::EXPOSURE_MODE, 1);
|
||||
api->SetOptionValue(Option::GAIN, 20); // [0.48]
|
||||
api->SetOptionValue(Option::BRIGHTNESS, 20); // [0,240]
|
||||
api->SetOptionValue(Option::CONTRAST, 20); // [0,255]
|
||||
}
|
||||
api->SetOptionValue(Option::IR_CONTROL, 80);
|
||||
api->SetOptionValue(Option::FRAME_RATE, 25);
|
||||
api->SetOptionValue(Option::IMU_FREQUENCY, 500);
|
||||
*/
|
||||
api->LogOptionInfos();
|
||||
|
||||
// Enable this will cache the motion datas until you get them.
|
||||
@@ -57,44 +72,14 @@ int main(int argc, char *argv[]) {
|
||||
auto &&motion_datas = api->GetMotionDatas();
|
||||
imu_count += motion_datas.size();
|
||||
|
||||
auto &&left_frame = left_datas.back().frame;
|
||||
auto &&right_frame = right_datas.back().frame;
|
||||
auto &&left_img = left_datas.back().frame;
|
||||
auto &&right_img = right_datas.back().frame;
|
||||
|
||||
cv::Mat img;
|
||||
|
||||
if (left_frame->format() == Format::GREY) {
|
||||
cv::Mat left_img(
|
||||
left_frame->height(), left_frame->width(), CV_8UC1,
|
||||
left_frame->data());
|
||||
cv::Mat right_img(
|
||||
right_frame->height(), right_frame->width(), CV_8UC1,
|
||||
right_frame->data());
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else if (left_frame->format() == Format::YUYV) {
|
||||
cv::Mat left_img(
|
||||
left_frame->height(), left_frame->width(), CV_8UC2,
|
||||
left_frame->data());
|
||||
cv::Mat right_img(
|
||||
right_frame->height(), right_frame->width(), CV_8UC2,
|
||||
right_frame->data());
|
||||
cv::cvtColor(left_img, left_img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::cvtColor(right_img, right_img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else if (left_frame->format() == Format::BGR888) {
|
||||
cv::Mat left_img(
|
||||
left_frame->height(), left_frame->width(), CV_8UC3,
|
||||
left_frame->data());
|
||||
cv::Mat right_img(
|
||||
right_frame->height(), right_frame->width(), CV_8UC3,
|
||||
right_frame->data());
|
||||
cv::cvtColor(left_img, left_img, CV_BGR2RGB);
|
||||
cv::cvtColor(right_img, right_img, CV_BGR2RGB);
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else {
|
||||
return -1;
|
||||
}
|
||||
cv::imshow("frame", img);
|
||||
if (img_count > 10 && imu_count > 50) { // save
|
||||
|
||||
{ // save
|
||||
for (auto &&left : left_datas) {
|
||||
dataset.SaveStreamData(Stream::LEFT, left);
|
||||
}
|
||||
|
||||
@@ -29,8 +29,23 @@ int main(int argc, char *argv[]) {
|
||||
auto &&device = device::select();
|
||||
if (!device)
|
||||
return 1;
|
||||
device->InitResolution(Resolution::RES_1280x400);
|
||||
device->SetStreamRequest(Format::BGR888, FrameRate::RATE_30_FPS);
|
||||
/*
|
||||
{ // auto-exposure
|
||||
device->SetOptionValue(Option::EXPOSURE_MODE, 0);
|
||||
device->SetOptionValue(Option::MAX_GAIN, 40); // [0.48]
|
||||
device->SetOptionValue(Option::MAX_EXPOSURE_TIME, 120); // [0,240]
|
||||
device->SetOptionValue(Option::DESIRED_BRIGHTNESS, 200); // [0,255]
|
||||
}
|
||||
{ // manual-exposure
|
||||
device->SetOptionValue(Option::EXPOSURE_MODE, 1);
|
||||
device->SetOptionValue(Option::GAIN, 20); // [0.48]
|
||||
device->SetOptionValue(Option::BRIGHTNESS, 20); // [0,240]
|
||||
device->SetOptionValue(Option::CONTRAST, 20); // [0,255]
|
||||
}
|
||||
device->SetOptionValue(Option::IR_CONTROL, 80);
|
||||
device->SetOptionValue(Option::FRAME_RATE, 25);
|
||||
device->SetOptionValue(Option::IMU_FREQUENCY, 500);
|
||||
*/
|
||||
device->LogOptionInfos();
|
||||
|
||||
// Enable this will cache the motion datas until you get them.
|
||||
@@ -62,42 +77,17 @@ int main(int argc, char *argv[]) {
|
||||
|
||||
auto &&left_frame = left_datas.back().frame;
|
||||
auto &&right_frame = right_datas.back().frame;
|
||||
|
||||
cv::Mat img;
|
||||
|
||||
if (left_frame->format() == Format::GREY) {
|
||||
cv::Mat left_img(
|
||||
left_frame->height(), left_frame->width(), CV_8UC1,
|
||||
left_frame->data());
|
||||
left_frame->height(), left_frame->width(), CV_8UC1, left_frame->data());
|
||||
cv::Mat right_img(
|
||||
right_frame->height(), right_frame->width(), CV_8UC1,
|
||||
right_frame->data());
|
||||
|
||||
cv::Mat img;
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else if (left_frame->format() == Format::YUYV) {
|
||||
cv::Mat left_img(
|
||||
left_frame->height(), left_frame->width(), CV_8UC2,
|
||||
left_frame->data());
|
||||
cv::Mat right_img(
|
||||
right_frame->height(), right_frame->width(), CV_8UC2,
|
||||
right_frame->data());
|
||||
cv::cvtColor(left_img, left_img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::cvtColor(right_img, right_img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else if (left_frame->format() == Format::BGR888) {
|
||||
cv::Mat left_img(
|
||||
left_frame->height(), left_frame->width(), CV_8UC3,
|
||||
left_frame->data());
|
||||
cv::Mat right_img(
|
||||
right_frame->height(), right_frame->width(), CV_8UC3,
|
||||
right_frame->data());
|
||||
cv::cvtColor(left_img, left_img, CV_BGR2RGB);
|
||||
cv::cvtColor(right_img, right_img, CV_BGR2RGB);
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else {
|
||||
return -1;
|
||||
}
|
||||
cv::imshow("frame", img);
|
||||
if (img_count > 10 && imu_count > 50) { // save
|
||||
|
||||
{ // save
|
||||
for (auto &&left : left_datas) {
|
||||
dataset.SaveStreamData(Stream::LEFT, left);
|
||||
}
|
||||
|
||||
@@ -81,7 +81,6 @@ class IMU(Data):
|
||||
|
||||
def __init__(self):
|
||||
super(IMU, self).__init__()
|
||||
self._flag = 0
|
||||
self._accel_x = 0
|
||||
self._accel_y = 0
|
||||
self._accel_z = 0
|
||||
@@ -89,14 +88,6 @@ class IMU(Data):
|
||||
self._gyro_y = 0
|
||||
self._gyro_z = 0
|
||||
|
||||
@property
|
||||
def flag(self):
|
||||
return self._flag
|
||||
|
||||
@flag.setter
|
||||
def flag(self, flag):
|
||||
self._flag = flag
|
||||
|
||||
@property
|
||||
def accel(self):
|
||||
return self._accel_x, self._accel_y, self._accel_z
|
||||
@@ -348,9 +339,9 @@ class MYNTEYE(Dataset):
|
||||
if index == -1:
|
||||
sys.exit('Error: Dataset is unexpected format, timestamp not found')
|
||||
|
||||
# unit from 1us to 1s
|
||||
info.timebeg = float(first.split(',')[index].strip()) * 0.000001
|
||||
info.timeend = float(last.split(',')[index].strip()) * 0.000001
|
||||
# unit from 0.01ms to 1s
|
||||
info.timebeg = float(first.split(',')[index].strip()) * 0.00001
|
||||
info.timeend = float(last.split(',')[index].strip()) * 0.00001
|
||||
# print('time: [{}, {}]'.format(info.timebeg, info.timeend))
|
||||
|
||||
return info
|
||||
@@ -373,7 +364,7 @@ class MYNTEYE(Dataset):
|
||||
for line in f:
|
||||
values = [_.strip() for _ in line.split(',')]
|
||||
img = Image()
|
||||
img.timestamp = float(values[fields['timestamp']]) * 0.000001
|
||||
img.timestamp = float(values[fields['timestamp']]) * 0.00001
|
||||
yield {What.img_left: img}
|
||||
if hit_img_right and self._info.has_img_right:
|
||||
with open(self._info.img_right_txt) as f:
|
||||
@@ -381,7 +372,7 @@ class MYNTEYE(Dataset):
|
||||
for line in f:
|
||||
values = [_.strip() for _ in line.split(',')]
|
||||
img = Image()
|
||||
img.timestamp = float(values[fields['timestamp']]) * 0.000001
|
||||
img.timestamp = float(values[fields['timestamp']]) * 0.00001
|
||||
yield {What.img_right: img}
|
||||
if (hit_imu or hit_temp) and self._info.has_imu:
|
||||
with open(self._info.imu_txt) as f:
|
||||
@@ -389,8 +380,7 @@ class MYNTEYE(Dataset):
|
||||
for line in f:
|
||||
values = [_.strip() for _ in line.split(',')]
|
||||
imu = IMU()
|
||||
imu.timestamp = float(values[fields['timestamp']]) * 0.000001
|
||||
imu.flag = values[fields['flag']]
|
||||
imu.timestamp = float(values[fields['timestamp']]) * 0.00001
|
||||
imu.accel_x = float(values[fields['accel_x']])
|
||||
imu.accel_y = float(values[fields['accel_y']])
|
||||
imu.accel_z = float(values[fields['accel_z']])
|
||||
|
||||
@@ -1,10 +1,10 @@
|
||||
%YAML:1.0
|
||||
---
|
||||
device_name: MYNT-EYE-S210A
|
||||
device_name: MYNT-EYE-S1000
|
||||
serial_number: "0386322C0009070E"
|
||||
firmware_version: "1.0"
|
||||
hardware_version: "1.0"
|
||||
spec_version: "1.1"
|
||||
firmware_version: "2.2"
|
||||
hardware_version: "2.0"
|
||||
spec_version: "1.0"
|
||||
lens_type: "0000"
|
||||
imu_type: "0000"
|
||||
nominal_baseline: 120
|
||||
|
||||
@@ -1,53 +1,32 @@
|
||||
%YAML:1.0
|
||||
---
|
||||
version: "1.1"
|
||||
in_left_map:
|
||||
in_left:
|
||||
-
|
||||
width: 640
|
||||
height: 400
|
||||
fx: 1.9739641213416058e+02
|
||||
fy: 1.9772337597617189e+02
|
||||
cx: 3.2611983633916327e+02
|
||||
cy: 1.9986969132833946e+02
|
||||
width: 752
|
||||
height: 480
|
||||
fx: 3.6220059643202876e+02
|
||||
fy: 3.6350065250745848e+02
|
||||
cx: 4.0658699068023441e+02
|
||||
cy: 2.3435161110061483e+02
|
||||
model: 0
|
||||
coeffs: [ 1.2135236310725651e-01, -8.5442776049177036e-02,
|
||||
2.4914898631983504e-03, -3.7752063658256863e-03, 0. ]
|
||||
coeffs: [ -2.5034765682756088e-01, 5.0579399202897619e-02,
|
||||
-7.0536676161976066e-04, -8.5255451307033846e-03, 0. ]
|
||||
in_right:
|
||||
-
|
||||
width: 1280
|
||||
height: 800
|
||||
fx: 1.9739641213416058e+02
|
||||
fy: 1.9772337597617189e+02
|
||||
cx: 3.2611983633916327e+02
|
||||
cy: 1.9986969132833946e+02
|
||||
width: 752
|
||||
height: 480
|
||||
fx: 3.6514014888558478e+02
|
||||
fy: 3.6513385298966961e+02
|
||||
cx: 3.8932395100630907e+02
|
||||
cy: 2.3495160212312547e+02
|
||||
model: 0
|
||||
coeffs: [ 1.2135236310725651e-01, -8.5442776049177036e-02,
|
||||
2.4914898631983504e-03, -3.7752063658256863e-03, 0. ]
|
||||
in_right_map:
|
||||
-
|
||||
width: 640
|
||||
height: 400
|
||||
fx: 2.0335498653655989e+02
|
||||
fy: 2.0453858622699008e+02
|
||||
cx: 3.1589962248180814e+02
|
||||
cy: 2.1871688038954812e+02
|
||||
model: 0
|
||||
coeffs: [ 2.2904330559241560e-02, -2.9561990079971841e-02,
|
||||
3.9725942760981507e-03, -3.9689073214945591e-03, 0. ]
|
||||
-
|
||||
width: 1280
|
||||
height: 800
|
||||
fx: 2.0335498653655989e+02
|
||||
fy: 2.0453858622699008e+02
|
||||
cx: 3.1589962248180814e+02
|
||||
cy: 2.1871688038954812e+02
|
||||
model: 0
|
||||
coeffs: [ 2.2904330559241560e-02, -2.9561990079971841e-02,
|
||||
3.9725942760981507e-03, -3.9689073214945591e-03, 0. ]
|
||||
coeffs: [ -3.0377346762098512e-01, 7.9929693673999838e-02,
|
||||
5.1547517530716883e-05, -6.7345903740579250e-04, 0. ]
|
||||
ex_right_to_left:
|
||||
rotation: [ 9.9998850083695123e-01, -1.9263678722299450e-03,
|
||||
-4.3917309443490191e-03, 1.8166060642710027e-03,
|
||||
9.9968925981619028e-01, -2.4861290203142431e-02,
|
||||
4.4382582477776426e-03, 2.4853026274046636e-02,
|
||||
9.9968126367795229e-01 ]
|
||||
translation: [ -8.2270200890555529e+01, -1.9535144360069059e+00,
|
||||
2.2588034344482368e+00 ]
|
||||
rotation: [ 9.9867908939669447e-01, -6.3445566137485428e-03,
|
||||
5.0988459509619687e-02, 5.9890316389333252e-03,
|
||||
9.9995670037792639e-01, 7.1224201868366971e-03,
|
||||
-5.1031440326695092e-02, -6.8076406092671274e-03,
|
||||
9.9867384471984544e-01 ]
|
||||
translation: [ -1.2002489764113250e+02, -1.1782637409050747e+00,
|
||||
-5.2058205159996538e+00 ]
|
||||
|
||||
@@ -13,7 +13,6 @@
|
||||
// limitations under the License.
|
||||
#include "writer/device_writer.h"
|
||||
|
||||
#include <map>
|
||||
#include <vector>
|
||||
|
||||
#include <opencv2/core/core.hpp>
|
||||
@@ -70,9 +69,9 @@ bool DeviceWriter::WriteImgParams(const img_params_t ¶ms) {
|
||||
nullptr, const_cast<img_params_t *>(¶ms), nullptr,
|
||||
&dev_info->spec_version)) {
|
||||
LOG(INFO) << "Write img params success";
|
||||
// LOG(INFO) << "Intrinsics left: {" << params.in_left << "}";
|
||||
// LOG(INFO) << "Intrinsics right: {" << params.in_right << "}";
|
||||
LOG(INFO) << "Extrinsics left to right: {" << params.ex_right_to_left
|
||||
LOG(INFO) << "Intrinsics left: {" << params.in_left << "}";
|
||||
LOG(INFO) << "Intrinsics right: {" << params.in_right << "}";
|
||||
LOG(INFO) << "Extrinsics right to left: {" << params.ex_right_to_left
|
||||
<< "}";
|
||||
return true;
|
||||
} else {
|
||||
@@ -126,16 +125,6 @@ cv::FileStorage &operator<<(
|
||||
return fs;
|
||||
}
|
||||
|
||||
cv::FileStorage &operator<<(
|
||||
cv::FileStorage &fs, const std::map<Resolution, Intrinsics> &mapIn) {
|
||||
fs << "[";
|
||||
std::map<Resolution, Intrinsics>::const_iterator it;
|
||||
for (it = mapIn.begin(); it != mapIn.end(); it++)
|
||||
fs << (*it).second;
|
||||
fs << "]";
|
||||
return fs;
|
||||
}
|
||||
|
||||
cv::FileStorage &operator<<(cv::FileStorage &fs, const ImuIntrinsics &in) {
|
||||
std::vector<double> scales;
|
||||
for (std::size_t i = 0; i < 3; i++) {
|
||||
@@ -187,25 +176,18 @@ bool DeviceWriter::SaveDeviceInfo(
|
||||
}
|
||||
|
||||
bool DeviceWriter::SaveImgParams(
|
||||
const dev_info_t &info, const img_params_t ¶ms,
|
||||
const std::string &filepath) {
|
||||
const img_params_t ¶ms, const std::string &filepath) {
|
||||
using FileStorage = cv::FileStorage;
|
||||
FileStorage fs(filepath, FileStorage::WRITE);
|
||||
if (!fs.isOpened()) {
|
||||
LOG(ERROR) << "Failed to save file: " << filepath;
|
||||
return false;
|
||||
}
|
||||
|
||||
if (params.in_left_map.size() == params.in_right_map.size()) {
|
||||
fs << "version" << info.spec_version.to_string() << "in_left_map"
|
||||
<< params.in_left_map << "in_right_map" << params.in_right_map
|
||||
<< "ex_right_to_left" << params.ex_right_to_left;
|
||||
fs << "in_left" << std::vector<Intrinsics>{params.in_left} << "in_right"
|
||||
<< std::vector<Intrinsics>{params.in_right} << "ex_right_to_left"
|
||||
<< params.ex_right_to_left;
|
||||
fs.release();
|
||||
return true;
|
||||
} else {
|
||||
fs.release();
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
bool DeviceWriter::SaveImuParams(
|
||||
@@ -228,7 +210,9 @@ void DeviceWriter::SaveAllInfos(const std::string &dir) {
|
||||
}
|
||||
SaveDeviceInfo(*device_->GetInfo(), dir + MYNTEYE_OS_SEP "device.info");
|
||||
SaveImgParams(
|
||||
*device_->GetInfo(), device_->GetImgParams(),
|
||||
{false, device_->GetIntrinsics(Stream::LEFT),
|
||||
device_->GetIntrinsics(Stream::RIGHT),
|
||||
device_->GetExtrinsics(Stream::RIGHT, Stream::LEFT)},
|
||||
dir + MYNTEYE_OS_SEP "img.params");
|
||||
auto &&m_in = device_->GetMotionIntrinsics();
|
||||
SaveImuParams(
|
||||
@@ -342,7 +326,6 @@ DeviceWriter::img_params_t DeviceWriter::LoadImgParams(
|
||||
}
|
||||
|
||||
img_params_t params;
|
||||
if (fs["version"].isNone()) {
|
||||
if (fs["in_left"].isNone()) {
|
||||
std::uint16_t w = 752;
|
||||
std::uint16_t h = 480;
|
||||
@@ -362,31 +345,15 @@ DeviceWriter::img_params_t DeviceWriter::LoadImgParams(
|
||||
fs["R"] >> R;
|
||||
fs["T"] >> T;
|
||||
|
||||
to_intrinsics(
|
||||
w, h, m, M1, D1, ¶ms.in_left_map[Resolution::RES_752x480]);
|
||||
to_intrinsics(
|
||||
w, h, m, M2, D2, ¶ms.in_right_map[Resolution::RES_752x480]);
|
||||
to_intrinsics(w, h, m, M1, D1, ¶ms.in_left);
|
||||
to_intrinsics(w, h, m, M2, D2, ¶ms.in_right);
|
||||
to_extrinsics(R, T, ¶ms.ex_right_to_left);
|
||||
} else {
|
||||
fs["in_left"][0] >> params.in_left_map[Resolution::RES_752x480];
|
||||
fs["in_right"][0] >> params.in_right_map[Resolution::RES_752x480];
|
||||
fs["in_left"][0] >> params.in_left;
|
||||
fs["in_right"][0] >> params.in_right;
|
||||
fs["ex_right_to_left"] >> params.ex_right_to_left;
|
||||
}
|
||||
} else {
|
||||
// TODO(Kalman): Is there a more reasonable way?
|
||||
if (static_cast<std::string>(fs["version"]) == "1.0") {
|
||||
fs["in_left_map"][0] >> params.in_left_map[Resolution::RES_752x480];
|
||||
fs["in_right_map"][0] >> params.in_right_map[Resolution::RES_752x480];
|
||||
fs["ex_right_to_left"] >> params.ex_right_to_left;
|
||||
}
|
||||
if (static_cast<std::string>(fs["version"]) == "1.1") {
|
||||
fs["in_left_map"][0] >> params.in_left_map[Resolution::RES_1280x400];
|
||||
fs["in_left_map"][1] >> params.in_left_map[Resolution::RES_2560x800];
|
||||
fs["in_right_map"][0] >> params.in_right_map[Resolution::RES_1280x400];
|
||||
fs["in_right_map"][1] >> params.in_right_map[Resolution::RES_2560x800];
|
||||
fs["ex_right_to_left"] >> params.ex_right_to_left;
|
||||
}
|
||||
}
|
||||
|
||||
fs.release();
|
||||
return params;
|
||||
}
|
||||
|
||||
@@ -31,8 +31,8 @@ namespace tools {
|
||||
class DeviceWriter {
|
||||
public:
|
||||
using dev_info_t = DeviceInfo;
|
||||
using img_params_t = device::img_params_t;
|
||||
using imu_params_t = device::imu_params_t;
|
||||
using img_params_t = Channels::img_params_t;
|
||||
using imu_params_t = Channels::imu_params_t;
|
||||
|
||||
explicit DeviceWriter(std::shared_ptr<Device> device);
|
||||
~DeviceWriter();
|
||||
@@ -47,9 +47,7 @@ class DeviceWriter {
|
||||
bool WriteImuParams(const std::string &filepath);
|
||||
|
||||
bool SaveDeviceInfo(const dev_info_t &info, const std::string &filepath);
|
||||
bool SaveImgParams(
|
||||
const dev_info_t &info, const img_params_t ¶ms,
|
||||
const std::string &filepath);
|
||||
bool SaveImgParams(const img_params_t ¶ms, const std::string &filepath);
|
||||
bool SaveImuParams(const imu_params_t ¶ms, const std::string &filepath);
|
||||
|
||||
/** Save all infos of this device */
|
||||
|
||||
@@ -104,7 +104,8 @@ struct MYNTEYE_API MotionData {
|
||||
ImuData imu;
|
||||
|
||||
bool operator==(const MotionData &other) const {
|
||||
return imu.timestamp == other.imu.timestamp;
|
||||
return imu.frame_id == other.imu.frame_id &&
|
||||
imu.timestamp == other.imu.timestamp;
|
||||
}
|
||||
};
|
||||
|
||||
@@ -363,6 +364,7 @@ BOOST_PYTHON_MODULE(mynteye_py) {
|
||||
// bp::register_ptr_to_python<std::shared_ptr<ImgData>>();
|
||||
|
||||
bp::class_<ImuData>("ImuData")
|
||||
.def_readonly("frame_id", &ImuData::frame_id)
|
||||
.def_readonly("timestamp", &ImuData::timestamp)
|
||||
.add_property(
|
||||
"accel", +[](ImuData *o) { return array_ref<double>{o->accel}; })
|
||||
|
||||
@@ -103,7 +103,6 @@ add_compile_options(-std=c++11)
|
||||
|
||||
include_directories(
|
||||
${catkin_INCLUDE_DIRS}
|
||||
${SDK_DIR}/src
|
||||
)
|
||||
|
||||
set(LINK_LIBS
|
||||
|
||||
@@ -13,9 +13,6 @@
|
||||
<arg name="depth_topic" default="depth/image_raw" />
|
||||
<arg name="points_topic" default="points/data_raw" />
|
||||
|
||||
<arg name="left_mono_topic" default="left/image_mono" />
|
||||
<arg name="right_mono_topic" default="right/image_mono" />
|
||||
|
||||
<arg name="imu_topic" default="imu/data_raw" />
|
||||
<arg name="temp_topic" default="temp/data_raw" />
|
||||
|
||||
@@ -29,33 +26,13 @@
|
||||
<arg name="points_frame_id" default="$(arg mynteye)_points_frame" />
|
||||
<arg name="depth_frame_id" default="$(arg mynteye)_depth_frame" />
|
||||
|
||||
<arg name="imu_frame_id" default="$(arg mynteye)_imu_frame" />
|
||||
<arg name="temp_frame_id" default="$(arg mynteye)_temp_frame" />
|
||||
|
||||
<arg name="gravity" default="9.8" />
|
||||
|
||||
<!-- stream toggles -->
|
||||
|
||||
<!-- Resolution -->
|
||||
<arg name="res_752x480" default="0" />
|
||||
<arg name="res_1280x400" default="1" />
|
||||
<arg name="res_2560x800" default="2" />
|
||||
|
||||
<!-- FrameRate -->
|
||||
<arg name="rate_10_fps" default="10" />
|
||||
<arg name="rate_20_fps" default="20" />
|
||||
<arg name="rate_25_fps" default="25" />
|
||||
<arg name="rate_30_fps" default="30" />
|
||||
<arg name="rate_60_fps" default="60" />
|
||||
|
||||
<!-- Format -->
|
||||
<arg name="grey" default="1497715271" />
|
||||
<arg name="yuyv" default="1497715271" />
|
||||
<arg name="bgr888" default="861030210" />
|
||||
|
||||
<arg name="resolution" default="$(arg res_1280x400)" />
|
||||
<arg name="framerate" default="$(arg rate_30_fps)" />
|
||||
<arg name="format" default="$(arg bgr888)" />
|
||||
|
||||
<arg name="enable_left_rect" default="false" />
|
||||
<arg name="enable_right_rect" default="false" />
|
||||
<arg name="enable_disparity" default="false" />
|
||||
@@ -65,46 +42,58 @@
|
||||
|
||||
<!-- device options, -1 will not set the value -->
|
||||
|
||||
<!-- gain range: [0,48] -->
|
||||
<arg name="gain" default="-1" />
|
||||
<!-- <arg name="gain" default="24" /> -->
|
||||
|
||||
<!-- brightness range: [0,240] -->
|
||||
<arg name="brightness" default="-1" />
|
||||
<!-- <arg name="brightness" default="120" /> -->
|
||||
|
||||
<!-- contrast range: [0,255] -->
|
||||
<arg name="contrast" default="-1" />
|
||||
<!-- <arg name="contrast" default="127" /> -->
|
||||
|
||||
<!-- frame_rate range: {10,15,20,25,30,35,40,45,50,55,60} -->
|
||||
<arg name="frame_rate" default="-1" />
|
||||
<!-- <arg name="frame_rate" default="25" /> -->
|
||||
|
||||
<!-- imu_frequency range: {100,200,250,333,500} -->
|
||||
<arg name="imu_frequency" default="-1" />
|
||||
<!-- <arg name="imu_frequency" default="200" /> -->
|
||||
|
||||
<!-- exposure_mode, 0: auto-exposure, 1: manual-exposure -->
|
||||
<arg name="exposure_mode" default="-1" />
|
||||
<!-- <arg name="exposure_mode" default="0" /> -->
|
||||
|
||||
<!-- max_gain range: [0,255] -->
|
||||
<!-- max_gain range: [0,48] -->
|
||||
<arg name="max_gain" default="-1" />
|
||||
<!-- <arg name="max_gain" default="8" /> -->
|
||||
<!-- <arg name="max_gain" default="48" /> -->
|
||||
|
||||
<!-- max_exposure_time range: [0,1000] -->
|
||||
<!-- max_exposure_time range: [0,240] -->
|
||||
<arg name="max_exposure_time" default="-1" />
|
||||
<!-- <arg name="max_exposure_time" default="333" /> -->
|
||||
<!-- <arg name="max_exposure_time" default="240" /> -->
|
||||
|
||||
<!-- desired_brightness range: [1,255] -->
|
||||
<!-- desired_brightness range: [0,255] -->
|
||||
<arg name="desired_brightness" default="-1" />
|
||||
<!-- <arg name="desired_brightness" default="122" /> -->
|
||||
<!-- <arg name="desired_brightness" default="192" /> -->
|
||||
|
||||
<!-- min_exposure_time range: [0,1000] -->
|
||||
<arg name="min_exposure_time" default="-1" />
|
||||
<!-- <arg name="min_exposure_time" default="0" /> -->
|
||||
<!-- ir_control range: [0,160] -->
|
||||
<arg name="ir_control" default="80" />
|
||||
<!-- <arg name="ir_control" default="0" /> -->
|
||||
|
||||
<!-- accel_range range: [6,48] -->
|
||||
<!-- hdr_mode, 0: 10-bit, 1: 12-bit -->
|
||||
<arg name="hdr_mode" default="-1" />
|
||||
<!-- <arg name="hdr_mode" default="0" /> -->
|
||||
|
||||
<!-- accel_range range: {4,8,16,32} -->
|
||||
<arg name="accel_range" default="-1" />
|
||||
<!-- <arg name="accel_range" default="6" /> -->
|
||||
<!-- <arg name="accel_range" default="8" /> -->
|
||||
|
||||
<!-- gyro_range range: [250,4000] -->
|
||||
<!-- gyro_range range: {500,1000,2000,4000} -->
|
||||
<arg name="gyro_range" default="-1" />
|
||||
<!-- <arg name="gyro_range" default="1000" /> -->
|
||||
|
||||
<!-- accel_low_filter range: [0,2] -->
|
||||
<arg name="accel_low_filter" default="-1" />
|
||||
<!-- <arg name="accel_low_filter" default="2" /> -->
|
||||
|
||||
<!-- gyro_low_filter range: [23,64] -->
|
||||
<arg name="gyro_low_filter" default="-1" />
|
||||
<!-- <arg name="gyro_low_filter" default="64" /> -->
|
||||
|
||||
<!-- Push down all topics/nodelets into "mynteye" namespace -->
|
||||
<group ns="$(arg mynteye)">
|
||||
|
||||
@@ -122,9 +111,6 @@
|
||||
<param name="points_topic" value="$(arg points_topic)" />
|
||||
<param name="depth_topic" value="$(arg depth_topic)" />
|
||||
|
||||
<param name="left_mono_topic" value="$(arg left_mono_topic)" />
|
||||
<param name="right_mono_topic" value="$(arg right_mono_topic)" />
|
||||
|
||||
<param name="imu_topic" value="$(arg imu_topic)" />
|
||||
<param name="temp_topic" value="$(arg temp_topic)" />
|
||||
|
||||
@@ -138,6 +124,7 @@
|
||||
<param name="points_frame_id" value="$(arg points_frame_id)" />
|
||||
<param name="depth_frame_id" value="$(arg depth_frame_id)" />
|
||||
|
||||
<param name="imu_frame_id" value="$(arg imu_frame_id)" />
|
||||
<param name="temp_frame_id" value="$(arg temp_frame_id)" />
|
||||
|
||||
<param name="gravity" value="$(arg gravity)" />
|
||||
@@ -151,23 +138,22 @@
|
||||
<param name="enable_points" value="$(arg enable_points)" />
|
||||
<param name="enable_depth" value="$(arg enable_depth)" />
|
||||
|
||||
<!-- init params -->
|
||||
<param name="resolution" value="$(arg resolution)" />
|
||||
<param name="framerate" value="$(arg framerate)" />
|
||||
<param name="format" value="$(arg format)" />
|
||||
|
||||
<!-- device options -->
|
||||
|
||||
<param name="gain" value="$(arg gain)" />
|
||||
<param name="brightness" value="$(arg brightness)" />
|
||||
<param name="contrast" value="$(arg contrast)" />
|
||||
<param name="frame_rate" value="$(arg frame_rate)" />
|
||||
<param name="imu_frequency" value="$(arg imu_frequency)" />
|
||||
<param name="exposure_mode" value="$(arg exposure_mode)" />
|
||||
<param name="max_gain" value="$(arg max_gain)" />
|
||||
<param name="max_exposure_time" value="$(arg max_exposure_time)" />
|
||||
<param name="desired_brightness" value="$(arg desired_brightness)" />
|
||||
<param name="min_exposure_time" value="$(arg max_exposure_time)" />
|
||||
<param name="ir_control" value="$(arg ir_control)" />
|
||||
<param name="hdr_mode" value="$(arg hdr_mode)" />
|
||||
<param name="accel_range" value="$(arg accel_range)" />
|
||||
<param name="gyro_range" value="$(arg gyro_range)" />
|
||||
<param name="accel_low_filter" value="$(arg accel_low_filter)" />
|
||||
<param name="gyro_low_filter" value="$(arg gyro_low_filter)" />
|
||||
|
||||
</node>
|
||||
|
||||
<!-- disable compressed depth plugin for image topics -->
|
||||
|
||||
@@ -7,7 +7,6 @@ Panels:
|
||||
- /Global Options1
|
||||
- /Status1
|
||||
- /Images1
|
||||
- /Images1/Gray1
|
||||
- /Images1/Rectified1
|
||||
- /Disparity1
|
||||
Splitter Ratio: 0.5
|
||||
@@ -78,34 +77,6 @@ Visualization Manager:
|
||||
Transport Hint: raw
|
||||
Unreliable: false
|
||||
Value: true
|
||||
- Class: rviz/Group
|
||||
Displays:
|
||||
- Class: rviz/Image
|
||||
Enabled: true
|
||||
Image Topic: /mynteye/left/image_mono
|
||||
Max Value: 1
|
||||
Median window: 5
|
||||
Min Value: 0
|
||||
Name: LeftMono
|
||||
Normalize Range: true
|
||||
Queue Size: 2
|
||||
Transport Hint: raw
|
||||
Unreliable: false
|
||||
Value: true
|
||||
- Class: rviz/Image
|
||||
Enabled: true
|
||||
Image Topic: /mynteye/right/image_mono
|
||||
Max Value: 1
|
||||
Median window: 5
|
||||
Min Value: 0
|
||||
Name: RightMono
|
||||
Normalize Range: true
|
||||
Queue Size: 2
|
||||
Transport Hint: raw
|
||||
Unreliable: false
|
||||
Value: true
|
||||
Enabled: true
|
||||
Name: Mono
|
||||
- Class: rviz/Group
|
||||
Displays:
|
||||
- Class: rviz/Image
|
||||
|
||||
@@ -50,7 +50,8 @@ inline double compute_time(const double end, const double start) {
|
||||
|
||||
class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
public:
|
||||
ROSWrapperNodelet() {}
|
||||
ROSWrapperNodelet() {
|
||||
}
|
||||
|
||||
~ROSWrapperNodelet() {
|
||||
// std::cout << __func__ << std::endl;
|
||||
@@ -71,15 +72,8 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
<< (right_count_ / compute_time(time_end, right_time_beg_));
|
||||
}
|
||||
if (imu_time_beg_ != -1) {
|
||||
if (publish_imu_by_sync_) {
|
||||
LOG(INFO) << "imu_sync_count: " << imu_sync_count_ << ", hz: "
|
||||
<< (imu_sync_count_ /
|
||||
compute_time(time_end, imu_time_beg_));
|
||||
} else {
|
||||
LOG(INFO) << "Imu count: " << imu_count_ << ", hz: "
|
||||
<< (imu_count_ /
|
||||
compute_time(time_end, imu_time_beg_));
|
||||
}
|
||||
<< (imu_count_ / compute_time(time_end, imu_time_beg_));
|
||||
}
|
||||
|
||||
// ROS messages could not be reliably printed here, using glog instead :(
|
||||
@@ -88,9 +82,10 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
}
|
||||
}
|
||||
|
||||
ros::Time hardTimeToSoftTime(double _hard_time) {
|
||||
ros::Time hardTimeToSoftTime(std::uint64_t _hard_time) {
|
||||
static bool isInited = false;
|
||||
static double soft_time_begin(0), hard_time_begin(0);
|
||||
static double soft_time_begin(0);
|
||||
static std::uint64_t hard_time_begin(0);
|
||||
|
||||
if (false == isInited) {
|
||||
soft_time_begin = ros::Time::now().toSec();
|
||||
@@ -99,22 +94,70 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
}
|
||||
|
||||
return ros::Time(
|
||||
soft_time_begin + (_hard_time - hard_time_begin) * 0.000001f);
|
||||
static_cast<double>(soft_time_begin +
|
||||
static_cast<double>(_hard_time - hard_time_begin) * 0.00001f));
|
||||
}
|
||||
|
||||
inline bool is_overflow(std::uint32_t now,
|
||||
std::uint32_t pre) {
|
||||
static std::uint64_t unit =
|
||||
std::numeric_limits<std::uint32_t>::max();
|
||||
|
||||
return (now < pre) && ((pre - now) > (unit / 2));
|
||||
}
|
||||
|
||||
inline bool is_repeated(std::uint32_t now,
|
||||
std::uint32_t pre) {
|
||||
return now == pre;
|
||||
}
|
||||
|
||||
inline bool is_abnormal(std::uint32_t now,
|
||||
std::uint32_t pre) {
|
||||
static std::uint64_t unit =
|
||||
std::numeric_limits<std::uint32_t>::max();
|
||||
|
||||
return (now < pre) && ((pre - now) < (unit / 4));
|
||||
}
|
||||
|
||||
ros::Time checkUpTimeStamp(std::uint32_t _hard_time,
|
||||
const Stream &stream) {
|
||||
static std::map<Stream, std::uint32_t> hard_time_now;
|
||||
static std::map<Stream, std::uint32_t> acc;
|
||||
static std::uint64_t unit_hard_time =
|
||||
std::numeric_limits<std::uint32_t>::max();
|
||||
|
||||
if (is_overflow(_hard_time, hard_time_now[stream])) {
|
||||
acc[stream]++;
|
||||
}
|
||||
|
||||
hard_time_now[stream] = _hard_time;
|
||||
|
||||
return hardTimeToSoftTime(
|
||||
acc[stream] * unit_hard_time + _hard_time);
|
||||
}
|
||||
|
||||
ros::Time checkUpImuTimeStamp(std::uint32_t _hard_time) {
|
||||
static std::uint32_t hard_time_now(0), acc(0);
|
||||
static std::uint64_t unit_hard_time =
|
||||
std::numeric_limits<std::uint32_t>::max();
|
||||
|
||||
if (is_overflow(_hard_time, hard_time_now)) {
|
||||
acc++;
|
||||
}
|
||||
|
||||
hard_time_now = _hard_time;
|
||||
|
||||
return hardTimeToSoftTime(
|
||||
acc * unit_hard_time + _hard_time);
|
||||
}
|
||||
|
||||
void onInit() override {
|
||||
initDevice();
|
||||
NODELET_FATAL_COND(api_ == nullptr, "No MYNT EYE device selected :(");
|
||||
|
||||
pthread_mutex_init(&mutex_data_, nullptr);
|
||||
nh_ = getMTNodeHandle();
|
||||
private_nh_ = getMTPrivateNodeHandle();
|
||||
int resolution = 0;
|
||||
int format = 0;
|
||||
int framerate = 20;
|
||||
private_nh_.getParam("resolution", resolution);
|
||||
private_nh_.getParam("framerate", framerate);
|
||||
private_nh_.getParam("format", format);
|
||||
frame_rate_ = framerate;
|
||||
|
||||
initDevice(resolution, format, framerate);
|
||||
NODELET_FATAL_COND(api_ == nullptr, "No MYNT EYE device selected :(");
|
||||
|
||||
// node params
|
||||
|
||||
@@ -139,15 +182,6 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
is_motion_published_ = false;
|
||||
is_started_ = false;
|
||||
|
||||
std::map<Stream, std::string> mono_names{{Stream::LEFT, "left_mono"},
|
||||
{Stream::RIGHT, "right_mono"}};
|
||||
|
||||
std::map<Stream, std::string> mono_topics{};
|
||||
for (auto &&it = mono_names.begin(); it != mono_names.end(); ++it) {
|
||||
mono_topics[it->first] = it->second;
|
||||
private_nh_.getParam(it->second + "_topic", mono_topics[it->first]);
|
||||
}
|
||||
|
||||
std::string imu_topic = "imu";
|
||||
std::string temp_topic = "temp";
|
||||
private_nh_.getParam("imu_topic", imu_topic);
|
||||
@@ -172,16 +206,20 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
// device options
|
||||
|
||||
std::map<Option, std::string> option_names = {
|
||||
{Option::GAIN, "gain"},
|
||||
{Option::BRIGHTNESS, "brightness"},
|
||||
{Option::CONTRAST, "contrast"},
|
||||
{Option::FRAME_RATE, "frame_rate"},
|
||||
{Option::IMU_FREQUENCY, "imu_frequency"},
|
||||
{Option::EXPOSURE_MODE, "exposure_mode"},
|
||||
{Option::MAX_GAIN, "max_gain"},
|
||||
{Option::MAX_EXPOSURE_TIME, "max_exposure_time"},
|
||||
{Option::DESIRED_BRIGHTNESS, "desired_brightness"},
|
||||
{Option::MIN_EXPOSURE_TIME, "min_exposure_time"},
|
||||
{Option::IR_CONTROL, "ir_control"},
|
||||
{Option::HDR_MODE, "hdr_mode"},
|
||||
{Option::ACCELEROMETER_RANGE, "accel_range"},
|
||||
{Option::GYROSCOPE_RANGE, "gyro_range"},
|
||||
{Option::ACCELEROMETER_LOW_PASS_FILTER, "accel_low_filter"},
|
||||
{Option::GYROSCOPE_LOW_PASS_FILTER, "gyro_low_filter"}};
|
||||
{Option::GYROSCOPE_RANGE, "gyro_range"}
|
||||
};
|
||||
for (auto &&it = option_names.begin(); it != option_names.end(); ++it) {
|
||||
if (!api_->Supports(it->first))
|
||||
continue;
|
||||
@@ -193,6 +231,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
}
|
||||
NODELET_INFO_STREAM(it->first << ": " << api_->GetOptionValue(it->first));
|
||||
}
|
||||
frame_rate_ = api_->GetOptionValue(Option::FRAME_RATE);
|
||||
|
||||
// publishers
|
||||
|
||||
@@ -208,18 +247,10 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
NODELET_INFO_STREAM("Advertized on topic " << topic);
|
||||
}
|
||||
|
||||
for (auto &&it = mono_topics.begin(); it != mono_topics.end(); ++it) {
|
||||
auto &&topic = mono_topics[it->first];
|
||||
if (it->first == Stream::LEFT || it->first == Stream::RIGHT) { // camera
|
||||
mono_publishers_[it->first] = it_mynteye.advertiseCamera(topic, 1);
|
||||
}
|
||||
NODELET_INFO_STREAM("Advertized on topic " << topic);
|
||||
}
|
||||
|
||||
camera_encodings_ = {{Stream::LEFT, enc::BGR8},
|
||||
{Stream::RIGHT, enc::BGR8},
|
||||
{Stream::LEFT_RECTIFIED, enc::BGR8},
|
||||
{Stream::RIGHT_RECTIFIED, enc::BGR8},
|
||||
camera_encodings_ = {{Stream::LEFT, enc::MONO8},
|
||||
{Stream::RIGHT, enc::MONO8},
|
||||
{Stream::LEFT_RECTIFIED, enc::MONO8},
|
||||
{Stream::RIGHT_RECTIFIED, enc::MONO8},
|
||||
{Stream::DISPARITY, enc::MONO8}, // float
|
||||
{Stream::DISPARITY_NORMALIZED, enc::MONO8},
|
||||
{Stream::DEPTH, enc::MONO16}};
|
||||
@@ -348,7 +379,9 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
api_->EnableStreamData(Stream::POINTS);
|
||||
api_->SetStreamCallback(
|
||||
Stream::POINTS, [this](const api::StreamData &data) {
|
||||
ros::Time stamp = hardTimeToSoftTime(data.img->timestamp);
|
||||
// ros::Time stamp = hardTimeToSoftTime(data.img->timestamp);
|
||||
ros::Time stamp = checkUpTimeStamp(
|
||||
data.img->timestamp, Stream::POINTS);
|
||||
static std::size_t count = 0;
|
||||
++count;
|
||||
publishPoints(data, count, stamp);
|
||||
@@ -368,7 +401,9 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
api_->EnableStreamData(stream);
|
||||
api_->SetStreamCallback(
|
||||
stream, [this, stream](const api::StreamData &data) {
|
||||
ros::Time stamp = hardTimeToSoftTime(data.img->timestamp);
|
||||
// ros::Time stamp = hardTimeToSoftTime(data.img->timestamp);
|
||||
ros::Time stamp = checkUpTimeStamp(
|
||||
data.img->timestamp, stream);
|
||||
static std::size_t count = 0;
|
||||
++count;
|
||||
publishCamera(stream, data, count, stamp);
|
||||
@@ -378,12 +413,13 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
}
|
||||
|
||||
void publishTopics() {
|
||||
if ((camera_publishers_[Stream::LEFT].getNumSubscribers() > 0 ||
|
||||
mono_publishers_[Stream::LEFT].getNumSubscribers() > 0) &&
|
||||
if (camera_publishers_[Stream::LEFT].getNumSubscribers() > 0 &&
|
||||
!is_published_[Stream::LEFT]) {
|
||||
api_->SetStreamCallback(
|
||||
Stream::LEFT, [this](const api::StreamData &data) {
|
||||
ros::Time stamp = hardTimeToSoftTime(data.img->timestamp);
|
||||
Stream::LEFT, [&](const api::StreamData &data) {
|
||||
// ros::Time stamp = hardTimeToSoftTime(data.img->timestamp);
|
||||
ros::Time stamp = checkUpTimeStamp(
|
||||
data.img->timestamp, Stream::LEFT);
|
||||
|
||||
// static double img_time_prev = -1;
|
||||
// NODELET_INFO_STREAM("ros_time_beg: " << FULL_PRECISION <<
|
||||
@@ -398,7 +434,6 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
|
||||
++left_count_;
|
||||
publishCamera(Stream::LEFT, data, left_count_, stamp);
|
||||
publishMono(Stream::LEFT, data, left_count_, stamp);
|
||||
NODELET_DEBUG_STREAM(
|
||||
Stream::LEFT << ", count: " << left_count_
|
||||
<< ", frame_id: " << data.img->frame_id
|
||||
@@ -409,16 +444,16 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
is_published_[Stream::LEFT] = true;
|
||||
}
|
||||
|
||||
if ((camera_publishers_[Stream::RIGHT].getNumSubscribers() > 0 ||
|
||||
mono_publishers_[Stream::RIGHT].getNumSubscribers() > 0) &&
|
||||
if (camera_publishers_[Stream::RIGHT].getNumSubscribers() > 0 &&
|
||||
!is_published_[Stream::RIGHT]) {
|
||||
api_->SetStreamCallback(
|
||||
Stream::RIGHT, [this](const api::StreamData &data) {
|
||||
ros::Time stamp = hardTimeToSoftTime(data.img->timestamp);
|
||||
Stream::RIGHT, [&](const api::StreamData &data) {
|
||||
// ros::Time stamp = hardTimeToSoftTime(data.img->timestamp);
|
||||
ros::Time stamp = checkUpTimeStamp(
|
||||
data.img->timestamp, Stream::RIGHT);
|
||||
|
||||
++right_count_;
|
||||
publishCamera(Stream::RIGHT, data, right_count_, stamp);
|
||||
publishMono(Stream::RIGHT, data, right_count_, stamp);
|
||||
NODELET_DEBUG_STREAM(
|
||||
Stream::RIGHT
|
||||
<< ", count: " << right_count_ << ", frame_id: "
|
||||
@@ -444,10 +479,12 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
|
||||
if (!is_motion_published_) {
|
||||
api_->SetMotionCallback([this](const api::MotionData &data) {
|
||||
ros::Time stamp = hardTimeToSoftTime(data.imu->timestamp);
|
||||
// ros::Time stamp = hardTimeToSoftTime(data.imu->timestamp);
|
||||
ros::Time stamp = checkUpImuTimeStamp(data.imu->timestamp);
|
||||
|
||||
// static double imu_time_prev = -1;
|
||||
// NODELET_INFO_STREAM("ros_time_beg: " << FULL_PRECISION << ros_time_beg
|
||||
// NODELET_INFO_STREAM("ros_time_beg: " << FULL_PRECISION <<
|
||||
// ros_time_beg
|
||||
// << ", imu_time_elapsed: " << FULL_PRECISION
|
||||
// << ((data.imu->timestamp - imu_time_beg) * 0.00001f)
|
||||
// << ", imu_time_diff: " << FULL_PRECISION
|
||||
@@ -456,26 +493,11 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
// imu_time_prev = data.imu->timestamp;
|
||||
|
||||
++imu_count_;
|
||||
if (publish_imu_by_sync_) {
|
||||
if (data.imu) {
|
||||
if (data.imu->flag == 1) { // accelerometer
|
||||
imu_accel_ = data.imu;
|
||||
publishImuBySync(stamp);
|
||||
} else if (data.imu->flag == 2) { // gyroscope
|
||||
imu_gyro_ = data.imu;
|
||||
publishImuBySync(stamp);
|
||||
} else {
|
||||
NODELET_WARN_STREAM("Imu type is unknown");
|
||||
}
|
||||
} else {
|
||||
NODELET_WARN_STREAM("Motion data is empty");
|
||||
}
|
||||
} else {
|
||||
publishImu(data, imu_count_, stamp);
|
||||
publishTemp(data.imu->temperature, imu_count_, stamp);
|
||||
}
|
||||
NODELET_DEBUG_STREAM(
|
||||
"Imu count: " << imu_count_ << ", timestamp: " << data.imu->timestamp
|
||||
"Imu count: " << imu_count_ << ", frame_id: " << data.imu->frame_id
|
||||
<< ", timestamp: " << data.imu->timestamp
|
||||
<< ", accel_x: " << data.imu->accel[0]
|
||||
<< ", accel_y: " << data.imu->accel[1]
|
||||
<< ", accel_z: " << data.imu->accel[2]
|
||||
@@ -506,12 +528,14 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
header.seq = seq;
|
||||
header.stamp = stamp;
|
||||
header.frame_id = frame_ids_[stream];
|
||||
pthread_mutex_lock(&mutex_data_);
|
||||
cv::Mat img = data.frame;
|
||||
if (stream == Stream::DISPARITY) { // 32FC1 > 8UC1 = MONO8
|
||||
img.convertTo(img, CV_8UC1);
|
||||
}
|
||||
auto &&msg =
|
||||
cv_bridge::CvImage(header, camera_encodings_[stream], img).toImageMsg();
|
||||
pthread_mutex_unlock(&mutex_data_);
|
||||
auto &&info = getCameraInfo(stream);
|
||||
info->header.stamp = msg->header.stamp;
|
||||
camera_publishers_[stream].publish(msg, info);
|
||||
@@ -537,23 +561,6 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
}
|
||||
*/
|
||||
|
||||
void publishMono(
|
||||
const Stream &stream, const api::StreamData &data, std::uint32_t seq,
|
||||
ros::Time stamp) {
|
||||
if (mono_publishers_[stream].getNumSubscribers() == 0)
|
||||
return;
|
||||
std_msgs::Header header;
|
||||
header.seq = seq;
|
||||
header.stamp = stamp;
|
||||
header.frame_id = frame_ids_[stream];
|
||||
cv::Mat mono;
|
||||
cv::cvtColor(data.frame, mono, CV_RGB2GRAY);
|
||||
auto &&msg = cv_bridge::CvImage(header, enc::MONO8, mono).toImageMsg();
|
||||
auto &&info = getCameraInfo(stream);
|
||||
info->header.stamp = msg->header.stamp;
|
||||
mono_publishers_[stream].publish(msg, info);
|
||||
}
|
||||
|
||||
void publishPoints(
|
||||
const api::StreamData &data, std::uint32_t seq, ros::Time stamp) {
|
||||
// if (points_publisher_.getNumSubscribers() == 0)
|
||||
@@ -659,59 +666,6 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
pub_imu_.publish(msg);
|
||||
}
|
||||
|
||||
void publishImuBySync(ros::Time stamp) {
|
||||
if (imu_accel_ == nullptr || imu_gyro_ == nullptr) {
|
||||
return;
|
||||
}
|
||||
sensor_msgs::Imu msg;
|
||||
|
||||
msg.header.seq = imu_sync_count_;
|
||||
msg.header.stamp = stamp;
|
||||
msg.header.frame_id = imu_frame_id_;
|
||||
|
||||
// acceleration should be in m/s^2 (not in g's)
|
||||
msg.linear_acceleration.x = imu_accel_->accel[0] * gravity_;
|
||||
msg.linear_acceleration.y = imu_accel_->accel[1] * gravity_;
|
||||
msg.linear_acceleration.z = imu_accel_->accel[2] * gravity_;
|
||||
|
||||
msg.linear_acceleration_covariance[0] = 0;
|
||||
msg.linear_acceleration_covariance[1] = 0;
|
||||
msg.linear_acceleration_covariance[2] = 0;
|
||||
|
||||
msg.linear_acceleration_covariance[3] = 0;
|
||||
msg.linear_acceleration_covariance[4] = 0;
|
||||
msg.linear_acceleration_covariance[5] = 0;
|
||||
|
||||
msg.linear_acceleration_covariance[6] = 0;
|
||||
msg.linear_acceleration_covariance[7] = 0;
|
||||
msg.linear_acceleration_covariance[8] = 0;
|
||||
|
||||
// velocity should be in rad/sec
|
||||
msg.angular_velocity.x = imu_gyro_->gyro[0] * M_PI / 180;
|
||||
msg.angular_velocity.y = imu_gyro_->gyro[1] * M_PI / 180;
|
||||
msg.angular_velocity.z = imu_gyro_->gyro[2] * M_PI / 180;
|
||||
|
||||
msg.angular_velocity_covariance[0] = 0;
|
||||
msg.angular_velocity_covariance[1] = 0;
|
||||
msg.angular_velocity_covariance[2] = 0;
|
||||
|
||||
msg.angular_velocity_covariance[3] = 0;
|
||||
msg.angular_velocity_covariance[4] = 0;
|
||||
msg.angular_velocity_covariance[5] = 0;
|
||||
|
||||
msg.angular_velocity_covariance[6] = 0;
|
||||
msg.angular_velocity_covariance[7] = 0;
|
||||
msg.angular_velocity_covariance[8] = 0;
|
||||
|
||||
pub_imu_.publish(msg);
|
||||
|
||||
publishTemp(imu_accel_->temperature, imu_sync_count_, stamp);
|
||||
|
||||
++imu_sync_count_;
|
||||
imu_accel_ = nullptr;
|
||||
imu_gyro_ = nullptr;
|
||||
}
|
||||
|
||||
void publishTemp(float temperature, std::uint32_t seq, ros::Time stamp) {
|
||||
if (pub_temp_.getNumSubscribers() == 0)
|
||||
return;
|
||||
@@ -724,7 +678,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
}
|
||||
|
||||
private:
|
||||
void initDevice(int resolution, int format, int framerate) {
|
||||
void initDevice() {
|
||||
NODELET_INFO_STREAM("Detecting MYNT EYE devices");
|
||||
|
||||
Context context;
|
||||
@@ -759,9 +713,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
}
|
||||
}
|
||||
|
||||
api_ = API::Create(device, static_cast<Resolution>(resolution));
|
||||
api_->SetStreamRequest(static_cast<Format>(format),
|
||||
static_cast<FrameRate>(framerate));
|
||||
api_ = API::Create(device);
|
||||
|
||||
computeRectTransforms();
|
||||
}
|
||||
@@ -773,6 +725,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
auto &&ex_right_to_left = api_->GetExtrinsics(Stream::RIGHT, Stream::LEFT);
|
||||
|
||||
cv::Size size{in_left.width, in_left.height};
|
||||
|
||||
cv::Mat M1 =
|
||||
(cv::Mat_<double>(3, 3) << in_left.fx, 0, in_left.cx, 0, in_left.fy,
|
||||
in_left.cy, 0, 0, 1);
|
||||
@@ -1017,6 +970,8 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
ros::NodeHandle nh_;
|
||||
ros::NodeHandle private_nh_;
|
||||
|
||||
pthread_mutex_t mutex_data_;
|
||||
|
||||
// camera:
|
||||
// LEFT, RIGHT, LEFT_RECTIFIED, RIGHT_RECTIFIED,
|
||||
// DISPARITY, DISPARITY_NORMALIZED,
|
||||
@@ -1025,14 +980,6 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
std::map<Stream, sensor_msgs::CameraInfoPtr> camera_info_ptrs_;
|
||||
std::map<Stream, std::string> camera_encodings_;
|
||||
|
||||
// image: LEFT_RECTIFIED, RIGHT_RECTIFIED, DISPARITY, DISPARITY_NORMALIZED,
|
||||
// DEPTH
|
||||
std::map<Stream, image_transport::Publisher> image_publishers_;
|
||||
std::map<Stream, std::string> image_encodings_;
|
||||
|
||||
// mono: LEFT, RIGHT
|
||||
std::map<Stream, image_transport::CameraPublisher> mono_publishers_;
|
||||
|
||||
// pointcloud: POINTS
|
||||
ros::Publisher points_publisher_;
|
||||
|
||||
@@ -1067,10 +1014,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
std::size_t left_count_ = 0;
|
||||
std::size_t right_count_ = 0;
|
||||
std::size_t imu_count_ = 0;
|
||||
std::size_t imu_sync_count_ = 0;
|
||||
std::shared_ptr<ImuData> imu_accel_;
|
||||
std::shared_ptr<ImuData> imu_gyro_;
|
||||
bool publish_imu_by_sync_ = false;
|
||||
|
||||
std::map<Stream, bool> is_published_;
|
||||
bool is_motion_published_;
|
||||
bool is_started_;
|
||||
|
||||
Reference in New Issue
Block a user