Merge branch 'develop' of http://gitlab.mynt.com/mynteye/mynt-eye-sdk-2 into develop

This commit is contained in:
TinyOh 2019-03-01 16:08:39 +08:00
commit 2896e00acf
18 changed files with 88 additions and 18 deletions

View File

@ -1,6 +1,6 @@
# MYNT® EYE S SDK # MYNT® EYE S SDK
[![](https://img.shields.io/badge/MYNT%20EYE%20S%20SDK-2.3.1-brightgreen.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK) [![](https://img.shields.io/badge/MYNT%20EYE%20S%20SDK-2.3.2-brightgreen.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK)
## Overview ## Overview
@ -17,11 +17,11 @@ Please follow the guide doc to install the SDK on different platforms.
## Documentations ## Documentations
* [API Doc](https://github.com/slightech/MYNT-EYE-S-SDK/releases): API reference, some guides and data spec. * [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/2893965/mynt-eye-s-sdk-apidoc-2.3.1-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2893979/mynt-eye-s-sdk-apidoc-2.3.1-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-S-SDK/) * en: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2913110/mynt-eye-s-sdk-apidoc-2.3.2-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2913111/mynt-eye-s-sdk-apidoc-2.3.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/2893985/mynt-eye-s-sdk-apidoc-2.3.1-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2893986/mynt-eye-s-sdk-apidoc-2.3.1-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.3.1-zh-Hans/mynt-eye-s-sdk-apidoc-2.3.1-zh-Hans/index.html) * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2913112/mynt-eye-s-sdk-apidoc-2.3.2-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2913113/mynt-eye-s-sdk-apidoc-2.3.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.3.2-zh-Hans/mynt-eye-s-sdk-apidoc-2.3.2-zh-Hans/index.html)
* [Guide Doc](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/releases): How to install and start using the SDK. * [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/2893975/mynt-eye-s-sdk-guide-2.3.1-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2893996/mynt-eye-s-sdk-guide-2.3.1-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-S-SDK-Guide/) * en: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2913052/mynt-eye-s-sdk-guide-2.3.2-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2913053/mynt-eye-s-sdk-guide-2.3.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/2893997/mynt-eye-s-sdk-guide-2.3.1-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2893997/mynt-eye-s-sdk-guide-2.3.1-zh-Hans.pdf) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/sdk/mynt-eye-s-sdk-guide-2.3.1-zh-Hans/mynt-eye-s-sdk-guide-2.3.1-zh-Hans/index.html) * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2913054/mynt-eye-s-sdk-guide-2.3.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/2913056/mynt-eye-s-sdk-guide-2.3.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.3.2-zh-Hans/mynt-eye-s-sdk-guide-2.3.2-zh-Hans/index.html)
> Supported languages: `en`, `zh-Hans`. > Supported languages: `en`, `zh-Hans`.

View File

@ -12,3 +12,5 @@
| Lens type | lens_type | - | × | √ Get/Set | 4 | vendor(2),product(2); default: 0 | | Lens type | lens_type | - | × | √ Get/Set | 4 | vendor(2),product(2); default: 0 |
| IMU type | imu_type | - | × | √ Get/Set | 4 | vendor(2),product(2); default: 0 | | IMU type | imu_type | - | × | √ Get/Set | 4 | vendor(2),product(2); default: 0 |
| Nominal baseline | nominal_baseline | - | × | √ Get/Set | 2 | unit: mm; default: 0 | | Nominal baseline | nominal_baseline | - | × | √ Get/Set | 2 | unit: mm; default: 0 |
| Auxiliary chip version | auxiliary_chip_version | - | × | √ Get | 2 | major,minor |
| isp version | isp_version | - | × | √ Get | 2 | major,minor |

View File

