diff --git a/.commitlintrc.js b/.commitlintrc.js new file mode 100644 index 0000000..bfc94c3 --- /dev/null +++ b/.commitlintrc.js @@ -0,0 +1,11 @@ +module.exports = { + extends: ['@commitlint/config-conventional'], + rules: { + 'type-enum': [2, 'always', [ + "feat", "fix", "docs", "style", "refactor", "perf", "test", "build", "ci", "chore", "revert" + ]], + 'scope-empty': [2, 'never'], + 'subject-full-stop': [0, 'never'], + 'subject-case': [0, 'never'] + } +}; diff --git a/.gitignore b/.gitignore index 396e1d4..84a2baa 100644 --- a/.gitignore +++ b/.gitignore @@ -21,6 +21,9 @@ _output/ /*.nsi /*.exe +/node_modules/ +/package-lock.json + # ros /wrappers/ros/build diff --git a/CMakeLists.txt b/CMakeLists.txt index bdf1fcd..5b885f3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,7 +14,7 @@ cmake_minimum_required(VERSION 3.0) -project(mynteye VERSION 2.2.2 LANGUAGES C CXX) +project(mynteye VERSION 2.2.3 LANGUAGES C CXX) include(cmake/Common.cmake) @@ -106,7 +106,6 @@ set_outdir( ) ## main - if(WITH_GLOG) add_executable(main src/main.cc) target_link_libraries(main glog::glog) @@ -124,6 +123,11 @@ 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) @@ -165,8 +169,13 @@ set(MYNTEYE_SRCS src/mynteye/device/config.cc src/mynteye/device/context.cc src/mynteye/device/device.cc - src/mynteye/device/device_s.cc src/mynteye/device/motions.cc + src/mynteye/device/standard/channels_adapter_s.cc + src/mynteye/device/standard/device_s.cc + src/mynteye/device/standard/streams_adapter_s.cc + src/mynteye/device/standard2/channels_adapter_s2.cc + src/mynteye/device/standard2/device_s2.cc + src/mynteye/device/standard2/streams_adapter_s2.cc src/mynteye/device/streams.cc src/mynteye/device/types.cc src/mynteye/device/utils.cc diff --git a/README.md b/README.md index 4d4cd35..2b6f796 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ # MYNT® EYE S SDK -[![](https://img.shields.io/badge/MYNT%20EYE%20S%20SDK-2.2.2-brightgreen.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK) +[![](https://img.shields.io/badge/MYNT%20EYE%20S%20SDK-2.2.3-brightgreen.svg?style=flat)](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://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2683636/mynt-eye-s-sdk-apidoc-2.2.2-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2683637/mynt-eye-s-sdk-apidoc-2.2.2-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-S-SDK/) - * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2683638/mynt-eye-s-sdk-apidoc-2.2.2-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2683639/mynt-eye-s-sdk-apidoc-2.2.2-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](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://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2708507/mynt-eye-s-sdk-apidoc-2.2.3-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2708508/mynt-eye-s-sdk-apidoc-2.2.3-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/api/mynt-eye-s-sdk-apidoc-2.2.3-en/mynt-eye-s-sdk-apidoc-2.2.3-en/index.html) + * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2708509/mynt-eye-s-sdk-apidoc-2.2.3-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2708510/mynt-eye-s-sdk-apidoc-2.2.3-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/api/mynt-eye-s-sdk-apidoc-2.2.3-zh-Hans/mynt-eye-s-sdk-apidoc-2.2.3-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://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2683625/mynt-eye-s-sdk-guide-2.2.2-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2683626/mynt-eye-s-sdk-guide-2.2.2-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-S-SDK-Guide/) - * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2683627/mynt-eye-s-sdk-guide-2.2.2-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2683628/mynt-eye-s-sdk-guide-2.2.2-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](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://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2708524/mynt-eye-s-sdk-guide-2.2.3-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2708525/mynt-eye-s-sdk-guide-2.2.3-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-S-SDK-Guide/) + * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2708528/mynt-eye-s-sdk-guide-2.2.3-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2708529/mynt-eye-s-sdk-guide-2.2.3-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/sdk/mynt-eye-s-sdk-guide-2.2.3-zh-Hans/mynt-eye-s-sdk-guide-2.2.3-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][]. The latest version is `2.2.3`. ## Usage diff --git a/cmake/Option.cmake b/cmake/Option.cmake index 98e9e49..9865c24 100644 --- a/cmake/Option.cmake +++ b/cmake/Option.cmake @@ -21,7 +21,6 @@ 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 @@ -32,7 +31,6 @@ 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) diff --git a/doc/en/api.doxyfile b/doc/en/api.doxyfile index 4960085..8775d79 100644 --- a/doc/en/api.doxyfile +++ b/doc/en/api.doxyfile @@ -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.3 # 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 diff --git a/doc/zh-Hans/api.doxyfile b/doc/zh-Hans/api.doxyfile index d2b5675..57592e0 100644 --- a/doc/zh-Hans/api.doxyfile +++ b/doc/zh-Hans/api.doxyfile @@ -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.3 # 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 diff --git a/doc/zh-Hans/spec_control_api.md b/doc/zh-Hans/spec_control_api.md index ca93fa4..6c1f9a8 100644 --- a/doc/zh-Hans/spec_control_api.md +++ b/doc/zh-Hans/spec_control_api.md @@ -6,25 +6,22 @@ | 名称 | 字段 | 字节数 | 默认值 | 最小值 | 最大值 | 是否储存 | Flash 地址 | 说明 | | :----- | :----- | :-------- | :-------- | :-------- | :-------- | :----------- | :----------- | :----- | -| 增益 | gain | 2 | 24 | 0 | 48 | √ | 0x12 | 关闭自动曝光,手动设定的参数 | -| 亮度 | brightness/exposure_time | 2 | 120 | 0 | 240 | √ | 0x14 | 关闭自动曝光,手动设定的参数 | -| 对比度 | contrast/black_level_calibration | 2 | 127 | 0 | 255 | √ | 0x10 | 关闭自动曝光,手动设定的参数 | +| 亮度 | brightness | 2 | 192 | 0 | 255 | √ | 0x14 | 关闭自动曝光,手动设定的参数 | > UVC 标准协议实现的控制,有现成的 API 进行 Get & Set ,包括 Min, Max, Default 。 ## 自定义协议 -| 名称 | 字段 | 字节数 | 默认值 | 最小值 | 最大值 | 是否储存 | 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 | | +| 名称 | 字段 | 字节数 | 默认值 | 最小值 | 最大值 | 是否储存 | 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 | 开始自动曝光,可设定的阈值 | | 加速度计量程 | 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 | | + diff --git a/doc/zh-Hans/spec_control_channel.md b/doc/zh-Hans/spec_control_channel.md index 64442d7..b232943 100644 --- a/doc/zh-Hans/spec_control_channel.md +++ b/doc/zh-Hans/spec_control_channel.md @@ -49,5 +49,5 @@ | File | ID | Max Size | | :--- | :- | :------- | | 硬件信息 | 1 | 250 | -| 图像参数 | 2 | 250 | +| 图像参数 | 2 | 404 | | IMU 参数 | 4 | 500 | diff --git a/doc/zh-Hans/spec_image_data.md b/doc/zh-Hans/spec_image_data.md index 8631da5..bb5261d 100644 --- a/doc/zh-Hans/spec_image_data.md +++ b/doc/zh-Hans/spec_image_data.md @@ -3,20 +3,19 @@ | 名称 | 字段 | 单位 | 字节数 | 说明 | | :----- | :----- | :----- | :-------- | :----- | | 帧 ID | frame_id | - | 2 | uint16_t; [0,65535] | -| 时间戳 | timestamp | 10 us | 4 | uint32_t | -| 曝光时间 | exposure_time | 10 us | 2 | uint16_t | +| 时间戳 | timestamp | 1 us | 8 | uint64_t | +| 曝光时间 | exposure_time | 1 us | 2 | uint16_t | > 图像数据传输方式:倒序排在图像尾部。 ## 图像数据包 -| 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 | 时间戳 | 曝光时间 | 校验码(数据内容所有字节异或) | +| 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 | 时间戳 | 曝光时间 | 校验码(数据内容所有字节异或) | * 数据包校验不过,会丢弃该帧。 -* 时间单位的精度为: 0.01 ms / 10 us 。 - * 4 字节能表示的最大时间约是 11.9 小时,溢出后将重累计。 +* 时间的单位精度为: 1 us 。 * 时间累计是从上电时从开始,而不是从打开时开始。 diff --git a/doc/zh-Hans/spec_imu_data.md b/doc/zh-Hans/spec_imu_data.md index e9072e9..34f3490 100644 --- a/doc/zh-Hans/spec_imu_data.md +++ b/doc/zh-Hans/spec_imu_data.md @@ -10,7 +10,7 @@ ## IMU 响应数据包 -IMU 响应数据包里会包含多个 IMU 包,而每个 IMU 包又带有多个 IMU 段。 +IMU 响应数据包里会包含1个 IMU 包,而每个 IMU 包又带有多个 IMU 段。 | Name | Header | State | Size | IMU Packets | Checksum | | :--- | :----- | :---- | :--- | :---------- | :------- | @@ -22,21 +22,21 @@ IMU 响应数据包里会包含多个 IMU 包,而每个 IMU 包又带有多个 IMU 包/小包,是一组 IMU 数据。 -| Name | Serial Number | Timestamp | Count | IMU Datas | -| :--- | :------------ | :-------- | :---- | :-------- | -| 字节数 | 4 | 4 | 1 | ... | -| 类型 | uint32_t | uint32_t | uint8_t | - | -| 描述 | 序列号 | IMU 基准时间戳 | IMU 段数量 | 所包含的 IMU 段 | +| Name | Count | IMU Datas | +| :--- | :-----| :-------- | +| 字节数 | 2 | ... | +| 类型 | uint16_t | - | +| 描述 | IMU 段数量 | 所包含的 IMU 段 | ### IMU 段 -| 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 三轴的值 | +| 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 三轴的值 | * 加速度计和陀螺仪的计量值换算成物理值公式: **real = data * range / 0x10000** 。 - * 加速度计量程默认值为 **8 g** ,陀螺仪量程默认值为 **1000 deg/s** 。 + * 加速度计量程默认值为 **12 g** ,陀螺仪量程默认值为 **1000 deg/s** 。 * 温度计量值换算成物理值公式: **real = data / ratio + offset** 。 * ``ratio`` 默认值为 **326.8** , ``offset`` 默认值为 **25℃** 。 diff --git a/include/mynteye/api/api.h b/include/mynteye/api/api.h index 580b567..37a9aed 100644 --- a/include/mynteye/api/api.h +++ b/include/mynteye/api/api.h @@ -28,6 +28,8 @@ MYNTEYE_BEGIN_NAMESPACE +struct DeviceInfo; + class Device; class Synthetic; @@ -72,8 +74,7 @@ struct MYNTEYE_API MotionData { bool operator==(const MotionData &other) const { if (imu && other.imu) { - return imu->frame_id == other.imu->frame_id && - imu->timestamp == other.imu->timestamp; + return imu->timestamp == other.imu->timestamp; } return false; } @@ -94,18 +95,6 @@ class MYNTEYE_API API { explicit API(std::shared_ptr device); virtual ~API(); - /** - * Create the API instance. - * @return the API instance. - * @note This will call device::select() to select a device. - */ - static std::shared_ptr Create(); - /** - * Create the API instance. - * @param device the selected device. - * @return the API instance. - */ - static std::shared_ptr Create(std::shared_ptr device); /** * Create the API instance. * @param argc the arg count. @@ -124,7 +113,13 @@ class MYNTEYE_API API { * @note This will init glog with args. */ static std::shared_ptr Create( - int argc, char *argv[], std::shared_ptr device); + int argc, char *argv[], const std::shared_ptr &device); + /** + * Create the API instance. + * @param device the selected device. + * @return the API instance. + */ + static std::shared_ptr Create(const std::shared_ptr &device); /** * Get the model. @@ -148,6 +143,11 @@ class MYNTEYE_API API { */ bool Supports(const AddOns &addon) const; + /** + * Log all stream requests and prompt user to select one. + */ + StreamRequest SelectStreamRequest(bool *ok) const; + /** * Get all stream requests of the capability. */ @@ -158,7 +158,28 @@ class MYNTEYE_API API { */ void ConfigStreamRequest( const Capabilities &capability, const StreamRequest &request); + /** + * Get the config stream requests of the capability. + */ + const StreamRequest &GetStreamRequest(const Capabilities &capability) const; + /** + * Get all stream requests of the key stream capability. + */ + const std::vector &GetStreamRequests() const; + /** + * Config the stream request to the key stream capability. + */ + void ConfigStreamRequest(const StreamRequest &request); + /** + * Get the config stream requests of the key stream capability. + */ + const StreamRequest &GetStreamRequest() const; + + /** + * Get the device info. + */ + std::shared_ptr GetInfo() const; /** * Get the device info. */ @@ -279,6 +300,8 @@ class MYNTEYE_API API { std::shared_ptr device_; std::unique_ptr synthetic_; + + void CheckImageParams(); }; MYNTEYE_END_NAMESPACE diff --git a/include/mynteye/device/callbacks.h b/include/mynteye/device/callbacks.h index f1775ce..19730f6 100644 --- a/include/mynteye/device/callbacks.h +++ b/include/mynteye/device/callbacks.h @@ -19,6 +19,7 @@ #include #include +#include #include #include @@ -29,6 +30,20 @@ MYNTEYE_BEGIN_NAMESPACE namespace device { +typedef struct ImgParams { + bool ok; + Intrinsics in_left; + Intrinsics in_right; + 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. diff --git a/include/mynteye/device/device.h b/include/mynteye/device/device.h index 11ee2fb..617aaf1 100644 --- a/include/mynteye/device/device.h +++ b/include/mynteye/device/device.h @@ -43,8 +43,10 @@ struct DeviceInfo; class API; class Channels; +class ChannelsAdapter; class Motions; class Streams; +class StreamsAdapter; template class AsyncCallback; @@ -66,7 +68,16 @@ class MYNTEYE_API Device { using stream_async_callback_ptr_t = std::shared_ptr; using motion_async_callback_ptr_t = std::shared_ptr; - Device(const Model &model, std::shared_ptr device); + using img_params_t = device::img_params_t; + using imu_params_t = device::imu_params_t; + + protected: + Device(const Model &model, + const std::shared_ptr &device, + const std::shared_ptr &streams_adapter, + const std::shared_ptr &channels_adapter); + + public: virtual ~Device(); /** @@ -112,6 +123,23 @@ class MYNTEYE_API Device { */ void ConfigStreamRequest( const Capabilities &capability, const StreamRequest &request); + /** + * Get the config stream requests of the capability. + */ + const StreamRequest &GetStreamRequest(const Capabilities &capability) const; + + /** + * Get all stream requests of the key stream capability. + */ + const std::vector &GetStreamRequests() const; + /** + * Config the stream request to the key stream capability. + */ + void ConfigStreamRequest(const StreamRequest &request); + /** + * Get the config stream requests of the key stream capability. + */ + const StreamRequest &GetStreamRequest() const; /** * Get the device info. @@ -231,15 +259,15 @@ class MYNTEYE_API Device { */ void WaitForStreams(); + /** + * Get the latest data of stream. + */ + device::StreamData GetStreamData(const Stream &stream); /** * Get the datas of stream. * @note default cache 4 datas at most. */ std::vector GetStreamDatas(const Stream &stream); - /** - * Get the latest data of stream. - */ - device::StreamData GetLatestStreamData(const Stream &stream); /** * Enable cache motion datas. @@ -271,8 +299,6 @@ class MYNTEYE_API Device { return motions_; } - const StreamRequest &GetStreamRequest(const Capabilities &capability); - virtual void StartVideoStreaming(); virtual void StopVideoStreaming(); @@ -281,7 +307,14 @@ class MYNTEYE_API Device { virtual void OnStereoStreamUpdate(); - virtual std::vector GetKeyStreams() const = 0; + virtual Capabilities GetKeyStreamCapability() const = 0; + + std::map GetImgParams() const { + return all_img_params_; + } + device::imu_params_t GetImuParams() const { + return imu_params_; + } bool video_streaming_; bool motion_tracking_; @@ -291,6 +324,9 @@ class MYNTEYE_API Device { std::shared_ptr device_; std::shared_ptr device_info_; + std::map all_img_params_; + device::imu_params_t imu_params_; + std::map stream_intrinsics_; std::map> stream_from_extrinsics_; @@ -314,6 +350,8 @@ class MYNTEYE_API Device { std::shared_ptr motions_; void ReadAllInfos(); + void UpdateStreamIntrinsics( + const Capabilities &capability, const StreamRequest &request); void CallbackPushedStreamData(const Stream &stream); void CallbackMotionData(const device::MotionData &data); diff --git a/include/mynteye/device/utils.h b/include/mynteye/device/utils.h index 0b64ce1..82e3255 100644 --- a/include/mynteye/device/utils.h +++ b/include/mynteye/device/utils.h @@ -19,6 +19,7 @@ #include #include "mynteye/mynteye.h" +#include "mynteye/types.h" MYNTEYE_BEGIN_NAMESPACE @@ -39,6 +40,16 @@ namespace device { */ MYNTEYE_API std::shared_ptr select(); +/** + * @ingroup utils + * + * List stream requests and prompt user to select one. + * + * @return the selected request. + */ +MYNTEYE_API MYNTEYE_NAMESPACE::StreamRequest select_request( + const std::shared_ptr &device, bool *ok); + } // namespace device namespace utils { @@ -58,14 +69,14 @@ MYNTEYE_API float get_real_exposure_time( /** * @ingroup utils - * + * * Get sdk root dir. */ MYNTEYE_API std::string get_sdk_root_dir(); /** * @ingroup utils - * + * * Get sdk install dir. */ MYNTEYE_API std::string get_sdk_install_dir(); diff --git a/include/mynteye/types.h b/include/mynteye/types.h index b622acd..3c8b2f9 100644 --- a/include/mynteye/types.h +++ b/include/mynteye/types.h @@ -37,6 +37,8 @@ MYNTEYE_BEGIN_NAMESPACE enum class Model : std::uint8_t { /** Standard */ STANDARD, + /** Standard 2 generation */ + STANDARD2, /** Last guard */ LAST }; @@ -74,6 +76,8 @@ enum class Stream : std::uint8_t { enum class Capabilities : std::uint8_t { /** Provides stereo stream */ STEREO, + /** Provide stereo color stream */ + STEREO_COLOR, /** Provides color stream */ COLOR, /** Provides depth stream */ @@ -141,6 +145,7 @@ enum class Option : std::uint8_t { * range: [0,255], default: 127 */ CONTRAST, + /** * Image frame rate, must set IMU_FREQUENCY together * @@ -153,6 +158,7 @@ enum class Option : std::uint8_t { * values: {100,200,250,333,500}, default: 200 */ IMU_FREQUENCY, + /** * Exposure mode * @@ -163,21 +169,31 @@ enum class Option : std::uint8_t { /** * Max gain, valid if auto-exposure * - * range: [0,48], default: 48 + * range of standard 1: [0,48], default: 48 + * range of standard 2: [0,255], default: 8 */ MAX_GAIN, /** * Max exposure time, valid if auto-exposure * - * range: [0,240], default: 240 + * range of standard 1: [0,240], default: 240 + * range of standard 2: [0,1000], default: 333 */ MAX_EXPOSURE_TIME, + /** + * min exposure time, valid if auto-exposure + * + * range: [0,1000], default: 0 + */ + MIN_EXPOSURE_TIME, /** * Desired brightness, valid if auto-exposure * - * range: [0,255], default: 192 + * range of standard 1: [0,255], default: 192 + * range of standard 2: [1,255], default: 122 */ DESIRED_BRIGHTNESS, + /** * IR control * @@ -191,22 +207,39 @@ enum class Option : std::uint8_t { * 1: 12-bit */ HDR_MODE, - /** Zero drift calibration */ - ZERO_DRIFT_CALIBRATION, - /** Erase chip */ - ERASE_CHIP, + /** * The range of accelerometer * - * values: {4,8,16,32}, default: 8 + * value of standard 1: {4,8,16,32}, default: 8 + * value of standard 2: {6,12,24,48}, default: 12 */ ACCELEROMETER_RANGE, /** * The range of gyroscope * - * values: {500,1000,2000,4000}, default: 1000 + * value of standard 1: {500,1000,2000,4000}, default: 1000 + * value of standard 2: {250,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, + + /** Zero drift calibration */ + ZERO_DRIFT_CALIBRATION, + /** Erase chip */ + ERASE_CHIP, + /** Last guard */ LAST }; @@ -278,6 +311,8 @@ 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 }; @@ -292,6 +327,26 @@ inline std::ostream &operator<<(std::ostream &os, const Format &value) { MYNTEYE_API std::size_t bytes_per_pixel(const Format &value); +/** + * Resolution. + */ +struct MYNTEYE_API Resolution { + /** Width */ + std::uint16_t width; + /** Height */ + std::uint16_t height; + + bool operator==(const Resolution &other) const { + return width == other.width && height == other.height; + } + bool operator!=(const Resolution &other) const { + return !(*this == other); + } + bool operator<(const Resolution &other) const { + return (width * height) < (other.width * other.height); + } +}; + /** * Stream request. */ @@ -302,9 +357,21 @@ struct MYNTEYE_API StreamRequest { std::uint16_t height; /** Stream pixel format */ Format format; - /** Stream frames per second (unused) */ + /** Stream frames per second */ 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(const Resolution &res, Format format, std::uint16_t fps) + : width(res.width), height(res.height), format(format), fps(fps) {} + + Resolution GetResolution() const { return {width, height}; } + bool operator==(const StreamRequest &other) const { return width == other.width && height == other.height && format == other.format && fps == other.fps; @@ -421,8 +488,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 0.01ms */ - std::uint32_t timestamp; + /** Image timestamp in 1us */ + std::uint64_t timestamp; /** Image exposure time, virtual value in [1, 480] */ std::uint16_t exposure_time; @@ -453,10 +520,18 @@ struct MYNTEYE_API ImgData { * IMU data. */ struct MYNTEYE_API ImuData { - /** Image frame id */ - std::uint16_t frame_id; - /** IMU timestamp in 0.01ms */ - std::uint32_t timestamp; + /** IMU frame id */ + std::uint32_t frame_id; + /** + * IMU accel or gyro flag + * + * 0: accel and gyro are both valid + * 1: accel is valid + * 2: gyro is valid + */ + std::uint8_t flag; + /** IMU timestamp in 1us */ + std::uint64_t timestamp; /** IMU accelerometer data for 3-axis: X, Y, Z. */ double accel[3]; /** IMU gyroscope data for 3-axis: X, Y, Z. */ @@ -465,7 +540,7 @@ struct MYNTEYE_API ImuData { double temperature; void Reset() { - frame_id = 0; + flag = 0; timestamp = 0; std::fill(accel, accel + 3, 0); std::fill(gyro, gyro + 3, 0); diff --git a/mynteye-config.cmake.in b/mynteye-config.cmake.in index 3514b78..f9f666a 100644 --- a/mynteye-config.cmake.in +++ b/mynteye-config.cmake.in @@ -13,6 +13,8 @@ # 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@) diff --git a/package.json b/package.json new file mode 100644 index 0000000..3a49bdf --- /dev/null +++ b/package.json @@ -0,0 +1,37 @@ +{ + "name": "mynt-eye-s-sdk", + "version": "1.0.0", + "description": "MYNT EYE S SDK", + "main": "index.js", + "directories": { + "doc": "doc", + "test": "test" + }, + "dependencies": {}, + "devDependencies": { + "@commitlint/cli": "^7.2.1", + "@commitlint/config-conventional": "^7.1.2", + "cz-conventional-changelog": "^2.1.0", + "husky": "^1.3.0" + }, + "scripts": { + "test": "echo \"Error: no test specified\" && exit 1" + }, + "repository": { + "type": "git", + "url": "https://github.com/slightech/MYNT-EYE-S-SDK.git" + }, + "keywords": [], + "author": "", + "license": "Apache-2.0", + "config": { + "commitizen": { + "path": "./node_modules/cz-conventional-changelog" + } + }, + "husky": { + "hooks": { + "commit-msg": "commitlint -E HUSKY_GIT_PARAMS" + } + } +} diff --git a/samples/CMakeLists.txt b/samples/CMakeLists.txt index 685e94b..2e826a0 100644 --- a/samples/CMakeLists.txt +++ b/samples/CMakeLists.txt @@ -53,6 +53,10 @@ 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 diff --git a/samples/api/camera.cc b/samples/api/camera.cc index 0d10a54..8678d31 100644 --- a/samples/api/camera.cc +++ b/samples/api/camera.cc @@ -21,12 +21,13 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; + + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); - // 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; @@ -55,8 +56,7 @@ int main(int argc, char *argv[]) { CHECK_NOTNULL(data.imu); ++imu_count; VLOG(2) << "Imu count: " << imu_count; - VLOG(2) << " frame_id: " << data.imu->frame_id - << ", timestamp: " << data.imu->timestamp + VLOG(2) << ", timestamp: " << data.imu->timestamp << ", accel_x: " << data.imu->accel[0] << ", accel_y: " << data.imu->accel[1] << ", accel_z: " << data.imu->accel[2] @@ -106,8 +106,7 @@ int main(int argc, char *argv[]) { auto &&motion_datas = api->GetMotionDatas(); motion_count += motion_datas.size(); for (auto &&data : motion_datas) { - LOG(INFO) << "Imu frame_id: " << data.imu->frame_id - << ", timestamp: " << data.imu->timestamp + LOG(INFO) << ", timestamp: " << data.imu->timestamp << ", accel_x: " << data.imu->accel[0] << ", accel_y: " << data.imu->accel[1] << ", accel_z: " << data.imu->accel[2] diff --git a/samples/api/get_depth_with_region.cc b/samples/api/get_depth_with_region.cc index 560b279..25fc417 100644 --- a/samples/api/get_depth_with_region.cc +++ b/samples/api/get_depth_with_region.cc @@ -144,8 +144,12 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; + + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); api->SetOptionValue(Option::IR_CONTROL, 80); diff --git a/samples/device/CMakeLists.txt b/samples/device/CMakeLists.txt index aa27b4e..cf7ac72 100644 --- a/samples/device/CMakeLists.txt +++ b/samples/device/CMakeLists.txt @@ -14,6 +14,10 @@ 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}" diff --git a/samples/device/camera.cc b/samples/device/camera.cc index 85af2ed..1fd4add 100644 --- a/samples/device/camera.cc +++ b/samples/device/camera.cc @@ -25,35 +25,19 @@ int main(int argc, char *argv[]) { glog_init _(argc, 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(); + if (!device) return 1; - // device->RunOptionAction(Option::ZERO_DRIFT_CALIBRATION); + bool ok; + auto &&request = device::select_request(device, &ok); + if (!ok) return 1; + device->ConfigStreamRequest(request); std::size_t left_count = 0; 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; @@ -63,19 +47,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) << " frame_id: " << data.imu->frame_id - << ", timestamp: " << data.imu->timestamp + VLOG(2) << ", timestamp: " << data.imu->timestamp << ", accel_x: " << data.imu->accel[0] << ", accel_y: " << data.imu->accel[1] << ", accel_z: " << data.imu->accel[2] @@ -88,7 +72,6 @@ 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; @@ -96,14 +79,13 @@ int main(int argc, char *argv[]) { while (true) { device->WaitForStreams(); - device::StreamData left_data = device->GetLatestStreamData(Stream::LEFT); - device::StreamData right_data = device->GetLatestStreamData(Stream::RIGHT); + device::StreamData left_data = device->GetStreamData(Stream::LEFT); + device::StreamData right_data = device->GetStreamData(Stream::RIGHT); auto &&motion_datas = device->GetMotionDatas(); motion_count += motion_datas.size(); for (auto &&data : motion_datas) { - LOG(INFO) << "Imu frame_id: " << data.imu->frame_id - << ", timestamp: " << data.imu->timestamp + LOG(INFO) << "timestamp: " << data.imu->timestamp << ", accel_x: " << data.imu->accel[0] << ", accel_y: " << data.imu->accel[1] << ", accel_z: " << data.imu->accel[2] @@ -113,15 +95,39 @@ int main(int argc, char *argv[]) { << ", temperature: " << data.imu->temperature; } - 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::Mat img; - cv::hconcat(left_img, right_img, 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::hconcat(left_img, right_img, img); + } else { + return -1; + } + cv::imshow("frame", img); char key = static_cast(cv::waitKey(1)); @@ -144,7 +150,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; } diff --git a/samples/tutorials/CMakeLists.txt b/samples/tutorials/CMakeLists.txt index 4f4696b..0f1b804 100644 --- a/samples/tutorials/CMakeLists.txt +++ b/samples/tutorials/CMakeLists.txt @@ -16,6 +16,7 @@ get_filename_component(DIR_NAME ${CMAKE_CURRENT_LIST_DIR} NAME) include_directories( ${CMAKE_CURRENT_SOURCE_DIR} + ${PRO_DIR}/src ) set_outdir( @@ -123,7 +124,6 @@ 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 diff --git a/samples/tutorials/control/auto_exposure.cc b/samples/tutorials/control/auto_exposure.cc index 0a18547..1c768c4 100644 --- a/samples/tutorials/control/auto_exposure.cc +++ b/samples/tutorials/control/auto_exposure.cc @@ -22,18 +22,24 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; + + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); // auto-exposure: 0 api->SetOptionValue(Option::EXPOSURE_MODE, 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); + // 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); LOG(INFO) << "Enable auto-exposure"; LOG(INFO) << "Set MAX_GAIN to " << api->GetOptionValue(Option::MAX_GAIN); @@ -41,10 +47,12 @@ 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(api->GetOptionValue(Option::FRAME_RATE)); + CVPainter painter(30); cv::namedWindow("frame"); diff --git a/samples/tutorials/control/framerate.cc b/samples/tutorials/control/framerate.cc index 3236bf0..52ca904 100644 --- a/samples/tutorials/control/framerate.cc +++ b/samples/tutorials/control/framerate.cc @@ -23,20 +23,12 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; - // 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); + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); // Count img std::atomic_uint img_count(0); @@ -46,13 +38,6 @@ 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"); @@ -85,7 +70,5 @@ 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; } diff --git a/samples/tutorials/control/imu_range.cc b/samples/tutorials/control/imu_range.cc index 0b0ba32..93f776c 100644 --- a/samples/tutorials/control/imu_range.cc +++ b/samples/tutorials/control/imu_range.cc @@ -23,12 +23,16 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; - // ACCELEROMETER_RANGE values: 4, 8, 16, 32 - api->SetOptionValue(Option::ACCELEROMETER_RANGE, 8); - // GYROSCOPE_RANGE values: 500, 1000, 2000, 4000 + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); + + // ACCELEROMETER_RANGE values: 6, 12, 24, 32 + api->SetOptionValue(Option::ACCELEROMETER_RANGE, 6); + // GYROSCOPE_RANGE values: 250, 500, 1000, 2000, 4000 api->SetOptionValue(Option::GYROSCOPE_RANGE, 1000); LOG(INFO) << "Set ACCELEROMETER_RANGE to " diff --git a/samples/tutorials/control/infrared.cc b/samples/tutorials/control/infrared.cc deleted file mode 100644 index a6310a7..0000000 --- a/samples/tutorials/control/infrared.cc +++ /dev/null @@ -1,61 +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 - -#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(cv::waitKey(1)); - if (key == 27 || key == 'q' || key == 'Q') { // ESC/Q - break; - } - } - - api->Stop(Source::VIDEO_STREAMING); - return 0; -} diff --git a/samples/tutorials/control/manual_exposure.cc b/samples/tutorials/control/manual_exposure.cc index 16ce32e..daa6fb9 100644 --- a/samples/tutorials/control/manual_exposure.cc +++ b/samples/tutorials/control/manual_exposure.cc @@ -22,27 +22,25 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; + + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); // 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(api->GetOptionValue(Option::FRAME_RATE)); + CVPainter painter(30); cv::namedWindow("frame"); diff --git a/samples/tutorials/data/get_depth.cc b/samples/tutorials/data/get_depth.cc index e973967..d2c4246 100644 --- a/samples/tutorials/data/get_depth.cc +++ b/samples/tutorials/data/get_depth.cc @@ -19,8 +19,12 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; + + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); api->EnableStreamData(Stream::DEPTH); diff --git a/samples/tutorials/data/get_device_info.cc b/samples/tutorials/data/get_device_info.cc index 5217c36..ddb3bd9 100644 --- a/samples/tutorials/data/get_device_info.cc +++ b/samples/tutorials/data/get_device_info.cc @@ -18,8 +18,7 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; LOG(INFO) << "Device name: " << api->GetInfo(Info::DEVICE_NAME); LOG(INFO) << "Serial number: " << api->GetInfo(Info::SERIAL_NUMBER); diff --git a/samples/tutorials/data/get_disparity.cc b/samples/tutorials/data/get_disparity.cc index 243d81e..582dc72 100644 --- a/samples/tutorials/data/get_disparity.cc +++ b/samples/tutorials/data/get_disparity.cc @@ -19,8 +19,12 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; + + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); // api->EnableStreamData(Stream::DISPARITY); api->EnableStreamData(Stream::DISPARITY_NORMALIZED); diff --git a/samples/tutorials/data/get_from_callbacks.cc b/samples/tutorials/data/get_from_callbacks.cc index 27c30a4..b1effcc 100644 --- a/samples/tutorials/data/get_from_callbacks.cc +++ b/samples/tutorials/data/get_from_callbacks.cc @@ -27,8 +27,12 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; + + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); // Attention: must not block the callbacks. diff --git a/samples/tutorials/data/get_img_params.cc b/samples/tutorials/data/get_img_params.cc index 6fa9b8f..41bfbce 100644 --- a/samples/tutorials/data/get_img_params.cc +++ b/samples/tutorials/data/get_img_params.cc @@ -18,8 +18,12 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; + + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); LOG(INFO) << "Intrinsics left: {" << api->GetIntrinsics(Stream::LEFT) << "}"; LOG(INFO) << "Intrinsics right: {" << api->GetIntrinsics(Stream::RIGHT) diff --git a/samples/tutorials/data/get_imu.cc b/samples/tutorials/data/get_imu.cc index a449f6e..c09d225 100644 --- a/samples/tutorials/data/get_imu.cc +++ b/samples/tutorials/data/get_imu.cc @@ -22,8 +22,12 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; + + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); // Enable this will cache the motion datas until you get them. api->EnableMotionDatas(); diff --git a/samples/tutorials/data/get_imu_params.cc b/samples/tutorials/data/get_imu_params.cc index 7757611..092aaec 100644 --- a/samples/tutorials/data/get_imu_params.cc +++ b/samples/tutorials/data/get_imu_params.cc @@ -18,8 +18,7 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; LOG(INFO) << "Motion intrinsics: {" << api->GetMotionIntrinsics() << "}"; LOG(INFO) << "Motion extrinsics left to imu: {" diff --git a/samples/tutorials/data/get_points.cc b/samples/tutorials/data/get_points.cc index 28294f5..ef2d91f 100644 --- a/samples/tutorials/data/get_points.cc +++ b/samples/tutorials/data/get_points.cc @@ -21,8 +21,12 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; + + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); api->EnableStreamData(Stream::POINTS); diff --git a/samples/tutorials/data/get_stereo.cc b/samples/tutorials/data/get_stereo.cc index 391c53e..1dd024a 100644 --- a/samples/tutorials/data/get_stereo.cc +++ b/samples/tutorials/data/get_stereo.cc @@ -19,8 +19,12 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; + + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); api->Start(Source::VIDEO_STREAMING); diff --git a/samples/tutorials/data/get_stereo_rectified.cc b/samples/tutorials/data/get_stereo_rectified.cc index 10c0bf5..dadba65 100644 --- a/samples/tutorials/data/get_stereo_rectified.cc +++ b/samples/tutorials/data/get_stereo_rectified.cc @@ -19,8 +19,12 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; + + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); api->EnableStreamData(Stream::LEFT_RECTIFIED); api->EnableStreamData(Stream::RIGHT_RECTIFIED); diff --git a/samples/tutorials/data/get_with_plugin.cc b/samples/tutorials/data/get_with_plugin.cc index e8a0e05..af943b0 100644 --- a/samples/tutorials/data/get_with_plugin.cc +++ b/samples/tutorials/data/get_with_plugin.cc @@ -19,8 +19,12 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; + + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); api->EnablePlugin("plugins/linux-x86_64/libplugin_g_cuda9.1_opencv3.4.0.so"); diff --git a/samples/tutorials/intermediate/get_depth_and_points.cc b/samples/tutorials/intermediate/get_depth_and_points.cc index 5761c62..5a2d5d8 100644 --- a/samples/tutorials/intermediate/get_depth_and_points.cc +++ b/samples/tutorials/intermediate/get_depth_and_points.cc @@ -148,8 +148,12 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { auto &&api = API::Create(argc, argv); - if (!api) - return 1; + if (!api) return 1; + + bool ok; + auto &&request = api->SelectStreamRequest(&ok); + if (!ok) return 1; + api->ConfigStreamRequest(request); api->SetOptionValue(Option::IR_CONTROL, 80); diff --git a/samples/tutorials/util/cv_painter.cc b/samples/tutorials/util/cv_painter.cc index d5344b5..cc9fefe 100644 --- a/samples/tutorials/util/cv_painter.cc +++ b/samples/tutorials/util/cv_painter.cc @@ -117,7 +117,7 @@ cv::Rect CVPainter::DrawImuData( if (gravity == BOTTOM_LEFT || gravity == BOTTOM_RIGHT) sign = -1; - Clear(ss) << "frame_id: " << data.frame_id << ", stamp: " << data.timestamp + Clear(ss) << "stamp: " << data.timestamp << ", temp: " << fmt_temp << data.temperature; cv::Rect rect_i = DrawText(img, ss.str(), gravity, 5); diff --git a/samples/uvc/camera.cc b/samples/uvc/camera.cc index 2a92930..49bebe8 100644 --- a/samples/uvc/camera.cc +++ b/samples/uvc/camera.cc @@ -108,7 +108,11 @@ int main(int argc, char *argv[]) { const auto frame_empty = [&frame]() { return frame == nullptr; }; uvc::set_device_mode( +#ifdef MYNTEYE_OS_MAC *device, 752, 480, static_cast(Format::YUYV), 25, +#else + *device, 1280, 400, static_cast(Format::BGR888), 20, +#endif [&mtx, &cv, &frame, &frame_ready]( const void *data, std::function continuation) { // reinterpret_cast(data); @@ -143,8 +147,12 @@ int main(int argc, char *argv[]) { } // only lastest frame is valid +#ifdef MYNTEYE_OS_MAC cv::Mat img(480, 752, CV_8UC2, const_cast(frame->data)); cv::cvtColor(img, img, cv::COLOR_YUV2BGR_YUY2); +#else + cv::Mat img(400, 1280, CV_8UC3, const_cast(frame->data)); +#endif cv::imshow("frame", img); frame = nullptr; diff --git a/scripts/init.sh b/scripts/init.sh index c75a70f..d724aae 100755 --- a/scripts/init.sh +++ b/scripts/init.sh @@ -15,6 +15,7 @@ # _VERBOSE_=1 # _INIT_LINTER_=1 +# _INIT_COMMITIZEN_=1 # _FORCE_INSRALL_=1 _INSTALL_OPTIONS_=$@ diff --git a/scripts/init_tools.sh b/scripts/init_tools.sh index 0078271..ab073a8 100644 --- a/scripts/init_tools.sh +++ b/scripts/init_tools.sh @@ -15,6 +15,7 @@ _INIT_BUILD_=1 # _INIT_LINTER_=1 +# _INIT_COMMITIZEN_=1 # _FORCE_INSRALL_=1 # _INSTALL_OPTIONS_=-y @@ -146,6 +147,7 @@ else # unexpected exit 1 fi + ## init linter - optional if [ -n "${_INIT_LINTER_}" ]; then @@ -217,3 +219,30 @@ else fi fi # _INIT_LINTER_ + + +## init commitizen - optional + +if [ -n "${_INIT_COMMITIZEN_}" ]; then + +if _detect_cmd npm; then + _echo_d "npm install commitizen -g; npm install" + npm install commitizen -g; npm install + # if _detect_cmd node; then + # commitizen init cz-conventional-changelog --save-dev --save-exact + # npm install --save-dev @commitlint/{config-conventional,cli} + # npm install husky --save-dev + # else + # _echo_en "Skipped commitizen init, as node not found" + # fi +else + _echo_en "Skipped npm install packages, as npm not found" + _echo + _echo_e "Download Node.js from https://nodejs.org/, then add to \`~/.bashrc\`." + _echo + _echo_e " export PATH=\"/home/john/node-v10.14.2-linux-x64/bin:\$PATH\"" + _echo + _echo_e "p.s. not \"apt-get install npm\", it's too old." +fi + +fi # _INIT_COMMITIZEN_ diff --git a/src/main.cc b/src/main.cc index 360e2a0..e87e1e9 100644 --- a/src/main.cc +++ b/src/main.cc @@ -16,12 +16,12 @@ #if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) #define GLOG_NO_ABBREVIATED_SEVERITIES #endif -#include #ifdef HAVE_LIB_GFLAGS #include #endif +#include "mynteye/logger.h" #include "mynteye/mynteye.h" int main(int /*argc*/, char *argv[]) { diff --git a/src/mynteye/api/api.cc b/src/mynteye/api/api.cc index 631f014..adc70e2 100644 --- a/src/mynteye/api/api.cc +++ b/src/mynteye/api/api.cc @@ -26,7 +26,6 @@ #include "mynteye/api/plugin.h" #include "mynteye/api/synthetic.h" #include "mynteye/device/device.h" -#include "mynteye/device/device_s.h" #include "mynteye/device/utils.h" #if defined(WITH_FILESYSTEM) && defined(WITH_NATIVE_FILESYSTEM) @@ -210,26 +209,7 @@ std::vector get_plugin_paths() { API::API(std::shared_ptr device) : device_(device) { VLOG(2) << __func__; - if (std::dynamic_pointer_cast(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."; - } - } + // std::dynamic_pointer_cast(device_); synthetic_.reset(new Synthetic(this)); } @@ -237,29 +217,19 @@ API::~API() { VLOG(2) << __func__; } -std::shared_ptr API::Create() { - return Create(device::select()); -} - -std::shared_ptr API::Create(std::shared_ptr device) { - if (!device) - return nullptr; - return std::make_shared(device); -} - std::shared_ptr API::Create(int argc, char *argv[]) { - static glog_init _(argc, argv); auto &&device = device::select(); - if (!device) - return nullptr; - return std::make_shared(device); + if (!device) return nullptr; + return Create(argc, argv, device); } std::shared_ptr API::Create( - int argc, char *argv[], std::shared_ptr device) { + int argc, char *argv[], const std::shared_ptr &device) { static glog_init _(argc, argv); - if (!device) - return nullptr; + return Create(device); +} + +std::shared_ptr API::Create(const std::shared_ptr &device) { return std::make_shared(device); } @@ -283,6 +253,10 @@ bool API::Supports(const AddOns &addon) const { return device_->Supports(addon); } +StreamRequest API::SelectStreamRequest(bool *ok) const { + return device::select_request(device_, ok); +} + const std::vector &API::GetStreamRequests( const Capabilities &capability) const { return device_->GetStreamRequests(capability); @@ -291,6 +265,29 @@ const std::vector &API::GetStreamRequests( void API::ConfigStreamRequest( const Capabilities &capability, const StreamRequest &request) { device_->ConfigStreamRequest(capability, request); + synthetic_->NotifyImageParamsChanged(); +} + +const StreamRequest &API::GetStreamRequest( + const Capabilities &capability) const { + return device_->GetStreamRequest(capability); +} + +const std::vector &API::GetStreamRequests() const { + return device_->GetStreamRequests(); +} + +void API::ConfigStreamRequest(const StreamRequest &request) { + device_->ConfigStreamRequest(request); + synthetic_->NotifyImageParamsChanged(); +} + +const StreamRequest &API::GetStreamRequest() const { + return device_->GetStreamRequest(); +} + +std::shared_ptr API::GetInfo() const { + return device_->GetInfo(); } std::string API::GetInfo(const Info &info) const { @@ -450,4 +447,23 @@ std::shared_ptr 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 diff --git a/src/mynteye/api/processor/rectify_processor.cc b/src/mynteye/api/processor/rectify_processor.cc index 9c570f0..86b0988 100644 --- a/src/mynteye/api/processor/rectify_processor.cc +++ b/src/mynteye/api/processor/rectify_processor.cc @@ -27,11 +27,9 @@ const char RectifyProcessor::NAME[] = "RectifyProcessor"; RectifyProcessor::RectifyProcessor( std::shared_ptr device, std::int32_t proc_period) - : Processor(std::move(proc_period)) { + : Processor(std::move(proc_period)), device_(device) { VLOG(2) << __func__ << ": proc_period=" << proc_period; - InitParams( - device->GetIntrinsics(Stream::LEFT), device->GetIntrinsics(Stream::RIGHT), - device->GetExtrinsics(Stream::RIGHT, Stream::LEFT)); + NotifyImageParamsChanged(); } RectifyProcessor::~RectifyProcessor() { @@ -42,6 +40,13 @@ std::string RectifyProcessor::Name() { return NAME; } +void RectifyProcessor::NotifyImageParamsChanged() { + InitParams( + device_->GetIntrinsics(Stream::LEFT), + device_->GetIntrinsics(Stream::RIGHT), + device_->GetExtrinsics(Stream::RIGHT, Stream::LEFT)); +} + Object *RectifyProcessor::OnCreateOutput() { return new ObjMat2(); } diff --git a/src/mynteye/api/processor/rectify_processor.h b/src/mynteye/api/processor/rectify_processor.h index 0cb33a0..30b615b 100644 --- a/src/mynteye/api/processor/rectify_processor.h +++ b/src/mynteye/api/processor/rectify_processor.h @@ -37,6 +37,8 @@ class RectifyProcessor : public Processor { std::string Name() override; + void NotifyImageParamsChanged(); + cv::Mat R1, P1, R2, P2, Q; cv::Mat map11, map12, map21, map22; @@ -48,6 +50,8 @@ class RectifyProcessor : public Processor { private: void InitParams( Intrinsics in_left, Intrinsics in_right, Extrinsics ex_right_to_left); + + std::shared_ptr device_; }; MYNTEYE_END_NAMESPACE diff --git a/src/mynteye/api/synthetic.cc b/src/mynteye/api/synthetic.cc index 3c7e298..22b7b17 100644 --- a/src/mynteye/api/synthetic.cc +++ b/src/mynteye/api/synthetic.cc @@ -17,6 +17,8 @@ #include #include +#include + #include "mynteye/logger.h" #include "mynteye/api/object.h" #include "mynteye/api/plugin.h" @@ -39,9 +41,16 @@ MYNTEYE_BEGIN_NAMESPACE namespace { cv::Mat frame2mat(const std::shared_ptr &frame) { - // 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()); + 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()); + return img; + } else { // Format::GRAY + return cv::Mat(frame->height(), frame->width(), CV_8UC1, frame->data()); + } } api::StreamData data2api(const device::StreamData &data) { @@ -74,6 +83,11 @@ Synthetic::~Synthetic() { } } +void Synthetic::NotifyImageParamsChanged() { + auto &&processor = find_processor(processor_); + if (processor) processor->NotifyImageParamsChanged(); +} + bool Synthetic::Supports(const Stream &stream) const { return stream_supports_mode_.find(stream) != stream_supports_mode_.end(); } @@ -152,7 +166,7 @@ api::StreamData Synthetic::GetStreamData(const Stream &stream) { auto &&mode = GetStreamEnabledMode(stream); if (mode == MODE_NATIVE) { auto &&device = api_->device(); - return data2api(device->GetLatestStreamData(stream)); + return data2api(device->GetStreamData(stream)); } else if (mode == MODE_SYNTHETIC) { if (stream == Stream::LEFT_RECTIFIED || stream == Stream::RIGHT_RECTIFIED) { static std::shared_ptr output = nullptr; @@ -302,42 +316,35 @@ void Synthetic::EnableStreamData(const Stream &stream, std::uint32_t depth) { break; stream_enabled_mode_[stream] = MODE_SYNTHETIC; CHECK(ActivateProcessor()); - } - return; + } return; case Stream::RIGHT_RECTIFIED: { if (!IsStreamDataEnabled(Stream::RIGHT)) break; stream_enabled_mode_[stream] = MODE_SYNTHETIC; CHECK(ActivateProcessor()); - } - return; + } return; case Stream::DISPARITY: { stream_enabled_mode_[stream] = MODE_SYNTHETIC; EnableStreamData(Stream::LEFT_RECTIFIED, depth + 1); EnableStreamData(Stream::RIGHT_RECTIFIED, depth + 1); CHECK(ActivateProcessor()); - } - return; + } return; case Stream::DISPARITY_NORMALIZED: { stream_enabled_mode_[stream] = MODE_SYNTHETIC; EnableStreamData(Stream::DISPARITY, depth + 1); CHECK(ActivateProcessor()); - } - return; + } return; case Stream::POINTS: { stream_enabled_mode_[stream] = MODE_SYNTHETIC; EnableStreamData(Stream::DISPARITY, depth + 1); CHECK(ActivateProcessor()); - } - return; + } return; case Stream::DEPTH: { stream_enabled_mode_[stream] = MODE_SYNTHETIC; EnableStreamData(Stream::POINTS, depth + 1); CHECK(ActivateProcessor()); - } - return; - default: - break; + } return; + default: break; } if (depth == 0) { LOG(WARNING) << "Enable stream data of " << stream << " failed"; @@ -390,8 +397,7 @@ void Synthetic::DisableStreamData(const Stream &stream, std::uint32_t depth) { case Stream::DEPTH: { DeactivateProcessor(); } break; - default: - return; + default: return; } if (depth > 0) { LOG(WARNING) << "Disable synthetic stream data of " << stream << " too"; diff --git a/src/mynteye/api/synthetic.h b/src/mynteye/api/synthetic.h index 441ddfb..27c9d44 100644 --- a/src/mynteye/api/synthetic.h +++ b/src/mynteye/api/synthetic.h @@ -43,6 +43,8 @@ class Synthetic { explicit Synthetic(API *api); ~Synthetic(); + void NotifyImageParamsChanged(); + bool Supports(const Stream &stream) const; mode_t SupportsMode(const Stream &stream) const; diff --git a/src/mynteye/device/channels.cc b/src/mynteye/device/channels.cc index 5864402..7a02618 100644 --- a/src/mynteye/device/channels.cc +++ b/src/mynteye/device/channels.cc @@ -19,6 +19,7 @@ #include #include #include +#include #include "mynteye/logger.h" #include "mynteye/util/strings.h" @@ -30,12 +31,12 @@ MYNTEYE_BEGIN_NAMESPACE namespace { -const uvc::xu mynteye_xu = {3, - 2, - {0x947a6d9f, - 0x8a2f, - 0x418d, - {0x85, 0x9e, 0x6c, 0x9a, 0xa0, 0x38, 0x10, 0x14}}}; +const uvc::xu mynteye_xu = {3, 2, + { + 0x947a6d9f, 0x8a2f, 0x418d, + {0x85, 0x9e, 0x6c, 0x9a, 0xa0, 0x38, 0x10, 0x14} + } +}; int XuCamCtrlId(Option option) { switch (option) { @@ -63,12 +64,21 @@ 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; } @@ -92,7 +102,7 @@ void CheckSpecVersion(const Version *spec_version) { LOG(FATAL) << "Spec version must be specified"; } - std::vector spec_versions{"1.0"}; + std::vector spec_versions{"1.0", "1.1"}; for (auto &&spec_ver : spec_versions) { if (*spec_version == Version(spec_ver)) { return; // supported @@ -109,12 +119,14 @@ void CheckSpecVersion(const Version *spec_version) { } // namespace -Channels::Channels(std::shared_ptr device) - : device_(device), - is_imu_tracking_(false), - imu_track_stop_(false), - imu_sn_(0), - imu_callback_(nullptr) { +Channels::Channels(const std::shared_ptr &device, + const std::shared_ptr &adapter) + : device_(device), + adapter_(adapter), + is_imu_tracking_(false), + imu_track_stop_(false), + imu_sn_(0), + imu_callback_(nullptr) { VLOG(2) << __func__; UpdateControlInfos(); } @@ -124,6 +136,14 @@ Channels::~Channels() { StopImuTracking(); } +std::int32_t Channels::GetAccelRangeDefault() { + return adapter_->GetAccelRangeDefault(); +} + +std::int32_t Channels::GetGyroRangeDefault() { + return adapter_->GetGyroRangeDefault(); +} + void Channels::LogControlInfos() const { for (auto &&it = control_infos_.begin(); it != control_infos_.end(); it++) { LOG(INFO) << it->first << ": min=" << it->second.min @@ -133,17 +153,23 @@ void Channels::LogControlInfos() const { } void Channels::UpdateControlInfos() { - for (auto &&option : std::vector