@ -12,6 +12,8 @@
| 镜头类型 | lens_type | - | × | √ Get/Set | 4 | vendor(2),product(2) ,未 Set 默认 0 | | 镜头类型 | lens_type | - | × | √ Get/Set | 4 | vendor(2),product(2) ,未 Set 默认 0 |
| IMU 类型 | imu_type | - | × | √ Get/Set | 4 | vendor(2),product(2) ,未 Set 默认 0 | | IMU 类型 | imu_type | - | × | √ Get/Set | 4 | vendor(2),product(2) ,未 Set 默认 0 |
| 基线长度 | nominal_baseline | - | × | √ Get/Set | 2 | 单位 mm ,未 set 默认 0 | | 基线长度 | nominal_baseline | - | × | √ Get/Set | 2 | 单位 mm ,未 set 默认 0 |
| 辅助芯片版本 | auxiliary_chip_version | - | × | √ Get | 2 | major,minor |
| ISP版本 | isp_version | - | × | √ Get | 2 | major,minor |
* 描述符获取:指通用 USB 设备信息,可用工具查看。 * 描述符获取:指通用 USB 设备信息,可用工具查看。
* 拓展通道获取指通过拓展通道UVC Extension Unit问硬件获取到的信息需要读取。 * 拓展通道获取指通过拓展通道UVC Extension Unit问硬件获取到的信息需要读取。

View File

@ -162,6 +162,8 @@ struct MYNTEYE_API DeviceInfo {
Type lens_type; Type lens_type;
Type imu_type; Type imu_type;
std::uint16_t nominal_baseline; std::uint16_t nominal_baseline;
Version auxiliary_chip_version;
Version isp_version;
}; };
#undef MYNTEYE_PROPERTY #undef MYNTEYE_PROPERTY

View File

@ -122,6 +122,10 @@ enum class Info : std::uint8_t {
IMU_TYPE, IMU_TYPE,
/** Nominal baseline */ /** Nominal baseline */
NOMINAL_BASELINE, NOMINAL_BASELINE,
/** Auxiliary chip version */
AUXILIARY_CHIP_VERSION,
/** Isp version */
ISP_VERSION,
/** SDK version*/ /** SDK version*/
SDK_VERSION, SDK_VERSION,
/** Last guard */ /** Last guard */

View File

@ -28,6 +28,9 @@ int main(int argc, char *argv[]) {
LOG(INFO) << "Lens type: " << api->GetInfo(Info::LENS_TYPE); LOG(INFO) << "Lens type: " << api->GetInfo(Info::LENS_TYPE);
LOG(INFO) << "IMU type: " << api->GetInfo(Info::IMU_TYPE); LOG(INFO) << "IMU type: " << api->GetInfo(Info::IMU_TYPE);
LOG(INFO) << "Nominal baseline: " << api->GetInfo(Info::NOMINAL_BASELINE); LOG(INFO) << "Nominal baseline: " << api->GetInfo(Info::NOMINAL_BASELINE);
LOG(INFO) << "Auxiliary chip version: "
<< api->GetInfo(Info::AUXILIARY_CHIP_VERSION);
LOG(INFO) << "Nominal baseline: " << api->GetInfo(Info::ISP_VERSION);
return 0; return 0;
} }

View File

@ -460,6 +460,7 @@ bool Channels::GetFiles(
while (i < end) { while (i < end) {
std::uint8_t file_id = *(data + i); std::uint8_t file_id = *(data + i);
std::uint16_t file_size = bytes::_from_data<std::uint16_t>(data + i + 1); std::uint16_t file_size = bytes::_from_data<std::uint16_t>(data + i + 1);
LOG(INFO) << "GetFiles:data_size : " << file_size;
VLOG(2) << "GetFiles id: " << static_cast<int>(file_id) VLOG(2) << "GetFiles id: " << static_cast<int>(file_id)
<< ", size: " << file_size; << ", size: " << file_size;
i += 3; i += 3;

View File

@ -32,6 +32,7 @@ std::size_t FileChannel::GetDeviceInfoFromData(
const std::uint8_t *data, const std::uint16_t &data_size, const std::uint8_t *data, const std::uint16_t &data_size,
device_info_t *info) { device_info_t *info) {
auto n = dev_info_parser_->GetFromData(data, data_size, info); auto n = dev_info_parser_->GetFromData(data, data_size, info);
LOG(INFO) << "GetDeviceInfoFromData:data_size : " << data_size;
auto spec_version = info->spec_version; auto spec_version = info->spec_version;
img_params_parser_->SetSpecVersion(spec_version); img_params_parser_->SetSpecVersion(spec_version);
imu_params_parser_->SetSpecVersion(spec_version); imu_params_parser_->SetSpecVersion(spec_version);
@ -113,6 +114,22 @@ std::size_t DeviceInfoParser::GetFromData(
info->nominal_baseline = bytes::_from_data<std::uint16_t>(data + i); info->nominal_baseline = bytes::_from_data<std::uint16_t>(data + i);
i += 2; i += 2;
if (info->spec_version >= Version(1, 2)) {
// auxiliary_chip_version, 2
info->auxiliary_chip_version.set_major(data[i]);
info->auxiliary_chip_version.set_minor(data[i + 1]);
i += 2;
// isp_version, 2
info->isp_version.set_major(data[i]);
info->isp_version.set_minor(data[i + 1]);
i += 2;
} else {
info->auxiliary_chip_version.set_major(0);
info->auxiliary_chip_version.set_minor(0);
info->isp_version.set_major(0);
info->isp_version.set_minor(0);
}
// get other infos according to spec_version // get other infos according to spec_version
MYNTEYE_UNUSED(data_size) MYNTEYE_UNUSED(data_size)
@ -155,6 +172,17 @@ std::size_t DeviceInfoParser::SetToData(
bytes::_to_data(info->nominal_baseline, data + i); bytes::_to_data(info->nominal_baseline, data + i);
i += 2; i += 2;
if (info->spec_version >= Version(1, 2)) {
// auxiliary_chip_version, 2
data[i] = info->auxiliary_chip_version.major();
data[i + 1] = info->auxiliary_chip_version.minor();
i += 2;
// isp_version, 2
data[i] = info->isp_version.major();
data[i + 1] = info->isp_version.minor();
i += 2;
}
// set other infos according to spec_version // set other infos according to spec_version
// others // others
@ -181,7 +209,7 @@ std::size_t ImgParamsParser::GetFromData(
return GetFromData_v1_0(data, data_size, img_params); return GetFromData_v1_0(data, data_size, img_params);
} }
// s210a old params // s210a old params
if (spec_version_ == Version(1, 1) && data_size == 404) { if (spec_version_ >= Version(1, 1) && data_size == 404) {
return GetFromData_v1_1(data, data_size, img_params); return GetFromData_v1_1(data, data_size, img_params);
} }
// get img params with new version format // get img params with new version format
@ -406,7 +434,7 @@ std::size_t ImuParamsParser::GetFromData(
return GetFromData_old(data, data_size, imu_params); return GetFromData_old(data, data_size, imu_params);
} }
// s210a old params // s210a old params
if (spec_version_ == Version(1, 1) && data_size == 384) { if (spec_version_ >= Version(1, 1) && data_size == 384) {
return GetFromData_old(data, data_size, imu_params); return GetFromData_old(data, data_size, imu_params);
} }
// get imu params with new version format // get imu params with new version format

View File

@ -234,6 +234,10 @@ std::string Device::GetInfo(const Info &info) const {
return device_info_->imu_type.to_string(); return device_info_->imu_type.to_string();
case Info::NOMINAL_BASELINE: case Info::NOMINAL_BASELINE:
return std::to_string(device_info_->nominal_baseline); return std::to_string(device_info_->nominal_baseline);
case Info::AUXILIARY_CHIP_VERSION:
return device_info_->auxiliary_chip_version.to_string();
case Info::ISP_VERSION:
return device_info_->isp_version.to_string();
default: default:
LOG(WARNING) << "Unknown device info"; LOG(WARNING) << "Unknown device info";
return ""; return "";

View File

@ -92,6 +92,8 @@ const char *to_string(const Info &value) {
CASE(LENS_TYPE) CASE(LENS_TYPE)
CASE(IMU_TYPE) CASE(IMU_TYPE)
CASE(NOMINAL_BASELINE) CASE(NOMINAL_BASELINE)
CASE(AUXILIARY_CHIP_VERSION)
CASE(ISP_VERSION)
default: default:
CHECK(is_valid(value)); CHECK(is_valid(value));
return "Info::UNKNOWN"; return "Info::UNKNOWN";

View File

@ -53,6 +53,8 @@ TEST(Info, VerifyToString) {
EXPECT_STREQ("Info::LENS_TYPE", to_string(Info::LENS_TYPE)); EXPECT_STREQ("Info::LENS_TYPE", to_string(Info::LENS_TYPE));
EXPECT_STREQ("Info::IMU_TYPE", to_string(Info::IMU_TYPE)); EXPECT_STREQ("Info::IMU_TYPE", to_string(Info::IMU_TYPE));
EXPECT_STREQ("Info::NOMINAL_BASELINE", to_string(Info::NOMINAL_BASELINE)); EXPECT_STREQ("Info::NOMINAL_BASELINE", to_string(Info::NOMINAL_BASELINE));
EXPECT_STREQ("Info::AUXILIARY_CHIP_VERSION", to_string(Info::AUXILIARY_CHIP_VERSION));
EXPECT_STREQ("Info::ISP_VERSION", to_string(Info::ISP_VERSION));
} }
TEST(Option, VerifyToString) { TEST(Option, VerifyToString) {

View File

@ -2,9 +2,11 @@
--- ---
device_name: MYNT-EYE-S210A device_name: MYNT-EYE-S210A
serial_number: "07C40D1C0009071F" serial_number: "07C40D1C0009071F"
firmware_version: "0.1" firmware_version: "1.1"
hardware_version: "1.0" hardware_version: "1.0"
spec_version: "1.1" spec_version: "1.2"
lens_type: "0000" lens_type: "0001"
imu_type: "0000" imu_type: "0001"
nominal_baseline: 0 nominal_baseline: 0
auxiliary_chip_version: "1.0"
isp_version: "1.0"

View File

@ -52,7 +52,11 @@ bool DeviceWriter::WriteDeviceInfo(const dev_info_t &info) {
<< ", spec_version: " << dev_info->spec_version.to_string() << ", spec_version: " << dev_info->spec_version.to_string()
<< ", lens_type: " << dev_info->lens_type.to_string() << ", lens_type: " << dev_info->lens_type.to_string()
<< ", imu_type: " << dev_info->imu_type.to_string() << ", imu_type: " << dev_info->imu_type.to_string()
<< ", nominal_baseline: " << dev_info->nominal_baseline << "}"; << ", nominal_baseline: " << dev_info->nominal_baseline
<< ", auxiliary_chip_version: "
<< dev_info->auxiliary_chip_version.to_string()
<< ", isp_version: "
<< dev_info->isp_version.to_string()<< "}";
return true; return true;
} else { } else {
LOG(ERROR) << "Write device info failed"; LOG(ERROR) << "Write device info failed";
@ -215,6 +219,8 @@ bool DeviceWriter::SaveDeviceInfo(
fs << "lens_type" << info.lens_type.to_string(); fs << "lens_type" << info.lens_type.to_string();
fs << "imu_type" << info.imu_type.to_string(); fs << "imu_type" << info.imu_type.to_string();
fs << "nominal_baseline" << info.nominal_baseline; fs << "nominal_baseline" << info.nominal_baseline;
fs << "auxiliary_chip_version" << info.auxiliary_chip_version.to_string();
fs << "isp_version" << info.isp_version.to_string();
// save other infos according to spec_version // save other infos according to spec_version
fs.release(); fs.release();
return true; return true;

View File

@ -104,7 +104,7 @@ struct MYNTEYE_API MotionData {
ImuData imu; ImuData imu;
bool operator==(const MotionData &other) const { bool operator==(const MotionData &other) const {
return imu.timestamp == other.imu.timestamp; return imu.timestamp == other.imu.timestamp;
} }
}; };
@ -247,6 +247,8 @@ BOOST_PYTHON_MODULE(mynteye_py) {
.value("LENS_TYPE", Info::LENS_TYPE) .value("LENS_TYPE", Info::LENS_TYPE)
.value("IMU_TYPE", Info::IMU_TYPE) .value("IMU_TYPE", Info::IMU_TYPE)
.value("NOMINAL_BASELINE", Info::NOMINAL_BASELINE) .value("NOMINAL_BASELINE", Info::NOMINAL_BASELINE)
.value("AUXILIARY_CHIP_VERSION", Info::AUXILIARY_CHIP_VERSION)
.value("ISP_VERSION", Info::ISP_VERSION)
#ifdef ENUM_EXPORT_VALUES #ifdef ENUM_EXPORT_VALUES
.export_values() .export_values()
#endif #endif

View File

@ -153,7 +153,7 @@
<!-- <arg name="standard2/ir_control" default="0" /> --> <!-- <arg name="standard2/ir_control" default="0" /> -->
<!-- standard2/accel_range range: [6,48] --> <!-- standard2/accel_range range: [6,48] -->
<arg name="standard2/accel_range" default="-1" /> <arg name="standard2/accel_range" default="24" />
<!-- <arg name="standard2/accel_range" default="6" /> --> <!-- <arg name="standard2/accel_range" default="6" /> -->
<!-- standard2/gyro_range range: [250,4000] --> <!-- standard2/gyro_range range: [250,4000] -->

View File

@ -54,6 +54,8 @@ def main():
'LENS_TYPE': GetInfoRequest.LENS_TYPE, 'LENS_TYPE': GetInfoRequest.LENS_TYPE,
'IMU_TYPE': GetInfoRequest.IMU_TYPE, 'IMU_TYPE': GetInfoRequest.IMU_TYPE,
'NOMINAL_BASELINE': GetInfoRequest.NOMINAL_BASELINE, 'NOMINAL_BASELINE': GetInfoRequest.NOMINAL_BASELINE,
'AUXILIARY_CHIP_VERSION': GetInfoRequest.AUXILIARY_CHIP_VERSION,
'ISP_VERSION': GetInfoRequest.ISP_VERSION,
} }
for k, v in get_device_info(**keys).items(): for k, v in get_device_info(**keys).items():
print('{}: {}'.format(k, v)) print('{}: {}'.format(k, v))

View File

@ -407,6 +407,12 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
case Request::NOMINAL_BASELINE: case Request::NOMINAL_BASELINE:
res.value = api_->GetInfo(Info::NOMINAL_BASELINE); res.value = api_->GetInfo(Info::NOMINAL_BASELINE);
break; break;
case Request::AUXILIARY_CHIP_VERSION:
res.value = api_->GetInfo(Info::AUXILIARY_CHIP_VERSION);
break;
case Request::ISP_VERSION:
res.value = api_->GetInfo(Info::ISP_VERSION);
break;
case Request::IMG_INTRINSICS: case Request::IMG_INTRINSICS:
{ {
auto intri_left = api_->GetIntrinsicsBase(Stream::LEFT); auto intri_left = api_->GetIntrinsicsBase(Stream::LEFT);

View File

@ -6,10 +6,12 @@ uint32 SPEC_VERSION=4
uint32 LENS_TYPE=5 uint32 LENS_TYPE=5
uint32 IMU_TYPE=6 uint32 IMU_TYPE=6
uint32 NOMINAL_BASELINE=7 uint32 NOMINAL_BASELINE=7
uint32 IMG_INTRINSICS=8 uint32 AUXILIARY_CHIP_VERSION=8
uint32 IMG_EXTRINSICS_RTOL=9 uint32 ISP_VERSION=9
uint32 IMU_INTRINSICS=10 uint32 IMG_INTRINSICS=10
uint32 IMU_EXTRINSICS=11 uint32 IMG_EXTRINSICS_RTOL=11
uint32 IMU_INTRINSICS=12
uint32 IMU_EXTRINSICS=13
uint32 key uint32 key
--- ---
string value string value