From c9483c2aca5f92c3c0684b43d7174d18d8dbbcd8 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Sun, 12 Aug 2018 11:36:04 +0800 Subject: [PATCH 01/77] Remove frame rate 60 --- include/mynteye/types.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/mynteye/types.h b/include/mynteye/types.h index 0ab79fd..51a8e40 100644 --- a/include/mynteye/types.h +++ b/include/mynteye/types.h @@ -144,7 +144,7 @@ enum class Option : std::uint8_t { /** * Image frame rate, must set IMU_FREQUENCY together * - * values: {10,15,20,25,30,35,40,45,50,55,60}, default: 25 + * values: {10,15,20,25,30,35,40,45,50,55}, default: 25 */ FRAME_RATE, /** From 28204d5c0adc09e5edbfce48dc6a6730e2ea3b85 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Mon, 13 Aug 2018 09:10:23 +0800 Subject: [PATCH 02/77] Format comments --- .../src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc index 64dd7b9..856581f 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc @@ -378,10 +378,8 @@ class ROSWrapperNodelet : public nodelet::Nodelet { void publishCamera( const Stream &stream, const api::StreamData &data, std::uint32_t seq, ros::Time stamp) { - /* -if (camera_publishers_[stream].getNumSubscribers() == 0) -return; - */ + // if (camera_publishers_[stream].getNumSubscribers() == 0) + // return; std_msgs::Header header; header.seq = seq; header.stamp = stamp; @@ -419,10 +417,8 @@ return; void publishPoints( const api::StreamData &data, std::uint32_t seq, ros::Time stamp) { - /* -if (points_publisher_.getNumSubscribers() == 0) -return; - */ + // if (points_publisher_.getNumSubscribers() == 0) + // return; auto &&in = api_->GetIntrinsics(Stream::LEFT); From 375acb534c2737b08f9d5a1d450b2a1311e41afd Mon Sep 17 00:00:00 2001 From: John Zhao Date: Mon, 13 Aug 2018 09:12:34 +0800 Subject: [PATCH 03/77] Update README.md --- README.md | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index b2f564e..f0b11a3 100644 --- a/README.md +++ b/README.md @@ -27,10 +27,9 @@ Please follow the guide doc to install the SDK on different platforms. ## Firmwares -[Google Drive]: https://drive.google.com/drive/folders/1tdFCcTBMNcImEGZ39tdOZmlX2SHKCr2f -[百度网盘]: https://pan.baidu.com/s/1yPQDp2r0x4jvNwn2UjlMUQ +[MYNTEYE_BOX]: http://doc.myntai.com/mynteye/s/download -Get firmwares from our online disks: [Google Drive][], [百度网盘][]. The latest version is `2.0.1-rc0`. +Get firmwares from our online disks: [MYNTEYE_BOX][]. The latest version is `2.0.1`. ## Usage From 66c9af58fc4f79a6e7be9a5582bef0da9ad4c3e2 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 14 Aug 2018 10:45:13 +0800 Subject: [PATCH 04/77] Install to default path --- Makefile | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/Makefile b/Makefile index 4f9da2a..66c986b 100644 --- a/Makefile +++ b/Makefile @@ -16,6 +16,12 @@ include CommonDefs.mk MKFILE_PATH := $(abspath $(lastword $(MAKEFILE_LIST))) MKFILE_DIR := $(patsubst %/,%,$(dir $(MKFILE_PATH))) +# CMAKE_INSTALL_PREFIX: +# https://cmake.org/cmake/help/latest/variable/CMAKE_INSTALL_PREFIX.html +# +# UNIX: /usr/local +# Windows: c:/Program Files/${PROJECT_NAME} + .DEFAULT_GOAL := help help: @@ -83,7 +89,8 @@ init: submodules build: third_party @$(call echo,Make $@) - @$(call cmake_build,./_build,..,-DCMAKE_INSTALL_PREFIX=$(MKFILE_DIR)/_install) + @$(call cmake_build,./_build,..) + @# @$(call cmake_build,./_build,..,-DCMAKE_INSTALL_PREFIX=$(MKFILE_DIR)/_install) .PHONY: build @@ -115,10 +122,10 @@ ifeq ($(HOST_OS),Win) ifneq ($(HOST_NAME),MinGW) @cd ./_build; msbuild.exe INSTALL.vcxproj /property:Configuration=Release else - @cd ./_build; make install + @cd ./_build; sudo make install endif else - @cd ./_build; make install + @cd ./_build; sudo make install endif .PHONY: install From bbf789b17452bee14ce29a76e8cbdcd8ce520d64 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 14 Aug 2018 11:05:23 +0800 Subject: [PATCH 05/77] Update doc version --- doc/en/api.doxyfile | 2 +- doc/zh-Hans/api.doxyfile | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/doc/en/api.doxyfile b/doc/en/api.doxyfile index d7d7e03..c4dcd32 100644 --- a/doc/en/api.doxyfile +++ b/doc/en/api.doxyfile @@ -38,7 +38,7 @@ PROJECT_NAME = "MYNT EYE SDK" # could be handy for archiving the generated documentation or if some version # control system is used. -PROJECT_NUMBER = 2.0.1-rc0 +PROJECT_NUMBER = 2.0.1-rc1 # 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 aa023f5..ac8ccb5 100644 --- a/doc/zh-Hans/api.doxyfile +++ b/doc/zh-Hans/api.doxyfile @@ -38,7 +38,7 @@ PROJECT_NAME = "MYNT EYE SDK" # could be handy for archiving the generated documentation or if some version # control system is used. -PROJECT_NUMBER = 2.0.1-rc0 +PROJECT_NUMBER = 2.0.1-rc1 # 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 From 5f24d0857e896fcdfe4556e412a489f020272f8a Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 14 Aug 2018 11:13:21 +0800 Subject: [PATCH 06/77] Update README.md --- README.md | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/README.md b/README.md index f0b11a3..762044c 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ # MYNT® EYE SDK -[![](https://img.shields.io/badge/MYNT%20EYE%20SDK-2.0.1--rc0-brightgreen.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2) +[![](https://img.shields.io/badge/MYNT%20EYE%20SDK-2.0.1--rc1-brightgreen.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2) ## Overview @@ -17,11 +17,12 @@ Please follow the guide doc to install the SDK on different platforms. ## Documentations * [API Doc](https://github.com/slightech/MYNT-EYE-SDK-2/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-SDK-2/files/2203869/mynt-eye-sdk-apidoc-2.0.1-rc0-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2203870/mynt-eye-sdk-apidoc-2.0.1-rc0-html-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-SDK-2/) - * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2203872/mynt-eye-sdk-apidoc-2.0.1-rc0-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2203874/mynt-eye-sdk-apidoc-2.0.1-rc0-html-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/api/mynt-eye-sdk-apidoc-2.0.1-rc0-html-zh-Hans/mynt-eye-sdk-apidoc-2.0.1-rc0-html-zh-Hans/index.html) + * en: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2285351/mynt-eye-sdk-apidoc-2.0.1-rc1-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2285352/mynt-eye-sdk-apidoc-2.0.1-rc1-html-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-SDK-2/) + * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2285353/mynt-eye-sdk-apidoc-2.0.1-rc1-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2285354/mynt-eye-sdk-apidoc-2.0.1-rc1-html-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/api/mynt-eye-sdk-apidoc-2.0.1-rc1-html-zh-Hans/mynt-eye-sdk-apidoc-2.0.1-rc1-html-zh-Hans/index.html) * [Guide Doc](https://github.com/slightech/MYNT-EYE-SDK-2-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-SDK-2-Guide/files/2203877/mynt-eye-sdk-guide-2.0.1-rc0-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2203879/mynt-eye-sdk-guide-2.0.1-rc0-html-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-SDK-2-Guide/) - * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2203880/mynt-eye-sdk-guide-2.0.1-rc0-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2203881/mynt-eye-sdk-guide-2.0.1-rc0-html-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/sdk/mynt-eye-sdk-guide-2.0.1-rc0-html-zh-Hans/mynt-eye-sdk-guide-2.0.1-rc0-html-zh-Hans/index.html ) + * en: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2281782/mynt-eye-sdk-guide-2.0.1-rc1-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2281783/mynt-eye-sdk-guide-2.0.1-rc1-html-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-SDK-2-Guide/) + * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2281785/mynt-eye-sdk-guide-2.0.1-rc1-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2281786/mynt-eye-sdk-guide-2.0.1-rc1-html-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/sdk/mynt-eye-sdk-guide-2.0.1-rc1-html-zh-Hans/mynt-eye-sdk-guide-2.0.1-rc1-html-zh-Hans/index.html) + > Supported languages: `en`, `zh-Hans`. From a96246cc20f7de8ab17a5d3d2108dcf546a322f9 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 14 Aug 2018 13:46:18 +0800 Subject: [PATCH 07/77] Change install dir on win --- Makefile | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index 66c986b..e8555fd 100644 --- a/Makefile +++ b/Makefile @@ -89,8 +89,11 @@ init: submodules build: third_party @$(call echo,Make $@) +ifeq ($(HOST_OS),Win) + @$(call cmake_build,./_build,..,-DCMAKE_INSTALL_PREFIX=$(MKFILE_DIR)/_install) +else @$(call cmake_build,./_build,..) - @# @$(call cmake_build,./_build,..,-DCMAKE_INSTALL_PREFIX=$(MKFILE_DIR)/_install) +endif .PHONY: build @@ -122,7 +125,7 @@ ifeq ($(HOST_OS),Win) ifneq ($(HOST_NAME),MinGW) @cd ./_build; msbuild.exe INSTALL.vcxproj /property:Configuration=Release else - @cd ./_build; sudo make install + @cd ./_build; make install endif else @cd ./_build; sudo make install From 1f003f505b949f3d2b207a30d60bbb463c3a44d0 Mon Sep 17 00:00:00 2001 From: Osenberg-Y Date: Tue, 14 Aug 2018 14:16:07 +0800 Subject: [PATCH 08/77] Fixed no pointcloud on ros --- wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc index 856581f..839d2d6 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc @@ -324,7 +324,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet { is_published_[stream] = true; } - if (camera_publishers_[Stream::POINTS].getNumSubscribers() > 0 && + if (points_publisher_.getNumSubscribers() > 0 && !is_published_[Stream::POINTS]) { api_->SetStreamCallback( Stream::POINTS, [this](const api::StreamData &data) { From d4343b574a259979abde4d9a34b03f565ccb4d7e Mon Sep 17 00:00:00 2001 From: Osenberg-Y Date: Fri, 17 Aug 2018 17:56:41 +0800 Subject: [PATCH 09/77] Optimized the display of raw image and imu rate information --- .../src/wrapper_nodelet.cc | 33 ++++++++++++++----- 1 file changed, 24 insertions(+), 9 deletions(-) diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc index 839d2d6..364a3d4 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc @@ -45,6 +45,9 @@ MYNTEYE_BEGIN_NAMESPACE namespace enc = sensor_msgs::image_encodings; +inline double compute_time(const double end, const double start) { + return end - start; +} class ROSWrapperNodelet : public nodelet::Nodelet { public: @@ -57,15 +60,21 @@ class ROSWrapperNodelet : public nodelet::Nodelet { } if (time_beg_ != -1) { double time_end = ros::Time::now().toSec(); - double time_elapsed = time_end - time_beg_; - LOG(INFO) << "Time elapsed: " << time_elapsed << " s"; - LOG(INFO) << "Left count: " << left_count_ - << ", fps: " << (left_count_ / time_elapsed); - LOG(INFO) << "Right count: " << right_count_ - << ", fps: " << (right_count_ / time_elapsed); - LOG(INFO) << "Imu count: " << imu_count_ - << ", hz: " << (imu_count_ / time_elapsed); + LOG(INFO) << "Time elapsed: " << compute_time(time_end, time_beg_) + << " s"; + if (left_time_beg_ != -1) { + LOG(INFO) << "Left count: " << left_count_ << ", fps: " + << (left_count_ / compute_time(time_end, left_time_beg_)); + } + if (right_time_beg_ != -1) { + LOG(INFO) << "Right count: " << right_count_ << ", fps: " + << (right_count_ / compute_time(time_end, right_time_beg_)); + } + if (imu_time_beg_ != -1) { + LOG(INFO) << "Imu count: " << imu_count_ << ", hz: " + << (imu_count_ / compute_time(time_end, imu_time_beg_)); + } // ROS messages could not be reliably printed here, using glog instead :( // ros::Duration(1).sleep(); // 1s @@ -285,6 +294,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet { << ", timestamp: " << data.img->timestamp << ", exposure_time: " << data.img->exposure_time); }); + left_time_beg_ = ros::Time::now().toSec(); is_published_[Stream::LEFT] = true; } @@ -302,6 +312,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet { << data.img->frame_id << ", timestamp: " << data.img->timestamp << ", exposure_time: " << data.img->exposure_time); }); + right_time_beg_ = ros::Time::now().toSec(); is_published_[Stream::RIGHT] = true; } @@ -365,11 +376,12 @@ class ROSWrapperNodelet : public nodelet::Nodelet { // Sleep 1ms, otherwise publish may drop some datas. ros::Duration(0.001).sleep(); }); + imu_time_beg_ = ros::Time::now().toSec(); is_motion_published_ = true; } - time_beg_ = ros::Time::now().toSec(); if (!is_started_) { + time_beg_ = ros::Time::now().toSec(); api_->Start(Source::ALL); is_started_ = true; } @@ -860,6 +872,9 @@ class ROSWrapperNodelet : public nodelet::Nodelet { cv::Rect left_roi_, right_roi_; double time_beg_ = -1; + double left_time_beg_ = -1; + double right_time_beg_ = -1; + double imu_time_beg_ = -1; std::size_t left_count_ = 0; std::size_t right_count_ = 0; std::size_t imu_count_ = 0; From 692cbac8d810bcca6a5fa6d53d4a9ae3eda9f44d Mon Sep 17 00:00:00 2001 From: Osenberg-Y Date: Tue, 28 Aug 2018 16:46:51 +0800 Subject: [PATCH 10/77] Temporary version --- .../launch/mynteye.launch | 2 +- .../src/wrapper_nodelet.cc | 113 ++++++++++++++---- 2 files changed, 90 insertions(+), 25 deletions(-) diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch b/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch index 3654689..a41e52f 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch @@ -38,7 +38,7 @@ - + diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc index 364a3d4..fccda6d 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc @@ -173,6 +173,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet { } NODELET_INFO_STREAM(it->first << ": " << api_->GetOptionValue(it->first)); } + frame_rate_ = api_->GetOptionValue(Option::FRAME_RATE); // publishers @@ -227,8 +228,10 @@ class ROSWrapperNodelet : public nodelet::Nodelet { NODELET_INFO_STREAM("Advertized service " << DEVICE_INFO_SERVICE); publishStaticTransforms(); + ros::Rate loop_rate(frame_rate_); while (private_nh_.ok()) { publishTopics(); + loop_rate.sleep(); } } @@ -268,6 +271,84 @@ class ROSWrapperNodelet : public nodelet::Nodelet { return true; } + void SetIsPublished(const Stream &stream) { + is_published_[stream] = false; + switch (stream) { + case Stream::LEFT_RECTIFIED: { + if (is_published_[Stream::RIGHT_RECTIFIED]) { + SetIsPublished(Stream::RIGHT_RECTIFIED); + } + if (is_published_[Stream::DISPARITY]) { + SetIsPublished(Stream::DISPARITY); + } + } break; + case Stream::RIGHT_RECTIFIED: { + if (is_published_[Stream::LEFT_RECTIFIED]) { + SetIsPublished(Stream::RIGHT_RECTIFIED); + } + if (is_published_[Stream::DISPARITY]) { + SetIsPublished(Stream::DISPARITY); + } + } break; + case Stream::DISPARITY: { + if (is_published_[Stream::DISPARITY_NORMALIZED]) { + SetIsPublished(Stream::DISPARITY_NORMALIZED); + } + if (is_published_[Stream::POINTS]) { + SetIsPublished(Stream::POINTS); + } + } break; + case Stream::DISPARITY_NORMALIZED: { + } break; + case Stream::POINTS: { + if (is_published_[Stream::DEPTH]) { + SetIsPublished(Stream::DEPTH); + } + } break; + case Stream::DEPTH: { + } break; + default: + return; + } + } + + void publishPoint(const Stream &stream) { + auto &&points_num = points_publisher_.getNumSubscribers(); + if (points_num == 0 && is_published_[stream]) { + SetIsPublished(stream); + api_->DisableStreamData(stream); + } else if (points_num > 0 && !is_published_[Stream::POINTS]) { + api_->EnableStreamData(Stream::POINTS); + api_->SetStreamCallback( + Stream::POINTS, [this](const api::StreamData &data) { + static std::size_t count = 0; + ++count; + publishPoints(data, count, ros::Time::now()); + }); + is_published_[Stream::POINTS] = true; + } + } + + void publishOthers(const Stream &stream) { + auto stream_num = camera_publishers_[stream].getNumSubscribers(); + if (stream_num == 0 && is_published_[stream]) { + // Stop computing when was not subcribed + SetIsPublished(stream); + api_->DisableStreamData(stream); + } else if (stream_num > 0 && !is_published_[stream]) { + // Start computing and publishing when was subcribed + api_->EnableStreamData(stream); + api_->SetStreamCallback( + stream, [this, stream](const api::StreamData &data) { + // data.img is null, not hard timestamp + static std::size_t count = 0; + ++count; + publishCamera(stream, data, count, ros::Time::now()); + }); + is_published_[stream] = true; + } + } + void publishTopics() { if (camera_publishers_[Stream::LEFT].getNumSubscribers() > 0 && !is_published_[Stream::LEFT]) { @@ -317,33 +398,16 @@ class ROSWrapperNodelet : public nodelet::Nodelet { } std::vector other_streams{ - Stream::LEFT_RECTIFIED, Stream::RIGHT_RECTIFIED, Stream::DISPARITY, - Stream::DISPARITY_NORMALIZED, Stream::DEPTH}; + Stream::LEFT_RECTIFIED, Stream::RIGHT_RECTIFIED, + Stream::DISPARITY, Stream::DISPARITY_NORMALIZED, + Stream::POINTS, Stream::DEPTH}; for (auto &&stream : other_streams) { - if (camera_publishers_[stream].getNumSubscribers() == 0 && - is_published_[stream]) { - continue; + if (stream != Stream::POINTS) { + publishOthers(stream); + } else { + publishPoint(stream); } - api_->SetStreamCallback( - stream, [this, stream](const api::StreamData &data) { - // data.img is null, not hard timestamp - static std::size_t count = 0; - ++count; - publishCamera(stream, data, count, ros::Time::now()); - }); - is_published_[stream] = true; - } - - if (points_publisher_.getNumSubscribers() > 0 && - !is_published_[Stream::POINTS]) { - api_->SetStreamCallback( - Stream::POINTS, [this](const api::StreamData &data) { - static std::size_t count = 0; - ++count; - publishPoints(data, count, ros::Time::now()); - }); - is_published_[Stream::POINTS] = true; } if (!is_motion_published_) { @@ -882,6 +946,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet { std::map is_published_; bool is_motion_published_; bool is_started_; + int frame_rate_; }; MYNTEYE_END_NAMESPACE From d80d506360adab30cee64a4e2ec61c96075527bb Mon Sep 17 00:00:00 2001 From: kalman Date: Sat, 1 Sep 2018 20:47:35 +0800 Subject: [PATCH 11/77] Throw error in v4l2 when time out --- src/uvc/uvc-v4l2.cc | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/src/uvc/uvc-v4l2.cc b/src/uvc/uvc-v4l2.cc index a064552..b530cb4 100755 --- a/src/uvc/uvc-v4l2.cc +++ b/src/uvc/uvc-v4l2.cc @@ -41,6 +41,9 @@ namespace uvc { LOG(severity) << str << " error " << errno << ", " << strerror(errno); \ } while (0) +#define NO_DATA_MAX_COUNT 200 + +int no_data_count = 0; /* class device_error : public std::exception { public: @@ -194,6 +197,7 @@ struct device { ~device() { VLOG(2) << __func__; stop_streaming(); + no_data_count = 0; if (fd != -1 && close(fd) < 0) { LOG_ERROR(WARNING, "close"); } @@ -386,6 +390,14 @@ struct device { throw_error("VIDIOC_QBUF"); }); } + + no_data_count = 0; + } else { + no_data_count++; + } + + if (no_data_count > NO_DATA_MAX_COUNT) { + throw_error("v4l2 get stream time out!"); } } From 54f01eec1a45ec09e61ed890f25b3c25ea8438d2 Mon Sep 17 00:00:00 2001 From: kalman Date: Sat, 1 Sep 2018 20:51:14 +0800 Subject: [PATCH 12/77] Miss blank line --- src/uvc/uvc-v4l2.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/src/uvc/uvc-v4l2.cc b/src/uvc/uvc-v4l2.cc index b530cb4..06fc8fc 100755 --- a/src/uvc/uvc-v4l2.cc +++ b/src/uvc/uvc-v4l2.cc @@ -44,6 +44,7 @@ namespace uvc { #define NO_DATA_MAX_COUNT 200 int no_data_count = 0; + /* class device_error : public std::exception { public: From 92585a3b8d220373bb570c3f5eec7fb8e31901d4 Mon Sep 17 00:00:00 2001 From: kalman Date: Sat, 1 Sep 2018 21:03:28 +0800 Subject: [PATCH 13/77] Replace LOG(WARNING) with VLOG(2) When get imu params failed or image packet is unaccepted --- src/device/device.cc | 6 +++--- src/internal/streams.cc | 18 +++++++++--------- 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/src/device/device.cc b/src/device/device.cc index e6a2542..cc4d2b8 100644 --- a/src/device/device.cc +++ b/src/device/device.cc @@ -252,7 +252,7 @@ MotionIntrinsics Device::GetMotionIntrinsics(bool *ok) const { return *motion_intrinsics_; } else { *ok = false; - LOG(WARNING) << "Motion intrinsics not found"; + VLOG(2) << "Motion intrinsics not found"; return {}; } } @@ -263,7 +263,7 @@ Extrinsics Device::GetMotionExtrinsics(const Stream &from, bool *ok) const { return motion_from_extrinsics_.at(from); } catch (const std::out_of_range &e) { *ok = false; - LOG(WARNING) << "Motion extrinsics from " << from << " not found"; + VLOG(2) << "Motion extrinsics from " << from << " not found"; return {}; } } @@ -580,7 +580,7 @@ void Device::ReadAllInfos() { VLOG(2) << "Motion extrinsics left to imu: {" << GetMotionExtrinsics(Stream::LEFT) << "}"; } else { - LOG(WARNING) << "Motion intrinsics & extrinsics not exist"; + VLOG(2) << "Motion intrinsics & extrinsics not exist"; } } diff --git a/src/internal/streams.cc b/src/internal/streams.cc index 4b049e3..97ae970 100644 --- a/src/internal/streams.cc +++ b/src/internal/streams.cc @@ -50,9 +50,9 @@ bool unpack_stereo_img_data( // << ", checksum=0x" << std::hex << static_cast(img_packet.checksum); if (img_packet.header != 0x3B) { - LOG(WARNING) << "Image packet header must be 0x3B, but 0x" << std::hex - << std::uppercase << std::setw(2) << std::setfill('0') - << static_cast(img_packet.header) << " now"; + VLOG(2) << "Image packet header must be 0x3B, but 0x" << std::hex + << std::uppercase << std::setw(2) << std::setfill('0') + << static_cast(img_packet.header) << " now"; return false; } @@ -61,11 +61,11 @@ bool unpack_stereo_img_data( checksum = (checksum ^ packet[i]); } if (img_packet.checksum != checksum) { - LOG(WARNING) << "Image packet checksum should be 0x" << std::hex - << std::uppercase << std::setw(2) << std::setfill('0') - << static_cast(img_packet.checksum) << ", but 0x" - << std::setw(2) << std::setfill('0') - << static_cast(checksum) << " now"; + VLOG(2) << "Image packet checksum should be 0x" << std::hex + << std::uppercase << std::setw(2) << std::setfill('0') + << static_cast(img_packet.checksum) << ", but 0x" + << std::setw(2) << std::setfill('0') << static_cast(checksum) + << " now"; return false; } @@ -160,7 +160,7 @@ bool Streams::PushStream(const Capabilities &capability, const void *data) { } else { // discard left DiscardStreamData(Stream::LEFT); - LOG(WARNING) << "Image packet is unaccepted, frame dropped"; + VLOG(2) << "Image packet is unaccepted, frame dropped"; pushed = false; } } break; From 55165b887876be8b532fef21cbd8319b051168a2 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 4 Sep 2018 10:47:54 +0800 Subject: [PATCH 14/77] Update init script, make linter optional --- CPPLINT.cfg | 2 + scripts/init.sh | 162 +------------------------------- scripts/init_tools.sh | 214 ++++++++++++++++++++++++++++++++++++++++++ 3 files changed, 221 insertions(+), 157 deletions(-) create mode 100644 CPPLINT.cfg create mode 100644 scripts/init_tools.sh diff --git a/CPPLINT.cfg b/CPPLINT.cfg new file mode 100644 index 0000000..95cd94f --- /dev/null +++ b/CPPLINT.cfg @@ -0,0 +1,2 @@ +set noparent +filter=-build/c++11 diff --git a/scripts/init.sh b/scripts/init.sh index c034f3e..ce193c2 100755 --- a/scripts/init.sh +++ b/scripts/init.sh @@ -14,181 +14,29 @@ # limitations under the License. # _VERBOSE_=1 +# _INIT_LINTER_=1 # _FORCE_INSRALL_=1 BASE_DIR=$(cd "$(dirname "$0")" && pwd) -source "$BASE_DIR/common/echo.sh" -source "$BASE_DIR/common/detect.sh" -source "$BASE_DIR/common/host.sh" - -PYTHON="python" -if [ "$HOST_OS" = "Win" ]; then - if ! _detect_cmd $PYTHON; then - PYTHON="python2" # try python2 on MSYS - fi -fi - -_detect $PYTHON 1 - -PYTHON_FOUND="${PYTHON}_FOUND" -if [ -z "${!PYTHON_FOUND}" ]; then - _echo_en "$PYTHON not found" -fi - -if [ "$HOST_OS" = "Linux" ]; then - _detect_install() { - _detect_cmd "$1" || [ $(dpkg-query -W -f='${Status}' "$1" 2> /dev/null \ - | grep -c "ok installed") -gt 0 ] - } -elif [ "$HOST_OS" = "Mac" ]; then - _detect_install() { - _detect_cmd "$1" || brew ls --versions "$1" > /dev/null - } -else - _detect_install() { - _detect_cmd "$1" - } -fi - -_install_deps() { - _cmd="$1"; shift; _deps_all=($@) - _echo "Install cmd: $_cmd" - _echo "Install deps: ${_deps_all[*]}" - if [ -n "${_FORCE_INSRALL_}" ]; then - _echo_d "$_cmd ${_deps_all[*]}" - $_cmd ${_deps_all[@]} - return - fi - _deps=() - for _dep in "${_deps_all[@]}"; do - _detect_install $_dep || _deps+=($_dep) - done - if [ ${#_deps[@]} -eq 0 ]; then - _echo_i "All deps already exist" - else - _echo_d "$_cmd ${_deps[*]} (not exists)" - $_cmd ${_deps[@]} - fi -} +source "$BASE_DIR/init_tools.sh" ## deps _echo_s "Init deps" if [ "$HOST_OS" = "Linux" ]; then - # detect apt-get - _detect apt-get - # apt-get install - _install_deps "sudo apt-get install" build-essential curl cmake git clang-format - _install_deps "sudo apt-get install" libv4l-dev - if ! _detect_cmd clang-format; then - # on Ubuntu 14.04, apt-cache search clang-format - _install_deps "sudo apt-get install" clang-format-3.9 - sudo ln -sf clang-format-3.9 /usr/bin/clang-format - sudo ln -sf clang-format-diff-3.9 /usr/bin/clang-format-diff - fi - # sudo - SUDO="sudo" + _install_deps "$SUDO apt-get install" libv4l-dev elif [ "$HOST_OS" = "Mac" ]; then - # detect brew - if ! _detect_cmd brew; then - _echo_sn "Install brew" - _detect curl - _detect ruby - ruby -e "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install)" - fi - # brew install - _install_deps "brew install" curl cmake git clang-format - # link clang-format-diff (if not compatible with Python 3, fix it by yourself) - [ -f "/usr/local/bin/clang-format-diff" ] || \ - ln -s /usr/local/share/clang/clang-format-diff.py /usr/local/bin/clang-format-diff _install_deps "brew install" libuvc elif [ "$HOST_OS" = "Win" ]; then - # detect pacman on MSYS - _detect pacman - # pacman install (common) - _install_deps "pacman -S" curl git clang-format - if [ "$HOST_NAME" = "MINGW" ]; then - # pacman install (MINGW) - _deps=() - if [ "$HOST_ARCH" = "x64" ]; then - _deps+=(mingw-w64-x86_64-toolchain mingw-w64-x86_64-cmake) - elif [ "$HOST_ARCH" = "x86" ]; then - _deps+=(mingw-w64-i686-toolchain mingw-w64-i686-cmake) - else - _echo_e "Unknown host arch :(" - exit 1 - fi - if ! [ ${#_deps[@]} -eq 0 ]; then - _echo_d "pacman -S ${_deps[*]}" - pacman -S ${_deps[@]} - fi - else - # detect cmake on MSYS - _detect cmake - fi - # update - # pacman -Syu - # search - # pacman -Ss make - # autoremove - # pacman -Qtdq | pacman -Rs - + # _install_deps "pacman -S" ? + _echo else # unexpected _echo_e "Unknown host os :(" exit 1 fi -## pip - -# detect pip -if ! _detect_cmd pip; then - if [ -n "${!PYTHON_FOUND}" ]; then - _echo_sn "Install pip" - [ -f "get-pip.py" ] || curl -O https://bootstrap.pypa.io/get-pip.py - $SUDO $PYTHON get-pip.py - else - _echo_en "Skipped install pip, as $PYTHON not found" - fi -fi -# pip install -if _detect_cmd pip; then - _echo_d "pip install --upgrade autopep8 cpplint pylint requests" - $SUDO pip install --upgrade autopep8 cpplint pylint requests -else - _echo_en "Skipped pip install packages, as pip not found" -fi - -## realpath - -# detect realpath -if ! _detect_cmd realpath; then - _echo_sn "Install realpath" - if [ "$HOST_OS" = "Linux" ]; then - # How to install realpath on Ubuntu 14.04 - # https://www.howtoinstall.co/en/ubuntu/trusty/realpath - sudo apt-get install coreutils realpath - elif [ "$HOST_OS" = "Mac" ]; then - brew install coreutils - elif [ "$HOST_OS" = "Win" ]; then - pacman -S coreutils - else # unexpected - _echo_e "Unknown host os :(" - exit 1 - fi -fi - -ROOT_DIR=$(realpath "$BASE_DIR/..") - -## init - -if [ -n "${!PYTHON_FOUND}" ]; then - _echo_s "Init git hooks" - $PYTHON "$ROOT_DIR/tools/linter/init-git-hooks.py" -else - _echo_en "Skipped init git hooks, as $PYTHON not found" -fi - ## cmake version _echo_s "Expect cmake version >= 3.0" diff --git a/scripts/init_tools.sh b/scripts/init_tools.sh new file mode 100644 index 0000000..232b536 --- /dev/null +++ b/scripts/init_tools.sh @@ -0,0 +1,214 @@ +#!/usr/bin/env bash +# Copyright 2018 Slightech Inc. 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. + +_INIT_BUILD_=1 +# _INIT_LINTER_=1 +# _FORCE_INSRALL_=1 + +BASE_DIR=$(cd "$(dirname "$0")" && pwd) + +source "$BASE_DIR/common/echo.sh" +source "$BASE_DIR/common/detect.sh" +source "$BASE_DIR/common/host.sh" + +## functions + +if [ "$HOST_OS" = "Linux" ]; then + _detect_install() { + _detect_cmd "$1" || [ $(dpkg-query -W -f='${Status}' "$1" 2> /dev/null \ + | grep -c "ok installed") -gt 0 ] + } +elif [ "$HOST_OS" = "Mac" ]; then + _detect_install() { + _detect_cmd "$1" || brew ls --versions "$1" > /dev/null + } +else + _detect_install() { + _detect_cmd "$1" + } +fi + +_install_deps() { + _cmd="$1"; shift; _deps_all=($@) + _echo "Install cmd: $_cmd" + _echo "Install deps: ${_deps_all[*]}" + if [ -n "${_FORCE_INSRALL_}" ]; then + _echo_d "$_cmd ${_deps_all[*]}" + $_cmd ${_deps_all[@]} + return + fi + _deps=() + for _dep in "${_deps_all[@]}"; do + _detect_install $_dep || _deps+=($_dep) + done + if [ ${#_deps[@]} -eq 0 ]; then + _echo_i "All deps already exist" + else + _echo_d "$_cmd ${_deps[*]} (not exists)" + $_cmd ${_deps[@]} + fi +} + +## init tools + +_echo_s "Init tools" + +if [ "$HOST_OS" = "Linux" ]; then + # sudo + SUDO="sudo" + # detect apt-get + _detect apt-get + # apt-get install + if [ -n "${_INIT_BUILD_}" ]; then + _install_deps "$SUDO apt-get install" build-essential curl cmake git make + fi + if [ -n "${_INIT_LINTER_}" ]; then + _install_deps "$SUDO apt-get install" clang-format + if ! _detect_cmd clang-format; then + # on Ubuntu 14.04, apt-cache search clang-format + _install_deps "$SUDO apt-get install" clang-format-3.9 + $SUDO ln -sf clang-format-3.9 /usr/bin/clang-format + $SUDO ln -sf clang-format-diff-3.9 /usr/bin/clang-format-diff + fi + fi +elif [ "$HOST_OS" = "Mac" ]; then + # detect brew + if ! _detect_cmd brew; then + _echo_sn "Install brew" + _detect curl + _detect ruby + ruby -e "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install)" + fi + # brew install + if [ -n "${_INIT_BUILD_}" ]; then + _install_deps "brew install" curl cmake git make + fi + if [ -n "${_INIT_LINTER_}" ]; then + _install_deps "brew install" clang-format + # link clang-format-diff (if not compatible with Python 3, fix it by yourself) + [ -f "/usr/local/bin/clang-format-diff" ] || \ + ln -s /usr/local/share/clang/clang-format-diff.py /usr/local/bin/clang-format-diff + fi +elif [ "$HOST_OS" = "Win" ]; then + # detect pacman on MSYS + _detect pacman + # pacman install + if [ -n "${_INIT_BUILD_}" ]; then + _install_deps "pacman -S" curl git make + if [ "$HOST_NAME" = "MINGW" ]; then + # MINGW: cmake + _deps=() + if [ "$HOST_ARCH" = "x64" ]; then + _deps+=(mingw-w64-x86_64-toolchain mingw-w64-x86_64-cmake) + elif [ "$HOST_ARCH" = "x86" ]; then + _deps+=(mingw-w64-i686-toolchain mingw-w64-i686-cmake) + else + _echo_e "Unknown host arch :(" + exit 1 + fi + if ! [ ${#_deps[@]} -eq 0 ]; then + _install_deps "pacman -S" ${_deps[@]} + fi + else + # Install CMake for Windows + # https://cmake.org/ + _detect cmake + fi + fi + if [ -n "${_INIT_LINTER_}" ]; then + _install_deps "pacman -S" clang-format + fi + # update + # pacman -Syu + # search + # pacman -Ss make + # autoremove + # pacman -Qtdq | pacman -Rs - +else # unexpected + _echo_e "Unknown host os :(" + exit 1 +fi + +## init linter - optional + +if [ -n "${_INIT_LINTER_}" ]; then + +# python + +PYTHON="python" +if [ "$HOST_OS" = "Win" ]; then + if ! _detect_cmd $PYTHON; then + PYTHON="python2" # try python2 on MSYS + fi +fi + +_detect $PYTHON 1 + +PYTHON_FOUND="${PYTHON}_FOUND" +if [ -z "${!PYTHON_FOUND}" ]; then + _echo_en "$PYTHON not found" +fi + +# pip + +# detect pip +if ! _detect_cmd pip; then + if [ -n "${!PYTHON_FOUND}" ]; then + _echo_sn "Install pip" + [ -f "get-pip.py" ] || curl -O https://bootstrap.pypa.io/get-pip.py + $SUDO $PYTHON get-pip.py + else + _echo_en "Skipped install pip, as $PYTHON not found" + fi +fi +# pip install +if _detect_cmd pip; then + _echo_d "pip install --upgrade autopep8 cpplint pylint requests" + $SUDO pip install --upgrade autopep8 cpplint pylint requests +else + _echo_en "Skipped pip install packages, as pip not found" +fi + +# realpath + +# detect realpath +if ! _detect_cmd realpath; then + _echo_sn "Install realpath" + if [ "$HOST_OS" = "Linux" ]; then + # How to install realpath on Ubuntu 14.04 + # https://www.howtoinstall.co/en/ubuntu/trusty/realpath + $SUDO apt-get install coreutils realpath + elif [ "$HOST_OS" = "Mac" ]; then + brew install coreutils + elif [ "$HOST_OS" = "Win" ]; then + pacman -S coreutils + else # unexpected + _echo_e "Unknown host os :(" + exit 1 + fi +fi + +ROOT_DIR=$(realpath "$BASE_DIR/..") + +# init git hooks + +if [ -n "${!PYTHON_FOUND}" ]; then + _echo_s "Init git hooks" + $PYTHON "$ROOT_DIR/tools/linter/init-git-hooks.py" +else + _echo_en "Skipped init git hooks, as $PYTHON not found" +fi + +fi # _INIT_LINTER_ From 30a9397602d709fa458d7d9101f784aee560b776 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 4 Sep 2018 14:35:27 +0800 Subject: [PATCH 15/77] Add glog option --- CMakeLists.txt | 26 +++++++++---------- Makefile | 11 +++++--- cmake/DetectGLog.cmake | 26 +++++++++++++++++++ cmake/Option.cmake | 17 ++++++++++++ mynteye-config.cmake.in | 3 +++ samples/CMakeLists.txt | 4 --- test/CMakeLists.txt | 8 +++--- tools/CMakeLists.txt | 8 +++--- wrappers/python/CMakeLists.txt | 4 --- .../src/mynt_eye_ros_wrapper/CMakeLists.txt | 13 +++++----- 10 files changed, 79 insertions(+), 41 deletions(-) create mode 100644 cmake/DetectGLog.cmake diff --git a/CMakeLists.txt b/CMakeLists.txt index 62c59a4..1da872b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -44,10 +44,6 @@ message(STATUS "CXX_FLAGS: ${CMAKE_CXX_FLAGS}") # packages -LIST(APPEND CMAKE_PREFIX_PATH third_party/glog/_build) -find_package(glog REQUIRED) -message(STATUS "Found glog: ${glog_VERSION}") - LIST(APPEND CMAKE_MODULE_PATH cmake) include(CMakePackageConfigHelpers) @@ -90,12 +86,14 @@ set(MYNTEYE_CMAKE_INSTALLDIR "${MYNTEYE_CMAKE_LIBDIR}/cmake/${MYNTEYE_NAME}") ## main -add_executable(main src/main.cc) -target_link_libraries(main glog::glog) -target_include_directories(main PRIVATE - ${CMAKE_CURRENT_SOURCE_DIR}/include - ${CMAKE_CURRENT_BINARY_DIR}/include -) +if(WITH_GLOG) + add_executable(main src/main.cc) + target_link_libraries(main glog::glog) + target_include_directories(main PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR}/include + ${CMAKE_CURRENT_BINARY_DIR}/include + ) +endif() ## libmynteye @@ -164,16 +162,16 @@ if(WITH_API) ) endif() -set(MYNTEYE_LINKLIBS - glog::glog - ${UVC_LIB} -) +set(MYNTEYE_LINKLIBS ${UVC_LIB}) if(WITH_API) list(APPEND MYNTEYE_LINKLIBS ${OpenCV_LIBS}) endif() if(WITH_BOOST_FILESYSTEM) list(APPEND MYNTEYE_LINKLIBS ${Boost_LIBRARIES}) endif() +if(WITH_GLOG) + list(APPEND MYNTEYE_LINKLIBS glog::glog) +endif() #message(STATUS "MYNTEYE_LINKLIBS: ${MYNTEYE_LINKLIBS}") add_library(${MYNTEYE_NAME} SHARED ${MYNTEYE_SRCS}) diff --git a/Makefile b/Makefile index e8555fd..5483d78 100644 --- a/Makefile +++ b/Makefile @@ -30,9 +30,10 @@ help: @echo " make apidoc make api doc" @echo " make opendoc open api doc (html)" @echo " make init init project" + @echo " make 3rdparty build 3rdparty: glog" @echo " make build build project" - @echo " make test build test and run" @echo " make install install project" + @echo " make test build test and run" @echo " make samples build samples" @echo " make tools build tools" @echo " make ros build ros wrapper" @@ -41,7 +42,7 @@ help: .PHONY: help -all: test tools samples +all: test samples tools .PHONY: all @@ -75,7 +76,9 @@ third_party: submodules @$(call echo,Make glog,33) @$(call cmake_build,./third_party/glog/_build) -.PHONY: submodules third_party +3rdparty: third_party + +.PHONY: submodules third_party 3rdparty # init @@ -87,7 +90,7 @@ init: submodules # build -build: third_party +build: submodules @$(call echo,Make $@) ifeq ($(HOST_OS),Win) @$(call cmake_build,./_build,..,-DCMAKE_INSTALL_PREFIX=$(MKFILE_DIR)/_install) diff --git a/cmake/DetectGLog.cmake b/cmake/DetectGLog.cmake new file mode 100644 index 0000000..daf42d7 --- /dev/null +++ b/cmake/DetectGLog.cmake @@ -0,0 +1,26 @@ +# 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(${CMAKE_CURRENT_LIST_DIR}/IncludeGuard.cmake) +cmake_include_guard() + +get_filename_component(__pro_dir ${CMAKE_CURRENT_LIST_DIR} DIRECTORY) +LIST(APPEND CMAKE_PREFIX_PATH ${__pro_dir}/third_party/glog/_build) + +find_package(glog REQUIRED) +if(glog_FOUND) + add_definitions(-DWITH_GLOG) +endif() + +unset(__pro_dir) diff --git a/cmake/Option.cmake b/cmake/Option.cmake index f649391..8a414fd 100644 --- a/cmake/Option.cmake +++ b/cmake/Option.cmake @@ -28,6 +28,9 @@ option(WITH_DEVICE_INFO_REQUIRED "Build with device info required" ON) option(WITH_BOOST "Include Boost support" ON) +# `make 3rdparty` could build glog submodule +option(WITH_GLOG "Include glog support" ON) + # packages @@ -59,6 +62,10 @@ if(NOT WITH_FILESYSTEM) endif() endif() +if(WITH_GLOG) + include(${CMAKE_CURRENT_LIST_DIR}/DetectGLog.cmake) +endif() + find_package(CUDA QUIET) # summary @@ -125,6 +132,16 @@ if(WITH_BOOST) endif() endif() +status(" WITH_GLOG: ${WITH_GLOG}") +if(WITH_GLOG) + if(glog_FOUND) + status(" glog: YES") + status(" glog_VERSION: ${glog_VERSION}") + else() + status(" glog: NO") + endif() +endif() + status("") status("Features:") status(" Filesystem: " diff --git a/mynteye-config.cmake.in b/mynteye-config.cmake.in index aaeb16a..3514b78 100644 --- a/mynteye-config.cmake.in +++ b/mynteye-config.cmake.in @@ -14,4 +14,7 @@ @PACKAGE_INIT@ +set(mynteye_WITH_API @WITH_API@) +set(mynteye_WITH_GLOG @WITH_GLOG@) + include("${CMAKE_CURRENT_LIST_DIR}/mynteye-targets.cmake") diff --git a/samples/CMakeLists.txt b/samples/CMakeLists.txt index 2a0c4c6..4781867 100644 --- a/samples/CMakeLists.txt +++ b/samples/CMakeLists.txt @@ -47,10 +47,6 @@ message(STATUS "CXX_FLAGS: ${CMAKE_CXX_FLAGS}") # packages -LIST(APPEND CMAKE_PREFIX_PATH ${PRO_DIR}/third_party/glog/_build) -find_package(glog REQUIRED) -message(STATUS "Found glog: ${glog_VERSION}") - LIST(APPEND CMAKE_PREFIX_PATH ${PRO_DIR}/_install/lib/cmake) find_package(mynteye REQUIRED) message(STATUS "Found mynteye: ${mynteye_VERSION}") diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 11c68cd..18be45b 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -57,16 +57,16 @@ message(STATUS "CXX_FLAGS: ${CMAKE_CXX_FLAGS}") # packages -LIST(APPEND CMAKE_PREFIX_PATH ${PRO_DIR}/third_party/glog/_build) -find_package(glog REQUIRED) -message(STATUS "Found glog: ${glog_VERSION}") - LIST(APPEND CMAKE_PREFIX_PATH ${PRO_DIR}/_install/lib/cmake) find_package(mynteye REQUIRED) 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) ## gtest diff --git a/tools/CMakeLists.txt b/tools/CMakeLists.txt index a617541..4d57c04 100644 --- a/tools/CMakeLists.txt +++ b/tools/CMakeLists.txt @@ -43,16 +43,16 @@ message(STATUS "CXX_FLAGS: ${CMAKE_CXX_FLAGS}") # packages -LIST(APPEND CMAKE_PREFIX_PATH ${PRO_DIR}/third_party/glog/_build) -find_package(glog REQUIRED) -message(STATUS "Found glog: ${glog_VERSION}") - LIST(APPEND CMAKE_PREFIX_PATH ${PRO_DIR}/_install/lib/cmake) find_package(mynteye REQUIRED) 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/wrappers/python/CMakeLists.txt b/wrappers/python/CMakeLists.txt index 4cecbff..384407d 100644 --- a/wrappers/python/CMakeLists.txt +++ b/wrappers/python/CMakeLists.txt @@ -77,10 +77,6 @@ message(STATUS "CXX_FLAGS: ${CMAKE_CXX_FLAGS}") # packages -LIST(APPEND CMAKE_PREFIX_PATH ${PRO_DIR}/third_party/glog/_build) -find_package(glog REQUIRED) -message(STATUS "Found glog: ${glog_VERSION}") - LIST(APPEND CMAKE_PREFIX_PATH ${PRO_DIR}/_install/lib/cmake) find_package(mynteye REQUIRED) message(STATUS "Found mynteye: ${mynteye_VERSION}") diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/CMakeLists.txt b/wrappers/ros/src/mynt_eye_ros_wrapper/CMakeLists.txt index 83ffce1..74a36d1 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/CMakeLists.txt +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/CMakeLists.txt @@ -56,9 +56,6 @@ checkPackage("sensor_msgs" "") checkPackage("std_msgs" "") checkPackage("tf" "") -find_package(OpenCV REQUIRED) -message(STATUS "Found OpenCV: ${OpenCV_VERSION}") - ## messages add_message_files( @@ -82,14 +79,16 @@ catkin_package( get_filename_component(SDK_DIR "${PROJECT_SOURCE_DIR}/../../../.." ABSOLUTE) -LIST(APPEND CMAKE_PREFIX_PATH ${SDK_DIR}/third_party/glog/_build) -find_package(glog REQUIRED) -message(STATUS "Found glog: ${glog_VERSION}") - LIST(APPEND CMAKE_PREFIX_PATH ${SDK_DIR}/_install/lib/cmake) find_package(mynteye REQUIRED) message(STATUS "Found mynteye: ${mynteye_VERSION}") +include(${SDK_DIR}/cmake/DetectOpenCV.cmake) + +if(mynteye_WITH_GLOG) + include(${SDK_DIR}/cmake/DetectGLog.cmake) +endif() + # targets add_compile_options(-std=c++11) From 4d5ff16f828a598f461f65d803e1f1ce23656fe4 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 4 Sep 2018 15:12:04 +0800 Subject: [PATCH 16/77] Change log header --- CMakeLists.txt | 2 +- doc/zh-Hans/guide_log.md | 4 ++-- include/mynteye/{glog_init.h => logger.h} | 6 +++--- samples/api/camera.cc | 2 +- samples/api/get_depth_with_region.cc | 2 -- samples/device/camera.cc | 2 +- samples/tutorials/control/auto_exposure.cc | 3 +-- samples/tutorials/control/framerate.cc | 3 +-- samples/tutorials/control/infrared.cc | 3 +-- samples/tutorials/control/manual_exposure.cc | 3 +-- samples/tutorials/data/get_depth.cc | 2 -- samples/tutorials/data/get_device_info.cc | 3 +-- samples/tutorials/data/get_disparity.cc | 2 -- samples/tutorials/data/get_from_callbacks.cc | 3 +-- samples/tutorials/data/get_img_params.cc | 3 +-- samples/tutorials/data/get_imu.cc | 3 +-- samples/tutorials/data/get_imu_params.cc | 3 +-- samples/tutorials/data/get_points.cc | 2 -- samples/tutorials/data/get_stereo.cc | 2 -- samples/tutorials/data/get_stereo_rectified.cc | 2 -- samples/tutorials/data/get_with_plugin.cc | 2 -- samples/tutorials/intermediate/get_all_device_info.cc | 2 +- samples/tutorials/intermediate/get_depth_and_points.cc | 2 -- samples/tutorials/util/cv_painter.cc | 3 +-- samples/tutorials/util/pc_viewer.cc | 4 ++-- samples/uvc/camera.cc | 2 +- src/api/api.cc | 4 +--- src/api/processor/depth_processor.cc | 2 +- src/api/processor/disparity_normalized_processor.cc | 4 ++-- src/api/processor/disparity_processor.cc | 4 ++-- src/api/processor/points_processor.cc | 4 ++-- src/api/processor/processor.cc | 4 ++-- src/api/processor/rectify_processor.cc | 4 ++-- src/api/synthetic.cc | 4 ++-- src/device/context.cc | 2 +- src/device/device.cc | 4 ++-- src/device/device_s.cc | 2 +- src/internal/async_callback_impl.h | 4 ++-- src/internal/channels.cc | 4 ++-- src/internal/dl.cc | 2 +- src/internal/files.cc | 2 +- src/internal/motions.cc | 2 +- src/internal/streams.cc | 4 ++-- src/internal/types.cc | 4 ++-- src/public/types.cc | 4 ++-- src/public/utils.cc | 2 +- src/uvc/uvc-libuvc.cc | 3 ++- src/uvc/uvc-v4l2.cc | 4 ++-- src/uvc/uvc-wmf.cc | 2 +- test/gtest_main.cc | 2 +- tools/dataset/dataset.cc | 3 +-- tools/dataset/record.cc | 2 +- tools/writer/device_info_writer.cc | 2 +- tools/writer/device_writer.cc | 3 +-- tools/writer/img_params_writer.cc | 2 +- tools/writer/imu_params_writer.cc | 2 +- tools/writer/save_all_infos.cc | 2 +- wrappers/python/src/mynteye_py.cc | 4 ++-- wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_node.cc | 2 +- .../ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc | 3 +-- 60 files changed, 71 insertions(+), 101 deletions(-) rename include/mynteye/{glog_init.h => logger.h} (94%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1da872b..dbb634d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -100,7 +100,7 @@ endif() set(MYNTEYE_PUBLIC_H ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/callbacks.h ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/global.h - ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/glog_init.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/logger.h ${CMAKE_CURRENT_BINARY_DIR}/include/mynteye/mynteye.h ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/types.h ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/utils.h diff --git a/doc/zh-Hans/guide_log.md b/doc/zh-Hans/guide_log.md index ef16629..7863260 100644 --- a/doc/zh-Hans/guide_log.md +++ b/doc/zh-Hans/guide_log.md @@ -1,6 +1,6 @@ # 日志 {#guide_log} -日志系统用的 `glog` ,通用配置在头文件 `glog_init.h` 里。 +日志系统用的 `glog` ,通用配置在头文件 `logger.h` 里。 * 日志文件会存储在当前工作目录, `make cleanlog` 可以清理。 -* 如果需要打开详细日志,请取消 `glog_init.h` 里注释的 `FLAGS_v = 2;` ,重新编译。 +* 如果需要打开详细日志,请取消 `logger.h` 里注释的 `FLAGS_v = 2;` ,重新编译。 diff --git a/include/mynteye/glog_init.h b/include/mynteye/logger.h similarity index 94% rename from include/mynteye/glog_init.h rename to include/mynteye/logger.h index e2ac989..a3f24d2 100644 --- a/include/mynteye/glog_init.h +++ b/include/mynteye/logger.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_GLOG_INIT_H_ // NOLINT -#define MYNTEYE_GLOG_INIT_H_ +#ifndef MYNTEYE_LOGGER_H_ +#define MYNTEYE_LOGGER_H_ #pragma once #include @@ -62,4 +62,4 @@ struct glog_init { } }; -#endif // MYNTEYE_GLOG_INIT_H_ NOLINT +#endif // MYNTEYE_LOGGER_H_ diff --git a/samples/api/camera.cc b/samples/api/camera.cc index 5cddd85..1159d2d 100644 --- a/samples/api/camera.cc +++ b/samples/api/camera.cc @@ -13,7 +13,7 @@ // limitations under the License. #include -#include +#include "mynteye/logger.h" #include "mynteye/api.h" #include "mynteye/times.h" diff --git a/samples/api/get_depth_with_region.cc b/samples/api/get_depth_with_region.cc index 0bd075c..5a1091b 100644 --- a/samples/api/get_depth_with_region.cc +++ b/samples/api/get_depth_with_region.cc @@ -14,8 +14,6 @@ #include #include -#include - #include "mynteye/api.h" namespace { diff --git a/samples/device/camera.cc b/samples/device/camera.cc index bcd9695..00b1f0d 100644 --- a/samples/device/camera.cc +++ b/samples/device/camera.cc @@ -14,7 +14,7 @@ #include #include -#include "mynteye/glog_init.h" +#include "mynteye/logger.h" #include "mynteye/device.h" #include "mynteye/utils.h" diff --git a/samples/tutorials/control/auto_exposure.cc b/samples/tutorials/control/auto_exposure.cc index efe77e6..b1bacc1 100644 --- a/samples/tutorials/control/auto_exposure.cc +++ b/samples/tutorials/control/auto_exposure.cc @@ -13,9 +13,8 @@ // limitations under the License. #include -#include - #include "mynteye/api.h" +#include "mynteye/logger.h" #include "util/cv_painter.h" diff --git a/samples/tutorials/control/framerate.cc b/samples/tutorials/control/framerate.cc index 1d05755..6a16a19 100644 --- a/samples/tutorials/control/framerate.cc +++ b/samples/tutorials/control/framerate.cc @@ -13,11 +13,10 @@ // limitations under the License. #include -#include - #include #include "mynteye/api.h" +#include "mynteye/logger.h" #include "mynteye/times.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/control/infrared.cc b/samples/tutorials/control/infrared.cc index 7ed6286..2a7ccd2 100644 --- a/samples/tutorials/control/infrared.cc +++ b/samples/tutorials/control/infrared.cc @@ -13,9 +13,8 @@ // limitations under the License. #include -#include - #include "mynteye/api.h" +#include "mynteye/logger.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/control/manual_exposure.cc b/samples/tutorials/control/manual_exposure.cc index 38afa32..386188b 100644 --- a/samples/tutorials/control/manual_exposure.cc +++ b/samples/tutorials/control/manual_exposure.cc @@ -13,9 +13,8 @@ // limitations under the License. #include -#include - #include "mynteye/api.h" +#include "mynteye/logger.h" #include "util/cv_painter.h" diff --git a/samples/tutorials/data/get_depth.cc b/samples/tutorials/data/get_depth.cc index 274c8ee..28ef244 100644 --- a/samples/tutorials/data/get_depth.cc +++ b/samples/tutorials/data/get_depth.cc @@ -13,8 +13,6 @@ // limitations under the License. #include -#include - #include "mynteye/api.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/data/get_device_info.cc b/samples/tutorials/data/get_device_info.cc index ee41348..d188fc6 100644 --- a/samples/tutorials/data/get_device_info.cc +++ b/samples/tutorials/data/get_device_info.cc @@ -11,9 +11,8 @@ // 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/api.h" +#include "mynteye/logger.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/data/get_disparity.cc b/samples/tutorials/data/get_disparity.cc index 5a9f798..aa02e42 100644 --- a/samples/tutorials/data/get_disparity.cc +++ b/samples/tutorials/data/get_disparity.cc @@ -13,8 +13,6 @@ // limitations under the License. #include -#include - #include "mynteye/api.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/data/get_from_callbacks.cc b/samples/tutorials/data/get_from_callbacks.cc index cb51875..d38b7ae 100644 --- a/samples/tutorials/data/get_from_callbacks.cc +++ b/samples/tutorials/data/get_from_callbacks.cc @@ -13,14 +13,13 @@ // limitations under the License. #include -#include - #include #include #include #include #include "mynteye/api.h" +#include "mynteye/logger.h" #include "util/cv_painter.h" diff --git a/samples/tutorials/data/get_img_params.cc b/samples/tutorials/data/get_img_params.cc index 5636120..7cfac2e 100644 --- a/samples/tutorials/data/get_img_params.cc +++ b/samples/tutorials/data/get_img_params.cc @@ -11,9 +11,8 @@ // 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/api.h" +#include "mynteye/logger.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/data/get_imu.cc b/samples/tutorials/data/get_imu.cc index 6ed0552..5cda4a4 100644 --- a/samples/tutorials/data/get_imu.cc +++ b/samples/tutorials/data/get_imu.cc @@ -13,9 +13,8 @@ // limitations under the License. #include -#include - #include "mynteye/api.h" +#include "mynteye/logger.h" #include "util/cv_painter.h" diff --git a/samples/tutorials/data/get_imu_params.cc b/samples/tutorials/data/get_imu_params.cc index ddcfd49..1a307f8 100644 --- a/samples/tutorials/data/get_imu_params.cc +++ b/samples/tutorials/data/get_imu_params.cc @@ -11,9 +11,8 @@ // 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/api.h" +#include "mynteye/logger.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/data/get_points.cc b/samples/tutorials/data/get_points.cc index 828418d..66f3341 100644 --- a/samples/tutorials/data/get_points.cc +++ b/samples/tutorials/data/get_points.cc @@ -13,8 +13,6 @@ // limitations under the License. #include -#include - #include "mynteye/api.h" #include "util/pc_viewer.h" diff --git a/samples/tutorials/data/get_stereo.cc b/samples/tutorials/data/get_stereo.cc index a82a9e9..7899765 100644 --- a/samples/tutorials/data/get_stereo.cc +++ b/samples/tutorials/data/get_stereo.cc @@ -13,8 +13,6 @@ // limitations under the License. #include -#include - #include "mynteye/api.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/data/get_stereo_rectified.cc b/samples/tutorials/data/get_stereo_rectified.cc index 04c4eae..ea1a8b5 100644 --- a/samples/tutorials/data/get_stereo_rectified.cc +++ b/samples/tutorials/data/get_stereo_rectified.cc @@ -13,8 +13,6 @@ // limitations under the License. #include -#include - #include "mynteye/api.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/data/get_with_plugin.cc b/samples/tutorials/data/get_with_plugin.cc index a2201ba..dbaa574 100644 --- a/samples/tutorials/data/get_with_plugin.cc +++ b/samples/tutorials/data/get_with_plugin.cc @@ -13,8 +13,6 @@ // limitations under the License. #include -#include - #include "mynteye/api.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/intermediate/get_all_device_info.cc b/samples/tutorials/intermediate/get_all_device_info.cc index b113c27..ec07c3a 100644 --- a/samples/tutorials/intermediate/get_all_device_info.cc +++ b/samples/tutorials/intermediate/get_all_device_info.cc @@ -13,7 +13,7 @@ // limitations under the License. #include "mynteye/context.h" #include "mynteye/device.h" -#include "mynteye/glog_init.h" +#include "mynteye/logger.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/intermediate/get_depth_and_points.cc b/samples/tutorials/intermediate/get_depth_and_points.cc index c137954..03391f5 100644 --- a/samples/tutorials/intermediate/get_depth_and_points.cc +++ b/samples/tutorials/intermediate/get_depth_and_points.cc @@ -14,8 +14,6 @@ #include #include -#include - #include "mynteye/api.h" #include "util/cv_painter.h" diff --git a/samples/tutorials/util/cv_painter.cc b/samples/tutorials/util/cv_painter.cc index c0c6f6a..eaa7d8a 100644 --- a/samples/tutorials/util/cv_painter.cc +++ b/samples/tutorials/util/cv_painter.cc @@ -13,8 +13,6 @@ // limitations under the License. #include "util/cv_painter.h" -#include - #include #include @@ -22,6 +20,7 @@ #include #include +#include "mynteye/logger.h" #include "mynteye/utils.h" #define FONT_FACE cv::FONT_HERSHEY_PLAIN diff --git a/samples/tutorials/util/pc_viewer.cc b/samples/tutorials/util/pc_viewer.cc index 2fb7394..bec96dc 100644 --- a/samples/tutorials/util/pc_viewer.cc +++ b/samples/tutorials/util/pc_viewer.cc @@ -13,12 +13,12 @@ // limitations under the License. #include "util/pc_viewer.h" -#include - // #include #include +#include "mynteye/logger.h" + std::shared_ptr CustomColorVis( pcl::PointCloud::ConstPtr pc) { // -------------------------------------------- diff --git a/samples/uvc/camera.cc b/samples/uvc/camera.cc index ac20e03..4b36b44 100644 --- a/samples/uvc/camera.cc +++ b/samples/uvc/camera.cc @@ -20,7 +20,7 @@ #include #include -#include "mynteye/glog_init.h" +#include "mynteye/logger.h" #include "mynteye/mynteye.h" #include "mynteye/types.h" #include "uvc/uvc.h" diff --git a/src/api/api.cc b/src/api/api.cc index ddf443a..8fb98bb 100644 --- a/src/api/api.cc +++ b/src/api/api.cc @@ -18,12 +18,10 @@ #include #endif -#include - #include #include -#include "mynteye/glog_init.h" +#include "mynteye/logger.h" #include "mynteye/utils.h" #include "api/plugin.h" diff --git a/src/api/processor/depth_processor.cc b/src/api/processor/depth_processor.cc index 73769de..433e47d 100644 --- a/src/api/processor/depth_processor.cc +++ b/src/api/processor/depth_processor.cc @@ -13,7 +13,7 @@ // limitations under the License. #include "api/processor/depth_processor.h" -#include +#include "mynteye/logger.h" #include diff --git a/src/api/processor/disparity_normalized_processor.cc b/src/api/processor/disparity_normalized_processor.cc index 0ce2a9a..6c24c6b 100644 --- a/src/api/processor/disparity_normalized_processor.cc +++ b/src/api/processor/disparity_normalized_processor.cc @@ -15,10 +15,10 @@ #include -#include - #include +#include "mynteye/logger.h" + MYNTEYE_BEGIN_NAMESPACE const char DisparityNormalizedProcessor::NAME[] = diff --git a/src/api/processor/disparity_processor.cc b/src/api/processor/disparity_processor.cc index dbb5ab3..041e246 100644 --- a/src/api/processor/disparity_processor.cc +++ b/src/api/processor/disparity_processor.cc @@ -15,10 +15,10 @@ #include -#include - #include +#include "mynteye/logger.h" + MYNTEYE_BEGIN_NAMESPACE const char DisparityProcessor::NAME[] = "DisparityProcessor"; diff --git a/src/api/processor/points_processor.cc b/src/api/processor/points_processor.cc index 0d594b1..02a70b2 100644 --- a/src/api/processor/points_processor.cc +++ b/src/api/processor/points_processor.cc @@ -15,10 +15,10 @@ #include -#include - #include +#include "mynteye/logger.h" + MYNTEYE_BEGIN_NAMESPACE const char PointsProcessor::NAME[] = "PointsProcessor"; diff --git a/src/api/processor/processor.cc b/src/api/processor/processor.cc index 8ba3bca..c0d45ab 100644 --- a/src/api/processor/processor.cc +++ b/src/api/processor/processor.cc @@ -13,11 +13,11 @@ // limitations under the License. #include "api/processor/processor.h" -#include - #include #include +#include "mynteye/logger.h" + #include "internal/strings.h" #include "internal/times.h" diff --git a/src/api/processor/rectify_processor.cc b/src/api/processor/rectify_processor.cc index 31ce62c..9a45b0f 100644 --- a/src/api/processor/rectify_processor.cc +++ b/src/api/processor/rectify_processor.cc @@ -16,10 +16,10 @@ #include #include -#include - #include +#include "mynteye/logger.h" + #include "device/device.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/api/synthetic.cc b/src/api/synthetic.cc index 3c5a194..a1a3730 100644 --- a/src/api/synthetic.cc +++ b/src/api/synthetic.cc @@ -13,12 +13,12 @@ // limitations under the License. #include "api/synthetic.h" -#include - #include #include #include +#include "mynteye/logger.h" + #include "api/plugin.h" #include "api/processor/depth_processor.h" #include "api/processor/disparity_normalized_processor.h" diff --git a/src/device/context.cc b/src/device/context.cc index e5c82c7..ef4f1ef 100644 --- a/src/device/context.cc +++ b/src/device/context.cc @@ -13,7 +13,7 @@ // limitations under the License. #include "device/context.h" -#include +#include "mynteye/logger.h" #include "device/device.h" #include "uvc/uvc.h" diff --git a/src/device/device.cc b/src/device/device.cc index cc4d2b8..2d16d9d 100644 --- a/src/device/device.cc +++ b/src/device/device.cc @@ -13,13 +13,13 @@ // limitations under the License. #include "device/device.h" -#include - #include #include #include #include +#include "mynteye/logger.h" + #include "device/device_s.h" #include "internal/async_callback.h" #include "internal/channels.h" diff --git a/src/device/device_s.cc b/src/device/device_s.cc index fdffe93..377453d 100644 --- a/src/device/device_s.cc +++ b/src/device/device_s.cc @@ -13,7 +13,7 @@ // limitations under the License. #include "device/device_s.h" -#include +#include "mynteye/logger.h" #include "internal/motions.h" diff --git a/src/internal/async_callback_impl.h b/src/internal/async_callback_impl.h index 3c502b3..cfffc0d 100644 --- a/src/internal/async_callback_impl.h +++ b/src/internal/async_callback_impl.h @@ -15,11 +15,11 @@ #define MYNTEYE_INTERNAL_ASYNC_CALLBACK_IMPL_H_ #pragma once -#include - #include #include +#include "mynteye/logger.h" + MYNTEYE_BEGIN_NAMESPACE template diff --git a/src/internal/channels.cc b/src/internal/channels.cc index e8eb253..679fe61 100644 --- a/src/internal/channels.cc +++ b/src/internal/channels.cc @@ -13,8 +13,6 @@ // limitations under the License. #include "internal/channels.h" -#include - #include #include #include @@ -22,6 +20,8 @@ #include #include +#include "mynteye/logger.h" + #include "internal/strings.h" #include "internal/times.h" diff --git a/src/internal/dl.cc b/src/internal/dl.cc index 8ba22b7..2de8150 100644 --- a/src/internal/dl.cc +++ b/src/internal/dl.cc @@ -13,7 +13,7 @@ // limitations under the License. #include "internal/dl.h" -#include +#include "mynteye/logger.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/internal/files.cc b/src/internal/files.cc index 7d54020..556d5c9 100644 --- a/src/internal/files.cc +++ b/src/internal/files.cc @@ -13,7 +13,7 @@ // limitations under the License. #include "internal/files.h" -#include +#include "mynteye/logger.h" #if defined(OS_WIN) && !defined(OS_MINGW) && !defined(OS_CYGWIN) #include diff --git a/src/internal/motions.cc b/src/internal/motions.cc index 7183c6a..27d3c67 100644 --- a/src/internal/motions.cc +++ b/src/internal/motions.cc @@ -13,7 +13,7 @@ // limitations under the License. #include "internal/motions.h" -#include +#include "mynteye/logger.h" #include "internal/channels.h" diff --git a/src/internal/streams.cc b/src/internal/streams.cc index 97ae970..1f9fe64 100644 --- a/src/internal/streams.cc +++ b/src/internal/streams.cc @@ -13,13 +13,13 @@ // limitations under the License. #include "internal/streams.h" -#include - #include #include #include #include +#include "mynteye/logger.h" + #include "internal/types.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/internal/types.cc b/src/internal/types.cc index c53ff0d..2f05409 100644 --- a/src/internal/types.cc +++ b/src/internal/types.cc @@ -13,12 +13,12 @@ // limitations under the License. #include "internal/types.h" -#include - #include #include #include +#include "mynteye/logger.h" + MYNTEYE_BEGIN_NAMESPACE std::string Version::to_string() const { diff --git a/src/public/types.cc b/src/public/types.cc index 296c8a4..d8b99da 100644 --- a/src/public/types.cc +++ b/src/public/types.cc @@ -13,11 +13,11 @@ // limitations under the License. #include "mynteye/types.h" -#include - #include #include +#include "mynteye/logger.h" + #define FULL_PRECISION \ std::fixed << std::setprecision(std::numeric_limits::max_digits10) diff --git a/src/public/utils.cc b/src/public/utils.cc index 4fc9202..36ba8ff 100644 --- a/src/public/utils.cc +++ b/src/public/utils.cc @@ -13,7 +13,7 @@ // limitations under the License. #include "mynteye/utils.h" -#include +#include "mynteye/logger.h" #include "device/context.h" #include "device/device.h" diff --git a/src/uvc/uvc-libuvc.cc b/src/uvc/uvc-libuvc.cc index 1b260d7..f2a9b92 100644 --- a/src/uvc/uvc-libuvc.cc +++ b/src/uvc/uvc-libuvc.cc @@ -13,9 +13,10 @@ // limitations under the License. #include "uvc/uvc.h" // NOLINT -#include #include +#include "mynteye/logger.h" + // #define ENABLE_DEBUG_SPAM MYNTEYE_BEGIN_NAMESPACE diff --git a/src/uvc/uvc-v4l2.cc b/src/uvc/uvc-v4l2.cc index 06fc8fc..d99a85b 100755 --- a/src/uvc/uvc-v4l2.cc +++ b/src/uvc/uvc-v4l2.cc @@ -25,13 +25,13 @@ #include #include -#include - #include #include #include #include +#include "mynteye/logger.h" + MYNTEYE_BEGIN_NAMESPACE namespace uvc { diff --git a/src/uvc/uvc-wmf.cc b/src/uvc/uvc-wmf.cc index 13f7f36..8e8d9c3 100644 --- a/src/uvc/uvc-wmf.cc +++ b/src/uvc/uvc-wmf.cc @@ -53,7 +53,7 @@ #include -#include +#include "mynteye/logger.h" #define VLOG_INFO VLOG(2) // #define VLOG_INFO LOG(INFO) diff --git a/test/gtest_main.cc b/test/gtest_main.cc index a0e1685..edca54b 100644 --- a/test/gtest_main.cc +++ b/test/gtest_main.cc @@ -15,7 +15,7 @@ #include "gtest/gtest.h" -#include "mynteye/glog_init.h" +#include "mynteye/logger.h" int main(int argc, char **argv) { glog_init _(argc, argv); diff --git a/tools/dataset/dataset.cc b/tools/dataset/dataset.cc index d156c37..165473f 100644 --- a/tools/dataset/dataset.cc +++ b/tools/dataset/dataset.cc @@ -19,14 +19,13 @@ #include #endif -#include - #include #include #include #include #include "mynteye/files.h" +#include "mynteye/logger.h" #define FULL_PRECISION \ std::fixed << std::setprecision(std::numeric_limits::max_digits10) diff --git a/tools/dataset/record.cc b/tools/dataset/record.cc index e3de362..dedf851 100644 --- a/tools/dataset/record.cc +++ b/tools/dataset/record.cc @@ -14,7 +14,7 @@ #include #include -#include "mynteye/glog_init.h" +#include "mynteye/logger.h" #include "mynteye/device.h" #include "mynteye/utils.h" diff --git a/tools/writer/device_info_writer.cc b/tools/writer/device_info_writer.cc index 1625b7a..6619a55 100644 --- a/tools/writer/device_info_writer.cc +++ b/tools/writer/device_info_writer.cc @@ -11,7 +11,7 @@ // 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 "mynteye/glog_init.h" +#include "mynteye/logger.h" #include "mynteye/device.h" #include "mynteye/utils.h" diff --git a/tools/writer/device_writer.cc b/tools/writer/device_writer.cc index 05a4e46..4a61001 100644 --- a/tools/writer/device_writer.cc +++ b/tools/writer/device_writer.cc @@ -15,12 +15,11 @@ #include -#include - #include #include "mynteye/device.h" #include "mynteye/files.h" +#include "mynteye/logger.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/tools/writer/img_params_writer.cc b/tools/writer/img_params_writer.cc index 77647a5..02950e9 100644 --- a/tools/writer/img_params_writer.cc +++ b/tools/writer/img_params_writer.cc @@ -11,7 +11,7 @@ // 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 "mynteye/glog_init.h" +#include "mynteye/logger.h" #include "mynteye/device.h" #include "mynteye/utils.h" diff --git a/tools/writer/imu_params_writer.cc b/tools/writer/imu_params_writer.cc index 9f2034b..a60c3fe 100644 --- a/tools/writer/imu_params_writer.cc +++ b/tools/writer/imu_params_writer.cc @@ -11,7 +11,7 @@ // 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 "mynteye/glog_init.h" +#include "mynteye/logger.h" #include "mynteye/device.h" #include "mynteye/utils.h" diff --git a/tools/writer/save_all_infos.cc b/tools/writer/save_all_infos.cc index a4ff051..c67b5d4 100644 --- a/tools/writer/save_all_infos.cc +++ b/tools/writer/save_all_infos.cc @@ -11,7 +11,7 @@ // 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 "mynteye/glog_init.h" +#include "mynteye/logger.h" #include "mynteye/device.h" #include "mynteye/utils.h" diff --git a/wrappers/python/src/mynteye_py.cc b/wrappers/python/src/mynteye_py.cc index 8107f55..ad7fbe9 100644 --- a/wrappers/python/src/mynteye_py.cc +++ b/wrappers/python/src/mynteye_py.cc @@ -26,7 +26,7 @@ #include #include "mynteye/api.h" -#include "mynteye/glog_init.h" +#include "mynteye/logger.h" #include "mynteye/utils.h" #include "array_indexing_suite.hpp" @@ -451,7 +451,7 @@ BOOST_PYTHON_MODULE(mynteye_py) { bp::register_ptr_to_python>(); - // glog_init.h - glog_init + // logger.h - glog_init bp::class_("glog_init", bp::no_init) .def("create", &glog_init_create) diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_node.cc b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_node.cc index 5a03045..6e12566 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_node.cc +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_node.cc @@ -14,7 +14,7 @@ #include #include -#include "mynteye/glog_init.h" +#include "mynteye/logger.h" int main(int argc, char *argv[]) { glog_init _(argc, argv); diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc index fccda6d..5e6e2de 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc @@ -28,8 +28,6 @@ #include #include -#include - #define _USE_MATH_DEFINES #include #include @@ -38,6 +36,7 @@ #include "mynteye/api.h" #include "mynteye/context.h" #include "mynteye/device.h" +#include "mynteye/logger.h" #define FULL_PRECISION \ std::fixed << std::setprecision(std::numeric_limits::max_digits10) From 02856194a055034fa5801cb0dd4c26691f4c989f Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 4 Sep 2018 15:59:38 +0800 Subject: [PATCH 17/77] Update find mynteye in cmakelists of wrappers --- wrappers/python/CMakeLists.txt | 22 ++++++++++--------- .../src/mynt_eye_ros_wrapper/CMakeLists.txt | 4 ++++ 2 files changed, 16 insertions(+), 10 deletions(-) diff --git a/wrappers/python/CMakeLists.txt b/wrappers/python/CMakeLists.txt index 384407d..b6b3ab9 100644 --- a/wrappers/python/CMakeLists.txt +++ b/wrappers/python/CMakeLists.txt @@ -47,14 +47,6 @@ if(OS_MAC) endif() endif() -# options - -include(${PRO_DIR}/cmake/Option.cmake) - -if(NOT WITH_API) - message(FATAL_ERROR "Must with API layer :(") -endif() - # flags if(OS_WIN) @@ -81,6 +73,18 @@ LIST(APPEND CMAKE_PREFIX_PATH ${PRO_DIR}/_install/lib/cmake) find_package(mynteye REQUIRED) message(STATUS "Found mynteye: ${mynteye_VERSION}") +if(NOT mynteye_WITH_API) + message(FATAL_ERROR "Must with API layer :(") +endif() + +include(${PRO_DIR}/cmake/DetectOpenCV.cmake) + +if(mynteye_WITH_GLOG) + include(${PRO_DIR}/cmake/DetectGLog.cmake) +endif() + +## boost & python + if(CMAKE_VERSION VERSION_LESS "3.10" OR CMAKE_VERSION VERSION_EQUAL "3.10") find_package(Boost ${BOOST_FIND_VERSION} REQUIRED COMPONENTS python${PYTHON_BOOST_CODE} # numpy${PYTHON_BOOST_CODE} @@ -99,8 +103,6 @@ message(STATUS "Found PythonLibs: ${PYTHONLIBS_VERSION_STRING}") message(STATUS " PYTHON_INCLUDE_DIRS: ${PYTHON_INCLUDE_DIRS}") message(STATUS " PYTHON_LIBRARIES: ${PYTHON_LIBRARIES}") -include(${PRO_DIR}/cmake/DetectOpenCV.cmake) - #LIST(APPEND CMAKE_MODULE_PATH ${PRO_DIR}/cmake) # targets diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/CMakeLists.txt b/wrappers/ros/src/mynt_eye_ros_wrapper/CMakeLists.txt index 74a36d1..ae85a88 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/CMakeLists.txt +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/CMakeLists.txt @@ -83,6 +83,10 @@ LIST(APPEND CMAKE_PREFIX_PATH ${SDK_DIR}/_install/lib/cmake) find_package(mynteye REQUIRED) message(STATUS "Found mynteye: ${mynteye_VERSION}") +if(NOT mynteye_WITH_API) + message(FATAL_ERROR "Must with API layer :(") +endif() + include(${SDK_DIR}/cmake/DetectOpenCV.cmake) if(mynteye_WITH_GLOG) From 94ecacef6c7ff6e3c432cec2758768e074ce55ed Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 4 Sep 2018 16:07:36 +0800 Subject: [PATCH 18/77] Build pass without glog --- CMakeLists.txt | 12 ++++++++++++ cmake/Option.cmake | 2 +- include/mynteye/logger.h | 32 ++++++++++++++++++++++++++++++++ src/internal/types.cc | 2 +- src/uvc/uvc-v4l2.cc | 4 ++++ 5 files changed, 50 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index dbb634d..d2f16df 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -44,6 +44,17 @@ message(STATUS "CXX_FLAGS: ${CMAKE_CXX_FLAGS}") # packages +find_package(Threads QUIET) + +macro(target_link_threads NAME) + if(THREADS_HAVE_PTHREAD_ARG) + target_compile_options(PUBLIC ${NAME} "-pthread") + endif() + if(CMAKE_THREAD_LIBS_INIT) + target_link_libraries(${NAME} "${CMAKE_THREAD_LIBS_INIT}") + endif() +endmacro() + LIST(APPEND CMAKE_MODULE_PATH cmake) include(CMakePackageConfigHelpers) @@ -176,6 +187,7 @@ endif() add_library(${MYNTEYE_NAME} SHARED ${MYNTEYE_SRCS}) target_link_libraries(${MYNTEYE_NAME} ${MYNTEYE_LINKLIBS}) +target_link_threads(${MYNTEYE_NAME}) if(OS_WIN) target_compile_definitions(${MYNTEYE_NAME} diff --git a/cmake/Option.cmake b/cmake/Option.cmake index 8a414fd..e50601a 100644 --- a/cmake/Option.cmake +++ b/cmake/Option.cmake @@ -29,7 +29,7 @@ option(WITH_DEVICE_INFO_REQUIRED "Build with device info required" ON) option(WITH_BOOST "Include Boost support" ON) # `make 3rdparty` could build glog submodule -option(WITH_GLOG "Include glog support" ON) +option(WITH_GLOG "Include glog support" OFF) # packages diff --git a/include/mynteye/logger.h b/include/mynteye/logger.h index a3f24d2..cedb8ec 100644 --- a/include/mynteye/logger.h +++ b/include/mynteye/logger.h @@ -15,6 +15,8 @@ #define MYNTEYE_LOGGER_H_ #pragma once +#ifdef WITH_GLOG + #include /** Helper to init glog with args. */ @@ -62,4 +64,34 @@ struct glog_init { } }; +#else + +#include + +struct glog_init { + glog_init(int argc, char *argv[]) { + (void)argc; + (void)argv; + } +}; + +#define LOG(severity) std::cout +#define LOG_IF(severity, condition) std::cout + +#define VLOG(verboselevel) std::cout +#define VLOG_IS_ON(verboselevel) false + +#define CHECK(val) std::cout + +#define CHECK_EQ(val1, val2) std::cout +#define CHECK_NE(val1, val2) +#define CHECK_LE(val1, val2) +#define CHECK_LT(val1, val2) +#define CHECK_GE(val1, val2) +#define CHECK_GT(val1, val2) + +#define CHECK_NOTNULL(val) + +#endif + #endif // MYNTEYE_LOGGER_H_ diff --git a/src/internal/types.cc b/src/internal/types.cc index 2f05409..c5aa1e7 100644 --- a/src/internal/types.cc +++ b/src/internal/types.cc @@ -15,7 +15,7 @@ #include #include -#include +#include #include "mynteye/logger.h" diff --git a/src/uvc/uvc-v4l2.cc b/src/uvc/uvc-v4l2.cc index d99a85b..292804c 100755 --- a/src/uvc/uvc-v4l2.cc +++ b/src/uvc/uvc-v4l2.cc @@ -16,6 +16,9 @@ #include #include #include +#include +#include + #include #include #include @@ -27,6 +30,7 @@ #include #include +#include #include #include From d96797c835657d5fb6bddd79a92bfc14226b36a3 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 4 Sep 2018 17:00:18 +0800 Subject: [PATCH 19/77] Add miniglog --- CMakeLists.txt | 15 ++ include/mynteye/logger.h | 20 +- include/mynteye/miniglog.h | 535 +++++++++++++++++++++++++++++++++++++ src/public/miniglog.cc | 39 +++ src/public/miniglog.readme | 1 + 5 files changed, 592 insertions(+), 18 deletions(-) create mode 100644 include/mynteye/miniglog.h create mode 100644 src/public/miniglog.cc create mode 100644 src/public/miniglog.readme diff --git a/CMakeLists.txt b/CMakeLists.txt index d2f16df..9305000 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -108,6 +108,13 @@ endif() ## libmynteye +if(NOT WITH_GLOG) + set(__MINIGLOG_FLAGS "-Wno-unused-parameter -Wno-format -Wno-return-type") + set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${__MINIGLOG_FLAGS}") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${__MINIGLOG_FLAGS}") + unset(__MINIGLOG_FLAGS) +endif() + set(MYNTEYE_PUBLIC_H ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/callbacks.h ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/global.h @@ -128,6 +135,11 @@ if(WITH_API) ${CMAKE_CURRENT_SOURCE_DIR}/src/api/processor/object.h ) 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/uvc/uvc-wmf.cc) @@ -172,6 +184,9 @@ if(WITH_API) src/api/processor/points_processor.cc ) endif() +if(NOT WITH_GLOG) + list(APPEND MYNTEYE_SRCS src/public/miniglog.cc) +endif() set(MYNTEYE_LINKLIBS ${UVC_LIB}) if(WITH_API) diff --git a/include/mynteye/logger.h b/include/mynteye/logger.h index cedb8ec..0b403bc 100644 --- a/include/mynteye/logger.h +++ b/include/mynteye/logger.h @@ -66,31 +66,15 @@ struct glog_init { #else -#include - struct glog_init { glog_init(int argc, char *argv[]) { (void)argc; (void)argv; + // Do nothing. } }; -#define LOG(severity) std::cout -#define LOG_IF(severity, condition) std::cout - -#define VLOG(verboselevel) std::cout -#define VLOG_IS_ON(verboselevel) false - -#define CHECK(val) std::cout - -#define CHECK_EQ(val1, val2) std::cout -#define CHECK_NE(val1, val2) -#define CHECK_LE(val1, val2) -#define CHECK_LT(val1, val2) -#define CHECK_GE(val1, val2) -#define CHECK_GT(val1, val2) - -#define CHECK_NOTNULL(val) +#include "mynteye/miniglog.h" #endif diff --git a/include/mynteye/miniglog.h b/include/mynteye/miniglog.h new file mode 100644 index 0000000..0e0a2a2 --- /dev/null +++ b/include/mynteye/miniglog.h @@ -0,0 +1,535 @@ +// Ceres Solver - A fast non-linear least squares minimizer +// Copyright 2015 Google Inc. All rights reserved. +// http://ceres-solver.org/ +// +// 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: settinger@google.com (Scott Ettinger) +// mierle@gmail.com (Keir Mierle) +// +// Simplified Glog style logging with Android support. Supported macros in +// decreasing severity level per line: +// +// VLOG(2), VLOG(N) +// VLOG(1), +// LOG(INFO), VLOG(0), LG +// LOG(WARNING), +// LOG(ERROR), +// LOG(FATAL), +// +// With VLOG(n), the output is directed to one of the 5 Android log levels: +// +// 2 - Verbose +// 1 - Debug +// 0 - Info +// -1 - Warning +// -2 - Error +// -3 - Fatal +// +// Any logging of level 2 and above is directed to the Verbose level. All +// Android log output is tagged with the string "native". +// +// If the symbol ANDROID is not defined, all output goes to std::cerr. +// This allows code to be built on a different system for debug. +// +// Portions of this code are taken from the GLOG package. This code is only a +// small subset of the GLOG functionality. Notable differences from GLOG +// behavior include lack of support for displaying unprintable characters and +// lack of stack trace information upon failure of the CHECK macros. On +// non-Android systems, log output goes to std::cerr and is not written to a +// file. +// +// CHECK macros are defined to test for conditions within code. Any CHECK that +// fails will log the failure and terminate the application. +// e.g. CHECK_GE(3, 2) will pass while CHECK_GE(3, 4) will fail after logging +// "Check failed 3 >= 4". +// +// The following CHECK macros are defined: +// +// CHECK(condition) - fails if condition is false and logs condition. +// CHECK_NOTNULL(variable) - fails if the variable is NULL. +// +// The following binary check macros are also defined : +// +// Macro Operator equivalent +// -------------------- ------------------- +// CHECK_EQ(val1, val2) val1 == val2 +// CHECK_NE(val1, val2) val1 != val2 +// CHECK_GT(val1, val2) val1 > val2 +// CHECK_GE(val1, val2) val1 >= val2 +// CHECK_LT(val1, val2) val1 < val2 +// CHECK_LE(val1, val2) val1 <= val2 +// +// Debug only versions of all of the check macros are also defined. These +// macros generate no code in a release build, but avoid unused variable +// warnings / errors. +// +// To use the debug only versions, prepend a D to the normal check macros, e.g. +// DCHECK_EQ(a, b). +#ifndef MYNTEYE_MINIGLOG_H_ +#define MYNTEYE_MINIGLOG_H_ + +#ifdef ANDROID +# include +#else +#include +#include +#include +#endif // ANDROID + +#include +#include +#include +#include +#include +#include +#include +#include + +// For appropriate definition of CERES_EXPORT macro. +// Modified from ceres miniglog version [begin] ------------------------------- +//#include "ceres/internal/port.h" +//#include "ceres/internal/disable_warnings.h" +#define CERES_EXPORT +// Modified from ceres miniglog version [end] --------------------------------- + +// Log severity level constants. +const int FATAL = -3; +const int ERROR = -2; +const int WARNING = -1; +const int INFO = 0; + +// ------------------------- Glog compatibility ------------------------------ + +namespace google { + +typedef int LogSeverity; +const int INFO = ::INFO; +const int WARNING = ::WARNING; +const int ERROR = ::ERROR; +const int FATAL = ::FATAL; + +// Sink class used for integration with mock and test functions. If sinks are +// added, all log output is also sent to each sink through the send function. +// In this implementation, WaitTillSent() is called immediately after the send. +// This implementation is not thread safe. +class CERES_EXPORT LogSink { + public: + virtual ~LogSink() {} + virtual void send(LogSeverity severity, + const char* full_filename, + const char* base_filename, + int line, + const struct tm* tm_time, + const char* message, + size_t message_len) = 0; + virtual void WaitTillSent() = 0; +}; + +// Global set of log sinks. The actual object is defined in logging.cc. +extern CERES_EXPORT std::set log_sinks_global; + +inline void InitGoogleLogging(char *argv) { + // Do nothing; this is ignored. +} + +// Note: the Log sink functions are not thread safe. +inline void AddLogSink(LogSink *sink) { + // TODO(settinger): Add locks for thread safety. + log_sinks_global.insert(sink); +} +inline void RemoveLogSink(LogSink *sink) { + log_sinks_global.erase(sink); +} + +} // namespace google + +// ---------------------------- Logger Class -------------------------------- + +// Class created for each use of the logging macros. +// The logger acts as a stream and routes the final stream contents to the +// Android logcat output at the proper filter level. If ANDROID is not +// defined, output is directed to std::cerr. This class should not +// be directly instantiated in code, rather it should be invoked through the +// use of the log macros LG, LOG, or VLOG. +class CERES_EXPORT MessageLogger { + public: + MessageLogger(const char *file, int line, const char *tag, int severity) + : file_(file), line_(line), tag_(tag), severity_(severity) { + // Pre-pend the stream with the file and line number. + StripBasename(std::string(file), &filename_only_); + stream_ << filename_only_ << ":" << line << " "; + } + + // Output the contents of the stream to the proper channel on destruction. + ~MessageLogger() { + stream_ << "\n"; + +#ifdef ANDROID + static const int android_log_levels[] = { + ANDROID_LOG_FATAL, // LOG(FATAL) + ANDROID_LOG_ERROR, // LOG(ERROR) + ANDROID_LOG_WARN, // LOG(WARNING) + ANDROID_LOG_INFO, // LOG(INFO), LG, VLOG(0) + ANDROID_LOG_DEBUG, // VLOG(1) + ANDROID_LOG_VERBOSE, // VLOG(2) .. VLOG(N) + }; + + // Bound the logging level. + const int kMaxVerboseLevel = 2; + int android_level_index = std::min(std::max(FATAL, severity_), + kMaxVerboseLevel) - FATAL; + int android_log_level = android_log_levels[android_level_index]; + + // Output the log string the Android log at the appropriate level. + __android_log_write(android_log_level, tag_.c_str(), stream_.str().c_str()); + + // Indicate termination if needed. + if (severity_ == FATAL) { + __android_log_write(ANDROID_LOG_FATAL, + tag_.c_str(), + "terminating.\n"); + } +#else + // For Ubuntu/Mac/Windows + // If not building on Android, log all output to std::cerr. + // Get timestamp + timeval curTime; + gettimeofday(&curTime, NULL); + int milli = curTime.tv_usec / 1000; + char buffer [20]; + strftime(buffer, 80, "%m-%d %H:%M:%S", localtime(&curTime.tv_sec)); + char time_cstr[24] = ""; + sprintf(time_cstr, "%s:%d ", buffer, milli); + // Get pid & tid + char tid_cstr[24] = ""; + pid_t pid = getpid(); + pthread_t tid = pthread_self(); + sprintf(tid_cstr, "%d/%u ", pid, tid); + if (severity_ == FATAL) { + // Magenta color if fatal + std::cerr << "\033[1;35m"<< tid_cstr << time_cstr << SeverityLabelStr() << stream_.str() << "\033[0m"; + } else if (severity_ == ERROR) { + // Red color if error + std::cerr << "\033[1;31m"<< tid_cstr << time_cstr << SeverityLabelStr() << stream_.str() << "\033[0m"; + } else if (severity_ == WARNING) { + // Yellow color if warning + std::cerr << "\033[1;33m"<< tid_cstr << time_cstr << SeverityLabelStr() << stream_.str() << "\033[0m"; + } else { + std::cerr << tid_cstr << time_cstr << SeverityLabelStr() << stream_.str(); + } +#endif + + LogToSinks(severity_); + WaitForSinks(); + + // Android logging at level FATAL does not terminate execution, so abort() + // is still required to stop the program. + if (severity_ == FATAL) { + abort(); + } + } + + // Return the stream associated with the logger object. + std::stringstream &stream() { return stream_; } + + private: + void LogToSinks(int severity) { + time_t rawtime; + time (&rawtime); + + struct tm timeinfo; +#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) + // On Windows, use secure localtime_s not localtime. + localtime_s(&timeinfo, &rawtime); +#else + // On non-Windows systems, use threadsafe localtime_r not localtime. + localtime_r(&rawtime, &timeinfo); +#endif + + std::set::iterator iter; + // Send the log message to all sinks. + for (iter = google::log_sinks_global.begin(); + iter != google::log_sinks_global.end(); ++iter) { + (*iter)->send(severity, file_.c_str(), filename_only_.c_str(), line_, + &timeinfo, stream_.str().c_str(), stream_.str().size()); + } + } + + void WaitForSinks() { + // TODO(settinger): Add locks for thread safety. + std::set::iterator iter; + + // Call WaitTillSent() for all sinks. + for (iter = google::log_sinks_global.begin(); + iter != google::log_sinks_global.end(); ++iter) { + (*iter)->WaitTillSent(); + } + } + + void StripBasename(const std::string &full_path, std::string *filename) { + // TODO(settinger): Add support for OSs with different path separators. + const char kSeparator = '/'; + size_t pos = full_path.rfind(kSeparator); + if (pos != std::string::npos) { + *filename = full_path.substr(pos + 1, std::string::npos); + } else { + *filename = full_path; + } + } + + char SeverityLabel() { + switch (severity_) { + case FATAL: + return 'F'; + case ERROR: + return 'E'; + case WARNING: + return 'W'; + case INFO: + return 'I'; + default: + return 'V'; + } + } + + std::string SeverityLabelStr() { + switch (severity_) { + case FATAL: + return "FATAL "; + case ERROR: + return "ERROR "; + case WARNING: + return "WARNING "; + case INFO: + return "INFO "; + default: + return "VERBOSE "; + } + } + + std::string file_; + std::string filename_only_; + int line_; + std::string tag_; + std::stringstream stream_; + int severity_; +}; + +// ---------------------- Logging Macro definitions -------------------------- + +// This class is used to explicitly ignore values in the conditional +// logging macros. This avoids compiler warnings like "value computed +// is not used" and "statement has no effect". +class CERES_EXPORT LoggerVoidify { + public: + LoggerVoidify() { } + // This has to be an operator with a precedence lower than << but + // higher than ?: + void operator&(const std::ostream &s) { } +}; + +// Log only if condition is met. Otherwise evaluates to void. +#define LOG_IF(severity, condition) \ + !(condition) ? (void) 0 : LoggerVoidify() & \ + MessageLogger((char *)__FILE__, __LINE__, "native", severity).stream() + +// Log only if condition is NOT met. Otherwise evaluates to void. +#define LOG_IF_FALSE(severity, condition) LOG_IF(severity, !(condition)) + +// LG is a convenient shortcut for LOG(INFO). Its use is in new +// google3 code is discouraged and the following shortcut exists for +// backward compatibility with existing code. +#ifdef MAX_LOG_LEVEL +# define LOG(n) LOG_IF(n, n <= MAX_LOG_LEVEL) +# define VLOG(n) LOG_IF(n, n <= MAX_LOG_LEVEL) +# define LG LOG_IF(INFO, INFO <= MAX_LOG_LEVEL) +# define VLOG_IF(n, condition) LOG_IF(n, (n <= MAX_LOG_LEVEL) && condition) +#else +# define LOG(n) MessageLogger((char *)__FILE__, __LINE__, "native", n).stream() // NOLINT +# define VLOG(n) MessageLogger((char *)__FILE__, __LINE__, "native", n).stream() // NOLINT +# define LG MessageLogger((char *)__FILE__, __LINE__, "native", INFO).stream() // NOLINT +# define VLOG_IF(n, condition) LOG_IF(n, condition) +#endif + +// Currently, VLOG is always on for levels below MAX_LOG_LEVEL. +#ifndef MAX_LOG_LEVEL +# define VLOG_IS_ON(x) (1) +#else +# define VLOG_IS_ON(x) (x <= MAX_LOG_LEVEL) +#endif + +#ifndef NDEBUG +# define DLOG LOG +#else +# define DLOG(severity) true ? (void) 0 : LoggerVoidify() & \ + MessageLogger((char *)__FILE__, __LINE__, "native", severity).stream() +#endif + + +// Log a message and terminate. +template +void LogMessageFatal(const char *file, int line, const T &message) { + MessageLogger((char *)__FILE__, __LINE__, "native", FATAL).stream() + << message; +} + +// ---------------------------- CHECK macros --------------------------------- + +// Check for a given boolean condition. +#define CHECK(condition) LOG_IF_FALSE(FATAL, condition) \ + << "Check failed: " #condition " " + +#ifndef NDEBUG +// Debug only version of CHECK +# define DCHECK(condition) LOG_IF_FALSE(FATAL, condition) \ + << "Check failed: " #condition " " +#else +// Optimized version - generates no code. +# define DCHECK(condition) if (false) LOG_IF_FALSE(FATAL, condition) \ + << "Check failed: " #condition " " +#endif // NDEBUG + +// ------------------------- CHECK_OP macros --------------------------------- + +// Generic binary operator check macro. This should not be directly invoked, +// instead use the binary comparison macros defined below. +#define CHECK_OP(val1, val2, op) LOG_IF_FALSE(FATAL, ((val1) op (val2))) \ + << "Check failed: " #val1 " " #op " " #val2 " " + +// Check_op macro definitions +#define CHECK_EQ(val1, val2) CHECK_OP(val1, val2, ==) +#define CHECK_NE(val1, val2) CHECK_OP(val1, val2, !=) +#define CHECK_LE(val1, val2) CHECK_OP(val1, val2, <=) +#define CHECK_LT(val1, val2) CHECK_OP(val1, val2, <) +#define CHECK_GE(val1, val2) CHECK_OP(val1, val2, >=) +#define CHECK_GT(val1, val2) CHECK_OP(val1, val2, >) + +// qiao.helloworld@gmail.com /tzu.ta.lin@gmail.com add +// Add logging macros which are missing in glog or are not accessible for +// whatever reason. +#define CHECK_NEAR(val1, val2, margin) \ + do { \ + CHECK_LE((val1), (val2)+(margin)); \ + CHECK_GE((val1), (val2)-(margin)); \ + } while (0) + +#ifndef NDEBUG +// Debug only versions of CHECK_OP macros. +# define DCHECK_EQ(val1, val2) CHECK_OP(val1, val2, ==) +# define DCHECK_NE(val1, val2) CHECK_OP(val1, val2, !=) +# define DCHECK_LE(val1, val2) CHECK_OP(val1, val2, <=) +# define DCHECK_LT(val1, val2) CHECK_OP(val1, val2, <) +# define DCHECK_GE(val1, val2) CHECK_OP(val1, val2, >=) +# define DCHECK_GT(val1, val2) CHECK_OP(val1, val2, >) +// qiao.helloworld@gmail.com /tzu.ta.lin@gmail.com add +# define DCHECK_NEAR(val1, val2, margin) CHECK_NEAR(val1, val2, margin) +#else +// These versions generate no code in optimized mode. +# define DCHECK_EQ(val1, val2) if (false) CHECK_OP(val1, val2, ==) +# define DCHECK_NE(val1, val2) if (false) CHECK_OP(val1, val2, !=) +# define DCHECK_LE(val1, val2) if (false) CHECK_OP(val1, val2, <=) +# define DCHECK_LT(val1, val2) if (false) CHECK_OP(val1, val2, <) +# define DCHECK_GE(val1, val2) if (false) CHECK_OP(val1, val2, >=) +# define DCHECK_GT(val1, val2) if (false) CHECK_OP(val1, val2, >) +// qiao.helloworld@gmail.com /tzu.ta.lin@gmail.com add +# define DCHECK_NEAR(val1, val2, margin) if (false) CHECK_NEAR(val1, val2, margin) +#endif // NDEBUG + +// ---------------------------CHECK_NOTNULL macros --------------------------- + +// Helpers for CHECK_NOTNULL(). Two are necessary to support both raw pointers +// and smart pointers. +template +T& CheckNotNullCommon(const char *file, int line, const char *names, T& t) { + if (t == NULL) { + LogMessageFatal(file, line, std::string(names)); + } + return t; +} + +template +T* CheckNotNull(const char *file, int line, const char *names, T* t) { + return CheckNotNullCommon(file, line, names, t); +} + +template +T& CheckNotNull(const char *file, int line, const char *names, T& t) { + return CheckNotNullCommon(file, line, names, t); +} + +// Check that a pointer is not null. +#define CHECK_NOTNULL(val) \ + CheckNotNull(__FILE__, __LINE__, "'" #val "' Must be non NULL", (val)) + +#ifndef NDEBUG +// Debug only version of CHECK_NOTNULL +#define DCHECK_NOTNULL(val) \ + CheckNotNull(__FILE__, __LINE__, "'" #val "' Must be non NULL", (val)) +#else +// Optimized version - generates no code. +#define DCHECK_NOTNULL(val) if (false)\ + CheckNotNull(__FILE__, __LINE__, "'" #val "' Must be non NULL", (val)) +#endif // NDEBUG + +// Modified from ceres miniglog version [begin] ------------------------------- +//#include "ceres/internal/reenable_warnings.h" +// Modified from ceres miniglog version [end] --------------------------------- + + +// ---------------------------TRACE macros --------------------------- +// qiao.helloworld@gmail.com /tzu.ta.lin@gmail.com add +#define __FILENAME__ \ + (strrchr(__FILE__, '/') ? strrchr(__FILE__, '/') + 1 : __FILE__) + +#define DEXEC(fn) \ + do { \ + DLOG(INFO) << "[EXEC " << #fn << " START]"; \ + std::chrono::steady_clock::time_point begin = \ + std::chrono::steady_clock::now(); \ + fn; \ + std::chrono::steady_clock::time_point end = \ + std::chrono::steady_clock::now(); \ + DLOG(INFO) << "[EXEC " << #fn << " FINISHED in " \ + << std::chrono::duration_cast \ + (end - begin).count() << " ms]"; \ + } while (0); +// DEXEC(fn) +// +// Usage: +// DEXEC(foo()); +// -- output -- +// foo.cpp: 123 [EXEC foo() START] +// foo.cpp: 123 [EXEC foo() FINISHED in 456 ms] + +#define DTRACE DLOG(INFO) << "of [" << __func__ << "]"; +// Usage: +// void foo() { +// DTRACE +// } +// -- output -- +// foo.cpp: 123 of [void foo(void)] + +#endif // MYNTEYE_MINIGLOG_H_ diff --git a/src/public/miniglog.cc b/src/public/miniglog.cc new file mode 100644 index 0000000..23a2c32 --- /dev/null +++ b/src/public/miniglog.cc @@ -0,0 +1,39 @@ +// Ceres Solver - A fast non-linear least squares minimizer +// Copyright 2015 Google Inc. All rights reserved. +// http://ceres-solver.org/ +// +// 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 log_sinks_global; + +} // namespace google diff --git a/src/public/miniglog.readme b/src/public/miniglog.readme new file mode 100644 index 0000000..9ce8c89 --- /dev/null +++ b/src/public/miniglog.readme @@ -0,0 +1 @@ +miniglog: https://github.com/tzutalin/miniglog From 2784937ad16ac0fa54ca75801996df523d768cfa Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 4 Sep 2018 17:11:39 +0800 Subject: [PATCH 20/77] Remove submodule glog --- .gitmodules | 3 --- Makefile | 10 +--------- cmake/Option.cmake | 3 ++- third_party/glog | 1 - 4 files changed, 3 insertions(+), 14 deletions(-) delete mode 160000 third_party/glog diff --git a/.gitmodules b/.gitmodules index d40f165..3a8bfae 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,9 +1,6 @@ [submodule "test/gtest"] path = test/gtest url = https://github.com/google/googletest.git -[submodule "third_party/glog"] - path = third_party/glog - url = https://github.com/google/glog.git [submodule "tools/linter"] path = tools/linter url = https://github.com/slightech/linter.git diff --git a/Makefile b/Makefile index 5483d78..974617f 100644 --- a/Makefile +++ b/Makefile @@ -30,7 +30,6 @@ help: @echo " make apidoc make api doc" @echo " make opendoc open api doc (html)" @echo " make init init project" - @echo " make 3rdparty build 3rdparty: glog" @echo " make build build project" @echo " make install install project" @echo " make test build test and run" @@ -71,14 +70,7 @@ cleandoc: submodules: @git submodule update --init -third_party: submodules - @$(call echo,Make $@) - @$(call echo,Make glog,33) - @$(call cmake_build,./third_party/glog/_build) - -3rdparty: third_party - -.PHONY: submodules third_party 3rdparty +.PHONY: submodules # init diff --git a/cmake/Option.cmake b/cmake/Option.cmake index e50601a..98e9e49 100644 --- a/cmake/Option.cmake +++ b/cmake/Option.cmake @@ -28,7 +28,8 @@ option(WITH_DEVICE_INFO_REQUIRED "Build with device info required" ON) option(WITH_BOOST "Include Boost support" ON) -# `make 3rdparty` could build glog submodule +# How to install glog? +# Ubuntu: `sudo apt-get install libgoogle-glog-dev` option(WITH_GLOG "Include glog support" OFF) diff --git a/third_party/glog b/third_party/glog deleted file mode 160000 index 8d7a107..0000000 --- a/third_party/glog +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 8d7a107d68c127f3f494bb7807b796c8c5a97a82 From 89c798daa8a0205290c94b58be83dd6ce60b2b0c Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 4 Sep 2018 17:18:35 +0800 Subject: [PATCH 21/77] Change max log size --- include/mynteye/logger.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/mynteye/logger.h b/include/mynteye/logger.h index 0b403bc..0168ce0 100644 --- a/include/mynteye/logger.h +++ b/include/mynteye/logger.h @@ -45,7 +45,7 @@ struct glog_init { FLAGS_log_dir = "."; // Sets the maximum log file size (in MB). - FLAGS_max_log_size = 1024; + FLAGS_max_log_size = 8; // Sets whether to avoid logging to the disk if the disk is full. FLAGS_stop_logging_if_full_disk = true; From ca605d6114938c51a61bf3c988d4cb4a62b7b5eb Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 4 Sep 2018 17:31:21 +0800 Subject: [PATCH 22/77] Set max log level to info for miniglog --- include/mynteye/logger.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/include/mynteye/logger.h b/include/mynteye/logger.h index 0168ce0..65c8270 100644 --- a/include/mynteye/logger.h +++ b/include/mynteye/logger.h @@ -74,6 +74,8 @@ struct glog_init { } }; +#define MAX_LOG_LEVEL google::INFO + #include "mynteye/miniglog.h" #endif From 36e90e379372c06211e71cbfb934654bf1581641 Mon Sep 17 00:00:00 2001 From: Osenberg-Y Date: Thu, 6 Sep 2018 19:45:51 +0800 Subject: [PATCH 23/77] Fix bug in repeatedly publishing camera infomation. --- wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch b/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch index a41e52f..0b3679a 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch @@ -6,8 +6,8 @@ - - + + From cf9e714626cd5c2a35bc42088a78a05c7a3e6138 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 11 Sep 2018 10:10:14 +0800 Subject: [PATCH 24/77] Fix flags on win --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9305000..d811781 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -108,7 +108,7 @@ endif() ## libmynteye -if(NOT WITH_GLOG) +if(NOT WITH_GLOG AND NOT OS_WIN) set(__MINIGLOG_FLAGS "-Wno-unused-parameter -Wno-format -Wno-return-type") set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${__MINIGLOG_FLAGS}") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${__MINIGLOG_FLAGS}") From 1b95e376a5a0368f7ae09d4c3061471d3362559f Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 11 Sep 2018 10:19:25 +0800 Subject: [PATCH 25/77] Update macros --- include/mynteye/global.h | 96 +++++++++---------- include/mynteye/logger.h | 2 +- include/mynteye/miniglog.h | 38 ++++---- include/mynteye/mynteye.h.in | 11 ++- samples/api/get_depth_with_region.cc | 4 +- samples/tutorials/data/get_from_callbacks.cc | 2 +- .../intermediate/get_depth_and_points.cc | 4 +- samples/uvc/camera.cc | 2 +- src/api/api.cc | 10 +- src/api/plugin.h | 20 ++-- src/api/processor/depth_processor.cc | 2 +- .../disparity_normalized_processor.cc | 2 +- src/api/processor/disparity_processor.cc | 2 +- src/api/processor/points_processor.cc | 2 +- src/api/processor/rectify_processor.cc | 2 +- src/api/synthetic.cc | 10 +- src/internal/channels.cc | 14 +-- src/internal/dl.cc | 12 ++- src/internal/dl.h | 6 +- src/internal/files.cc | 11 ++- src/internal/times.h | 2 +- src/uvc/uvc-libuvc.cc | 66 ++++++------- tools/dataset/dataset.cc | 10 +- tools/writer/device_writer.cc | 6 +- tools/writer/save_all_infos.cc | 2 +- 25 files changed, 176 insertions(+), 162 deletions(-) diff --git a/include/mynteye/global.h b/include/mynteye/global.h index 7a58f4e..710d93f 100644 --- a/include/mynteye/global.h +++ b/include/mynteye/global.h @@ -16,72 +16,70 @@ #pragma once #ifdef _WIN32 -#define OS_WIN -#ifdef _WIN64 -#define OS_WIN64 -#else -#define OS_WIN32 -#endif -#if defined(__MINGW32__) || defined(__MINGW64__) -#define OS_MINGW -#ifdef __MINGW64__ -#define OS_MINGW64 -#else -#define OS_MINGW32 -#endif -#elif defined(__CYGWIN__) || defined(__CYGWIN32__) -#define OS_CYGWIN -#endif + #define MYNTEYE_OS_WIN + #ifdef _WIN64 + #define MYNTEYE_OS_WIN64 + #else + #define MYNTEYE_OS_WIN32 + #endif + #if defined(__MINGW32__) || defined(__MINGW64__) + #define MYNTEYE_OS_MINGW + #ifdef __MINGW64__ + #define MYNTEYE_OS_MINGW64 + #else + #define MYNTEYE_OS_MINGW32 + #endif + #elif defined(__CYGWIN__) || defined(__CYGWIN32__) + #define MYNTEYE_OS_CYGWIN + #endif #elif __APPLE__ -#include "TargetConditionals.h" -#if TARGET_IPHONE_SIMULATOR -#define OS_IPHONE -#define OS_IPHONE_SIMULATOR -#elif TARGET_OS_IPHONE -#define OS_IPHONE -#elif TARGET_OS_MAC -#define OS_MAC -#else -#error "Unknown Apple platform" -#endif + #include + #if TARGET_IPHONE_SIMULATOR + #define MYNTEYE_OS_IPHONE + #define MYNTEYE_OS_IPHONE_SIMULATOR + #elif TARGET_OS_IPHONE + #define MYNTEYE_OS_IPHONE + #elif TARGET_OS_MAC + #define MYNTEYE_OS_MAC + #else + #error "Unknown Apple platform" + #endif #elif __ANDROID__ -#define OS_ANDROID + #define MYNTEYE_OS_ANDROID #elif __linux__ -#define OS_LINUX + #define MYNTEYE_OS_LINUX #elif __unix__ -#define OS_UNIX + #define MYNTEYE_OS_UNIX #elif defined(_POSIX_VERSION) -#define OS_POSIX + #define MYNTEYE_OS_POSIX #else -#error "Unknown compiler" + #error "Unknown compiler" #endif -#ifdef OS_WIN -#define DECL_EXPORT __declspec(dllexport) -#define DECL_IMPORT __declspec(dllimport) -#define DECL_HIDDEN +#ifdef MYNTEYE_OS_WIN +#define MYNTEYE_DECL_EXPORT __declspec(dllexport) +#define MYNTEYE_DECL_IMPORT __declspec(dllimport) +#define MYNTEYE_DECL_HIDDEN #else -#define DECL_EXPORT __attribute__((visibility("default"))) -#define DECL_IMPORT __attribute__((visibility("default"))) -#define DECL_HIDDEN __attribute__((visibility("hidden"))) +#define MYNTEYE_DECL_EXPORT __attribute__((visibility("default"))) +#define MYNTEYE_DECL_IMPORT __attribute__((visibility("default"))) +#define MYNTEYE_DECL_HIDDEN __attribute__((visibility("hidden"))) #endif -#if defined(OS_WIN) && !defined(OS_MINGW) && !defined(OS_CYGWIN) -#define OS_SEP "\\" +#if defined(MYNTEYE_OS_WIN) && !defined(MYNTEYE_OS_MINGW) && \ + !defined(MYNTEYE_OS_CYGWIN) +#define MYNTEYE_OS_SEP "\\" #else -#define OS_SEP "/" +#define MYNTEYE_OS_SEP "/" #endif -#define STRINGIFY_HELPER(X) #X -#define STRINGIFY(X) STRINGIFY_HELPER(X) +#define MYNTEYE_STRINGIFY_HELPER(X) #X +#define MYNTEYE_STRINGIFY(X) MYNTEYE_STRINGIFY_HELPER(X) -#define DISABLE_COPY(Class) \ +#define MYNTEYE_DISABLE_COPY(Class) \ Class(const Class &) = delete; \ Class &operator=(const Class &) = delete; -#define UNUSED(x) (void)x; - -template -void unused(T &&...) {} +#define MYNTEYE_UNUSED(x) (void)x; #endif // MYNTEYE_GLOBAL_H_ diff --git a/include/mynteye/logger.h b/include/mynteye/logger.h index 65c8270..83a7642 100644 --- a/include/mynteye/logger.h +++ b/include/mynteye/logger.h @@ -74,7 +74,7 @@ struct glog_init { } }; -#define MAX_LOG_LEVEL google::INFO +#define MYNTEYE_MAX_LOG_LEVEL google::INFO #include "mynteye/miniglog.h" diff --git a/include/mynteye/miniglog.h b/include/mynteye/miniglog.h index 0e0a2a2..e267c69 100644 --- a/include/mynteye/miniglog.h +++ b/include/mynteye/miniglog.h @@ -91,14 +91,6 @@ #ifndef MYNTEYE_MINIGLOG_H_ #define MYNTEYE_MINIGLOG_H_ -#ifdef ANDROID -# include -#else -#include -#include -#include -#endif // ANDROID - #include #include #include @@ -108,6 +100,18 @@ #include #include +#include "mynteye/global.h" + +#if defined(MYNTEYE_OS_ANDROID) +#include +#elif defined(MYNTEYE_OS_WIN) +#include +#else +#include +#include +#include +#endif // ANDROID + // For appropriate definition of CERES_EXPORT macro. // Modified from ceres miniglog version [begin] ------------------------------- //#include "ceres/internal/port.h" @@ -187,7 +191,7 @@ class CERES_EXPORT MessageLogger { ~MessageLogger() { stream_ << "\n"; -#ifdef ANDROID +#if defined(MYNTEYE_OS_ANDROID) static const int android_log_levels[] = { ANDROID_LOG_FATAL, // LOG(FATAL) ANDROID_LOG_ERROR, // LOG(ERROR) @@ -362,11 +366,11 @@ class CERES_EXPORT LoggerVoidify { // LG is a convenient shortcut for LOG(INFO). Its use is in new // google3 code is discouraged and the following shortcut exists for // backward compatibility with existing code. -#ifdef MAX_LOG_LEVEL -# define LOG(n) LOG_IF(n, n <= MAX_LOG_LEVEL) -# define VLOG(n) LOG_IF(n, n <= MAX_LOG_LEVEL) -# define LG LOG_IF(INFO, INFO <= MAX_LOG_LEVEL) -# define VLOG_IF(n, condition) LOG_IF(n, (n <= MAX_LOG_LEVEL) && condition) +#ifdef MYNTEYE_MAX_LOG_LEVEL +# define LOG(n) LOG_IF(n, n <= MYNTEYE_MAX_LOG_LEVEL) +# define VLOG(n) LOG_IF(n, n <= MYNTEYE_MAX_LOG_LEVEL) +# define LG LOG_IF(INFO, INFO <= MYNTEYE_MAX_LOG_LEVEL) +# define VLOG_IF(n, condition) LOG_IF(n, (n <= MYNTEYE_MAX_LOG_LEVEL) && condition) #else # define LOG(n) MessageLogger((char *)__FILE__, __LINE__, "native", n).stream() // NOLINT # define VLOG(n) MessageLogger((char *)__FILE__, __LINE__, "native", n).stream() // NOLINT @@ -374,11 +378,11 @@ class CERES_EXPORT LoggerVoidify { # define VLOG_IF(n, condition) LOG_IF(n, condition) #endif -// Currently, VLOG is always on for levels below MAX_LOG_LEVEL. -#ifndef MAX_LOG_LEVEL +// Currently, VLOG is always on for levels below MYNTEYE_MAX_LOG_LEVEL. +#ifndef MYNTEYE_MAX_LOG_LEVEL # define VLOG_IS_ON(x) (1) #else -# define VLOG_IS_ON(x) (x <= MAX_LOG_LEVEL) +# define VLOG_IS_ON(x) (x <= MYNTEYE_MAX_LOG_LEVEL) #endif #ifndef NDEBUG diff --git a/include/mynteye/mynteye.h.in b/include/mynteye/mynteye.h.in index c2c8eff..094742b 100644 --- a/include/mynteye/mynteye.h.in +++ b/include/mynteye/mynteye.h.in @@ -21,9 +21,9 @@ # define MYNTEYE_API #else # ifdef MYNTEYE_EXPORTS -# define MYNTEYE_API DECL_EXPORT +# define MYNTEYE_API MYNTEYE_DECL_EXPORT # else -# define MYNTEYE_API DECL_IMPORT +# define MYNTEYE_API MYNTEYE_DECL_IMPORT # endif #endif @@ -61,4 +61,11 @@ MYNTEYE_API_VERSION_CHECK( \ const char MYNTEYE_SDK_ROOT_DIR[] = "@MYNTEYE_SDK_ROOT_DIR@"; const char MYNTEYE_SDK_INSTALL_DIR[] = "@MYNTEYE_SDK_INSTALL_DIR@"; +MYNTEYE_BEGIN_NAMESPACE + +template +void UNUSED(T &&...) {} + +MYNTEYE_END_NAMESPACE + #endif // MYNTEYE_MYNTEYE_H_ diff --git a/samples/api/get_depth_with_region.cc b/samples/api/get_depth_with_region.cc index 5a1091b..c0918c3 100644 --- a/samples/api/get_depth_with_region.cc +++ b/samples/api/get_depth_with_region.cc @@ -29,7 +29,7 @@ class DepthRegion { * 鼠标事件:默认不选中区域,随鼠标移动而显示。单击后,则会选中区域来显示。你可以再单击已选中区域或双击未选中区域,取消选中。 */ void OnMouse(const int &event, const int &x, const int &y, const int &flags) { - UNUSED(flags) + MYNTEYE_UNUSED(flags) if (event != CV_EVENT_MOUSEMOVE && event != CV_EVENT_LBUTTONDOWN) { return; } @@ -161,7 +161,7 @@ int main(int argc, char *argv[]) { DepthRegion depth_region(3); auto depth_info = []( const cv::Mat &depth, const cv::Point &point, const std::uint32_t &n) { - UNUSED(depth) + MYNTEYE_UNUSED(depth) std::ostringstream os; os << "depth pos: [" << point.y << ", " << point.x << "]" << "±" << n << ", unit: mm"; diff --git a/samples/tutorials/data/get_from_callbacks.cc b/samples/tutorials/data/get_from_callbacks.cc index d38b7ae..667c956 100644 --- a/samples/tutorials/data/get_from_callbacks.cc +++ b/samples/tutorials/data/get_from_callbacks.cc @@ -52,7 +52,7 @@ int main(int argc, char *argv[]) { api->SetStreamCallback( Stream::DEPTH, [&depth_count, &depth, &depth_mtx](const api::StreamData &data) { - UNUSED(data) + MYNTEYE_UNUSED(data) ++depth_count; { std::lock_guard _(depth_mtx); diff --git a/samples/tutorials/intermediate/get_depth_and_points.cc b/samples/tutorials/intermediate/get_depth_and_points.cc index 03391f5..6c54da0 100644 --- a/samples/tutorials/intermediate/get_depth_and_points.cc +++ b/samples/tutorials/intermediate/get_depth_and_points.cc @@ -32,7 +32,7 @@ class DepthRegion { * 鼠标事件:默认不选中区域,随鼠标移动而显示。单击后,则会选中区域来显示。你可以再单击已选中区域或双击未选中区域,取消选中。 */ void OnMouse(const int &event, const int &x, const int &y, const int &flags) { - UNUSED(flags) + MYNTEYE_UNUSED(flags) if (event != CV_EVENT_MOUSEMOVE && event != CV_EVENT_LBUTTONDOWN) { return; } @@ -164,7 +164,7 @@ int main(int argc, char *argv[]) { DepthRegion depth_region(3); auto depth_info = []( const cv::Mat &depth, const cv::Point &point, const std::uint32_t &n) { - UNUSED(depth) + MYNTEYE_UNUSED(depth) std::ostringstream os; os << "depth pos: [" << point.y << ", " << point.x << "]" << "±" << n << ", unit: mm"; diff --git a/samples/uvc/camera.cc b/samples/uvc/camera.cc index 4b36b44..5f301d6 100644 --- a/samples/uvc/camera.cc +++ b/samples/uvc/camera.cc @@ -157,7 +157,7 @@ int main(int argc, char *argv[]) { t = static_cast(cv::getTickCount() - t); fps = cv::getTickFrequency() / t; } - UNUSED(fps) + MYNTEYE_UNUSED(fps) uvc::stop_streaming(*device); // cv::destroyAllWindows(); diff --git a/src/api/api.cc b/src/api/api.cc index 8fb98bb..fc102ef 100644 --- a/src/api/api.cc +++ b/src/api/api.cc @@ -31,7 +31,7 @@ #include "internal/dl.h" #if defined(WITH_FILESYSTEM) && defined(WITH_NATIVE_FILESYSTEM) -#if defined(OS_WIN) +#if defined(MYNTEYE_OS_WIN) #include #endif #endif @@ -68,7 +68,7 @@ bool dir_exists(const fs::path &p) { #elif defined(WITH_NATIVE_FILESYSTEM) -#if defined(OS_WIN) +#if defined(MYNTEYE_OS_WIN) bool file_exists(const std::string &p) { DWORD attrs = GetFileAttributes(p.c_str()); @@ -90,7 +90,7 @@ bool dir_exists(const std::string &p) { std::vector get_plugin_paths() { std::string info_path(MYNTEYE_SDK_INSTALL_DIR); - info_path.append(OS_SEP "share" OS_SEP "mynteye" OS_SEP "build.info"); + info_path.append(MYNTEYE_OS_SEP "share" MYNTEYE_OS_SEP "mynteye" MYNTEYE_OS_SEP "build.info"); cv::FileStorage fs(info_path, cv::FileStorage::READ); if (!fs.isOpened()) { @@ -187,13 +187,13 @@ std::vector get_plugin_paths() { std::vector dirs{MYNTEYE_SDK_ROOT_DIR, MYNTEYE_SDK_INSTALL_DIR}; for (auto &&plat : plats) { for (auto &&dir : dirs) { - auto &&plat_dir = dir + OS_SEP "plugins" + OS_SEP + plat; + auto &&plat_dir = dir + MYNTEYE_OS_SEP "plugins" + MYNTEYE_OS_SEP + plat; // VLOG(2) << "plat_dir: " << plat_dir; if (!dir_exists(plat_dir)) continue; for (auto &&name : names) { // VLOG(2) << " name: " << name; - auto &&path = plat_dir + OS_SEP + name; + auto &&path = plat_dir + MYNTEYE_OS_SEP + name; if (!file_exists(path)) continue; paths.push_back(path); diff --git a/src/api/plugin.h b/src/api/plugin.h index 325f6bf..1924468 100644 --- a/src/api/plugin.h +++ b/src/api/plugin.h @@ -53,8 +53,8 @@ class MYNTEYE_API Plugin { * @return `true` if you process rectify. */ virtual bool OnRectifyProcess(Object *const in, Object *const out) { - UNUSED(in) - UNUSED(out) + MYNTEYE_UNUSED(in) + MYNTEYE_UNUSED(out) return false; } @@ -65,8 +65,8 @@ class MYNTEYE_API Plugin { * @return `true` if you process disparity. */ virtual bool OnDisparityProcess(Object *const in, Object *const out) { - UNUSED(in) - UNUSED(out) + MYNTEYE_UNUSED(in) + MYNTEYE_UNUSED(out) return false; } @@ -78,8 +78,8 @@ class MYNTEYE_API Plugin { */ virtual bool OnDisparityNormalizedProcess( Object *const in, Object *const out) { - UNUSED(in) - UNUSED(out) + MYNTEYE_UNUSED(in) + MYNTEYE_UNUSED(out) return false; } @@ -90,8 +90,8 @@ class MYNTEYE_API Plugin { * @return `true` if you process points. */ virtual bool OnPointsProcess(Object *const in, Object *const out) { - UNUSED(in) - UNUSED(out) + MYNTEYE_UNUSED(in) + MYNTEYE_UNUSED(out) return false; } @@ -102,8 +102,8 @@ class MYNTEYE_API Plugin { * @return `true` if you process depth. */ virtual bool OnDepthProcess(Object *const in, Object *const out) { - UNUSED(in) - UNUSED(out) + MYNTEYE_UNUSED(in) + MYNTEYE_UNUSED(out) return false; } diff --git a/src/api/processor/depth_processor.cc b/src/api/processor/depth_processor.cc index 433e47d..cf05d8f 100644 --- a/src/api/processor/depth_processor.cc +++ b/src/api/processor/depth_processor.cc @@ -40,7 +40,7 @@ Object *DepthProcessor::OnCreateOutput() { bool DepthProcessor::OnProcess( Object *const in, Object *const out, Processor *const parent) { - UNUSED(parent) + MYNTEYE_UNUSED(parent) const ObjMat *input = Object::Cast(in); ObjMat *output = Object::Cast(out); cv::Mat channels[3 /*input->value.channels()*/]; diff --git a/src/api/processor/disparity_normalized_processor.cc b/src/api/processor/disparity_normalized_processor.cc index 6c24c6b..85f020d 100644 --- a/src/api/processor/disparity_normalized_processor.cc +++ b/src/api/processor/disparity_normalized_processor.cc @@ -44,7 +44,7 @@ Object *DisparityNormalizedProcessor::OnCreateOutput() { bool DisparityNormalizedProcessor::OnProcess( Object *const in, Object *const out, Processor *const parent) { - UNUSED(parent) + MYNTEYE_UNUSED(parent) const ObjMat *input = Object::Cast(in); ObjMat *output = Object::Cast(out); cv::normalize(input->value, output->value, 0, 255, cv::NORM_MINMAX, CV_8UC1); diff --git a/src/api/processor/disparity_processor.cc b/src/api/processor/disparity_processor.cc index 041e246..96ad273 100644 --- a/src/api/processor/disparity_processor.cc +++ b/src/api/processor/disparity_processor.cc @@ -74,7 +74,7 @@ Object *DisparityProcessor::OnCreateOutput() { bool DisparityProcessor::OnProcess( Object *const in, Object *const out, Processor *const parent) { - UNUSED(parent) + MYNTEYE_UNUSED(parent) const ObjMat2 *input = Object::Cast(in); ObjMat *output = Object::Cast(out); diff --git a/src/api/processor/points_processor.cc b/src/api/processor/points_processor.cc index 02a70b2..8bc57da 100644 --- a/src/api/processor/points_processor.cc +++ b/src/api/processor/points_processor.cc @@ -42,7 +42,7 @@ Object *PointsProcessor::OnCreateOutput() { bool PointsProcessor::OnProcess( Object *const in, Object *const out, Processor *const parent) { - UNUSED(parent) + MYNTEYE_UNUSED(parent) const ObjMat *input = Object::Cast(in); ObjMat *output = Object::Cast(out); cv::reprojectImageTo3D(input->value, output->value, Q_, true); diff --git a/src/api/processor/rectify_processor.cc b/src/api/processor/rectify_processor.cc index 9a45b0f..7b791c6 100644 --- a/src/api/processor/rectify_processor.cc +++ b/src/api/processor/rectify_processor.cc @@ -49,7 +49,7 @@ Object *RectifyProcessor::OnCreateOutput() { bool RectifyProcessor::OnProcess( Object *const in, Object *const out, Processor *const parent) { - UNUSED(parent) + MYNTEYE_UNUSED(parent) const ObjMat2 *input = Object::Cast(in); ObjMat2 *output = Object::Cast(out); cv::remap(input->first, output->first, map11, map12, cv::INTER_LINEAR); diff --git a/src/api/synthetic.cc b/src/api/synthetic.cc index a1a3730..a73e6ad 100644 --- a/src/api/synthetic.cc +++ b/src/api/synthetic.cc @@ -498,7 +498,7 @@ void Synthetic::ProcessNativeStream( bool Synthetic::OnRectifyProcess( Object *const in, Object *const out, Processor *const parent) { - UNUSED(parent) + MYNTEYE_UNUSED(parent) if (plugin_ && plugin_->OnRectifyProcess(in, out)) { return true; } @@ -508,7 +508,7 @@ bool Synthetic::OnRectifyProcess( bool Synthetic::OnDisparityProcess( Object *const in, Object *const out, Processor *const parent) { - UNUSED(parent) + MYNTEYE_UNUSED(parent) if (plugin_ && plugin_->OnDisparityProcess(in, out)) { return true; } @@ -517,7 +517,7 @@ bool Synthetic::OnDisparityProcess( bool Synthetic::OnDisparityNormalizedProcess( Object *const in, Object *const out, Processor *const parent) { - UNUSED(parent) + MYNTEYE_UNUSED(parent) if (plugin_ && plugin_->OnDisparityNormalizedProcess(in, out)) { return true; } @@ -526,7 +526,7 @@ bool Synthetic::OnDisparityNormalizedProcess( bool Synthetic::OnPointsProcess( Object *const in, Object *const out, Processor *const parent) { - UNUSED(parent) + MYNTEYE_UNUSED(parent) if (plugin_ && plugin_->OnPointsProcess(in, out)) { return true; } @@ -535,7 +535,7 @@ bool Synthetic::OnPointsProcess( bool Synthetic::OnDepthProcess( Object *const in, Object *const out, Processor *const parent) { - UNUSED(parent) + MYNTEYE_UNUSED(parent) if (plugin_ && plugin_->OnDepthProcess(in, out)) { return true; } diff --git a/src/internal/channels.cc b/src/internal/channels.cc index 679fe61..2c3fd8d 100644 --- a/src/internal/channels.cc +++ b/src/internal/channels.cc @@ -453,7 +453,7 @@ std::size_t from_data( } i += 40; - UNUSED(spec_version) + MYNTEYE_UNUSED(spec_version) return i; } @@ -484,7 +484,7 @@ std::size_t from_data( } i += 24; - UNUSED(spec_version) + MYNTEYE_UNUSED(spec_version) return i; } @@ -505,7 +505,7 @@ std::size_t from_data( } i += 24; - UNUSED(spec_version) + MYNTEYE_UNUSED(spec_version) return i; } @@ -684,7 +684,7 @@ std::size_t to_data( _to_data(info->nominal_baseline, data + i); i += 2; - UNUSED(spec_version) + MYNTEYE_UNUSED(spec_version) // others std::size_t size = i - 3; @@ -725,7 +725,7 @@ std::size_t to_data( } i += 40; - UNUSED(spec_version) + MYNTEYE_UNUSED(spec_version) return i; } @@ -756,7 +756,7 @@ std::size_t to_data( } i += 24; - UNUSED(spec_version) + MYNTEYE_UNUSED(spec_version) return i; } @@ -777,7 +777,7 @@ std::size_t to_data( } i += 24; - UNUSED(spec_version) + MYNTEYE_UNUSED(spec_version) return i; } diff --git a/src/internal/dl.cc b/src/internal/dl.cc index 2de8150..13170d2 100644 --- a/src/internal/dl.cc +++ b/src/internal/dl.cc @@ -17,7 +17,8 @@ MYNTEYE_BEGIN_NAMESPACE -#if defined(OS_WIN) && !defined(OS_MINGW) && !defined(OS_CYGWIN) +#if defined(MYNTEYE_OS_WIN) && !defined(MYNTEYE_OS_MINGW) && \ + !defined(MYNTEYE_OS_CYGWIN) namespace { @@ -62,7 +63,8 @@ bool DL::Open(const char *filename) { // Close(); return false; } -#if defined(OS_WIN) && !defined(OS_MINGW) && !defined(OS_CYGWIN) +#if defined(MYNTEYE_OS_WIN) && !defined(MYNTEYE_OS_MINGW) && \ + !defined(MYNTEYE_OS_CYGWIN) handle = LoadLibraryEx(filename, nullptr, 0); #else handle = dlopen(filename, RTLD_LAZY); @@ -84,7 +86,7 @@ void *DL::Sym(const char *symbol) { VLOG(2) << "Not opened, do nothing"; return nullptr; } -#if defined(OS_WIN) && !defined(OS_MINGW) && !defined(OS_CYGWIN) +#if defined(MYNTEYE_OS_WIN) && !defined(MYNTEYE_OS_MINGW) && !defined(MYNTEYE_OS_CYGWIN) void *f = GetProcAddress(handle, symbol); if (f == nullptr) { VLOG(2) << "Load symbol failed: " << symbol; @@ -106,7 +108,7 @@ int DL::Close() { if (handle == nullptr) { VLOG(2) << "Not opened, do nothing"; } else { -#if defined(OS_WIN) && !defined(OS_MINGW) && !defined(OS_CYGWIN) +#if defined(MYNTEYE_OS_WIN) && !defined(MYNTEYE_OS_MINGW) && !defined(MYNTEYE_OS_CYGWIN) ret = FreeLibrary(handle) ? 0 : 1; #else ret = dlclose(handle); @@ -117,7 +119,7 @@ int DL::Close() { } const char *DL::Error() { -#if defined(OS_WIN) && !defined(OS_MINGW) && !defined(OS_CYGWIN) +#if defined(MYNTEYE_OS_WIN) && !defined(MYNTEYE_OS_MINGW) && !defined(MYNTEYE_OS_CYGWIN) return GetLastErrorAsString().c_str(); #else return dlerror(); diff --git a/src/internal/dl.h b/src/internal/dl.h index 901608a..b5748f7 100644 --- a/src/internal/dl.h +++ b/src/internal/dl.h @@ -17,7 +17,8 @@ #include "mynteye/mynteye.h" -#if defined(OS_WIN) && !defined(OS_MINGW) && !defined(OS_CYGWIN) +#if defined(MYNTEYE_OS_WIN) && !defined(MYNTEYE_OS_MINGW) && \ + !defined(MYNTEYE_OS_CYGWIN) #include #else #include @@ -25,7 +26,8 @@ MYNTEYE_BEGIN_NAMESPACE -#if defined(OS_WIN) && !defined(OS_MINGW) && !defined(OS_CYGWIN) +#if defined(MYNTEYE_OS_WIN) && !defined(MYNTEYE_OS_MINGW) && \ + !defined(MYNTEYE_OS_CYGWIN) using DLLIB = HMODULE; #else using DLLIB = void *; diff --git a/src/internal/files.cc b/src/internal/files.cc index 556d5c9..5acb602 100644 --- a/src/internal/files.cc +++ b/src/internal/files.cc @@ -15,7 +15,8 @@ #include "mynteye/logger.h" -#if defined(OS_WIN) && !defined(OS_MINGW) && !defined(OS_CYGWIN) +#if defined(MYNTEYE_OS_WIN) && !defined(MYNTEYE_OS_MINGW) && \ + !defined(MYNTEYE_OS_CYGWIN) #include #else #include @@ -28,9 +29,9 @@ MYNTEYE_BEGIN_NAMESPACE namespace files { bool _mkdir(const std::string &path) { -#if defined(OS_MINGW) || defined(OS_CYGWIN) +#if defined(MYNTEYE_OS_MINGW) || defined(MYNTEYE_OS_CYGWIN) const int status = ::mkdir(path.c_str()); -#elif defined(OS_WIN) +#elif defined(MYNTEYE_OS_WIN) const int status = ::_mkdir(path.c_str()); #else const int status = @@ -51,7 +52,7 @@ bool _mkdir(const std::string &path) { } bool mkdir(const std::string &path) { - auto &&dirs = strings::split(path, OS_SEP); + auto &&dirs = strings::split(path, MYNTEYE_OS_SEP); auto &&size = dirs.size(); if (size <= 0) return false; @@ -59,7 +60,7 @@ bool mkdir(const std::string &path) { if (!_mkdir(p)) return false; for (std::size_t i = 1; i < size; i++) { - p.append(OS_SEP).append(dirs[i]); + p.append(MYNTEYE_OS_SEP).append(dirs[i]); if (!_mkdir(p)) return false; } diff --git a/src/internal/times.h b/src/internal/times.h index 266973a..89457fd 100644 --- a/src/internal/times.h +++ b/src/internal/times.h @@ -186,7 +186,7 @@ inline std::string to_string( const system_clock::time_point &t, const std::tm *tm, const char *fmt = "%F %T", std::int32_t precision = 6) { std::stringstream ss; -#if defined(OS_ANDROID) || defined(OS_LINUX) +#if defined(MYNTEYE_OS_ANDROID) || defined(MYNTEYE_OS_LINUX) char foo[20]; strftime(foo, sizeof(foo), fmt, tm); ss << foo; diff --git a/src/uvc/uvc-libuvc.cc b/src/uvc/uvc-libuvc.cc index f2a9b92..7594579 100644 --- a/src/uvc/uvc-libuvc.cc +++ b/src/uvc/uvc-libuvc.cc @@ -113,13 +113,13 @@ int get_product_id(const device &device) { std::string get_name(const device &device) { // TODO(JohnZhao) - UNUSED(device) + MYNTEYE_UNUSED(device) return ""; } std::string get_video_name(const device &device) { // TODO(JohnZhao) - UNUSED(device) + MYNTEYE_UNUSED(device) return ""; } @@ -127,21 +127,21 @@ 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) + MYNTEYE_UNUSED(device) + MYNTEYE_UNUSED(option) + MYNTEYE_UNUSED(min) + MYNTEYE_UNUSED(max) + MYNTEYE_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) + MYNTEYE_UNUSED(device) + MYNTEYE_UNUSED(option) + MYNTEYE_UNUSED(query) + MYNTEYE_UNUSED(value) return false; } @@ -149,13 +149,13 @@ 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) + MYNTEYE_UNUSED(device) + MYNTEYE_UNUSED(xu) + MYNTEYE_UNUSED(selector) + MYNTEYE_UNUSED(id) + MYNTEYE_UNUSED(min) + MYNTEYE_UNUSED(max) + MYNTEYE_UNUSED(def) return false; } @@ -163,12 +163,12 @@ 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) + MYNTEYE_UNUSED(device) + MYNTEYE_UNUSED(xu) + MYNTEYE_UNUSED(selector) + MYNTEYE_UNUSED(query) + MYNTEYE_UNUSED(size) + MYNTEYE_UNUSED(data) return false; } @@ -176,23 +176,23 @@ 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) + MYNTEYE_UNUSED(device) + MYNTEYE_UNUSED(width) + MYNTEYE_UNUSED(height) + MYNTEYE_UNUSED(fourcc) + MYNTEYE_UNUSED(fps) + MYNTEYE_UNUSED(callback) } void start_streaming(device &device, int num_transfer_bufs) { // NOLINT // TODO(JohnZhao) - UNUSED(device) - UNUSED(num_transfer_bufs) + MYNTEYE_UNUSED(device) + MYNTEYE_UNUSED(num_transfer_bufs) } void stop_streaming(device &device) { // NOLINT // TODO(JohnZhao) - UNUSED(device) + MYNTEYE_UNUSED(device) } } // namespace uvc diff --git a/tools/dataset/dataset.cc b/tools/dataset/dataset.cc index 165473f..06e56c4 100644 --- a/tools/dataset/dataset.cc +++ b/tools/dataset/dataset.cc @@ -66,7 +66,7 @@ void Dataset::SaveStreamData( << std::endl; if (data.frame) { std::stringstream ss; - ss << writer->outdir << OS_SEP << std::dec + ss << writer->outdir << MYNTEYE_OS_SEP << std::dec << std::setw(IMAGE_FILENAME_WIDTH) << std::setfill('0') << seq << ".png"; cv::Mat img( data.frame->height(), data.frame->width(), CV_8UC1, data.frame->data()); @@ -94,15 +94,15 @@ Dataset::writer_t Dataset::GetStreamWriter(const Stream &stream) { writer_t writer = std::make_shared(); switch (stream) { case Stream::LEFT: { - writer->outdir = outdir_ + OS_SEP "left"; + writer->outdir = outdir_ + MYNTEYE_OS_SEP "left"; } break; case Stream::RIGHT: { - writer->outdir = outdir_ + OS_SEP "right"; + writer->outdir = outdir_ + MYNTEYE_OS_SEP "right"; } break; default: LOG(FATAL) << "Unsupported stream: " << stream; } - writer->outfile = writer->outdir + OS_SEP "stream.txt"; + writer->outfile = writer->outdir + MYNTEYE_OS_SEP "stream.txt"; files::mkdir(writer->outdir); writer->ofs.open(writer->outfile, std::ofstream::out); @@ -119,7 +119,7 @@ Dataset::writer_t Dataset::GetMotionWriter() { if (motion_writer_ == nullptr) { writer_t writer = std::make_shared(); writer->outdir = outdir_; - writer->outfile = writer->outdir + OS_SEP "motion.txt"; + writer->outfile = writer->outdir + MYNTEYE_OS_SEP "motion.txt"; files::mkdir(writer->outdir); writer->ofs.open(writer->outfile, std::ofstream::out); diff --git a/tools/writer/device_writer.cc b/tools/writer/device_writer.cc index 4a61001..3db0a26 100644 --- a/tools/writer/device_writer.cc +++ b/tools/writer/device_writer.cc @@ -208,19 +208,19 @@ void DeviceWriter::SaveAllInfos(const std::string &dir) { if (!files::mkdir(dir)) { LOG(FATAL) << "Create directory failed: " << dir; } - SaveDeviceInfo(*device_->GetInfo(), dir + OS_SEP "device.info"); + SaveDeviceInfo(*device_->GetInfo(), dir + MYNTEYE_OS_SEP "device.info"); SaveImgParams( {false, device_->GetIntrinsics(Stream::LEFT), device_->GetIntrinsics(Stream::RIGHT), device_->GetExtrinsics(Stream::RIGHT, Stream::LEFT)}, - dir + OS_SEP "img.params"); + dir + MYNTEYE_OS_SEP "img.params"); auto &&m_in = device_->GetMotionIntrinsics(); SaveImuParams( { false, m_in.accel, m_in.gyro, device_->GetMotionExtrinsics(Stream::LEFT), }, - dir + OS_SEP "imu.params"); + dir + MYNTEYE_OS_SEP "imu.params"); } namespace { diff --git a/tools/writer/save_all_infos.cc b/tools/writer/save_all_infos.cc index c67b5d4..3f484bd 100644 --- a/tools/writer/save_all_infos.cc +++ b/tools/writer/save_all_infos.cc @@ -32,7 +32,7 @@ int main(int argc, char *argv[]) { if (!device) return 1; - dir.append(OS_SEP "SN").append(device->GetInfo()->serial_number); + dir.append(MYNTEYE_OS_SEP "SN").append(device->GetInfo()->serial_number); tools::DeviceWriter writer(device); writer.SaveAllInfos(dir); From c6f195360fe300919d6e8e33dfe46c28c1084b85 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 11 Sep 2018 10:58:42 +0800 Subject: [PATCH 26/77] Change make install --- Makefile | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Makefile b/Makefile index 974617f..634466a 100644 --- a/Makefile +++ b/Makefile @@ -123,7 +123,11 @@ else @cd ./_build; make install endif else +ifeq ($(HOST_OS),Linux) @cd ./_build; sudo make install +else + @cd ./_build; make install +endif endif .PHONY: install From 0bcd3c02b9fbaa79e6ef92e91884b1b3c48a7908 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 11 Sep 2018 13:13:40 +0800 Subject: [PATCH 27/77] Fix miniglog on win --- include/mynteye/miniglog.h | 204 ++++++++++--------------------------- src/public/miniglog.cc | 6 +- src/public/miniglog.readme | 4 +- 3 files changed, 60 insertions(+), 154 deletions(-) diff --git a/include/mynteye/miniglog.h b/include/mynteye/miniglog.h index e267c69..1a4204f 100644 --- a/include/mynteye/miniglog.h +++ b/include/mynteye/miniglog.h @@ -1,6 +1,6 @@ // Ceres Solver - A fast non-linear least squares minimizer -// Copyright 2015 Google Inc. All rights reserved. -// http://ceres-solver.org/ +// Copyright 2013 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: @@ -100,46 +100,42 @@ #include #include -#include "mynteye/global.h" +#include "mynteye/mynteye.h" -#if defined(MYNTEYE_OS_ANDROID) -#include -#elif defined(MYNTEYE_OS_WIN) -#include -#else -#include -#include -#include +#ifdef MYNTEYE_OS_ANDROID +# include #endif // ANDROID -// For appropriate definition of CERES_EXPORT macro. -// Modified from ceres miniglog version [begin] ------------------------------- -//#include "ceres/internal/port.h" -//#include "ceres/internal/disable_warnings.h" -#define CERES_EXPORT -// Modified from ceres miniglog version [end] --------------------------------- - // Log severity level constants. +#ifndef ERROR // NOT windows.h const int FATAL = -3; const int ERROR = -2; const int WARNING = -1; const int INFO = 0; +#else +const int FATAL = -1; +// const int ERROR = 0; +const int WARNING = 1; +const int INFO = 2; +#endif // ------------------------- Glog compatibility ------------------------------ namespace google { typedef int LogSeverity; -const int INFO = ::INFO; -const int WARNING = ::WARNING; -const int ERROR = ::ERROR; const int FATAL = ::FATAL; +#ifndef ERROR // NOT windows.h +const int ERROR = ::ERROR; +#endif +const int WARNING = ::WARNING; +const int INFO = ::INFO; // Sink class used for integration with mock and test functions. If sinks are // added, all log output is also sent to each sink through the send function. // In this implementation, WaitTillSent() is called immediately after the send. // This implementation is not thread safe. -class CERES_EXPORT LogSink { +class MYNTEYE_API LogSink { public: virtual ~LogSink() {} virtual void send(LogSeverity severity, @@ -153,9 +149,12 @@ class CERES_EXPORT LogSink { }; // Global set of log sinks. The actual object is defined in logging.cc. -extern CERES_EXPORT std::set log_sinks_global; +MYNTEYE_API extern std::set log_sinks_global; -inline void InitGoogleLogging(char *argv) { +// Added by chachi - a runtime global maximum log level. Defined in logging.cc +MYNTEYE_API extern int log_severity_global; + +inline void InitGoogleLogging(char */*argv*/) { // Do nothing; this is ignored. } @@ -178,20 +177,20 @@ inline void RemoveLogSink(LogSink *sink) { // defined, output is directed to std::cerr. This class should not // be directly instantiated in code, rather it should be invoked through the // use of the log macros LG, LOG, or VLOG. -class CERES_EXPORT MessageLogger { +class MYNTEYE_API MessageLogger { public: MessageLogger(const char *file, int line, const char *tag, int severity) : file_(file), line_(line), tag_(tag), severity_(severity) { // Pre-pend the stream with the file and line number. StripBasename(std::string(file), &filename_only_); - stream_ << filename_only_ << ":" << line << " "; + stream_ << SeverityLabel() << "/" << filename_only_ << ":" << line << " "; } // Output the contents of the stream to the proper channel on destruction. ~MessageLogger() { stream_ << "\n"; -#if defined(MYNTEYE_OS_ANDROID) +#ifdef MYNTEYE_OS_ANDROID static const int android_log_levels[] = { ANDROID_LOG_FATAL, // LOG(FATAL) ANDROID_LOG_ERROR, // LOG(ERROR) @@ -217,34 +216,9 @@ class CERES_EXPORT MessageLogger { "terminating.\n"); } #else - // For Ubuntu/Mac/Windows // If not building on Android, log all output to std::cerr. - // Get timestamp - timeval curTime; - gettimeofday(&curTime, NULL); - int milli = curTime.tv_usec / 1000; - char buffer [20]; - strftime(buffer, 80, "%m-%d %H:%M:%S", localtime(&curTime.tv_sec)); - char time_cstr[24] = ""; - sprintf(time_cstr, "%s:%d ", buffer, milli); - // Get pid & tid - char tid_cstr[24] = ""; - pid_t pid = getpid(); - pthread_t tid = pthread_self(); - sprintf(tid_cstr, "%d/%u ", pid, tid); - if (severity_ == FATAL) { - // Magenta color if fatal - std::cerr << "\033[1;35m"<< tid_cstr << time_cstr << SeverityLabelStr() << stream_.str() << "\033[0m"; - } else if (severity_ == ERROR) { - // Red color if error - std::cerr << "\033[1;31m"<< tid_cstr << time_cstr << SeverityLabelStr() << stream_.str() << "\033[0m"; - } else if (severity_ == WARNING) { - // Yellow color if warning - std::cerr << "\033[1;33m"<< tid_cstr << time_cstr << SeverityLabelStr() << stream_.str() << "\033[0m"; - } else { - std::cerr << tid_cstr << time_cstr << SeverityLabelStr() << stream_.str(); - } -#endif + std::cerr << stream_.str(); +#endif // ANDROID LogToSinks(severity_); WaitForSinks(); @@ -262,23 +236,16 @@ class CERES_EXPORT MessageLogger { private: void LogToSinks(int severity) { time_t rawtime; + struct tm* timeinfo; + time (&rawtime); - - struct tm timeinfo; -#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) - // On Windows, use secure localtime_s not localtime. - localtime_s(&timeinfo, &rawtime); -#else - // On non-Windows systems, use threadsafe localtime_r not localtime. - localtime_r(&rawtime, &timeinfo); -#endif - + timeinfo = localtime(&rawtime); std::set::iterator iter; // Send the log message to all sinks. for (iter = google::log_sinks_global.begin(); iter != google::log_sinks_global.end(); ++iter) { (*iter)->send(severity, file_.c_str(), filename_only_.c_str(), line_, - &timeinfo, stream_.str().c_str(), stream_.str().size()); + timeinfo, stream_.str().c_str(), stream_.str().size()); } } @@ -306,34 +273,19 @@ class CERES_EXPORT MessageLogger { char SeverityLabel() { switch (severity_) { - case FATAL: - return 'F'; - case ERROR: - return 'E'; - case WARNING: - return 'W'; case INFO: return 'I'; + case WARNING: + return 'W'; + case ERROR: + return 'E'; + case FATAL: + return 'F'; default: return 'V'; } } - std::string SeverityLabelStr() { - switch (severity_) { - case FATAL: - return "FATAL "; - case ERROR: - return "ERROR "; - case WARNING: - return "WARNING "; - case INFO: - return "INFO "; - default: - return "VERBOSE "; - } - } - std::string file_; std::string filename_only_; int line_; @@ -347,18 +299,19 @@ class CERES_EXPORT MessageLogger { // This class is used to explicitly ignore values in the conditional // logging macros. This avoids compiler warnings like "value computed // is not used" and "statement has no effect". -class CERES_EXPORT LoggerVoidify { +class MYNTEYE_API LoggerVoidify { public: LoggerVoidify() { } // This has to be an operator with a precedence lower than << but // higher than ?: - void operator&(const std::ostream &s) { } + void operator&(const std::ostream &/*s*/) { } }; // Log only if condition is met. Otherwise evaluates to void. #define LOG_IF(severity, condition) \ - !(condition) ? (void) 0 : LoggerVoidify() & \ - MessageLogger((char *)__FILE__, __LINE__, "native", severity).stream() + (static_cast(severity) > google::log_severity_global || !(condition)) ? \ + (void) 0 : LoggerVoidify() & \ + MessageLogger((char *)__FILE__, __LINE__, "native", severity).stream() // Log only if condition is NOT met. Otherwise evaluates to void. #define LOG_IF_FALSE(severity, condition) LOG_IF(severity, !(condition)) @@ -367,14 +320,15 @@ class CERES_EXPORT LoggerVoidify { // google3 code is discouraged and the following shortcut exists for // backward compatibility with existing code. #ifdef MYNTEYE_MAX_LOG_LEVEL -# define LOG(n) LOG_IF(n, n <= MYNTEYE_MAX_LOG_LEVEL) -# define VLOG(n) LOG_IF(n, n <= MYNTEYE_MAX_LOG_LEVEL) -# define LG LOG_IF(INFO, INFO <= MYNTEYE_MAX_LOG_LEVEL) -# define VLOG_IF(n, condition) LOG_IF(n, (n <= MYNTEYE_MAX_LOG_LEVEL) && condition) +# define LOG(n) LOG_IF(n, (n <= MYNTEYE_MAX_LOG_LEVEL)) +# define VLOG(n) LOG_IF(n, (n <= MYNTEYE_MAX_LOG_LEVEL)) +# define LG LOG_IF(INFO, (INFO <= MYNTEYE_MAX_LOG_LEVEL)) +# define VLOG_IF(n, condition) \ + LOG_IF(n, (n <= MYNTEYE_MAX_LOG_LEVEL) && condition) #else -# define LOG(n) MessageLogger((char *)__FILE__, __LINE__, "native", n).stream() // NOLINT -# define VLOG(n) MessageLogger((char *)__FILE__, __LINE__, "native", n).stream() // NOLINT -# define LG MessageLogger((char *)__FILE__, __LINE__, "native", INFO).stream() // NOLINT +# define LOG(n) LOG_IF(n, true) +# define VLOG(n) LOG_IF(n, true) +# define LG LOG_IF(INFO, true) # define VLOG_IF(n, condition) LOG_IF(n, condition) #endif @@ -396,8 +350,7 @@ class CERES_EXPORT LoggerVoidify { // Log a message and terminate. template void LogMessageFatal(const char *file, int line, const T &message) { - MessageLogger((char *)__FILE__, __LINE__, "native", FATAL).stream() - << message; + MessageLogger(file, line, "native", FATAL).stream() << message; } // ---------------------------- CHECK macros --------------------------------- @@ -420,7 +373,7 @@ void LogMessageFatal(const char *file, int line, const T &message) { // Generic binary operator check macro. This should not be directly invoked, // instead use the binary comparison macros defined below. -#define CHECK_OP(val1, val2, op) LOG_IF_FALSE(FATAL, ((val1) op (val2))) \ +#define CHECK_OP(val1, val2, op) LOG_IF_FALSE(FATAL, (val1 op val2)) \ << "Check failed: " #val1 " " #op " " #val2 " " // Check_op macro definitions @@ -431,15 +384,6 @@ void LogMessageFatal(const char *file, int line, const T &message) { #define CHECK_GE(val1, val2) CHECK_OP(val1, val2, >=) #define CHECK_GT(val1, val2) CHECK_OP(val1, val2, >) -// qiao.helloworld@gmail.com /tzu.ta.lin@gmail.com add -// Add logging macros which are missing in glog or are not accessible for -// whatever reason. -#define CHECK_NEAR(val1, val2, margin) \ - do { \ - CHECK_LE((val1), (val2)+(margin)); \ - CHECK_GE((val1), (val2)-(margin)); \ - } while (0) - #ifndef NDEBUG // Debug only versions of CHECK_OP macros. # define DCHECK_EQ(val1, val2) CHECK_OP(val1, val2, ==) @@ -448,8 +392,6 @@ void LogMessageFatal(const char *file, int line, const T &message) { # define DCHECK_LT(val1, val2) CHECK_OP(val1, val2, <) # define DCHECK_GE(val1, val2) CHECK_OP(val1, val2, >=) # define DCHECK_GT(val1, val2) CHECK_OP(val1, val2, >) -// qiao.helloworld@gmail.com /tzu.ta.lin@gmail.com add -# define DCHECK_NEAR(val1, val2, margin) CHECK_NEAR(val1, val2, margin) #else // These versions generate no code in optimized mode. # define DCHECK_EQ(val1, val2) if (false) CHECK_OP(val1, val2, ==) @@ -458,8 +400,6 @@ void LogMessageFatal(const char *file, int line, const T &message) { # define DCHECK_LT(val1, val2) if (false) CHECK_OP(val1, val2, <) # define DCHECK_GE(val1, val2) if (false) CHECK_OP(val1, val2, >=) # define DCHECK_GT(val1, val2) if (false) CHECK_OP(val1, val2, >) -// qiao.helloworld@gmail.com /tzu.ta.lin@gmail.com add -# define DCHECK_NEAR(val1, val2, margin) if (false) CHECK_NEAR(val1, val2, margin) #endif // NDEBUG // ---------------------------CHECK_NOTNULL macros --------------------------- @@ -498,42 +438,4 @@ T& CheckNotNull(const char *file, int line, const char *names, T& t) { CheckNotNull(__FILE__, __LINE__, "'" #val "' Must be non NULL", (val)) #endif // NDEBUG -// Modified from ceres miniglog version [begin] ------------------------------- -//#include "ceres/internal/reenable_warnings.h" -// Modified from ceres miniglog version [end] --------------------------------- - - -// ---------------------------TRACE macros --------------------------- -// qiao.helloworld@gmail.com /tzu.ta.lin@gmail.com add -#define __FILENAME__ \ - (strrchr(__FILE__, '/') ? strrchr(__FILE__, '/') + 1 : __FILE__) - -#define DEXEC(fn) \ - do { \ - DLOG(INFO) << "[EXEC " << #fn << " START]"; \ - std::chrono::steady_clock::time_point begin = \ - std::chrono::steady_clock::now(); \ - fn; \ - std::chrono::steady_clock::time_point end = \ - std::chrono::steady_clock::now(); \ - DLOG(INFO) << "[EXEC " << #fn << " FINISHED in " \ - << std::chrono::duration_cast \ - (end - begin).count() << " ms]"; \ - } while (0); -// DEXEC(fn) -// -// Usage: -// DEXEC(foo()); -// -- output -- -// foo.cpp: 123 [EXEC foo() START] -// foo.cpp: 123 [EXEC foo() FINISHED in 456 ms] - -#define DTRACE DLOG(INFO) << "of [" << __func__ << "]"; -// Usage: -// void foo() { -// DTRACE -// } -// -- output -- -// foo.cpp: 123 of [void foo(void)] - #endif // MYNTEYE_MINIGLOG_H_ diff --git a/src/public/miniglog.cc b/src/public/miniglog.cc index 23a2c32..0bda4be 100644 --- a/src/public/miniglog.cc +++ b/src/public/miniglog.cc @@ -1,6 +1,6 @@ // Ceres Solver - A fast non-linear least squares minimizer -// Copyright 2015 Google Inc. All rights reserved. -// http://ceres-solver.org/ +// 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: @@ -36,4 +36,6 @@ namespace google { // that there is only one instance of this across the entire program. std::set log_sinks_global; +int log_severity_global(INFO); + } // namespace google diff --git a/src/public/miniglog.readme b/src/public/miniglog.readme index 9ce8c89..e10b189 100644 --- a/src/public/miniglog.readme +++ b/src/public/miniglog.readme @@ -1 +1,3 @@ -miniglog: https://github.com/tzutalin/miniglog +miniglog: + * https://github.com/arpg/miniglog + * https://github.com/tzutalin/miniglog From a26dbec7b1237a346c9f44438e813909d489bc4c Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 11 Sep 2018 13:36:55 +0800 Subject: [PATCH 28/77] Fix log level & strip basename --- include/mynteye/miniglog.h | 42 +++++++++++++++++++++++++++++++------- 1 file changed, 35 insertions(+), 7 deletions(-) diff --git a/include/mynteye/miniglog.h b/include/mynteye/miniglog.h index 1a4204f..02d377a 100644 --- a/include/mynteye/miniglog.h +++ b/include/mynteye/miniglog.h @@ -107,16 +107,22 @@ #endif // ANDROID // Log severity level constants. +#ifdef MYNTEYE_OS_WIN + +const int FATAL = -1; #ifndef ERROR // NOT windows.h +const int ERROR = 0; +#endif +const int WARNING = 1; +const int INFO = 2; + +#else + const int FATAL = -3; const int ERROR = -2; const int WARNING = -1; const int INFO = 0; -#else -const int FATAL = -1; -// const int ERROR = 0; -const int WARNING = 1; -const int INFO = 2; + #endif // ------------------------- Glog compatibility ------------------------------ @@ -262,8 +268,8 @@ class MYNTEYE_API MessageLogger { void StripBasename(const std::string &full_path, std::string *filename) { // TODO(settinger): Add support for OSs with different path separators. - const char kSeparator = '/'; - size_t pos = full_path.rfind(kSeparator); + // const char kSeparator = '/'; + size_t pos = full_path.rfind(MYNTEYE_OS_SEP); if (pos != std::string::npos) { *filename = full_path.substr(pos + 1, std::string::npos); } else { @@ -339,6 +345,28 @@ class MYNTEYE_API LoggerVoidify { # define VLOG_IS_ON(x) (x <= MYNTEYE_MAX_LOG_LEVEL) #endif +#ifdef MYNTEYE_OS_WIN // INFO is 2, change VLOG(2) to VLOG(4) +#undef VLOG +#undef VLOG_IF +#undef VLOG_IS_ON + +#ifdef MYNTEYE_MAX_LOG_LEVEL +# define VLOG(n) LOG_IF(n+2, (n+2 <= MYNTEYE_MAX_LOG_LEVEL)) +# define VLOG_IF(n, condition) \ + LOG_IF(n+2, (n+2 <= MYNTEYE_MAX_LOG_LEVEL) && condition) +#else +# define VLOG(n) LOG_IF(n+2, true) +# define VLOG_IF(n, condition) LOG_IF(n+2, condition) +#endif + +#ifndef MYNTEYE_MAX_LOG_LEVEL +# define VLOG_IS_ON(x) (1+2) +#else +# define VLOG_IS_ON(x) (x+2 <= MYNTEYE_MAX_LOG_LEVEL) +#endif + +#endif + #ifndef NDEBUG # define DLOG LOG #else From 2ae3116f0d6efbd4fe0a305e215366310d6f22ad Mon Sep 17 00:00:00 2001 From: John Zhao Date: Wed, 26 Sep 2018 16:01:47 +0800 Subject: [PATCH 29/77] Update doc version --- doc/en/api.doxyfile | 2 +- doc/zh-Hans/api.doxyfile | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/doc/en/api.doxyfile b/doc/en/api.doxyfile index c4dcd32..49b790d 100644 --- a/doc/en/api.doxyfile +++ b/doc/en/api.doxyfile @@ -38,7 +38,7 @@ PROJECT_NAME = "MYNT EYE SDK" # could be handy for archiving the generated documentation or if some version # control system is used. -PROJECT_NUMBER = 2.0.1-rc1 +PROJECT_NUMBER = 2.0.1-rc2 # 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 ac8ccb5..5244c89 100644 --- a/doc/zh-Hans/api.doxyfile +++ b/doc/zh-Hans/api.doxyfile @@ -38,7 +38,7 @@ PROJECT_NAME = "MYNT EYE SDK" # could be handy for archiving the generated documentation or if some version # control system is used. -PROJECT_NUMBER = 2.0.1-rc1 +PROJECT_NUMBER = 2.0.1-rc2 # 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 From 6435bf04a2a0be77dfc91f54693359be464b2056 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Thu, 27 Sep 2018 09:31:42 +0800 Subject: [PATCH 30/77] Fix generate apidoc --- Makefile | 3 ++- doc/en/api.doxyfile | 5 +++-- doc/zh-Hans/api.doxyfile | 5 +++-- 3 files changed, 8 insertions(+), 5 deletions(-) diff --git a/Makefile b/Makefile index 634466a..d53de50 100644 --- a/Makefile +++ b/Makefile @@ -49,7 +49,8 @@ all: test samples tools apidoc: @$(call echo,Make $@) - @[ -e ./_install/include ] || $(MAKE) install + @# @[ -e ./_install/include ] || $(MAKE) install + @[ -e /usr/local/include/mynteye ] || $(MAKE) install @$(SH) ./doc/build.sh opendoc: apidoc diff --git a/doc/en/api.doxyfile b/doc/en/api.doxyfile index 49b790d..dba062c 100644 --- a/doc/en/api.doxyfile +++ b/doc/en/api.doxyfile @@ -801,7 +801,7 @@ INPUT = mainpage.md \ specs_ctrl.md \ spec_control_api.md \ spec_control_channel.md \ - ../../_install/include + /usr/local/include/mynteye # This tag can be used to specify the character encoding of the source files # that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses @@ -884,7 +884,8 @@ RECURSIVE = YES # Note that relative paths are relative to the directory from which doxygen is # run. -EXCLUDE = +EXCLUDE = /usr/local/include/mynteye/logger.h \ + /usr/local/include/mynteye/miniglog.h # The EXCLUDE_SYMLINKS tag can be used to select whether or not files or # directories that are symbolic links (a Unix file system feature) are excluded diff --git a/doc/zh-Hans/api.doxyfile b/doc/zh-Hans/api.doxyfile index 5244c89..f58d65d 100644 --- a/doc/zh-Hans/api.doxyfile +++ b/doc/zh-Hans/api.doxyfile @@ -801,7 +801,7 @@ INPUT = mainpage.md \ specs_ctrl.md \ spec_control_api.md \ spec_control_channel.md \ - ../../_install/include + /usr/local/include/mynteye # This tag can be used to specify the character encoding of the source files # that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses @@ -884,7 +884,8 @@ RECURSIVE = YES # Note that relative paths are relative to the directory from which doxygen is # run. -EXCLUDE = +EXCLUDE = /usr/local/include/mynteye/logger.h \ + /usr/local/include/mynteye/miniglog.h # The EXCLUDE_SYMLINKS tag can be used to select whether or not files or # directories that are symbolic links (a Unix file system feature) are excluded From 12f5a8f3ccc73b2bb77a0139855625f3b0e948e1 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Thu, 27 Sep 2018 09:56:17 +0800 Subject: [PATCH 31/77] Update README.md --- README.md | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/README.md b/README.md index 762044c..9da2d38 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ # MYNT® EYE SDK -[![](https://img.shields.io/badge/MYNT%20EYE%20SDK-2.0.1--rc1-brightgreen.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2) +[![](https://img.shields.io/badge/MYNT%20EYE%20SDK-2.0.1--rc2-brightgreen.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2) ## Overview @@ -17,12 +17,11 @@ Please follow the guide doc to install the SDK on different platforms. ## Documentations * [API Doc](https://github.com/slightech/MYNT-EYE-SDK-2/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-SDK-2/files/2285351/mynt-eye-sdk-apidoc-2.0.1-rc1-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2285352/mynt-eye-sdk-apidoc-2.0.1-rc1-html-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-SDK-2/) - * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2285353/mynt-eye-sdk-apidoc-2.0.1-rc1-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2285354/mynt-eye-sdk-apidoc-2.0.1-rc1-html-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/api/mynt-eye-sdk-apidoc-2.0.1-rc1-html-zh-Hans/mynt-eye-sdk-apidoc-2.0.1-rc1-html-zh-Hans/index.html) + * en: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2422149/mynt-eye-sdk-apidoc-2.0.1-rc2-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2422151/mynt-eye-sdk-apidoc-2.0.1-rc2-html-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-SDK-2/) + * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2422152/mynt-eye-sdk-apidoc-2.0.1-rc2-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2422153/mynt-eye-sdk-apidoc-2.0.1-rc2-html-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/api/mynt-eye-sdk-apidoc-2.0.1-rc2-html-zh-Hans/mynt-eye-sdk-apidoc-2.0.1-rc2-html-zh-Hans/index.html) * [Guide Doc](https://github.com/slightech/MYNT-EYE-SDK-2-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-SDK-2-Guide/files/2281782/mynt-eye-sdk-guide-2.0.1-rc1-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2281783/mynt-eye-sdk-guide-2.0.1-rc1-html-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-SDK-2-Guide/) - * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2281785/mynt-eye-sdk-guide-2.0.1-rc1-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2281786/mynt-eye-sdk-guide-2.0.1-rc1-html-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/sdk/mynt-eye-sdk-guide-2.0.1-rc1-html-zh-Hans/mynt-eye-sdk-guide-2.0.1-rc1-html-zh-Hans/index.html) - + * en: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2422160/mynt-eye-sdk-guide-2.0.1-rc2-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2422161/mynt-eye-sdk-guide-2.0.1-rc2-html-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-SDK-2-Guide/) + * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2422162/mynt-eye-sdk-guide-2.0.1-rc2-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2422164/mynt-eye-sdk-guide-2.0.1-rc2-html-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/sdk/mynt-eye-sdk-guide-2.0.1-rc2-html-zh-Hans/mynt-eye-sdk-guide-2.0.1-rc2-html-zh-Hans/index.html) > Supported languages: `en`, `zh-Hans`. From 204fff217539f9875a11e078d4716b08e124f589 Mon Sep 17 00:00:00 2001 From: kalman Date: Wed, 17 Oct 2018 10:59:50 +0800 Subject: [PATCH 32/77] Update device.info,img.params and imu params --- tools/writer/config/device.info | 2 +- tools/writer/config/img.params | 60 ++++++++++++++++----------------- tools/writer/config/imu.params | 18 +++++----- 3 files changed, 40 insertions(+), 40 deletions(-) diff --git a/tools/writer/config/device.info b/tools/writer/config/device.info index 5016ecc..815923b 100644 --- a/tools/writer/config/device.info +++ b/tools/writer/config/device.info @@ -2,7 +2,7 @@ --- device_name: MYNT-EYE-S1000 serial_number: "0386322C0009070E" -firmware_version: "2.0" +firmware_version: "2.2" hardware_version: "2.0" spec_version: "1.0" lens_type: "0000" diff --git a/tools/writer/config/img.params b/tools/writer/config/img.params index a97b2e0..bb5fbce 100644 --- a/tools/writer/config/img.params +++ b/tools/writer/config/img.params @@ -1,32 +1,32 @@ %YAML:1.0 --- -in_left: - - - width: 752 - height: 480 - fx: 7.3638305001095546e+02 - fy: 7.2350066150722432e+02 - cx: 3.5691961817119693e+02 - cy: 2.1727271340923883e+02 - model: 0 - coeffs: [ -5.4898645145016478e-01, 5.2837141203888638e-01, 0., 0., - 0. ] -in_right: - - - width: 752 - height: 480 - fx: 7.3638305001095546e+02 - fy: 7.2350066150722432e+02 - cx: 4.5668367112303980e+02 - cy: 2.5070083335536796e+02 - model: 0 - coeffs: [ -5.1012886039889305e-01, 3.8764476500996770e-01, 0., 0., - 0. ] -ex_right_to_left: - rotation: [ 9.9701893306553813e-01, -9.5378124886236681e-04, - -7.7151392794850615e-02, 1.4493996762830500e-03, - 9.9997867219985104e-01, 6.3682325649414354e-03, - 7.7143673424555026e-02, -6.4610716411527686e-03, - 9.9699905125522237e-01 ] - translation: [ -1.1888991734400047e+02, -4.5605803870530912e-02, - -3.9531373691193386e+00 ] +M1: !!opencv-matrix + rows: 3 + cols: 3 + dt: d + data: [7.0580528313369666e+02, 0.0000000000000000e+00, 3.9948998919893694e+02, 0.0000000000000000e+00, 7.0575619835820726e+02, 2.4787289482695121e+02, 0.0000000000000000e+00, 0.0000000000000000e+00, 1.0000000000000000e+00] +D1: !!opencv-matrix + rows: 1 + cols: 5 + dt: d + data: [-4.6552404514131829e-01, 2.3785911744625499e-01, 7.1382174731459054e-04, -9.0521175159124524e-04, 0.0000000000000000e+00] +M2: !!opencv-matrix + rows: 3 + cols: 3 + dt: d + data: [7.0873956955525932e+02, 0.0000000000000000e+00, 3.8004681343447817e+02, 0.0000000000000000e+00, 7.0823391571075069e+02, 2.3111368468836466e+02, 0.0000000000000000e+00, 0.0000000000000000e+00, 1.0000000000000000e+00] +D2: !!opencv-matrix + rows: 1 + cols: 5 + dt: d + data: [-4.5938049437344691e-01, 2.0968051724034908e-01, 1.1071355339345569e-03, -6.2121270120321431e-04, 0.0000000000000000e+00] +R: !!opencv-matrix + rows: 3 + cols: 3 + dt: d + data: [9.9999877906799961e-01, 1.5267382378091109e-03, 3.3306585441506117e-04, -1.5281619167571623e-03, 9.9998951436316075e-01, 4.3169300302323549e-03, -3.2647153986033672e-04, -4.3174337381088283e-03, 9.9999062654719451e-01] +T: !!opencv-matrix + rows: 3 + cols: 1 + dt: d + data: [-1.2079697095106799e+02, 3.5210975863837529e-01, 1.0200361378962297e-01] diff --git a/tools/writer/config/imu.params b/tools/writer/config/imu.params index 070f13a..b80f2c4 100644 --- a/tools/writer/config/imu.params +++ b/tools/writer/config/imu.params @@ -1,15 +1,15 @@ %YAML:1.0 --- in_accel: - scale: [ 0., 0., 0., 0., 0., 0., 0., 0., 0. ] - drift: [ 0., 0., 0. ] - noise: [ 0., 0., 0. ] - bias: [ 0., 0., 0. ] + scale: [ 1., 0., 0., 0., 1., 0., 0., 0., 1. ] + drift: [ 0.0, 0.0, 0.0 ] + noise: [ 0.016925432397973516, 0.016735310195561025, 0.017452487504590969 ] + bias: [ 0.00019031356589714596, 0.00016996777864587261, 0.00054490537096493644 ] in_gyro: - scale: [ 0., 0., 0., 0., 0., 0., 0., 0., 0. ] + scale: [ 1., 0., 0., 0., 1., 0., 0., 0., 1. ] drift: [ 0., 0., 0. ] - noise: [ 0., 0., 0. ] - bias: [ 0., 0., 0. ] + noise: [ 0.0010848026158819934, 0.0012466367883501759, 0.0011003229919806443 ] + bias: [ 0.000023404834136742844, 0.000023596771567764949, 0.000014970418056326829 ] ex_left_to_imu: - rotation: [ 0., 0., 0., 0., 0., 0., 0., 0., 0. ] - translation: [ 0., 0., 0. ] + rotation: [ -0.0064662, -0.99994994, -0.00763565, 0.99997909, -0.00646566, -0.00009558, 0.0000462, -0.00763611, 0.99997084 ] + translation: [ 0.00533646, -0.04302922, 0.02303124 ] From 1f96a6ee29e1dc6facdd322780dec03ba5697347 Mon Sep 17 00:00:00 2001 From: kalman Date: Wed, 17 Oct 2018 11:12:40 +0800 Subject: [PATCH 33/77] Add frame rate 60 --- doc/en/spec_control_api.md | 2 +- doc/zh-Hans/spec_control_api.md | 2 +- include/mynteye/types.h | 2 +- samples/tutorials/control/framerate.cc | 2 +- src/internal/channels.cc | 2 +- src/public/utils.cc | 3 +++ wrappers/python/samples/mynteye.py | 2 +- wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch | 2 +- 8 files changed, 10 insertions(+), 7 deletions(-) diff --git a/doc/en/spec_control_api.md b/doc/en/spec_control_api.md index 46d2366..249613b 100644 --- a/doc/en/spec_control_api.md +++ b/doc/en/spec_control_api.md @@ -14,7 +14,7 @@ There are two control modes, one is through UVC standard protocol, the other is | Name | Field | Bytes | Default | Min | Max | Stored | Flash Address | Channel | Note | | :--- | :---- | :---- | :------ | :-- | :-- | :----- | :------------ | :------ | :----- | -| Frame rate | frame_rate | 2 | 25 | 10 | √ | 0x21 | XU_CAM_CTRL | values: {10,15,20,25,30,35,40,45,50,55} | +| Frame rate | frame_rate | 2 | 25 | 10 | √ | 0x21 | XU_CAM_CTRL | values: {10,15,20,25,30,35,40,45,50,55,60} | | IMU frequency | imu_frequency | 2 | 200 | 100 | 500 | √ | 0x23 | XU_CAM_CTRL | values: {100,200,250,333,500} | | Exposure mode | exposure_mode | 1 | 0 | 0 | 1 | √ | 0x0F | XU_CAM_CTRL | 0: enable auto-exposure; 1: manual-exposure | | Max gain | max_gain | 2 | 48 | 0 | 48 | √ | 0x1D | XU_CAM_CTRL | valid if auto-exposure | diff --git a/doc/zh-Hans/spec_control_api.md b/doc/zh-Hans/spec_control_api.md index 9c3bea1..d1c9601 100644 --- a/doc/zh-Hans/spec_control_api.md +++ b/doc/zh-Hans/spec_control_api.md @@ -16,7 +16,7 @@ | 名称 | 字段 | 字节数 | 默认值 | 最小值 | 最大值 | 是否储存 | Flash 地址 | 所属通道 | 说明 | | :----- | :----- | :-------- | :-------- | :-------- | :-------- | :----------- | :----------- | :----------- | :----- | -| 图像帧率 | frame_rate | 2 | 25 | 10 | √ | 0x21 | XU_CAM_CTRL | 步进为5,即有效值为{10,15,20,25,30,35,40,45,50,55} | +| 图像帧率 | frame_rate | 2 | 25 | 10 | √ | 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 | 开始自动曝光,可设定的阈值 | diff --git a/include/mynteye/types.h b/include/mynteye/types.h index 51a8e40..0ab79fd 100644 --- a/include/mynteye/types.h +++ b/include/mynteye/types.h @@ -144,7 +144,7 @@ enum class Option : std::uint8_t { /** * Image frame rate, must set IMU_FREQUENCY together * - * values: {10,15,20,25,30,35,40,45,50,55}, default: 25 + * values: {10,15,20,25,30,35,40,45,50,55,60}, default: 25 */ FRAME_RATE, /** diff --git a/samples/tutorials/control/framerate.cc b/samples/tutorials/control/framerate.cc index 6a16a19..a6ab3b3 100644 --- a/samples/tutorials/control/framerate.cc +++ b/samples/tutorials/control/framerate.cc @@ -29,7 +29,7 @@ int main(int argc, char *argv[]) { // 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 + // 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); diff --git a/src/internal/channels.cc b/src/internal/channels.cc index 2c3fd8d..68bd2b6 100644 --- a/src/internal/channels.cc +++ b/src/internal/channels.cc @@ -224,7 +224,7 @@ void Channels::SetControlValue(const Option &option, std::int32_t value) { } break; case Option::FRAME_RATE: { if (!in_range() || - !in_values({10, 15, 20, 25, 30, 35, 40, 45, 50, 55})) + !in_values({10, 15, 20, 25, 30, 35, 40, 45, 50, 55, 60})) break; XuCamCtrlSet(option, value); } break; diff --git a/src/public/utils.cc b/src/public/utils.cc index 36ba8ff..566a389 100644 --- a/src/public/utils.cc +++ b/src/public/utils.cc @@ -100,6 +100,9 @@ float get_real_exposure_time( case 55: real_max = 16.325; break; + case 60: + real_max = 15; + break; default: LOG(ERROR) << "Invalid frame rate: " << frame_rate; return exposure_time; diff --git a/wrappers/python/samples/mynteye.py b/wrappers/python/samples/mynteye.py index 608787b..1e70f75 100644 --- a/wrappers/python/samples/mynteye.py +++ b/wrappers/python/samples/mynteye.py @@ -99,7 +99,7 @@ def main(): # set_option_value def set_rate(frame_rate=25, imu_frequency=500): # pylint: disable=unused-variable - # FRAME_RATE values: 10, 15, 20, 25, 30, 35, 40, 45, 50, 55 + # FRAME_RATE values: 10, 15, 20, 25, 30, 35, 40, 45, 50, 55, 60 api.set_option_value(mynteye.FRAME_RATE, frame_rate) # IMU_FREQUENCY values: 100, 200, 250, 333, 500 api.set_option_value(mynteye.IMU_FREQUENCY, imu_frequency) diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch b/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch index 0b3679a..2ef423d 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch @@ -54,7 +54,7 @@ - + From 4d644a1d712b4000be0b39fe4d2e3d0df39045f1 Mon Sep 17 00:00:00 2001 From: kalman Date: Thu, 18 Oct 2018 15:11:21 +0800 Subject: [PATCH 34/77] Update img.params --- tools/writer/config/img.params | 60 +++++++++++++++++----------------- 1 file changed, 30 insertions(+), 30 deletions(-) diff --git a/tools/writer/config/img.params b/tools/writer/config/img.params index bb5fbce..1384e3e 100644 --- a/tools/writer/config/img.params +++ b/tools/writer/config/img.params @@ -1,32 +1,32 @@ %YAML:1.0 --- -M1: !!opencv-matrix - rows: 3 - cols: 3 - dt: d - data: [7.0580528313369666e+02, 0.0000000000000000e+00, 3.9948998919893694e+02, 0.0000000000000000e+00, 7.0575619835820726e+02, 2.4787289482695121e+02, 0.0000000000000000e+00, 0.0000000000000000e+00, 1.0000000000000000e+00] -D1: !!opencv-matrix - rows: 1 - cols: 5 - dt: d - data: [-4.6552404514131829e-01, 2.3785911744625499e-01, 7.1382174731459054e-04, -9.0521175159124524e-04, 0.0000000000000000e+00] -M2: !!opencv-matrix - rows: 3 - cols: 3 - dt: d - data: [7.0873956955525932e+02, 0.0000000000000000e+00, 3.8004681343447817e+02, 0.0000000000000000e+00, 7.0823391571075069e+02, 2.3111368468836466e+02, 0.0000000000000000e+00, 0.0000000000000000e+00, 1.0000000000000000e+00] -D2: !!opencv-matrix - rows: 1 - cols: 5 - dt: d - data: [-4.5938049437344691e-01, 2.0968051724034908e-01, 1.1071355339345569e-03, -6.2121270120321431e-04, 0.0000000000000000e+00] -R: !!opencv-matrix - rows: 3 - cols: 3 - dt: d - data: [9.9999877906799961e-01, 1.5267382378091109e-03, 3.3306585441506117e-04, -1.5281619167571623e-03, 9.9998951436316075e-01, 4.3169300302323549e-03, -3.2647153986033672e-04, -4.3174337381088283e-03, 9.9999062654719451e-01] -T: !!opencv-matrix - rows: 3 - cols: 1 - dt: d - data: [-1.2079697095106799e+02, 3.5210975863837529e-01, 1.0200361378962297e-01] +in_left: + - + width: 752 + height: 480 + fx: 3.6220059643202876e+02 + fy: 3.6350065250745848e+02 + cx: 4.0658699068023441e+02 + cy: 2.3435161110061483e+02 + model: 0 + coeffs: [ -2.5034765682756088e-01, 5.0579399202897619e-02, + -7.0536676161976066e-04, -8.5255451307033846e-03, 0. ] +in_right: + - + width: 752 + height: 480 + fx: 3.6514014888558478e+02 + fy: 3.6513385298966961e+02 + cx: 3.8932395100630907e+02 + cy: 2.3495160212312547e+02 + model: 0 + coeffs: [ -3.0377346762098512e-01, 7.9929693673999838e-02, + 5.1547517530716883e-05, -6.7345903740579250e-04, 0. ] +ex_right_to_left: + 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 ] From 721ad22b0ae44965e65efd4a65cfb669cfadb864 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Mon, 22 Oct 2018 22:18:22 +0800 Subject: [PATCH 35/77] Update version --- CMakeLists.txt | 2 +- doc/build.sh | 18 ++++++++++++++++-- doc/en/api.doxyfile | 2 +- doc/en/spec_control_api.md | 2 +- doc/zh-Hans/api.doxyfile | 2 +- doc/zh-Hans/spec_control_api.md | 2 +- 6 files changed, 21 insertions(+), 7 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index d811781..865aad5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,7 +14,7 @@ cmake_minimum_required(VERSION 3.0) -project(mynteye VERSION 2.0.1 LANGUAGES C CXX) +project(mynteye VERSION 2.2.1 LANGUAGES C CXX) include(cmake/Common.cmake) diff --git a/doc/build.sh b/doc/build.sh index c2f368c..bd05e5e 100755 --- a/doc/build.sh +++ b/doc/build.sh @@ -52,16 +52,30 @@ for lang in "${LANGS[@]}"; do _mkdir "$OUTPUT/$lang" _echo_i "doxygen $DOXYFILE" doxygen $DOXYFILE + + version=`cat $DOXYFILE | grep -m1 "^PROJECT_NUMBER\s*=" | \ + sed -E "s/^.*=[[:space:]]*(.*)[[:space:]]*$/\1/g"` + + # html + if [ -d "$OUTPUT/$lang/html" ]; then + dirname="mynt-eye-sdk-apidoc"; \ + [ -n "$version" ] && dirname="$dirname-$version"; \ + dirname="$dirname-$lang" + cd "$OUTPUT/$lang" + [ -d "$dirname" ] && rm -rf "$dirname" + mv "html" "$dirname" && zip -r "$dirname.zip" "$dirname" + fi + + # latex if [ $pdflatex_FOUND ] && [ -f "$OUTPUT/$lang/latex/Makefile" ]; then _echo_in "doxygen make latex" - version=`cat $DOXYFILE | grep -m1 "^PROJECT_NUMBER\s*=" | \ - sed -E "s/^.*=[[:space:]]*(.*)[[:space:]]*$/\1/g"` filename="mynt-eye-sdk-apidoc"; \ [ -n "$version" ] && filename="$filename-$version"; \ filename="$filename-$lang.pdf" cd "$OUTPUT/$lang/latex" && _texcjk refman.tex && make [ -f "refman.pdf" ] && mv "refman.pdf" "../$filename" fi + _echo_d "doxygen completed" else _echo_e "$DOXYFILE not found" diff --git a/doc/en/api.doxyfile b/doc/en/api.doxyfile index dba062c..4a8f5ca 100644 --- a/doc/en/api.doxyfile +++ b/doc/en/api.doxyfile @@ -38,7 +38,7 @@ PROJECT_NAME = "MYNT EYE SDK" # could be handy for archiving the generated documentation or if some version # control system is used. -PROJECT_NUMBER = 2.0.1-rc2 +PROJECT_NUMBER = 2.2.1-rc # 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/en/spec_control_api.md b/doc/en/spec_control_api.md index 249613b..475bf06 100644 --- a/doc/en/spec_control_api.md +++ b/doc/en/spec_control_api.md @@ -14,7 +14,7 @@ There are two control modes, one is through UVC standard protocol, the other is | Name | Field | Bytes | Default | Min | Max | Stored | Flash Address | Channel | Note | | :--- | :---- | :---- | :------ | :-- | :-- | :----- | :------------ | :------ | :----- | -| Frame rate | frame_rate | 2 | 25 | 10 | √ | 0x21 | XU_CAM_CTRL | values: {10,15,20,25,30,35,40,45,50,55,60} | +| Frame rate | frame_rate | 2 | 25 | 10 | 60 | √ | 0x21 | XU_CAM_CTRL | values: {10,15,20,25,30,35,40,45,50,55,60} | | IMU frequency | imu_frequency | 2 | 200 | 100 | 500 | √ | 0x23 | XU_CAM_CTRL | values: {100,200,250,333,500} | | Exposure mode | exposure_mode | 1 | 0 | 0 | 1 | √ | 0x0F | XU_CAM_CTRL | 0: enable auto-exposure; 1: manual-exposure | | Max gain | max_gain | 2 | 48 | 0 | 48 | √ | 0x1D | XU_CAM_CTRL | valid if auto-exposure | diff --git a/doc/zh-Hans/api.doxyfile b/doc/zh-Hans/api.doxyfile index f58d65d..f89f9b2 100644 --- a/doc/zh-Hans/api.doxyfile +++ b/doc/zh-Hans/api.doxyfile @@ -38,7 +38,7 @@ PROJECT_NAME = "MYNT EYE SDK" # could be handy for archiving the generated documentation or if some version # control system is used. -PROJECT_NUMBER = 2.0.1-rc2 +PROJECT_NUMBER = 2.2.1-rc # 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 d1c9601..6301461 100644 --- a/doc/zh-Hans/spec_control_api.md +++ b/doc/zh-Hans/spec_control_api.md @@ -16,7 +16,7 @@ | 名称 | 字段 | 字节数 | 默认值 | 最小值 | 最大值 | 是否储存 | Flash 地址 | 所属通道 | 说明 | | :----- | :----- | :-------- | :-------- | :-------- | :-------- | :----------- | :----------- | :----------- | :----- | -| 图像帧率 | frame_rate | 2 | 25 | 10 | √ | 0x21 | XU_CAM_CTRL | 步进为5,即有效值为{10,15,20,25,30,35,40,45,50,55,60} | +| 图像帧率 | 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 | 开始自动曝光,可设定的阈值 | From b07930cd558d0e8fc37088f1815c01d645c3b2c6 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Mon, 22 Oct 2018 22:47:55 +0800 Subject: [PATCH 36/77] Update README.md --- README.md | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/README.md b/README.md index 9da2d38..e22e4ad 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ # MYNT® EYE SDK -[![](https://img.shields.io/badge/MYNT%20EYE%20SDK-2.0.1--rc2-brightgreen.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2) +[![](https://img.shields.io/badge/MYNT%20EYE%20SDK-2.2.1--rc-brightgreen.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2) ## 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-SDK-2/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-SDK-2/files/2422149/mynt-eye-sdk-apidoc-2.0.1-rc2-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2422151/mynt-eye-sdk-apidoc-2.0.1-rc2-html-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-SDK-2/) - * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2422152/mynt-eye-sdk-apidoc-2.0.1-rc2-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2422153/mynt-eye-sdk-apidoc-2.0.1-rc2-html-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/api/mynt-eye-sdk-apidoc-2.0.1-rc2-html-zh-Hans/mynt-eye-sdk-apidoc-2.0.1-rc2-html-zh-Hans/index.html) + * en: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2501756/mynt-eye-sdk-apidoc-2.2.1-rc-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2501763/mynt-eye-sdk-apidoc-2.2.1-rc-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-SDK-2/) + * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2501770/mynt-eye-sdk-apidoc-2.2.1-rc-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2501782/mynt-eye-sdk-apidoc-2.2.1-rc-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/api/mynt-eye-sdk-apidoc-2.2.1-rc-zh-Hans/mynt-eye-sdk-apidoc-2.2.1-rc-zh-Hans/index.html) * [Guide Doc](https://github.com/slightech/MYNT-EYE-SDK-2-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-SDK-2-Guide/files/2422160/mynt-eye-sdk-guide-2.0.1-rc2-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2422161/mynt-eye-sdk-guide-2.0.1-rc2-html-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-SDK-2-Guide/) - * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2422162/mynt-eye-sdk-guide-2.0.1-rc2-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2422164/mynt-eye-sdk-guide-2.0.1-rc2-html-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/sdk/mynt-eye-sdk-guide-2.0.1-rc2-html-zh-Hans/mynt-eye-sdk-guide-2.0.1-rc2-html-zh-Hans/index.html) + * en: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2501821/mynt-eye-sdk-guide-2.2.1-rc-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2501822/mynt-eye-sdk-guide-2.2.1-rc-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-SDK-2-Guide/) + * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2501823/mynt-eye-sdk-guide-2.2.1-rc-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2501827/mynt-eye-sdk-guide-2.2.1-rc-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/sdk/mynt-eye-sdk-guide-2.2.1-rc-zh-Hans/mynt-eye-sdk-guide-2.2.1-rc-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.0.1`. +Get firmwares from our online disks: [MYNTEYE_BOX][]. The latest version is `2.2.1`. ## Usage From e0161ef6967b19f0f5bb85b6a947e85ef6354454 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Wed, 24 Oct 2018 11:06:31 +0800 Subject: [PATCH 37/77] Update init & makefile --- Makefile | 6 ++++-- scripts/init.sh | 1 + scripts/init_tools.sh | 5 +++++ 3 files changed, 10 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index d53de50..17bd6fa 100644 --- a/Makefile +++ b/Makefile @@ -22,6 +22,8 @@ MKFILE_DIR := $(patsubst %/,%,$(dir $(MKFILE_PATH))) # UNIX: /usr/local # Windows: c:/Program Files/${PROJECT_NAME} +SUDO ?= sudo + .DEFAULT_GOAL := help help: @@ -77,7 +79,7 @@ submodules: init: submodules @$(call echo,Make $@) - @$(SH) ./scripts/init.sh + @$(SH) ./scripts/init.sh $(INIT_OPTIONS) .PHONY: init @@ -125,7 +127,7 @@ else endif else ifeq ($(HOST_OS),Linux) - @cd ./_build; sudo make install + @cd ./_build; $(SUDO) make install else @cd ./_build; make install endif diff --git a/scripts/init.sh b/scripts/init.sh index ce193c2..c75a70f 100755 --- a/scripts/init.sh +++ b/scripts/init.sh @@ -16,6 +16,7 @@ # _VERBOSE_=1 # _INIT_LINTER_=1 # _FORCE_INSRALL_=1 +_INSTALL_OPTIONS_=$@ BASE_DIR=$(cd "$(dirname "$0")" && pwd) diff --git a/scripts/init_tools.sh b/scripts/init_tools.sh index 232b536..0078271 100644 --- a/scripts/init_tools.sh +++ b/scripts/init_tools.sh @@ -16,6 +16,7 @@ _INIT_BUILD_=1 # _INIT_LINTER_=1 # _FORCE_INSRALL_=1 +# _INSTALL_OPTIONS_=-y BASE_DIR=$(cd "$(dirname "$0")" && pwd) @@ -42,6 +43,9 @@ fi _install_deps() { _cmd="$1"; shift; _deps_all=($@) + if [ -n "${_INSTALL_OPTIONS_}" ]; then + _cmd="$_cmd $_INSTALL_OPTIONS_" + fi _echo "Install cmd: $_cmd" _echo "Install deps: ${_deps_all[*]}" if [ -n "${_FORCE_INSRALL_}" ]; then @@ -68,6 +72,7 @@ _echo_s "Init tools" if [ "$HOST_OS" = "Linux" ]; then # sudo SUDO="sudo" + _detect_cmd $SUDO || SUDO= # detect apt-get _detect apt-get # apt-get install From 8c016597d270c6cc0f3fbc73178cac0f0521ecab Mon Sep 17 00:00:00 2001 From: John Zhao Date: Wed, 24 Oct 2018 14:10:22 +0800 Subject: [PATCH 38/77] Add jenkinsfile --- Jenkinsfile | 96 +++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 96 insertions(+) create mode 100644 Jenkinsfile diff --git a/Jenkinsfile b/Jenkinsfile new file mode 100644 index 0000000..f40191c --- /dev/null +++ b/Jenkinsfile @@ -0,0 +1,96 @@ +pipeline { + agent { + docker { image 'ros:kinetic-ros-core-xenial' } + } + + stages { + stage('Prepare') { + steps { + echo "WORKSPACE: ${env.WORKSPACE}" + echo 'apt-get ..' + sh ''' + apt-get update + apt-get install -y ros-kinetic-opencv3 + export OpenCV_DIR=/opt/ros/kinetic/share/OpenCV-3.3.1-dev + ''' + } + } + stage('Init') { + steps { + echo 'make init ..' + sh 'make init INIT_OPTIONS=-y' + } + } + stage('Build') { + steps { + echo 'make build ..' + sh 'make build' + } + } + stage('Install') { + steps { + echo 'make install ..' + sh 'make install SUDO=' + } + } + stage('Test') { + steps { + echo 'make test ..' + sh 'make test SUDO=' + } + } + stage('Samples') { + steps { + echo 'make samples ..' + sh 'make samples SUDO=' + } + } + stage('Tools') { + steps { + echo 'make tools ..' + sh 'make tools SUDO=' + } + } + stage('ROS') { + steps { + echo 'make ros ..' + sh ''' + rosdep install --from-paths wrappers/ros/src --ignore-src --rosdistro kinetic -y + make ros SUDO= + ''' + } + } + /* + stage('Clean') { + steps { + echo 'clean ..' + sh ''' + rm -rf /var/lib/apt/lists/* + ''' + } + } + */ + } + + post { + always { + echo 'This will always run' + } + success { + echo 'This will run only if successful' + } + failure { + echo 'This will run only if failed' + mail to: 'mynteye@slightech.com', + subject: "Failed Pipeline: ${currentBuild.fullDisplayName}", + body: "Something is wrong with ${env.BUILD_URL}" + } + unstable { + echo 'This will run only if the run was marked as unstable' + } + changed { + echo 'This will run only if the state of the Pipeline has changed' + echo 'For example, if the Pipeline was previously failing but is now successful' + } + } +} From 1529e77ffd98ae7fbdf1669106eedcc037f4f6f8 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Wed, 24 Oct 2018 16:47:29 +0800 Subject: [PATCH 39/77] Update jenkinsfile --- Jenkinsfile | 26 ++++++++++++++++++-------- 1 file changed, 18 insertions(+), 8 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index f40191c..09805e7 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -1,17 +1,24 @@ pipeline { agent { - docker { image 'ros:kinetic-ros-core-xenial' } + // docker { image 'ros:kinetic-ros-core-xenial' } + docker { image 'ros:kinetic-ros-base-xenial' } } + /* + environment { + // FindOpenCV.cmake + OpenCV_DIR = '/opt/ros/kinetic/share/OpenCV-3.3.1-dev' + } + */ + stages { stage('Prepare') { steps { - echo "WORKSPACE: ${env.WORKSPACE}" + echo "WORKSPACE: ${env.WORKSPACE}" echo 'apt-get ..' sh ''' apt-get update apt-get install -y ros-kinetic-opencv3 - export OpenCV_DIR=/opt/ros/kinetic/share/OpenCV-3.3.1-dev ''' } } @@ -19,42 +26,45 @@ pipeline { steps { echo 'make init ..' sh 'make init INIT_OPTIONS=-y' + // echo 'skip get submodules and make test' + // sh './scripts/init.sh -y' } } stage('Build') { steps { echo 'make build ..' - sh 'make build' + sh '. /opt/ros/kinetic/setup.sh; make build' } } stage('Install') { steps { echo 'make install ..' - sh 'make install SUDO=' + sh '. /opt/ros/kinetic/setup.sh; make install SUDO=' } } stage('Test') { steps { echo 'make test ..' - sh 'make test SUDO=' + sh '. /opt/ros/kinetic/setup.sh; make test SUDO=' } } stage('Samples') { steps { echo 'make samples ..' - sh 'make samples SUDO=' + sh '. /opt/ros/kinetic/setup.sh; make samples SUDO=' } } stage('Tools') { steps { echo 'make tools ..' - sh 'make tools SUDO=' + sh '. /opt/ros/kinetic/setup.sh; make tools SUDO=' } } stage('ROS') { steps { echo 'make ros ..' sh ''' + . /opt/ros/kinetic/setup.sh rosdep install --from-paths wrappers/ros/src --ignore-src --rosdistro kinetic -y make ros SUDO= ''' From 08271be063fdefdfe26a4df2d65df59c5d0080f9 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Fri, 26 Oct 2018 15:39:34 +0800 Subject: [PATCH 40/77] Add frame id to synthetic streams --- Makefile | 11 +++++ include/mynteye/callbacks.h | 2 + .../intermediate/get_depth_and_points.cc | 5 ++ src/api/api.h | 2 + src/api/processor/depth_processor.cc | 1 + .../disparity_normalized_processor.cc | 1 + src/api/processor/disparity_processor.cc | 1 + src/api/processor/object.h | 18 +++++-- src/api/processor/points_processor.cc | 1 + src/api/processor/rectify_processor.cc | 2 + src/api/synthetic.cc | 48 +++++++++++-------- src/internal/streams.cc | 6 ++- 12 files changed, 74 insertions(+), 24 deletions(-) diff --git a/Makefile b/Makefile index 17bd6fa..479c994 100644 --- a/Makefile +++ b/Makefile @@ -135,6 +135,17 @@ endif .PHONY: install +uninstall: + @$(call echo,Make $@) +ifeq ($(HOST_OS),Linux) + $(SUDO) rm -rf /usr/local/lib/libmynteye* + $(SUDO) rm -rf /usr/local/include/mynteye/ + $(SUDO) rm -rf /usr/local/lib/cmake/mynteye/ + $(SUDO) rm -rf /usr/local/share/mynteye/ +endif + +.PHONY: uninstall + # samples samples: install diff --git a/include/mynteye/callbacks.h b/include/mynteye/callbacks.h index d1f2c0c..4d05a0f 100644 --- a/include/mynteye/callbacks.h +++ b/include/mynteye/callbacks.h @@ -113,6 +113,8 @@ struct MYNTEYE_API StreamData { std::shared_ptr img; /** Frame. */ std::shared_ptr frame; + /** Frame ID. */ + std::uint16_t frame_id; }; /** diff --git a/samples/tutorials/intermediate/get_depth_and_points.cc b/samples/tutorials/intermediate/get_depth_and_points.cc index 6c54da0..8ac27cb 100644 --- a/samples/tutorials/intermediate/get_depth_and_points.cc +++ b/samples/tutorials/intermediate/get_depth_and_points.cc @@ -15,6 +15,7 @@ #include #include "mynteye/api.h" +// #include "mynteye/logger.h" #include "util/cv_painter.h" #include "util/pc_viewer.h" @@ -186,6 +187,8 @@ int main(int argc, char *argv[]) { painter.DrawImgData(img, *left_data.img); cv::imshow("frame", img); + // LOG(INFO) << "left id: " << left_data.frame_id + // << ", right id: " << right_data.frame_id; auto &&disp_data = api->GetStreamData(Stream::DISPARITY_NORMALIZED); auto &&depth_data = api->GetStreamData(Stream::DEPTH); @@ -204,6 +207,7 @@ int main(int argc, char *argv[]) { depth_region.DrawRect(depth_frame); cv::imshow("depth", depth_frame); + // LOG(INFO) << "depth id: " << disp_data.frame_id; depth_region.ShowElems( depth_data.frame, @@ -223,6 +227,7 @@ int main(int argc, char *argv[]) { auto &&points_data = api->GetStreamData(Stream::POINTS); if (!points_data.frame.empty()) { pcviewer.Update(points_data.frame); + // LOG(INFO) << "points id: " << points_data.frame_id; } char key = static_cast(cv::waitKey(1)); diff --git a/src/api/api.h b/src/api/api.h index a7f0ff8..8264c3c 100644 --- a/src/api/api.h +++ b/src/api/api.h @@ -49,6 +49,8 @@ struct MYNTEYE_API StreamData { cv::Mat frame; /** Raw frame. */ std::shared_ptr frame_raw; + /** Frame ID. */ + std::uint16_t frame_id; bool operator==(const StreamData &other) const { if (img && other.img) { diff --git a/src/api/processor/depth_processor.cc b/src/api/processor/depth_processor.cc index cf05d8f..39dcf48 100644 --- a/src/api/processor/depth_processor.cc +++ b/src/api/processor/depth_processor.cc @@ -46,6 +46,7 @@ bool DepthProcessor::OnProcess( cv::Mat channels[3 /*input->value.channels()*/]; cv::split(input->value, channels); channels[2].convertTo(output->value, CV_16UC1); + output->id = input->id; return true; } diff --git a/src/api/processor/disparity_normalized_processor.cc b/src/api/processor/disparity_normalized_processor.cc index 85f020d..e9ccabb 100644 --- a/src/api/processor/disparity_normalized_processor.cc +++ b/src/api/processor/disparity_normalized_processor.cc @@ -49,6 +49,7 @@ bool DisparityNormalizedProcessor::OnProcess( ObjMat *output = Object::Cast(out); cv::normalize(input->value, output->value, 0, 255, cv::NORM_MINMAX, CV_8UC1); // cv::normalize maybe return empty == + output->id = input->id; return !output->value.empty(); } diff --git a/src/api/processor/disparity_processor.cc b/src/api/processor/disparity_processor.cc index 96ad273..6a265f7 100644 --- a/src/api/processor/disparity_processor.cc +++ b/src/api/processor/disparity_processor.cc @@ -99,6 +99,7 @@ bool DisparityProcessor::OnProcess( sgbm_->compute(input->first, input->second, disparity); #endif output->value = disparity / 16 + 1; + output->id = input->first_id; return true; } diff --git a/src/api/processor/object.h b/src/api/processor/object.h index 808b150..309546b 100644 --- a/src/api/processor/object.h +++ b/src/api/processor/object.h @@ -56,14 +56,18 @@ struct MYNTEYE_API Object { */ struct MYNTEYE_API ObjMat : public Object { ObjMat() = default; - explicit ObjMat(const cv::Mat &value) : value(value) {} + ObjMat(const cv::Mat &value, std::uint16_t id) + : value(value), id(id) {} /** The value */ cv::Mat value; + /** The id **/ + std::uint16_t id; Object *Clone() const { ObjMat *mat = new ObjMat; mat->value = value.clone(); + mat->id = id; return mat; } @@ -77,19 +81,27 @@ struct MYNTEYE_API ObjMat : public Object { */ struct MYNTEYE_API ObjMat2 : public Object { ObjMat2() = default; - ObjMat2(const cv::Mat &first, const cv::Mat &second) - : first(first), second(second) {} + ObjMat2(const cv::Mat &first, std::uint16_t first_id, + const cv::Mat &second, std::uint16_t second_id) + : first(first), first_id(first_id), + second(second), second_id(second_id) {} /** The first value */ cv::Mat first; + /** The first id **/ + std::uint16_t first_id; /** The second value */ cv::Mat second; + /** The second id **/ + std::uint16_t second_id; Object *Clone() const { ObjMat2 *mat2 = new ObjMat2; mat2->first = first.clone(); + mat2->first_id = first_id; mat2->second = second.clone(); + mat2->second_id = second_id; return mat2; } diff --git a/src/api/processor/points_processor.cc b/src/api/processor/points_processor.cc index 8bc57da..c56ac78 100644 --- a/src/api/processor/points_processor.cc +++ b/src/api/processor/points_processor.cc @@ -46,6 +46,7 @@ bool PointsProcessor::OnProcess( const ObjMat *input = Object::Cast(in); ObjMat *output = Object::Cast(out); cv::reprojectImageTo3D(input->value, output->value, Q_, true); + output->id = input->id; return true; } diff --git a/src/api/processor/rectify_processor.cc b/src/api/processor/rectify_processor.cc index 7b791c6..592f869 100644 --- a/src/api/processor/rectify_processor.cc +++ b/src/api/processor/rectify_processor.cc @@ -54,6 +54,8 @@ bool RectifyProcessor::OnProcess( ObjMat2 *output = Object::Cast(out); cv::remap(input->first, output->first, map11, map12, cv::INTER_LINEAR); cv::remap(input->second, output->second, map21, map22, cv::INTER_LINEAR); + output->first_id = input->first_id; + output->second_id = input->second_id; return true; } diff --git a/src/api/synthetic.cc b/src/api/synthetic.cc index a73e6ad..c58574c 100644 --- a/src/api/synthetic.cc +++ b/src/api/synthetic.cc @@ -46,7 +46,7 @@ cv::Mat frame2mat(const std::shared_ptr &frame) { } api::StreamData data2api(const device::StreamData &data) { - return {data.img, frame2mat(data.frame), data.frame}; + return {data.img, frame2mat(data.frame), data.frame, data.frame_id}; } void process_childs( @@ -165,9 +165,9 @@ api::StreamData Synthetic::GetStreamData(const Stream &stream) { } if (output != nullptr) { if (stream == Stream::LEFT_RECTIFIED) { - return {nullptr, output->first, nullptr}; + return {nullptr, output->first, nullptr, output->first_id}; } else { - return {nullptr, output->second, nullptr}; + return {nullptr, output->second, nullptr, output->second_id}; } } VLOG(2) << "Rectify not ready now"; @@ -179,7 +179,7 @@ api::StreamData Synthetic::GetStreamData(const Stream &stream) { auto &&out = processor->GetOutput(); if (out != nullptr) { auto &&output = Object::Cast(out); - return {nullptr, output->value, nullptr}; + return {nullptr, output->value, nullptr, output->id}; } VLOG(2) << "Disparity not ready now"; } break; @@ -189,7 +189,7 @@ api::StreamData Synthetic::GetStreamData(const Stream &stream) { auto &&out = processor->GetOutput(); if (out != nullptr) { auto &&output = Object::Cast(out); - return {nullptr, output->value, nullptr}; + return {nullptr, output->value, nullptr, output->id}; } VLOG(2) << "Disparity normalized not ready now"; } break; @@ -198,7 +198,7 @@ api::StreamData Synthetic::GetStreamData(const Stream &stream) { auto &&out = processor->GetOutput(); if (out != nullptr) { auto &&output = Object::Cast(out); - return {nullptr, output->value, nullptr}; + return {nullptr, output->value, nullptr, output->id}; } VLOG(2) << "Points not ready now"; } break; @@ -207,7 +207,7 @@ api::StreamData Synthetic::GetStreamData(const Stream &stream) { auto &&out = processor->GetOutput(); if (out != nullptr) { auto &&output = Object::Cast(out); - return {nullptr, output->value, nullptr}; + return {nullptr, output->value, nullptr, output->id}; } VLOG(2) << "Depth not ready now"; } break; @@ -456,7 +456,8 @@ void Synthetic::ProcessNativeStream( if (left_data.img && right_data.img && left_data.img->frame_id == right_data.img->frame_id) { auto &&processor = find_processor(processor_); - processor->Process(ObjMat2{left_data.frame, right_data.frame}); + processor->Process(ObjMat2{left_data.frame, left_data.frame_id, + right_data.frame, right_data.frame_id}); } return; } @@ -472,24 +473,28 @@ void Synthetic::ProcessNativeStream( left_rect_data.img->frame_id == right_rect_data.img->frame_id) { process_childs( processor_, RectifyProcessor::NAME, - ObjMat2{left_rect_data.frame, right_rect_data.frame}); + ObjMat2{left_rect_data.frame, left_rect_data.frame_id, + right_rect_data.frame, right_rect_data.frame_id}); } return; } switch (stream) { case Stream::DISPARITY: { - process_childs(processor_, DisparityProcessor::NAME, ObjMat{data.frame}); + process_childs(processor_, DisparityProcessor::NAME, + ObjMat{data.frame, data.frame_id}); } break; case Stream::DISPARITY_NORMALIZED: { - process_childs( - processor_, DisparityNormalizedProcessor::NAME, ObjMat{data.frame}); + process_childs(processor_, DisparityNormalizedProcessor::NAME, + ObjMat{data.frame, data.frame_id}); } break; case Stream::POINTS: { - process_childs(processor_, PointsProcessor::NAME, ObjMat{data.frame}); + process_childs(processor_, PointsProcessor::NAME, + ObjMat{data.frame, data.frame_id}); } break; case Stream::DEPTH: { - process_childs(processor_, DepthProcessor::NAME, ObjMat{data.frame}); + process_childs(processor_, DepthProcessor::NAME, + ObjMat{data.frame, data.frame_id}); } break; default: break; @@ -546,18 +551,19 @@ void Synthetic::OnRectifyPostProcess(Object *const out) { const ObjMat2 *output = Object::Cast(out); if (HasStreamCallback(Stream::LEFT_RECTIFIED)) { stream_callbacks_.at(Stream::LEFT_RECTIFIED)( - {nullptr, output->first, nullptr}); + {nullptr, output->first, nullptr, output->first_id}); } if (HasStreamCallback(Stream::RIGHT_RECTIFIED)) { stream_callbacks_.at(Stream::RIGHT_RECTIFIED)( - {nullptr, output->second, nullptr}); + {nullptr, output->second, nullptr, output->second_id}); } } void Synthetic::OnDisparityPostProcess(Object *const out) { const ObjMat *output = Object::Cast(out); if (HasStreamCallback(Stream::DISPARITY)) { - stream_callbacks_.at(Stream::DISPARITY)({nullptr, output->value, nullptr}); + stream_callbacks_.at(Stream::DISPARITY)( + {nullptr, output->value, nullptr, output->id}); } } @@ -565,21 +571,23 @@ void Synthetic::OnDisparityNormalizedPostProcess(Object *const out) { const ObjMat *output = Object::Cast(out); if (HasStreamCallback(Stream::DISPARITY_NORMALIZED)) { stream_callbacks_.at(Stream::DISPARITY_NORMALIZED)( - {nullptr, output->value, nullptr}); + {nullptr, output->value, nullptr, output->id}); } } void Synthetic::OnPointsPostProcess(Object *const out) { const ObjMat *output = Object::Cast(out); if (HasStreamCallback(Stream::POINTS)) { - stream_callbacks_.at(Stream::POINTS)({nullptr, output->value, nullptr}); + stream_callbacks_.at(Stream::POINTS)( + {nullptr, output->value, nullptr, output->id}); } } void Synthetic::OnDepthPostProcess(Object *const out) { const ObjMat *output = Object::Cast(out); if (HasStreamCallback(Stream::DEPTH)) { - stream_callbacks_.at(Stream::DEPTH)({nullptr, output->value, nullptr}); + stream_callbacks_.at(Stream::DEPTH)( + {nullptr, output->value, nullptr, output->id}); } } diff --git a/src/internal/streams.cc b/src/internal/streams.cc index 1f9fe64..963766e 100644 --- a/src/internal/streams.cc +++ b/src/internal/streams.cc @@ -147,10 +147,12 @@ bool Streams::PushStream(const Capabilities &capability, const void *data) { // 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, 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; // unpack frame unpack_img_pixels_map_[Stream::LEFT]( data, request, left_data.frame.get()); @@ -267,13 +269,14 @@ void Streams::AllocStreamData( // reuse the dropped data data.img = datas.front().img; data.frame = datas.front().frame; + data.frame_id = 0; datas.erase(datas.begin()); VLOG(2) << "Stream data of " << stream << " is dropped as out of limits"; } } if (stream == Stream::LEFT || stream == Stream::RIGHT) { - if(!data.img) { + if (!data.img) { data.img = std::make_shared(); } } else { @@ -283,6 +286,7 @@ void Streams::AllocStreamData( data.frame = std::make_shared( request.width, request.height, format, nullptr); } + data.frame_id = 0; stream_datas_map_[stream].push_back(data); } From 972ab79a760395cccb907bbe4cb52b1257287f09 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Sat, 27 Oct 2018 21:24:04 +0800 Subject: [PATCH 41/77] Rearrage include and src --- CMakeLists.txt | 150 ++++++++++-------- include/deprecated/mynteye/api.h | 1 + include/deprecated/mynteye/callbacks.h | 1 + include/deprecated/mynteye/context.h | 1 + include/deprecated/mynteye/device.h | 1 + include/deprecated/mynteye/files.h | 1 + include/deprecated/mynteye/glog_init.h | 1 + include/deprecated/mynteye/object.h | 1 + include/deprecated/mynteye/plugin.h | 1 + include/deprecated/mynteye/strings.h | 1 + include/deprecated/mynteye/times.h | 1 + include/deprecated/mynteye/utils.h | 1 + {src => include/mynteye}/api/api.h | 10 +- .../mynteye/api}/object.h | 10 +- {src => include/mynteye}/api/plugin.h | 11 +- include/mynteye/{ => device}/callbacks.h | 6 +- {src => include/mynteye}/device/context.h | 6 +- {src => include/mynteye}/device/device.h | 8 +- include/mynteye/{ => device}/utils.h | 6 +- include/mynteye/mynteye.h.in | 2 +- include/mynteye/types.h | 4 +- .../internal => include/mynteye/util}/files.h | 6 +- .../mynteye/util}/strings.h | 6 +- .../internal => include/mynteye/util}/times.h | 6 +- samples/uvc/camera.cc | 2 +- src/{ => mynteye}/api/api.cc | 15 +- src/{internal => mynteye/api}/dl.cc | 2 +- src/{internal => mynteye/api}/dl.h | 6 +- .../processor => mynteye/api}/processor.cc | 7 +- .../processor => mynteye/api}/processor.h | 9 +- .../api/processor/depth_processor.cc | 6 +- .../api/processor/depth_processor.h | 8 +- .../disparity_normalized_processor.cc | 6 +- .../disparity_normalized_processor.h | 8 +- .../api/processor/disparity_processor.cc | 6 +- .../api/processor/disparity_processor.h | 8 +- .../api/processor/points_processor.cc | 6 +- .../api/processor/points_processor.h | 12 +- .../api/processor/rectify_processor.cc | 9 +- .../api/processor/rectify_processor.h | 12 +- src/{ => mynteye}/api/synthetic.cc | 21 ++- src/{ => mynteye}/api/synthetic.h | 8 +- .../device}/async_callback.h | 8 +- .../device}/async_callback_impl.h | 6 +- src/{internal => mynteye/device}/channels.cc | 7 +- src/{internal => mynteye/device}/channels.h | 11 +- src/{internal => mynteye/device}/config.cc | 2 +- src/{internal => mynteye/device}/config.h | 6 +- src/{ => mynteye}/device/context.cc | 6 +- src/{ => mynteye}/device/device.cc | 23 ++- src/{ => mynteye}/device/device_s.cc | 5 +- src/{ => mynteye}/device/device_s.h | 8 +- src/{internal => mynteye/device}/motions.cc | 5 +- src/{internal => mynteye/device}/motions.h | 8 +- src/{internal => mynteye/device}/streams.cc | 5 +- src/{internal => mynteye/device}/streams.h | 8 +- src/{internal => mynteye/device}/types.cc | 2 +- src/{internal => mynteye/device}/types.h | 6 +- src/{public => mynteye/device}/utils.cc | 6 +- src/{public => mynteye}/miniglog.cc | 0 src/{public => mynteye}/miniglog.readme | 0 src/{public => mynteye}/types.cc | 0 src/{internal => mynteye/util}/files.cc | 4 +- src/{internal => mynteye/util}/strings.cc | 2 +- src/{ => mynteye}/uvc/README.md | 0 src/{ => mynteye}/uvc/uvc-libuvc.cc | 2 +- src/{ => mynteye}/uvc/uvc-v4l2.cc | 2 +- src/{ => mynteye}/uvc/uvc-wmf.cc | 2 +- src/{ => mynteye}/uvc/uvc.h | 6 +- test/{internal => device}/types_test.cc | 2 +- test/{public => }/types_test.cc | 0 tools/writer/device_writer.h | 5 +- 72 files changed, 280 insertions(+), 260 deletions(-) create mode 100644 include/deprecated/mynteye/api.h create mode 100644 include/deprecated/mynteye/callbacks.h create mode 100644 include/deprecated/mynteye/context.h create mode 100644 include/deprecated/mynteye/device.h create mode 100644 include/deprecated/mynteye/files.h create mode 100644 include/deprecated/mynteye/glog_init.h create mode 100644 include/deprecated/mynteye/object.h create mode 100644 include/deprecated/mynteye/plugin.h create mode 100644 include/deprecated/mynteye/strings.h create mode 100644 include/deprecated/mynteye/times.h create mode 100644 include/deprecated/mynteye/utils.h rename {src => include/mynteye}/api/api.h (98%) rename {src/api/processor => include/mynteye/api}/object.h (96%) rename {src => include/mynteye}/api/plugin.h (96%) rename include/mynteye/{ => device}/callbacks.h (96%) rename {src => include/mynteye}/device/context.h (91%) rename {src => include/mynteye}/device/device.h (98%) rename include/mynteye/{ => device}/utils.h (93%) rename {src/internal => include/mynteye/util}/files.h (86%) rename {src/internal => include/mynteye/util}/strings.h (92%) rename {src/internal => include/mynteye/util}/times.h (97%) rename src/{ => mynteye}/api/api.cc (98%) rename src/{internal => mynteye/api}/dl.cc (99%) rename src/{internal => mynteye/api}/dl.h (93%) rename src/{api/processor => mynteye/api}/processor.cc (98%) rename src/{api/processor => mynteye/api}/processor.h (95%) rename src/{ => mynteye}/api/processor/depth_processor.cc (96%) rename src/{ => mynteye}/api/processor/depth_processor.h (84%) rename src/{ => mynteye}/api/processor/disparity_normalized_processor.cc (96%) rename src/{ => mynteye}/api/processor/disparity_normalized_processor.h (82%) rename src/{ => mynteye}/api/processor/disparity_processor.cc (98%) rename src/{ => mynteye}/api/processor/disparity_processor.h (85%) rename src/{ => mynteye}/api/processor/points_processor.cc (96%) rename src/{ => mynteye}/api/processor/points_processor.h (85%) rename src/{ => mynteye}/api/processor/rectify_processor.cc (97%) rename src/{ => mynteye}/api/processor/rectify_processor.h (87%) rename src/{ => mynteye}/api/synthetic.cc (97%) rename src/{ => mynteye}/api/synthetic.h (97%) rename src/{internal => mynteye/device}/async_callback.h (87%) rename src/{internal => mynteye/device}/async_callback_impl.h (93%) rename src/{internal => mynteye/device}/channels.cc (99%) rename src/{internal => mynteye/device}/channels.h (95%) rename src/{internal => mynteye/device}/config.cc (97%) rename src/{internal => mynteye/device}/config.h (91%) rename src/{ => mynteye}/device/context.cc (93%) rename src/{ => mynteye}/device/device.cc (97%) rename src/{ => mynteye}/device/device_s.cc (93%) rename src/{ => mynteye}/device/device_s.h (87%) rename src/{internal => mynteye/device}/motions.cc (97%) rename src/{internal => mynteye/device}/motions.h (90%) rename src/{internal => mynteye/device}/streams.cc (99%) rename src/{internal => mynteye/device}/streams.h (94%) rename src/{internal => mynteye/device}/types.cc (98%) rename src/{internal => mynteye/device}/types.h (98%) rename src/{public => mynteye/device}/utils.cc (96%) rename src/{public => mynteye}/miniglog.cc (100%) rename src/{public => mynteye}/miniglog.readme (100%) rename src/{public => mynteye}/types.cc (100%) rename src/{internal => mynteye/util}/files.cc (96%) rename src/{internal => mynteye/util}/strings.cc (98%) rename src/{ => mynteye}/uvc/README.md (100%) rename src/{ => mynteye}/uvc/uvc-libuvc.cc (99%) rename src/{ => mynteye}/uvc/uvc-v4l2.cc (99%) rename src/{ => mynteye}/uvc/uvc-wmf.cc (96%) rename src/{ => mynteye}/uvc/uvc.h (97%) rename test/{internal => device}/types_test.cc (98%) rename test/{public => }/types_test.cc (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 865aad5..31f7a63 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -90,11 +90,6 @@ set_outdir( "${OUT_DIR}/bin" ) -set(MYNTEYE_CMAKE_INCLUDE_DIR "${CMAKE_INSTALL_PREFIX}/include") -set(MYNTEYE_CMAKE_BINDIR "${CMAKE_INSTALL_PREFIX}/bin") -set(MYNTEYE_CMAKE_LIBDIR "${CMAKE_INSTALL_PREFIX}/lib") -set(MYNTEYE_CMAKE_INSTALLDIR "${MYNTEYE_CMAKE_LIBDIR}/cmake/${MYNTEYE_NAME}") - ## main if(WITH_GLOG) @@ -115,77 +110,51 @@ if(NOT WITH_GLOG AND NOT OS_WIN) unset(__MINIGLOG_FLAGS) endif() -set(MYNTEYE_PUBLIC_H - ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/callbacks.h - ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/global.h - ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/logger.h - ${CMAKE_CURRENT_BINARY_DIR}/include/mynteye/mynteye.h - ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/types.h - ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/utils.h - ${CMAKE_CURRENT_SOURCE_DIR}/src/device/context.h - ${CMAKE_CURRENT_SOURCE_DIR}/src/device/device.h - ${CMAKE_CURRENT_SOURCE_DIR}/src/internal/files.h - ${CMAKE_CURRENT_SOURCE_DIR}/src/internal/strings.h - ${CMAKE_CURRENT_SOURCE_DIR}/src/internal/times.h -) -if(WITH_API) - list(APPEND MYNTEYE_PUBLIC_H - ${CMAKE_CURRENT_SOURCE_DIR}/src/api/api.h - ${CMAKE_CURRENT_SOURCE_DIR}/src/api/plugin.h - ${CMAKE_CURRENT_SOURCE_DIR}/src/api/processor/object.h - ) -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/uvc/uvc-wmf.cc) + set(UVC_SRC src/mynteye/uvc/uvc-wmf.cc) elseif(OS_MAC) - set(UVC_SRC src/uvc/uvc-libuvc.cc) + set(UVC_SRC src/mynteye/uvc/uvc-libuvc.cc) find_package(libuvc REQUIRED) set(UVC_LIB ${libuvc_LIBRARIES}) include_directories(${libuvc_INCLUDE_DIRS}) elseif(OS_LINUX) - set(UVC_SRC src/uvc/uvc-v4l2.cc) + set(UVC_SRC src/mynteye/uvc/uvc-v4l2.cc) else() message(FATAL_ERROR "Unsupported OS.") endif() set(MYNTEYE_SRCS ${UVC_SRC} - src/internal/channels.cc - src/internal/config.cc - src/internal/dl.cc - src/internal/files.cc - src/internal/motions.cc - src/internal/streams.cc - src/internal/strings.cc - src/internal/types.cc - src/public/types.cc - src/public/utils.cc - src/device/context.cc - src/device/device.cc - src/device/device_s.cc + src/mynteye/types.cc + src/mynteye/util/files.cc + src/mynteye/util/strings.cc + src/mynteye/device/channels.cc + 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/streams.cc + src/mynteye/device/types.cc + src/mynteye/device/utils.cc ) if(WITH_API) list(APPEND MYNTEYE_SRCS - src/api/api.cc - src/api/synthetic.cc - src/api/processor/processor.cc - src/api/processor/rectify_processor.cc - src/api/processor/disparity_processor.cc - src/api/processor/disparity_normalized_processor.cc - src/api/processor/depth_processor.cc - src/api/processor/points_processor.cc + src/mynteye/api/api.cc + src/mynteye/api/dl.cc + src/mynteye/api/processor.cc + src/mynteye/api/synthetic.cc + src/mynteye/api/processor/rectify_processor.cc + src/mynteye/api/processor/disparity_processor.cc + src/mynteye/api/processor/disparity_normalized_processor.cc + src/mynteye/api/processor/depth_processor.cc + src/mynteye/api/processor/points_processor.cc ) endif() if(NOT WITH_GLOG) - list(APPEND MYNTEYE_SRCS src/public/miniglog.cc) + list(APPEND MYNTEYE_SRCS src/mynteye/miniglog.cc) endif() set(MYNTEYE_LINKLIBS ${UVC_LIB}) @@ -214,27 +183,78 @@ target_include_directories(${MYNTEYE_NAME} PUBLIC "$" "$" "$" - "$" + "$" ) set_target_properties(${MYNTEYE_NAME} PROPERTIES VERSION ${PROJECT_VERSION} SOVERSION ${PROJECT_VERSION_MAJOR} ) -set_target_properties(${MYNTEYE_NAME} PROPERTIES - PUBLIC_HEADER "${MYNTEYE_PUBLIC_H}" -) # install -#message(STATUS "MYNTEYE_CMAKE_INCLUDE_DIR: ${MYNTEYE_CMAKE_INCLUDE_DIR}") -#message(STATUS "MYNTEYE_CMAKE_BINDIR: ${MYNTEYE_CMAKE_BINDIR}") -#message(STATUS "MYNTEYE_CMAKE_LIBDIR: ${MYNTEYE_CMAKE_LIBDIR}") -#message(STATUS "MYNTEYE_CMAKE_INSTALLDIR: ${MYNTEYE_CMAKE_INSTALLDIR}") +set(MYNTEYE_CMAKE_INCLUDE_DIR "${CMAKE_INSTALL_PREFIX}/include/${MYNTEYE_NAME}") +set(MYNTEYE_CMAKE_BINDIR "${CMAKE_INSTALL_PREFIX}/bin") +set(MYNTEYE_CMAKE_LIBDIR "${CMAKE_INSTALL_PREFIX}/lib") +set(MYNTEYE_CMAKE_INSTALLDIR "${MYNTEYE_CMAKE_LIBDIR}/cmake/${MYNTEYE_NAME}") + +install(FILES + ${CMAKE_CURRENT_BINARY_DIR}/include/mynteye/mynteye.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/global.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/logger.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/types.h + DESTINATION ${MYNTEYE_CMAKE_INCLUDE_DIR} +) +install(FILES + ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/device/callbacks.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/device/context.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/device/device.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/device/utils.h + DESTINATION ${MYNTEYE_CMAKE_INCLUDE_DIR}/device +) +install(FILES + ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/util/files.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/util/strings.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/util/times.h + DESTINATION ${MYNTEYE_CMAKE_INCLUDE_DIR}/util +) +if(WITH_API) + install(FILES + ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/api/api.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/api/plugin.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/api/object.h + DESTINATION ${MYNTEYE_CMAKE_INCLUDE_DIR}/api + ) +endif() +if(NOT WITH_GLOG) + install(FILES + ${CMAKE_CURRENT_SOURCE_DIR}/include/mynteye/miniglog.h + DESTINATION ${MYNTEYE_CMAKE_INCLUDE_DIR} + ) +endif() + +install(FILES + ${CMAKE_CURRENT_SOURCE_DIR}/include/deprecated/mynteye/callbacks.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/deprecated/mynteye/context.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/deprecated/mynteye/device.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/deprecated/mynteye/files.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/deprecated/mynteye/glog_init.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/deprecated/mynteye/strings.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/deprecated/mynteye/times.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/deprecated/mynteye/utils.h + DESTINATION ${MYNTEYE_CMAKE_INCLUDE_DIR} +) +if(WITH_API) + install(FILES + ${CMAKE_CURRENT_SOURCE_DIR}/include/deprecated/mynteye/api.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/deprecated/mynteye/plugin.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/deprecated/mynteye/object.h + DESTINATION ${MYNTEYE_CMAKE_INCLUDE_DIR} + ) +endif() install(TARGETS ${MYNTEYE_NAME} EXPORT ${MYNTEYE_NAME}-targets - PUBLIC_HEADER DESTINATION ${MYNTEYE_CMAKE_INCLUDE_DIR}/${MYNTEYE_NAME} RUNTIME DESTINATION ${MYNTEYE_CMAKE_BINDIR} LIBRARY DESTINATION ${MYNTEYE_CMAKE_LIBDIR} ARCHIVE DESTINATION ${MYNTEYE_CMAKE_LIBDIR} diff --git a/include/deprecated/mynteye/api.h b/include/deprecated/mynteye/api.h new file mode 100644 index 0000000..26b4bf5 --- /dev/null +++ b/include/deprecated/mynteye/api.h @@ -0,0 +1 @@ +#include "mynteye/api/api.h" diff --git a/include/deprecated/mynteye/callbacks.h b/include/deprecated/mynteye/callbacks.h new file mode 100644 index 0000000..8f1cd45 --- /dev/null +++ b/include/deprecated/mynteye/callbacks.h @@ -0,0 +1 @@ +#include "mynteye/device/callbacks.h" diff --git a/include/deprecated/mynteye/context.h b/include/deprecated/mynteye/context.h new file mode 100644 index 0000000..8cd87d9 --- /dev/null +++ b/include/deprecated/mynteye/context.h @@ -0,0 +1 @@ +#include "mynteye/device/context.h" diff --git a/include/deprecated/mynteye/device.h b/include/deprecated/mynteye/device.h new file mode 100644 index 0000000..d8648ce --- /dev/null +++ b/include/deprecated/mynteye/device.h @@ -0,0 +1 @@ +#include "mynteye/device/device.h" diff --git a/include/deprecated/mynteye/files.h b/include/deprecated/mynteye/files.h new file mode 100644 index 0000000..335edc2 --- /dev/null +++ b/include/deprecated/mynteye/files.h @@ -0,0 +1 @@ +#include "mynteye/util/files.h" diff --git a/include/deprecated/mynteye/glog_init.h b/include/deprecated/mynteye/glog_init.h new file mode 100644 index 0000000..e094384 --- /dev/null +++ b/include/deprecated/mynteye/glog_init.h @@ -0,0 +1 @@ +#include "mynteye/logger.h" diff --git a/include/deprecated/mynteye/object.h b/include/deprecated/mynteye/object.h new file mode 100644 index 0000000..90bc8d7 --- /dev/null +++ b/include/deprecated/mynteye/object.h @@ -0,0 +1 @@ +#include "mynteye/api/object.h" diff --git a/include/deprecated/mynteye/plugin.h b/include/deprecated/mynteye/plugin.h new file mode 100644 index 0000000..52c6cd9 --- /dev/null +++ b/include/deprecated/mynteye/plugin.h @@ -0,0 +1 @@ +#include "mynteye/api/plugin.h" diff --git a/include/deprecated/mynteye/strings.h b/include/deprecated/mynteye/strings.h new file mode 100644 index 0000000..83b19b5 --- /dev/null +++ b/include/deprecated/mynteye/strings.h @@ -0,0 +1 @@ +#include "mynteye/util/strings.h" diff --git a/include/deprecated/mynteye/times.h b/include/deprecated/mynteye/times.h new file mode 100644 index 0000000..cb3fcd2 --- /dev/null +++ b/include/deprecated/mynteye/times.h @@ -0,0 +1 @@ +#include "mynteye/util/times.h" diff --git a/include/deprecated/mynteye/utils.h b/include/deprecated/mynteye/utils.h new file mode 100644 index 0000000..abd0fe2 --- /dev/null +++ b/include/deprecated/mynteye/utils.h @@ -0,0 +1 @@ +#include "mynteye/device/utils.h" diff --git a/src/api/api.h b/include/mynteye/api/api.h similarity index 98% rename from src/api/api.h rename to include/mynteye/api/api.h index 8264c3c..7374453 100644 --- a/src/api/api.h +++ b/include/mynteye/api/api.h @@ -11,17 +11,17 @@ // 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. -#ifndef MYNTEYE_API_H_ // NOLINT -#define MYNTEYE_API_H_ +#ifndef MYNTEYE_API_API_H_ +#define MYNTEYE_API_API_H_ #pragma once -#include - #include #include #include #include +#include + #include "mynteye/mynteye.h" #include "mynteye/types.h" @@ -282,4 +282,4 @@ class MYNTEYE_API API { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_API_H_ NOLINT +#endif // MYNTEYE_API_API_H_ diff --git a/src/api/processor/object.h b/include/mynteye/api/object.h similarity index 96% rename from src/api/processor/object.h rename to include/mynteye/api/object.h index 309546b..7777a2f 100644 --- a/src/api/processor/object.h +++ b/include/mynteye/api/object.h @@ -11,14 +11,14 @@ // 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. -#ifndef MYNTEYE_OBJECT_H_ // NOLINT -#define MYNTEYE_OBJECT_H_ +#ifndef MYNTEYE_API_OBJECT_H_ +#define MYNTEYE_API_OBJECT_H_ #pragma once -#include - #include +#include + #include "mynteye/mynteye.h" MYNTEYE_BEGIN_NAMESPACE @@ -112,4 +112,4 @@ struct MYNTEYE_API ObjMat2 : public Object { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_OBJECT_H_ NOLINT +#endif // MYNTEYE_API_OBJECT_H_ diff --git a/src/api/plugin.h b/include/mynteye/api/plugin.h similarity index 96% rename from src/api/plugin.h rename to include/mynteye/api/plugin.h index 1924468..181ad59 100644 --- a/src/api/plugin.h +++ b/include/mynteye/api/plugin.h @@ -11,14 +11,14 @@ // 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. -#ifndef MYNTEYE_PLUGIN_H_ // NOLINT -#define MYNTEYE_PLUGIN_H_ +#ifndef MYNTEYE_API_PLUGIN_H_ +#define MYNTEYE_API_PLUGIN_H_ #pragma once -#include - #include +#include + #include "mynteye/mynteye.h" #ifndef MYNTEYE_PLUGIN_VERSION_CODE @@ -135,6 +135,7 @@ MYNTEYE_API mynteye::Plugin *plugin_create(); * Destroy the plugin. */ MYNTEYE_API void plugin_destroy(mynteye::Plugin *plugin); + } -#endif // MYNTEYE_PLUGIN_H_ NOLINT +#endif // MYNTEYE_API_PLUGIN_H_ diff --git a/include/mynteye/callbacks.h b/include/mynteye/device/callbacks.h similarity index 96% rename from include/mynteye/callbacks.h rename to include/mynteye/device/callbacks.h index 4d05a0f..f1775ce 100644 --- a/include/mynteye/callbacks.h +++ b/include/mynteye/device/callbacks.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_CALLBACKS_H_ // NOLINT -#define MYNTEYE_CALLBACKS_H_ +#ifndef MYNTEYE_DEVICE_CALLBACKS_H_ +#define MYNTEYE_DEVICE_CALLBACKS_H_ #pragma once #include @@ -133,4 +133,4 @@ using MotionCallback = std::function; MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_CALLBACKS_H_ NOLINT +#endif // MYNTEYE_DEVICE_CALLBACKS_H_ diff --git a/src/device/context.h b/include/mynteye/device/context.h similarity index 91% rename from src/device/context.h rename to include/mynteye/device/context.h index 487cacf..bedd84f 100644 --- a/src/device/context.h +++ b/include/mynteye/device/context.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_CONTEXT_H_ // NOLINT -#define MYNTEYE_CONTEXT_H_ +#ifndef MYNTEYE_DEVICE_CONTEXT_H_ +#define MYNTEYE_DEVICE_CONTEXT_H_ #pragma once #include @@ -53,4 +53,4 @@ class MYNTEYE_API Context { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_CONTEXT_H_ NOLINT +#endif // MYNTEYE_DEVICE_CONTEXT_H_ diff --git a/src/device/device.h b/include/mynteye/device/device.h similarity index 98% rename from src/device/device.h rename to include/mynteye/device/device.h index 6d11cd2..2d81632 100644 --- a/src/device/device.h +++ b/include/mynteye/device/device.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_DEVICE_H_ // NOLINT -#define MYNTEYE_DEVICE_H_ +#ifndef MYNTEYE_DEVICE_DEVICE_H_ +#define MYNTEYE_DEVICE_DEVICE_H_ #pragma once #include @@ -22,9 +22,9 @@ #include #include -#include "mynteye/callbacks.h" #include "mynteye/mynteye.h" #include "mynteye/types.h" +#include "mynteye/device/callbacks.h" MYNTEYE_BEGIN_NAMESPACE @@ -322,4 +322,4 @@ class MYNTEYE_API Device { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_DEVICE_H_ NOLINT +#endif // MYNTEYE_DEVICE_DEVICE_H_ diff --git a/include/mynteye/utils.h b/include/mynteye/device/utils.h similarity index 93% rename from include/mynteye/utils.h rename to include/mynteye/device/utils.h index 8f210f7..f8c3939 100644 --- a/include/mynteye/utils.h +++ b/include/mynteye/device/utils.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_UTILS_H_ // NOLINT -#define MYNTEYE_UTILS_H_ +#ifndef MYNTEYE_DEVICE_UTILS_H_ +#define MYNTEYE_DEVICE_UTILS_H_ #pragma once #include @@ -59,4 +59,4 @@ MYNTEYE_API float get_real_exposure_time( MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_UTILS_H_ NOLINT +#endif // MYNTEYE_DEVICE_UTILS_H_ diff --git a/include/mynteye/mynteye.h.in b/include/mynteye/mynteye.h.in index 094742b..ee58cdf 100644 --- a/include/mynteye/mynteye.h.in +++ b/include/mynteye/mynteye.h.in @@ -45,7 +45,7 @@ MYNTEYE_API_VERSION_CHECK( \ ((major<<16)|(minor<<8)|(patch)) // NOLINT /* MYNTEYE_API_VERSION in "X.Y.Z" format */ -#define MYNTEYE_API_VERSION_STR (STRINGIFY(MYNTEYE_API_VERSION_MAJOR.MYNTEYE_API_VERSION_MINOR.MYNTEYE_API_VERSION_PATCH)) // NOLINT +#define MYNTEYE_API_VERSION_STR (MYNTEYE_STRINGIFY(MYNTEYE_API_VERSION_MAJOR.MYNTEYE_API_VERSION_MINOR.MYNTEYE_API_VERSION_PATCH)) // NOLINT #cmakedefine MYNTEYE_NAMESPACE @MYNTEYE_NAMESPACE@ #if defined(MYNTEYE_NAMESPACE) diff --git a/include/mynteye/types.h b/include/mynteye/types.h index 0ab79fd..c055fa5 100644 --- a/include/mynteye/types.h +++ b/include/mynteye/types.h @@ -11,7 +11,7 @@ // 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. -#ifndef MYNTEYE_TYPES_H_ // NOLINT +#ifndef MYNTEYE_TYPES_H_ #define MYNTEYE_TYPES_H_ #pragma once @@ -483,4 +483,4 @@ std::ostream &operator<<(std::ostream &os, const OptionInfo &info); MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_TYPES_H_ NOLINT +#endif // MYNTEYE_TYPES_H_ diff --git a/src/internal/files.h b/include/mynteye/util/files.h similarity index 86% rename from src/internal/files.h rename to include/mynteye/util/files.h index 1f9b402..0ac6ca0 100644 --- a/src/internal/files.h +++ b/include/mynteye/util/files.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_INTERNAL_FILES_H_ // NOLINT -#define MYNTEYE_INTERNAL_FILES_H_ +#ifndef MYNTEYE_UTIL_FILES_H_ +#define MYNTEYE_UTIL_FILES_H_ #pragma once #include @@ -29,4 +29,4 @@ MYNTEYE_API bool mkdir(const std::string &path); MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_INTERNAL_FILES_H_ NOLINT +#endif // MYNTEYE_UTIL_FILES_H_ diff --git a/src/internal/strings.h b/include/mynteye/util/strings.h similarity index 92% rename from src/internal/strings.h rename to include/mynteye/util/strings.h index a6ccdcd..d297464 100644 --- a/src/internal/strings.h +++ b/include/mynteye/util/strings.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_INTERNAL_STRINGS_H_ // NOLINT -#define MYNTEYE_INTERNAL_STRINGS_H_ +#ifndef MYNTEYE_UTIL_STRINGS_H_ +#define MYNTEYE_UTIL_STRINGS_H_ #pragma once #include @@ -59,4 +59,4 @@ std::string trim_copy(const std::string &text); MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_INTERNAL_STRINGS_H_ NOLINT +#endif // MYNTEYE_UTIL_STRINGS_H_ diff --git a/src/internal/times.h b/include/mynteye/util/times.h similarity index 97% rename from src/internal/times.h rename to include/mynteye/util/times.h index 89457fd..c1e8038 100644 --- a/src/internal/times.h +++ b/include/mynteye/util/times.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_INTERNAL_TIMES_H_ // NOLINT -#define MYNTEYE_INTERNAL_TIMES_H_ +#ifndef MYNTEYE_UTIL_TIMES_H_ +#define MYNTEYE_UTIL_TIMES_H_ #pragma once #include @@ -220,4 +220,4 @@ inline std::string to_utc_string( MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_INTERNAL_TIMES_H_ NOLINT +#endif // MYNTEYE_UTIL_TIMES_H_ diff --git a/samples/uvc/camera.cc b/samples/uvc/camera.cc index 5f301d6..f5f1b05 100644 --- a/samples/uvc/camera.cc +++ b/samples/uvc/camera.cc @@ -23,7 +23,7 @@ #include "mynteye/logger.h" #include "mynteye/mynteye.h" #include "mynteye/types.h" -#include "uvc/uvc.h" +#include "mynteye/uvc/uvc.h" struct frame { const void *data = nullptr; diff --git a/src/api/api.cc b/src/mynteye/api/api.cc similarity index 98% rename from src/api/api.cc rename to src/mynteye/api/api.cc index fc102ef..99f585d 100644 --- a/src/api/api.cc +++ b/src/mynteye/api/api.cc @@ -11,7 +11,7 @@ // 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 "api/api.h" +#include "mynteye/api/api.h" #ifdef WITH_BOOST_FILESYSTEM #include @@ -22,13 +22,12 @@ #include #include "mynteye/logger.h" -#include "mynteye/utils.h" - -#include "api/plugin.h" -#include "api/synthetic.h" -#include "device/device.h" -#include "device/device_s.h" -#include "internal/dl.h" +#include "mynteye/api/dl.h" +#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) #if defined(MYNTEYE_OS_WIN) diff --git a/src/internal/dl.cc b/src/mynteye/api/dl.cc similarity index 99% rename from src/internal/dl.cc rename to src/mynteye/api/dl.cc index 13170d2..d7559b6 100644 --- a/src/internal/dl.cc +++ b/src/mynteye/api/dl.cc @@ -11,7 +11,7 @@ // 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 "internal/dl.h" +#include "mynteye/api/dl.h" #include "mynteye/logger.h" diff --git a/src/internal/dl.h b/src/mynteye/api/dl.h similarity index 93% rename from src/internal/dl.h rename to src/mynteye/api/dl.h index b5748f7..be0c05b 100644 --- a/src/internal/dl.h +++ b/src/mynteye/api/dl.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_INTERNAL_DL_H_ // NOLINT -#define MYNTEYE_INTERNAL_DL_H_ +#ifndef MYNTEYE_API_DL_H_ +#define MYNTEYE_API_DL_H_ #pragma once #include "mynteye/mynteye.h" @@ -68,4 +68,4 @@ Func *DL::Sym(const char *symbol) { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_INTERNAL_DL_H_ NOLINT +#endif // MYNTEYE_API_DL_H_ diff --git a/src/api/processor/processor.cc b/src/mynteye/api/processor.cc similarity index 98% rename from src/api/processor/processor.cc rename to src/mynteye/api/processor.cc index c0d45ab..2583b5a 100644 --- a/src/api/processor/processor.cc +++ b/src/mynteye/api/processor.cc @@ -11,15 +11,14 @@ // 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 "api/processor/processor.h" +#include "mynteye/api/processor.h" #include #include #include "mynteye/logger.h" - -#include "internal/strings.h" -#include "internal/times.h" +#include "mynteye/util/strings.h" +#include "mynteye/util/times.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/api/processor/processor.h b/src/mynteye/api/processor.h similarity index 95% rename from src/api/processor/processor.h rename to src/mynteye/api/processor.h index 82b2681..11fa6f7 100644 --- a/src/api/processor/processor.h +++ b/src/mynteye/api/processor.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_PROCESSOR_H_ // NOLINT -#define MYNTEYE_PROCESSOR_H_ +#ifndef MYNTEYE_API_PROCESSOR_H_ +#define MYNTEYE_API_PROCESSOR_H_ #pragma once #include @@ -25,8 +25,7 @@ #include #include "mynteye/mynteye.h" - -#include "api/processor/object.h" +#include "mynteye/api/object.h" MYNTEYE_BEGIN_NAMESPACE @@ -119,4 +118,4 @@ void iterate_processors( MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_PROCESSOR_H_ NOLINT +#endif // MYNTEYE_API_PROCESSOR_H_ diff --git a/src/api/processor/depth_processor.cc b/src/mynteye/api/processor/depth_processor.cc similarity index 96% rename from src/api/processor/depth_processor.cc rename to src/mynteye/api/processor/depth_processor.cc index 39dcf48..8243226 100644 --- a/src/api/processor/depth_processor.cc +++ b/src/mynteye/api/processor/depth_processor.cc @@ -11,12 +11,12 @@ // 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 "api/processor/depth_processor.h" - -#include "mynteye/logger.h" +#include "mynteye/api/processor/depth_processor.h" #include +#include "mynteye/logger.h" + MYNTEYE_BEGIN_NAMESPACE const char DepthProcessor::NAME[] = "DepthProcessor"; diff --git a/src/api/processor/depth_processor.h b/src/mynteye/api/processor/depth_processor.h similarity index 84% rename from src/api/processor/depth_processor.h rename to src/mynteye/api/processor/depth_processor.h index 44fe231..c0e0aba 100644 --- a/src/api/processor/depth_processor.h +++ b/src/mynteye/api/processor/depth_processor.h @@ -11,13 +11,13 @@ // 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. -#ifndef MYNTEYE_DEPTH_PROCESSOR_H_ // NOLINT -#define MYNTEYE_DEPTH_PROCESSOR_H_ +#ifndef MYNTEYE_API_PROCESSOR_DEPTH_PROCESSOR_H_ +#define MYNTEYE_API_PROCESSOR_DEPTH_PROCESSOR_H_ #pragma once #include -#include "api/processor/processor.h" +#include "mynteye/api/processor.h" MYNTEYE_BEGIN_NAMESPACE @@ -38,4 +38,4 @@ class DepthProcessor : public Processor { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_DEPTH_PROCESSOR_H_ NOLINT +#endif // MYNTEYE_API_PROCESSOR_DEPTH_PROCESSOR_H_ diff --git a/src/api/processor/disparity_normalized_processor.cc b/src/mynteye/api/processor/disparity_normalized_processor.cc similarity index 96% rename from src/api/processor/disparity_normalized_processor.cc rename to src/mynteye/api/processor/disparity_normalized_processor.cc index e9ccabb..4b8fe64 100644 --- a/src/api/processor/disparity_normalized_processor.cc +++ b/src/mynteye/api/processor/disparity_normalized_processor.cc @@ -11,12 +11,12 @@ // 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 "api/processor/disparity_normalized_processor.h" - -#include +#include "mynteye/api/processor/disparity_normalized_processor.h" #include +#include + #include "mynteye/logger.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/api/processor/disparity_normalized_processor.h b/src/mynteye/api/processor/disparity_normalized_processor.h similarity index 82% rename from src/api/processor/disparity_normalized_processor.h rename to src/mynteye/api/processor/disparity_normalized_processor.h index 779f1f7..99d395b 100644 --- a/src/api/processor/disparity_normalized_processor.h +++ b/src/mynteye/api/processor/disparity_normalized_processor.h @@ -11,13 +11,13 @@ // 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. -#ifndef MYNTEYE_DISPARITY_NORMALIZED_PROCESSOR_H_ // NOLINT -#define MYNTEYE_DISPARITY_NORMALIZED_PROCESSOR_H_ +#ifndef MYNTEYE_API_PROCESSOR_DISPARITY_NORMALIZED_PROCESSOR_H_ +#define MYNTEYE_API_PROCESSOR_DISPARITY_NORMALIZED_PROCESSOR_H_ #pragma once #include -#include "api/processor/processor.h" +#include "mynteye/api/processor.h" MYNTEYE_BEGIN_NAMESPACE @@ -38,4 +38,4 @@ class DisparityNormalizedProcessor : public Processor { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_DISPARITY_NORMALIZED_PROCESSOR_H_ NOLINT +#endif // MYNTEYE_API_PROCESSOR_DISPARITY_NORMALIZED_PROCESSOR_H_ diff --git a/src/api/processor/disparity_processor.cc b/src/mynteye/api/processor/disparity_processor.cc similarity index 98% rename from src/api/processor/disparity_processor.cc rename to src/mynteye/api/processor/disparity_processor.cc index 6a265f7..a4bd5ae 100644 --- a/src/api/processor/disparity_processor.cc +++ b/src/mynteye/api/processor/disparity_processor.cc @@ -11,12 +11,12 @@ // 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 "api/processor/disparity_processor.h" - -#include +#include "mynteye/api/processor/disparity_processor.h" #include +#include + #include "mynteye/logger.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/api/processor/disparity_processor.h b/src/mynteye/api/processor/disparity_processor.h similarity index 85% rename from src/api/processor/disparity_processor.h rename to src/mynteye/api/processor/disparity_processor.h index 82b075f..370dca3 100644 --- a/src/api/processor/disparity_processor.h +++ b/src/mynteye/api/processor/disparity_processor.h @@ -11,13 +11,13 @@ // 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. -#ifndef MYNTEYE_DISPARITY_PROCESSOR_H_ // NOLINT -#define MYNTEYE_DISPARITY_PROCESSOR_H_ +#ifndef MYNTEYE_API_PROCESSOR_DISPARITY_PROCESSOR_H_ +#define MYNTEYE_API_PROCESSOR_DISPARITY_PROCESSOR_H_ #pragma once #include -#include "api/processor/processor.h" +#include "mynteye/api/processor.h" namespace cv { @@ -47,4 +47,4 @@ class DisparityProcessor : public Processor { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_DISPARITY_PROCESSOR_H_ NOLINT +#endif // MYNTEYE_API_PROCESSOR_DISPARITY_PROCESSOR_H_ diff --git a/src/api/processor/points_processor.cc b/src/mynteye/api/processor/points_processor.cc similarity index 96% rename from src/api/processor/points_processor.cc rename to src/mynteye/api/processor/points_processor.cc index c56ac78..3fa28e8 100644 --- a/src/api/processor/points_processor.cc +++ b/src/mynteye/api/processor/points_processor.cc @@ -11,12 +11,12 @@ // 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 "api/processor/points_processor.h" - -#include +#include "mynteye/api/processor/points_processor.h" #include +#include + #include "mynteye/logger.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/api/processor/points_processor.h b/src/mynteye/api/processor/points_processor.h similarity index 85% rename from src/api/processor/points_processor.h rename to src/mynteye/api/processor/points_processor.h index 04599da..e571091 100644 --- a/src/api/processor/points_processor.h +++ b/src/mynteye/api/processor/points_processor.h @@ -11,15 +11,15 @@ // 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. -#ifndef MYNTEYE_POINTS_PROCESSOR_H_ // NOLINT -#define MYNTEYE_POINTS_PROCESSOR_H_ +#ifndef MYNTEYE_API_PROCESSOR_POINTS_PROCESSOR_H_ +#define MYNTEYE_API_PROCESSOR_POINTS_PROCESSOR_H_ #pragma once -#include - #include -#include "api/processor/processor.h" +#include + +#include "mynteye/api/processor.h" MYNTEYE_BEGIN_NAMESPACE @@ -43,4 +43,4 @@ class PointsProcessor : public Processor { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_POINTS_PROCESSOR_H_ NOLINT +#endif // MYNTEYE_API_PROCESSOR_POINTS_PROCESSOR_H_ diff --git a/src/api/processor/rectify_processor.cc b/src/mynteye/api/processor/rectify_processor.cc similarity index 97% rename from src/api/processor/rectify_processor.cc rename to src/mynteye/api/processor/rectify_processor.cc index 592f869..87ba1c2 100644 --- a/src/api/processor/rectify_processor.cc +++ b/src/mynteye/api/processor/rectify_processor.cc @@ -11,16 +11,15 @@ // 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 "api/processor/rectify_processor.h" +#include "mynteye/api/processor/rectify_processor.h" + +#include #include #include -#include - #include "mynteye/logger.h" - -#include "device/device.h" +#include "mynteye/device/device.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/api/processor/rectify_processor.h b/src/mynteye/api/processor/rectify_processor.h similarity index 87% rename from src/api/processor/rectify_processor.h rename to src/mynteye/api/processor/rectify_processor.h index e3d9c2c..0cb33a0 100644 --- a/src/api/processor/rectify_processor.h +++ b/src/mynteye/api/processor/rectify_processor.h @@ -11,17 +11,17 @@ // 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. -#ifndef MYNTEYE_RECTIFY_PROCESSOR_H_ // NOLINT -#define MYNTEYE_RECTIFY_PROCESSOR_H_ +#ifndef MYNTEYE_API_PROCESSOR_RECTIFY_PROCESSOR_H_ +#define MYNTEYE_API_PROCESSOR_RECTIFY_PROCESSOR_H_ #pragma once -#include - #include #include -#include "api/processor/processor.h" +#include + #include "mynteye/types.h" +#include "mynteye/api/processor.h" MYNTEYE_BEGIN_NAMESPACE @@ -52,4 +52,4 @@ class RectifyProcessor : public Processor { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_RECTIFY_PROCESSOR_H_ NOLINT +#endif // MYNTEYE_API_PROCESSOR_RECTIFY_PROCESSOR_H_ diff --git a/src/api/synthetic.cc b/src/mynteye/api/synthetic.cc similarity index 97% rename from src/api/synthetic.cc rename to src/mynteye/api/synthetic.cc index c58574c..9eff8a9 100644 --- a/src/api/synthetic.cc +++ b/src/mynteye/api/synthetic.cc @@ -11,23 +11,22 @@ // 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 "api/synthetic.h" +#include "mynteye/api/synthetic.h" #include #include #include #include "mynteye/logger.h" - -#include "api/plugin.h" -#include "api/processor/depth_processor.h" -#include "api/processor/disparity_normalized_processor.h" -#include "api/processor/disparity_processor.h" -#include "api/processor/object.h" -#include "api/processor/points_processor.h" -#include "api/processor/processor.h" -#include "api/processor/rectify_processor.h" -#include "device/device.h" +#include "mynteye/api/object.h" +#include "mynteye/api/plugin.h" +#include "mynteye/api/processor.h" +#include "mynteye/api/processor/depth_processor.h" +#include "mynteye/api/processor/disparity_normalized_processor.h" +#include "mynteye/api/processor/disparity_processor.h" +#include "mynteye/api/processor/points_processor.h" +#include "mynteye/api/processor/rectify_processor.h" +#include "mynteye/device/device.h" #define RECTIFY_PROC_PERIOD 0 #define DISPARITY_PROC_PERIOD 0 diff --git a/src/api/synthetic.h b/src/mynteye/api/synthetic.h similarity index 97% rename from src/api/synthetic.h rename to src/mynteye/api/synthetic.h index 2153ed9..441ddfb 100644 --- a/src/api/synthetic.h +++ b/src/mynteye/api/synthetic.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_SYNTHETIC_H_ // NOLINT -#define MYNTEYE_SYNTHETIC_H_ +#ifndef MYNTEYE_API_SYNTHETIC_H_ +#define MYNTEYE_API_SYNTHETIC_H_ #pragma once #include @@ -20,7 +20,7 @@ #include #include -#include "api/api.h" +#include "mynteye/api/api.h" MYNTEYE_BEGIN_NAMESPACE @@ -169,4 +169,4 @@ bool Synthetic::DeactivateProcessor(bool childs) { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_SYNTHETIC_H_ NOLINT +#endif // MYNTEYE_API_SYNTHETIC_H_ diff --git a/src/internal/async_callback.h b/src/mynteye/device/async_callback.h similarity index 87% rename from src/internal/async_callback.h rename to src/mynteye/device/async_callback.h index c00f4b4..d416fb1 100644 --- a/src/internal/async_callback.h +++ b/src/mynteye/device/async_callback.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_INTERNAL_ASYNC_CALLBACK_H_ // NOLINT -#define MYNTEYE_INTERNAL_ASYNC_CALLBACK_H_ +#ifndef MYNTEYE_DEVICE_ASYNC_CALLBACK_H_ +#define MYNTEYE_DEVICE_ASYNC_CALLBACK_H_ #pragma once #include @@ -57,6 +57,6 @@ class AsyncCallback { MYNTEYE_END_NAMESPACE -#include "internal/async_callback_impl.h" +#include "mynteye/device/async_callback_impl.h" -#endif // MYNTEYE_INTERNAL_ASYNC_CALLBACK_H_ NOLINT +#endif // MYNTEYE_DEVICE_ASYNC_CALLBACK_H_ diff --git a/src/internal/async_callback_impl.h b/src/mynteye/device/async_callback_impl.h similarity index 93% rename from src/internal/async_callback_impl.h rename to src/mynteye/device/async_callback_impl.h index cfffc0d..9e79f26 100644 --- a/src/internal/async_callback_impl.h +++ b/src/mynteye/device/async_callback_impl.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_INTERNAL_ASYNC_CALLBACK_IMPL_H_ // NOLINT -#define MYNTEYE_INTERNAL_ASYNC_CALLBACK_IMPL_H_ +#ifndef MYNTEYE_DEVICE_ASYNC_CALLBACK_IMPL_H_ +#define MYNTEYE_DEVICE_ASYNC_CALLBACK_IMPL_H_ #pragma once #include @@ -89,4 +89,4 @@ void AsyncCallback::Run() { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_INTERNAL_ASYNC_CALLBACK_IMPL_H_ NOLINT +#endif // MYNTEYE_DEVICE_ASYNC_CALLBACK_IMPL_H_ diff --git a/src/internal/channels.cc b/src/mynteye/device/channels.cc similarity index 99% rename from src/internal/channels.cc rename to src/mynteye/device/channels.cc index 68bd2b6..85082b1 100644 --- a/src/internal/channels.cc +++ b/src/mynteye/device/channels.cc @@ -11,7 +11,7 @@ // 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 "internal/channels.h" +#include "mynteye/device/channels.h" #include #include @@ -21,9 +21,8 @@ #include #include "mynteye/logger.h" - -#include "internal/strings.h" -#include "internal/times.h" +#include "mynteye/util/strings.h" +#include "mynteye/util/times.h" #define IMU_TRACK_PERIOD 25 // ms diff --git a/src/internal/channels.h b/src/mynteye/device/channels.h similarity index 95% rename from src/internal/channels.h rename to src/mynteye/device/channels.h index 9e1b0e6..573d59b 100644 --- a/src/internal/channels.h +++ b/src/mynteye/device/channels.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_INTERNAL_CHANNELS_H_ // NOLINT -#define MYNTEYE_INTERNAL_CHANNELS_H_ +#ifndef MYNTEYE_DEVICE_CHANNELS_H_ +#define MYNTEYE_DEVICE_CHANNELS_H_ #pragma once #include @@ -21,9 +21,8 @@ #include "mynteye/mynteye.h" #include "mynteye/types.h" - -#include "internal/types.h" -#include "uvc/uvc.h" +#include "mynteye/device/types.h" +#include "mynteye/uvc/uvc.h" MYNTEYE_BEGIN_NAMESPACE @@ -154,4 +153,4 @@ class MYNTEYE_API Channels { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_INTERNAL_CHANNELS_H_ NOLINT +#endif // MYNTEYE_DEVICE_CHANNELS_H_ diff --git a/src/internal/config.cc b/src/mynteye/device/config.cc similarity index 97% rename from src/internal/config.cc rename to src/mynteye/device/config.cc index f9d5a53..5e4a171 100644 --- a/src/internal/config.cc +++ b/src/mynteye/device/config.cc @@ -11,7 +11,7 @@ // 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 "internal/config.h" +#include "mynteye/device/config.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/internal/config.h b/src/mynteye/device/config.h similarity index 91% rename from src/internal/config.h rename to src/mynteye/device/config.h index 77f5a55..f38dab0 100644 --- a/src/internal/config.h +++ b/src/mynteye/device/config.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_INTERNAL_CONFIG_H_ // NOLINT -#define MYNTEYE_INTERNAL_CONFIG_H_ +#ifndef MYNTEYE_DEVICE_CONFIG_H_ +#define MYNTEYE_DEVICE_CONFIG_H_ #pragma once #include @@ -39,4 +39,4 @@ extern const std::map> MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_INTERNAL_CONFIG_H_ NOLINT +#endif // MYNTEYE_DEVICE_CONFIG_H_ diff --git a/src/device/context.cc b/src/mynteye/device/context.cc similarity index 93% rename from src/device/context.cc rename to src/mynteye/device/context.cc index ef4f1ef..ec86c3e 100644 --- a/src/device/context.cc +++ b/src/mynteye/device/context.cc @@ -11,12 +11,12 @@ // 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 "device/context.h" +#include "mynteye/device/context.h" #include "mynteye/logger.h" -#include "device/device.h" -#include "uvc/uvc.h" +#include "mynteye/device/device.h" +#include "mynteye/uvc/uvc.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/device/device.cc b/src/mynteye/device/device.cc similarity index 97% rename from src/device/device.cc rename to src/mynteye/device/device.cc index 2d16d9d..32c79ed 100644 --- a/src/device/device.cc +++ b/src/mynteye/device/device.cc @@ -11,7 +11,7 @@ // 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 "device/device.h" +#include "mynteye/device/device.h" #include #include @@ -19,17 +19,16 @@ #include #include "mynteye/logger.h" - -#include "device/device_s.h" -#include "internal/async_callback.h" -#include "internal/channels.h" -#include "internal/config.h" -#include "internal/motions.h" -#include "internal/streams.h" -#include "internal/strings.h" -#include "internal/times.h" -#include "internal/types.h" -#include "uvc/uvc.h" +#include "mynteye/device/async_callback.h" +#include "mynteye/device/channels.h" +#include "mynteye/device/config.h" +#include "mynteye/device/device_s.h" +#include "mynteye/device/motions.h" +#include "mynteye/device/streams.h" +#include "mynteye/device/types.h" +#include "mynteye/util/strings.h" +#include "mynteye/util/times.h" +#include "mynteye/uvc/uvc.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/device/device_s.cc b/src/mynteye/device/device_s.cc similarity index 93% rename from src/device/device_s.cc rename to src/mynteye/device/device_s.cc index 377453d..e30f3d4 100644 --- a/src/device/device_s.cc +++ b/src/mynteye/device/device_s.cc @@ -11,11 +11,10 @@ // 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 "device/device_s.h" +#include "mynteye/device/device_s.h" #include "mynteye/logger.h" - -#include "internal/motions.h" +#include "mynteye/device/motions.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/device/device_s.h b/src/mynteye/device/device_s.h similarity index 87% rename from src/device/device_s.h rename to src/mynteye/device/device_s.h index 2a600b4..3a850e2 100644 --- a/src/device/device_s.h +++ b/src/mynteye/device/device_s.h @@ -11,14 +11,14 @@ // 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. -#ifndef MYNTEYE_DEVICE_S_H_ // NOLINT -#define MYNTEYE_DEVICE_S_H_ +#ifndef MYNTEYE_DEVICE_DEVICE_S_H_ +#define MYNTEYE_DEVICE_DEVICE_S_H_ #pragma once #include #include -#include "device/device.h" +#include "mynteye/device/device.h" MYNTEYE_BEGIN_NAMESPACE @@ -34,4 +34,4 @@ class StandardDevice : public Device { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_DEVICE_S_H_ NOLINT +#endif // MYNTEYE_DEVICE_DEVICE_S_H_ diff --git a/src/internal/motions.cc b/src/mynteye/device/motions.cc similarity index 97% rename from src/internal/motions.cc rename to src/mynteye/device/motions.cc index 27d3c67..cd1a8d4 100644 --- a/src/internal/motions.cc +++ b/src/mynteye/device/motions.cc @@ -11,11 +11,10 @@ // 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 "internal/motions.h" +#include "mynteye/device/motions.h" #include "mynteye/logger.h" - -#include "internal/channels.h" +#include "mynteye/device/channels.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/internal/motions.h b/src/mynteye/device/motions.h similarity index 90% rename from src/internal/motions.h rename to src/mynteye/device/motions.h index 0472605..5d98fb0 100644 --- a/src/internal/motions.h +++ b/src/mynteye/device/motions.h @@ -11,16 +11,16 @@ // 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. -#ifndef MYNTEYE_INTERNAL_MOTIONS_H_ // NOLINT -#define MYNTEYE_INTERNAL_MOTIONS_H_ +#ifndef MYNTEYE_DEVICE_MOTIONS_H_ +#define MYNTEYE_DEVICE_MOTIONS_H_ #pragma once #include #include #include -#include "mynteye/callbacks.h" #include "mynteye/mynteye.h" +#include "mynteye/device/callbacks.h" MYNTEYE_BEGIN_NAMESPACE @@ -61,4 +61,4 @@ class Motions { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_INTERNAL_MOTIONS_H_ NOLINT +#endif // MYNTEYE_DEVICE_MOTIONS_H_ diff --git a/src/internal/streams.cc b/src/mynteye/device/streams.cc similarity index 99% rename from src/internal/streams.cc rename to src/mynteye/device/streams.cc index 963766e..a57c2c8 100644 --- a/src/internal/streams.cc +++ b/src/mynteye/device/streams.cc @@ -11,7 +11,7 @@ // 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 "internal/streams.h" +#include "mynteye/device/streams.h" #include #include @@ -19,8 +19,7 @@ #include #include "mynteye/logger.h" - -#include "internal/types.h" +#include "mynteye/device/types.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/internal/streams.h b/src/mynteye/device/streams.h similarity index 94% rename from src/internal/streams.h rename to src/mynteye/device/streams.h index eecb6b9..01757b9 100644 --- a/src/internal/streams.h +++ b/src/mynteye/device/streams.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_INTERNAL_STREAMS_H_ // NOLINT -#define MYNTEYE_INTERNAL_STREAMS_H_ +#ifndef MYNTEYE_DEVICE_STREAMS_H_ +#define MYNTEYE_DEVICE_STREAMS_H_ #pragma once #include @@ -21,9 +21,9 @@ #include #include -#include "mynteye/callbacks.h" #include "mynteye/mynteye.h" #include "mynteye/types.h" +#include "mynteye/device/callbacks.h" MYNTEYE_BEGIN_NAMESPACE @@ -90,4 +90,4 @@ class Streams { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_INTERNAL_STREAMS_H_ NOLINT +#endif // MYNTEYE_DEVICE_STREAMS_H_ diff --git a/src/internal/types.cc b/src/mynteye/device/types.cc similarity index 98% rename from src/internal/types.cc rename to src/mynteye/device/types.cc index c5aa1e7..f29ce8e 100644 --- a/src/internal/types.cc +++ b/src/mynteye/device/types.cc @@ -11,7 +11,7 @@ // 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 "internal/types.h" +#include "mynteye/device/types.h" #include #include diff --git a/src/internal/types.h b/src/mynteye/device/types.h similarity index 98% rename from src/internal/types.h rename to src/mynteye/device/types.h index 216fe89..d704a5d 100644 --- a/src/internal/types.h +++ b/src/mynteye/device/types.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_INTERNAL_TYPES_H_ // NOLINT -#define MYNTEYE_INTERNAL_TYPES_H_ +#ifndef MYNTEYE_DEVICE_TYPES_H_ +#define MYNTEYE_DEVICE_TYPES_H_ #pragma once #include @@ -293,4 +293,4 @@ struct ImuResPacket { MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_INTERNAL_TYPES_H_ NOLINT +#endif // MYNTEYE_DEVICE_TYPES_H_ diff --git a/src/public/utils.cc b/src/mynteye/device/utils.cc similarity index 96% rename from src/public/utils.cc rename to src/mynteye/device/utils.cc index 566a389..52b8ba7 100644 --- a/src/public/utils.cc +++ b/src/mynteye/device/utils.cc @@ -11,12 +11,12 @@ // 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 "mynteye/utils.h" +#include "mynteye/device/utils.h" #include "mynteye/logger.h" -#include "device/context.h" -#include "device/device.h" +#include "mynteye/device/context.h" +#include "mynteye/device/device.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/public/miniglog.cc b/src/mynteye/miniglog.cc similarity index 100% rename from src/public/miniglog.cc rename to src/mynteye/miniglog.cc diff --git a/src/public/miniglog.readme b/src/mynteye/miniglog.readme similarity index 100% rename from src/public/miniglog.readme rename to src/mynteye/miniglog.readme diff --git a/src/public/types.cc b/src/mynteye/types.cc similarity index 100% rename from src/public/types.cc rename to src/mynteye/types.cc diff --git a/src/internal/files.cc b/src/mynteye/util/files.cc similarity index 96% rename from src/internal/files.cc rename to src/mynteye/util/files.cc index 5acb602..2e87b3b 100644 --- a/src/internal/files.cc +++ b/src/mynteye/util/files.cc @@ -11,7 +11,7 @@ // 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 "internal/files.h" +#include "mynteye/util/files.h" #include "mynteye/logger.h" @@ -22,7 +22,7 @@ #include #endif -#include "internal/strings.h" +#include "mynteye/util/strings.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/src/internal/strings.cc b/src/mynteye/util/strings.cc similarity index 98% rename from src/internal/strings.cc rename to src/mynteye/util/strings.cc index 7ce294b..fbfe3f7 100644 --- a/src/internal/strings.cc +++ b/src/mynteye/util/strings.cc @@ -11,7 +11,7 @@ // 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 "internal/strings.h" +#include "mynteye/util/strings.h" #include #include diff --git a/src/uvc/README.md b/src/mynteye/uvc/README.md similarity index 100% rename from src/uvc/README.md rename to src/mynteye/uvc/README.md diff --git a/src/uvc/uvc-libuvc.cc b/src/mynteye/uvc/uvc-libuvc.cc similarity index 99% rename from src/uvc/uvc-libuvc.cc rename to src/mynteye/uvc/uvc-libuvc.cc index 7594579..e5e157b 100644 --- a/src/uvc/uvc-libuvc.cc +++ b/src/mynteye/uvc/uvc-libuvc.cc @@ -11,7 +11,7 @@ // 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 "mynteye/uvc/uvc.h" #include diff --git a/src/uvc/uvc-v4l2.cc b/src/mynteye/uvc/uvc-v4l2.cc similarity index 99% rename from src/uvc/uvc-v4l2.cc rename to src/mynteye/uvc/uvc-v4l2.cc index 292804c..bbb5cff 100755 --- a/src/uvc/uvc-v4l2.cc +++ b/src/mynteye/uvc/uvc-v4l2.cc @@ -11,7 +11,7 @@ // 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 "mynteye/uvc/uvc.h" #include #include diff --git a/src/uvc/uvc-wmf.cc b/src/mynteye/uvc/uvc-wmf.cc similarity index 96% rename from src/uvc/uvc-wmf.cc rename to src/mynteye/uvc/uvc-wmf.cc index 8e8d9c3..a425ead 100644 --- a/src/uvc/uvc-wmf.cc +++ b/src/mynteye/uvc/uvc-wmf.cc @@ -11,7 +11,7 @@ // 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 "mynteye/uvc/uvc.h" #include #include diff --git a/src/uvc/uvc.h b/src/mynteye/uvc/uvc.h similarity index 97% rename from src/uvc/uvc.h rename to src/mynteye/uvc/uvc.h index 7ac3177..c4720e7 100644 --- a/src/uvc/uvc.h +++ b/src/mynteye/uvc/uvc.h @@ -11,8 +11,8 @@ // 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. -#ifndef MYNTEYE_UVC_H_ // NOLINT -#define MYNTEYE_UVC_H_ +#ifndef MYNTEYE_UVC_UVC_H_ +#define MYNTEYE_UVC_UVC_H_ #pragma once #include @@ -106,4 +106,4 @@ MYNTEYE_API void stop_streaming(device &device); // NOL MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_UVC_H_ NOLINT +#endif // MYNTEYE_UVC_UVC_H_ diff --git a/test/internal/types_test.cc b/test/device/types_test.cc similarity index 98% rename from test/internal/types_test.cc rename to test/device/types_test.cc index c502f08..083cf9b 100644 --- a/test/internal/types_test.cc +++ b/test/device/types_test.cc @@ -13,7 +13,7 @@ // limitations under the License. #include "gtest/gtest.h" -#include "internal/types.h" +#include "mynteye/device/types.h" MYNTEYE_USE_NAMESPACE diff --git a/test/public/types_test.cc b/test/types_test.cc similarity index 100% rename from test/public/types_test.cc rename to test/types_test.cc diff --git a/tools/writer/device_writer.h b/tools/writer/device_writer.h index f65005e..a51631c 100644 --- a/tools/writer/device_writer.h +++ b/tools/writer/device_writer.h @@ -19,9 +19,8 @@ #include #include "mynteye/mynteye.h" - -#include "internal/channels.h" -#include "internal/types.h" +#include "mynteye/device/channels.h" +#include "mynteye/device/types.h" MYNTEYE_BEGIN_NAMESPACE From e95a5e6b1d821f863d262811169e315729f3eb8f Mon Sep 17 00:00:00 2001 From: John Zhao Date: Sat, 27 Oct 2018 21:51:44 +0800 Subject: [PATCH 42/77] Change includes --- samples/api/camera.cc | 5 ++--- samples/api/get_depth_with_region.cc | 2 +- samples/device/camera.cc | 8 +++----- samples/tutorials/control/auto_exposure.cc | 2 +- samples/tutorials/control/framerate.cc | 8 ++++---- samples/tutorials/control/infrared.cc | 2 +- samples/tutorials/control/manual_exposure.cc | 2 +- samples/tutorials/data/get_depth.cc | 2 +- samples/tutorials/data/get_device_info.cc | 2 +- samples/tutorials/data/get_disparity.cc | 2 +- samples/tutorials/data/get_from_callbacks.cc | 6 +++--- samples/tutorials/data/get_img_params.cc | 2 +- samples/tutorials/data/get_imu.cc | 2 +- samples/tutorials/data/get_imu_params.cc | 2 +- samples/tutorials/data/get_points.cc | 2 +- samples/tutorials/data/get_stereo.cc | 2 +- samples/tutorials/data/get_stereo_rectified.cc | 2 +- samples/tutorials/data/get_with_plugin.cc | 2 +- samples/tutorials/intermediate/get_all_device_info.cc | 4 ++-- samples/tutorials/intermediate/get_depth_and_points.cc | 2 +- samples/tutorials/util/cv_painter.cc | 6 +++--- samples/tutorials/util/cv_painter.h | 4 ++-- samples/tutorials/util/pc_viewer.h | 4 ++-- samples/uvc/camera.cc | 6 +++--- tools/dataset/dataset.cc | 2 +- tools/dataset/dataset.h | 2 +- tools/dataset/record.cc | 8 +++----- tools/writer/device_info_writer.cc | 5 ++--- tools/writer/device_writer.cc | 8 ++++---- tools/writer/img_params_writer.cc | 5 ++--- tools/writer/imu_params_writer.cc | 5 ++--- tools/writer/save_all_infos.cc | 5 ++--- wrappers/python/src/mynteye_py.cc | 7 +++---- .../ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc | 6 +++--- 34 files changed, 62 insertions(+), 72 deletions(-) diff --git a/samples/api/camera.cc b/samples/api/camera.cc index 1159d2d..0d10a54 100644 --- a/samples/api/camera.cc +++ b/samples/api/camera.cc @@ -14,9 +14,8 @@ #include #include "mynteye/logger.h" - -#include "mynteye/api.h" -#include "mynteye/times.h" +#include "mynteye/api/api.h" +#include "mynteye/util/times.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/api/get_depth_with_region.cc b/samples/api/get_depth_with_region.cc index c0918c3..f3d5ee1 100644 --- a/samples/api/get_depth_with_region.cc +++ b/samples/api/get_depth_with_region.cc @@ -14,7 +14,7 @@ #include #include -#include "mynteye/api.h" +#include "mynteye/api/api.h" namespace { diff --git a/samples/device/camera.cc b/samples/device/camera.cc index 00b1f0d..85af2ed 100644 --- a/samples/device/camera.cc +++ b/samples/device/camera.cc @@ -15,11 +15,9 @@ #include #include "mynteye/logger.h" - -#include "mynteye/device.h" -#include "mynteye/utils.h" - -#include "mynteye/times.h" +#include "mynteye/device/device.h" +#include "mynteye/device/utils.h" +#include "mynteye/util/times.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/control/auto_exposure.cc b/samples/tutorials/control/auto_exposure.cc index b1bacc1..0a18547 100644 --- a/samples/tutorials/control/auto_exposure.cc +++ b/samples/tutorials/control/auto_exposure.cc @@ -13,8 +13,8 @@ // limitations under the License. #include -#include "mynteye/api.h" #include "mynteye/logger.h" +#include "mynteye/api/api.h" #include "util/cv_painter.h" diff --git a/samples/tutorials/control/framerate.cc b/samples/tutorials/control/framerate.cc index a6ab3b3..3236bf0 100644 --- a/samples/tutorials/control/framerate.cc +++ b/samples/tutorials/control/framerate.cc @@ -11,13 +11,13 @@ // 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 -#include "mynteye/api.h" +#include + #include "mynteye/logger.h" -#include "mynteye/times.h" +#include "mynteye/api/api.h" +#include "mynteye/util/times.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/control/infrared.cc b/samples/tutorials/control/infrared.cc index 2a7ccd2..a6310a7 100644 --- a/samples/tutorials/control/infrared.cc +++ b/samples/tutorials/control/infrared.cc @@ -13,8 +13,8 @@ // limitations under the License. #include -#include "mynteye/api.h" #include "mynteye/logger.h" +#include "mynteye/api/api.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/control/manual_exposure.cc b/samples/tutorials/control/manual_exposure.cc index 386188b..16ce32e 100644 --- a/samples/tutorials/control/manual_exposure.cc +++ b/samples/tutorials/control/manual_exposure.cc @@ -13,8 +13,8 @@ // limitations under the License. #include -#include "mynteye/api.h" #include "mynteye/logger.h" +#include "mynteye/api/api.h" #include "util/cv_painter.h" diff --git a/samples/tutorials/data/get_depth.cc b/samples/tutorials/data/get_depth.cc index 28ef244..e973967 100644 --- a/samples/tutorials/data/get_depth.cc +++ b/samples/tutorials/data/get_depth.cc @@ -13,7 +13,7 @@ // limitations under the License. #include -#include "mynteye/api.h" +#include "mynteye/api/api.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/data/get_device_info.cc b/samples/tutorials/data/get_device_info.cc index d188fc6..5217c36 100644 --- a/samples/tutorials/data/get_device_info.cc +++ b/samples/tutorials/data/get_device_info.cc @@ -11,8 +11,8 @@ // 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 "mynteye/api.h" #include "mynteye/logger.h" +#include "mynteye/api/api.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/data/get_disparity.cc b/samples/tutorials/data/get_disparity.cc index aa02e42..243d81e 100644 --- a/samples/tutorials/data/get_disparity.cc +++ b/samples/tutorials/data/get_disparity.cc @@ -13,7 +13,7 @@ // limitations under the License. #include -#include "mynteye/api.h" +#include "mynteye/api/api.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/data/get_from_callbacks.cc b/samples/tutorials/data/get_from_callbacks.cc index 667c956..27c30a4 100644 --- a/samples/tutorials/data/get_from_callbacks.cc +++ b/samples/tutorials/data/get_from_callbacks.cc @@ -11,15 +11,15 @@ // 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 #include #include #include -#include "mynteye/api.h" +#include + #include "mynteye/logger.h" +#include "mynteye/api/api.h" #include "util/cv_painter.h" diff --git a/samples/tutorials/data/get_img_params.cc b/samples/tutorials/data/get_img_params.cc index 7cfac2e..6fa9b8f 100644 --- a/samples/tutorials/data/get_img_params.cc +++ b/samples/tutorials/data/get_img_params.cc @@ -11,8 +11,8 @@ // 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 "mynteye/api.h" #include "mynteye/logger.h" +#include "mynteye/api/api.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/data/get_imu.cc b/samples/tutorials/data/get_imu.cc index 5cda4a4..a449f6e 100644 --- a/samples/tutorials/data/get_imu.cc +++ b/samples/tutorials/data/get_imu.cc @@ -13,8 +13,8 @@ // limitations under the License. #include -#include "mynteye/api.h" #include "mynteye/logger.h" +#include "mynteye/api/api.h" #include "util/cv_painter.h" diff --git a/samples/tutorials/data/get_imu_params.cc b/samples/tutorials/data/get_imu_params.cc index 1a307f8..7757611 100644 --- a/samples/tutorials/data/get_imu_params.cc +++ b/samples/tutorials/data/get_imu_params.cc @@ -11,8 +11,8 @@ // 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 "mynteye/api.h" #include "mynteye/logger.h" +#include "mynteye/api/api.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/data/get_points.cc b/samples/tutorials/data/get_points.cc index 66f3341..28294f5 100644 --- a/samples/tutorials/data/get_points.cc +++ b/samples/tutorials/data/get_points.cc @@ -13,7 +13,7 @@ // limitations under the License. #include -#include "mynteye/api.h" +#include "mynteye/api/api.h" #include "util/pc_viewer.h" diff --git a/samples/tutorials/data/get_stereo.cc b/samples/tutorials/data/get_stereo.cc index 7899765..391c53e 100644 --- a/samples/tutorials/data/get_stereo.cc +++ b/samples/tutorials/data/get_stereo.cc @@ -13,7 +13,7 @@ // limitations under the License. #include -#include "mynteye/api.h" +#include "mynteye/api/api.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/data/get_stereo_rectified.cc b/samples/tutorials/data/get_stereo_rectified.cc index ea1a8b5..10c0bf5 100644 --- a/samples/tutorials/data/get_stereo_rectified.cc +++ b/samples/tutorials/data/get_stereo_rectified.cc @@ -13,7 +13,7 @@ // limitations under the License. #include -#include "mynteye/api.h" +#include "mynteye/api/api.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/data/get_with_plugin.cc b/samples/tutorials/data/get_with_plugin.cc index dbaa574..e8a0e05 100644 --- a/samples/tutorials/data/get_with_plugin.cc +++ b/samples/tutorials/data/get_with_plugin.cc @@ -13,7 +13,7 @@ // limitations under the License. #include -#include "mynteye/api.h" +#include "mynteye/api/api.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/intermediate/get_all_device_info.cc b/samples/tutorials/intermediate/get_all_device_info.cc index ec07c3a..1c335f7 100644 --- a/samples/tutorials/intermediate/get_all_device_info.cc +++ b/samples/tutorials/intermediate/get_all_device_info.cc @@ -11,9 +11,9 @@ // 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 "mynteye/context.h" -#include "mynteye/device.h" #include "mynteye/logger.h" +#include "mynteye/device/context.h" +#include "mynteye/device/device.h" MYNTEYE_USE_NAMESPACE diff --git a/samples/tutorials/intermediate/get_depth_and_points.cc b/samples/tutorials/intermediate/get_depth_and_points.cc index 8ac27cb..0f5d276 100644 --- a/samples/tutorials/intermediate/get_depth_and_points.cc +++ b/samples/tutorials/intermediate/get_depth_and_points.cc @@ -14,8 +14,8 @@ #include #include -#include "mynteye/api.h" // #include "mynteye/logger.h" +#include "mynteye/api/api.h" #include "util/cv_painter.h" #include "util/pc_viewer.h" diff --git a/samples/tutorials/util/cv_painter.cc b/samples/tutorials/util/cv_painter.cc index eaa7d8a..410dfec 100644 --- a/samples/tutorials/util/cv_painter.cc +++ b/samples/tutorials/util/cv_painter.cc @@ -13,15 +13,15 @@ // limitations under the License. #include "util/cv_painter.h" -#include - #include #include #include #include +#include + #include "mynteye/logger.h" -#include "mynteye/utils.h" +#include "mynteye/device/utils.h" #define FONT_FACE cv::FONT_HERSHEY_PLAIN #define FONT_SCALE 1 diff --git a/samples/tutorials/util/cv_painter.h b/samples/tutorials/util/cv_painter.h index bd606a7..decde17 100644 --- a/samples/tutorials/util/cv_painter.h +++ b/samples/tutorials/util/cv_painter.h @@ -15,10 +15,10 @@ #define MYNTEYE_TUTORIALS_CV_PAINTER_H_ #pragma once -#include - #include +#include + #include "mynteye/types.h" class CVPainter { diff --git a/samples/tutorials/util/pc_viewer.h b/samples/tutorials/util/pc_viewer.h index 4092265..1cf781b 100644 --- a/samples/tutorials/util/pc_viewer.h +++ b/samples/tutorials/util/pc_viewer.h @@ -15,12 +15,12 @@ #define MYNTEYE_TUTORIALS_PC_VIEWER_H_ #pragma once +#include + #include #include -#include - class PCViewer { public: PCViewer(); diff --git a/samples/uvc/camera.cc b/samples/uvc/camera.cc index f5f1b05..2a92930 100644 --- a/samples/uvc/camera.cc +++ b/samples/uvc/camera.cc @@ -11,15 +11,15 @@ // 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 - #include #include #include #include #include +#include +#include + #include "mynteye/logger.h" #include "mynteye/mynteye.h" #include "mynteye/types.h" diff --git a/tools/dataset/dataset.cc b/tools/dataset/dataset.cc index 06e56c4..390e1a3 100644 --- a/tools/dataset/dataset.cc +++ b/tools/dataset/dataset.cc @@ -24,8 +24,8 @@ #include #include -#include "mynteye/files.h" #include "mynteye/logger.h" +#include "mynteye/util/files.h" #define FULL_PRECISION \ std::fixed << std::setprecision(std::numeric_limits::max_digits10) diff --git a/tools/dataset/dataset.h b/tools/dataset/dataset.h index 06f52c4..03edfa1 100644 --- a/tools/dataset/dataset.h +++ b/tools/dataset/dataset.h @@ -20,8 +20,8 @@ #include #include -#include "mynteye/callbacks.h" #include "mynteye/mynteye.h" +#include "mynteye/device/callbacks.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/tools/dataset/record.cc b/tools/dataset/record.cc index dedf851..63ada53 100644 --- a/tools/dataset/record.cc +++ b/tools/dataset/record.cc @@ -15,11 +15,9 @@ #include #include "mynteye/logger.h" - -#include "mynteye/device.h" -#include "mynteye/utils.h" - -#include "mynteye/times.h" +#include "mynteye/device/device.h" +#include "mynteye/device/utils.h" +#include "mynteye/util/times.h" #include "dataset/dataset.h" diff --git a/tools/writer/device_info_writer.cc b/tools/writer/device_info_writer.cc index 6619a55..5dc3112 100644 --- a/tools/writer/device_info_writer.cc +++ b/tools/writer/device_info_writer.cc @@ -12,9 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. #include "mynteye/logger.h" - -#include "mynteye/device.h" -#include "mynteye/utils.h" +#include "mynteye/device/device.h" +#include "mynteye/device/utils.h" #include "writer/device_writer.h" diff --git a/tools/writer/device_writer.cc b/tools/writer/device_writer.cc index 3db0a26..bba788c 100644 --- a/tools/writer/device_writer.cc +++ b/tools/writer/device_writer.cc @@ -13,13 +13,13 @@ // limitations under the License. #include "writer/device_writer.h" -#include - #include -#include "mynteye/device.h" -#include "mynteye/files.h" +#include + #include "mynteye/logger.h" +#include "mynteye/device/device.h" +#include "mynteye/util/files.h" MYNTEYE_BEGIN_NAMESPACE diff --git a/tools/writer/img_params_writer.cc b/tools/writer/img_params_writer.cc index 02950e9..fa0325d 100644 --- a/tools/writer/img_params_writer.cc +++ b/tools/writer/img_params_writer.cc @@ -12,9 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. #include "mynteye/logger.h" - -#include "mynteye/device.h" -#include "mynteye/utils.h" +#include "mynteye/device/device.h" +#include "mynteye/device/utils.h" #include "writer/device_writer.h" diff --git a/tools/writer/imu_params_writer.cc b/tools/writer/imu_params_writer.cc index a60c3fe..3b48917 100644 --- a/tools/writer/imu_params_writer.cc +++ b/tools/writer/imu_params_writer.cc @@ -12,9 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. #include "mynteye/logger.h" - -#include "mynteye/device.h" -#include "mynteye/utils.h" +#include "mynteye/device/device.h" +#include "mynteye/device/utils.h" #include "writer/device_writer.h" diff --git a/tools/writer/save_all_infos.cc b/tools/writer/save_all_infos.cc index 3f484bd..4aa3cfd 100644 --- a/tools/writer/save_all_infos.cc +++ b/tools/writer/save_all_infos.cc @@ -12,9 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. #include "mynteye/logger.h" - -#include "mynteye/device.h" -#include "mynteye/utils.h" +#include "mynteye/device/device.h" +#include "mynteye/device/utils.h" #include "writer/device_writer.h" diff --git a/wrappers/python/src/mynteye_py.cc b/wrappers/python/src/mynteye_py.cc index ad7fbe9..2dbb369 100644 --- a/wrappers/python/src/mynteye_py.cc +++ b/wrappers/python/src/mynteye_py.cc @@ -11,6 +11,7 @@ // 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 #include @@ -23,11 +24,9 @@ #include -#include - -#include "mynteye/api.h" #include "mynteye/logger.h" -#include "mynteye/utils.h" +#include "mynteye/api/api.h" +#include "mynteye/device/utils.h" #include "array_indexing_suite.hpp" #include "array_ref.hpp" diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc index 5e6e2de..0402e76 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc @@ -33,10 +33,10 @@ #include #include -#include "mynteye/api.h" -#include "mynteye/context.h" -#include "mynteye/device.h" #include "mynteye/logger.h" +#include "mynteye/api/api.h" +#include "mynteye/device/context.h" +#include "mynteye/device/device.h" #define FULL_PRECISION \ std::fixed << std::setprecision(std::numeric_limits::max_digits10) From 3d38b43d042a93f7ef78c4601f600a78445be193 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Mon, 29 Oct 2018 12:08:19 +0800 Subject: [PATCH 43/77] Update jenkinsfile --- Jenkinsfile | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 09805e7..619ee8e 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -1,7 +1,7 @@ pipeline { agent { - // docker { image 'ros:kinetic-ros-core-xenial' } - docker { image 'ros:kinetic-ros-base-xenial' } + // docker { image 'ros:kinetic-ros-base-xenial' } + docker { image 'joinaero/kinetic-ros-opencv-xenial' } } /* @@ -16,10 +16,7 @@ pipeline { steps { echo "WORKSPACE: ${env.WORKSPACE}" echo 'apt-get ..' - sh ''' - apt-get update - apt-get install -y ros-kinetic-opencv3 - ''' + sh 'apt-get update' } } stage('Init') { @@ -91,7 +88,7 @@ pipeline { } failure { echo 'This will run only if failed' - mail to: 'mynteye@slightech.com', + mail to: 'mynteye-ci@slightech.com', subject: "Failed Pipeline: ${currentBuild.fullDisplayName}", body: "Something is wrong with ${env.BUILD_URL}" } From 8e302b9d072ecaeb20900a64c5c08dbdf168fef5 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Tue, 30 Oct 2018 15:56:09 +0800 Subject: [PATCH 44/77] Update dataset record --- tools/dataset/CMakeLists.txt | 6 ++ tools/dataset/dataset.cc | 28 ++++++++ tools/dataset/dataset.h | 4 ++ tools/dataset/record.cc | 56 +++++++--------- tools/dataset/record2.cc | 126 +++++++++++++++++++++++++++++++++++ 5 files changed, 188 insertions(+), 32 deletions(-) create mode 100644 tools/dataset/record2.cc diff --git a/tools/dataset/CMakeLists.txt b/tools/dataset/CMakeLists.txt index 33d8809..6948cc9 100644 --- a/tools/dataset/CMakeLists.txt +++ b/tools/dataset/CMakeLists.txt @@ -27,3 +27,9 @@ make_executable(record LINK_LIBS mynteye ${OpenCV_LIBS} DLL_SEARCH_PATHS ${PRO_DIR}/_install/bin ${OpenCV_LIB_SEARCH_PATH} ) + +make_executable(record2 + SRCS record2.cc dataset.cc + LINK_LIBS mynteye ${OpenCV_LIBS} + DLL_SEARCH_PATHS ${PRO_DIR}/_install/bin ${OpenCV_LIB_SEARCH_PATH} +) diff --git a/tools/dataset/dataset.cc b/tools/dataset/dataset.cc index 390e1a3..628ae14 100644 --- a/tools/dataset/dataset.cc +++ b/tools/dataset/dataset.cc @@ -87,6 +87,34 @@ void Dataset::SaveMotionData(const device::MotionData &data) { ++motion_count_; } +void Dataset::SaveStreamData( + const Stream &stream, const api::StreamData &data) { + auto &&writer = GetStreamWriter(stream); + auto seq = stream_counts_[stream]; + writer->ofs << seq << ", " << data.img->frame_id << ", " + << data.img->timestamp << ", " << data.img->exposure_time + << std::endl; + if (!data.frame.empty()) { + std::stringstream ss; + ss << writer->outdir << MYNTEYE_OS_SEP << std::dec + << std::setw(IMAGE_FILENAME_WIDTH) << std::setfill('0') << seq << ".png"; + cv::imwrite(ss.str(), data.frame); + } + ++stream_counts_[stream]; +} + +void Dataset::SaveMotionData(const api::MotionData &data) { + auto &&writer = GetMotionWriter(); + auto seq = motion_count_; + 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_; +} + Dataset::writer_t Dataset::GetStreamWriter(const Stream &stream) { try { return stream_writers_.at(stream); diff --git a/tools/dataset/dataset.h b/tools/dataset/dataset.h index 03edfa1..4e37740 100644 --- a/tools/dataset/dataset.h +++ b/tools/dataset/dataset.h @@ -21,6 +21,7 @@ #include #include "mynteye/mynteye.h" +#include "mynteye/api/api.h" #include "mynteye/device/callbacks.h" MYNTEYE_BEGIN_NAMESPACE @@ -43,6 +44,9 @@ class Dataset { void SaveStreamData(const Stream &stream, const device::StreamData &data); void SaveMotionData(const device::MotionData &data); + void SaveStreamData(const Stream &stream, const api::StreamData &data); + void SaveMotionData(const api::MotionData &data); + private: writer_t GetStreamWriter(const Stream &stream); writer_t GetMotionWriter(); diff --git a/tools/dataset/record.cc b/tools/dataset/record.cc index 63ada53..c9267ab 100644 --- a/tools/dataset/record.cc +++ b/tools/dataset/record.cc @@ -15,8 +15,7 @@ #include #include "mynteye/logger.h" -#include "mynteye/device/device.h" -#include "mynteye/device/utils.h" +#include "mynteye/api/api.h" #include "mynteye/util/times.h" #include "dataset/dataset.h" @@ -24,33 +23,31 @@ MYNTEYE_USE_NAMESPACE int main(int argc, char *argv[]) { - glog_init _(argc, argv); - - auto &&device = device::select(); - if (!device) + auto &&api = API::Create(argc, argv); + if (!api) 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] + 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 - 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] + 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] } - device->SetOptionValue(Option::IR_CONTROL, 80); - device->SetOptionValue(Option::FRAME_RATE, 25); - device->SetOptionValue(Option::IMU_FREQUENCY, 500); + api->SetOptionValue(Option::IR_CONTROL, 80); + api->SetOptionValue(Option::FRAME_RATE, 25); + api->SetOptionValue(Option::IMU_FREQUENCY, 500); */ - device->LogOptionInfos(); + api->LogOptionInfos(); // Enable this will cache the motion datas until you get them. - device->EnableMotionDatas(); - device->Start(Source::ALL); + api->EnableMotionDatas(); + api->Start(Source::ALL); const char *outdir; if (argc >= 2) { @@ -66,22 +63,17 @@ int main(int argc, char *argv[]) { std::size_t imu_count = 0; auto &&time_beg = times::now(); while (true) { - device->WaitForStreams(); + api->WaitForStreams(); - auto &&left_datas = device->GetStreamDatas(Stream::LEFT); - auto &&right_datas = device->GetStreamDatas(Stream::RIGHT); + auto &&left_datas = api->GetStreamDatas(Stream::LEFT); + auto &&right_datas = api->GetStreamDatas(Stream::RIGHT); img_count += left_datas.size(); - auto &&motion_datas = device->GetMotionDatas(); + auto &&motion_datas = api->GetMotionDatas(); imu_count += motion_datas.size(); - auto &&left_frame = left_datas.back().frame; - auto &&right_frame = right_datas.back().frame; - 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()); + auto &&left_img = left_datas.back().frame; + auto &&right_img = right_datas.back().frame; cv::Mat img; cv::hconcat(left_img, right_img, img); @@ -111,7 +103,7 @@ int main(int argc, char *argv[]) { std::cout << " to " << outdir << std::endl; auto &&time_end = times::now(); - device->Stop(Source::ALL); + api->Stop(Source::ALL); float elapsed_ms = times::count(time_end - time_beg) * 0.001f; diff --git a/tools/dataset/record2.cc b/tools/dataset/record2.cc new file mode 100644 index 0000000..63ada53 --- /dev/null +++ b/tools/dataset/record2.cc @@ -0,0 +1,126 @@ +// 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 + +#include "mynteye/logger.h" +#include "mynteye/device/device.h" +#include "mynteye/device/utils.h" +#include "mynteye/util/times.h" + +#include "dataset/dataset.h" + +MYNTEYE_USE_NAMESPACE + +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(); + + // Enable this will cache the motion datas until you get them. + device->EnableMotionDatas(); + device->Start(Source::ALL); + + const char *outdir; + if (argc >= 2) { + outdir = argv[1]; + } else { + outdir = "./dataset"; + } + tools::Dataset dataset(outdir); + + cv::namedWindow("frame"); + + std::size_t img_count = 0; + std::size_t imu_count = 0; + auto &&time_beg = times::now(); + while (true) { + device->WaitForStreams(); + + auto &&left_datas = device->GetStreamDatas(Stream::LEFT); + auto &&right_datas = device->GetStreamDatas(Stream::RIGHT); + img_count += left_datas.size(); + + auto &&motion_datas = device->GetMotionDatas(); + imu_count += motion_datas.size(); + + auto &&left_frame = left_datas.back().frame; + auto &&right_frame = right_datas.back().frame; + 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::Mat img; + cv::hconcat(left_img, right_img, img); + cv::imshow("frame", img); + + { // save + for (auto &&left : left_datas) { + dataset.SaveStreamData(Stream::LEFT, left); + } + for (auto &&right : right_datas) { + dataset.SaveStreamData(Stream::RIGHT, right); + } + + for (auto &&motion : motion_datas) { + dataset.SaveMotionData(motion); + } + + std::cout << "\rSaved " << img_count << " imgs" + << ", " << imu_count << " imus" << std::flush; + } + + char key = static_cast(cv::waitKey(1)); + if (key == 27 || key == 'q' || key == 'Q') { // ESC/Q + break; + } + } + std::cout << " to " << outdir << std::endl; + auto &&time_end = times::now(); + + device->Stop(Source::ALL); + + float elapsed_ms = + times::count(time_end - time_beg) * 0.001f; + LOG(INFO) << "Time beg: " << times::to_local_string(time_beg) + << ", end: " << times::to_local_string(time_end) + << ", 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; +} From 4c535150568fb22f1e2be78fbbcc95118b0f6845 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Wed, 31 Oct 2018 10:38:27 +0800 Subject: [PATCH 45/77] Improve ros cmake files --- .../src/mynt_eye_ros_wrapper/CMakeLists.txt | 15 +++++--- .../cmake/DetectOpenCV.cmake | 37 +++++++++++++++++++ .../cmake/IncludeGuard.cmake | 23 ++++++++++++ 3 files changed, 69 insertions(+), 6 deletions(-) create mode 100644 wrappers/ros/src/mynt_eye_ros_wrapper/cmake/DetectOpenCV.cmake create mode 100644 wrappers/ros/src/mynt_eye_ros_wrapper/cmake/IncludeGuard.cmake diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/CMakeLists.txt b/wrappers/ros/src/mynt_eye_ros_wrapper/CMakeLists.txt index ae85a88..92cea6c 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/CMakeLists.txt +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/CMakeLists.txt @@ -15,8 +15,6 @@ cmake_minimum_required(VERSION 2.8.3) project(mynt_eye_ros_wrapper) -get_filename_component(SDK_DIR "${PROJECT_SOURCE_DIR}/../../../.." ABSOLUTE) - if(NOT CMAKE_BUILD_TYPE) set(CMAKE_BUILD_TYPE Release) endif() @@ -77,9 +75,11 @@ catkin_package( CATKIN_DEPENDS cv_bridge geometry_msgs image_transport nodelet roscpp sensor_msgs std_msgs tf ) -get_filename_component(SDK_DIR "${PROJECT_SOURCE_DIR}/../../../.." ABSOLUTE) +#get_filename_component(SDK_DIR "${PROJECT_SOURCE_DIR}/../../../.." ABSOLUTE) +#LIST(APPEND CMAKE_PREFIX_PATH ${SDK_DIR}/_install/lib/cmake) + +LIST(APPEND CMAKE_MODULE_PATH cmake) -LIST(APPEND CMAKE_PREFIX_PATH ${SDK_DIR}/_install/lib/cmake) find_package(mynteye REQUIRED) message(STATUS "Found mynteye: ${mynteye_VERSION}") @@ -87,10 +87,13 @@ if(NOT mynteye_WITH_API) message(FATAL_ERROR "Must with API layer :(") endif() -include(${SDK_DIR}/cmake/DetectOpenCV.cmake) +include(cmake/DetectOpenCV.cmake) if(mynteye_WITH_GLOG) - include(${SDK_DIR}/cmake/DetectGLog.cmake) + find_package(glog REQUIRED) + if(glog_FOUND) + add_definitions(-DWITH_GLOG) + endif() endif() # targets diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/cmake/DetectOpenCV.cmake b/wrappers/ros/src/mynt_eye_ros_wrapper/cmake/DetectOpenCV.cmake new file mode 100644 index 0000000..4673876 --- /dev/null +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/cmake/DetectOpenCV.cmake @@ -0,0 +1,37 @@ +# 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(${CMAKE_CURRENT_LIST_DIR}/IncludeGuard.cmake) +cmake_include_guard() + +find_package(OpenCV REQUIRED) +message(STATUS "Found OpenCV: ${OpenCV_VERSION}") +if(OpenCV_VERSION VERSION_LESS 3.0) + add_definitions(-DUSE_OPENCV2) +elseif(OpenCV_VERSION VERSION_LESS 4.0) + add_definitions(-DUSE_OPENCV3) +else() + add_definitions(-DUSE_OPENCV4) +endif() + +list(FIND OpenCV_LIBS "opencv_world" __index) +if(${__index} GREATER -1) + set(WITH_OPENCV_WORLD TRUE) +endif() + +if(MSVC OR MSYS OR MINGW) + get_filename_component(OpenCV_LIB_SEARCH_PATH "${OpenCV_LIB_PATH}/../bin" ABSOLUTE) +else() + set(OpenCV_LIB_SEARCH_PATH "${OpenCV_LIB_PATH}") +endif() diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/cmake/IncludeGuard.cmake b/wrappers/ros/src/mynt_eye_ros_wrapper/cmake/IncludeGuard.cmake new file mode 100644 index 0000000..4c5dd68 --- /dev/null +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/cmake/IncludeGuard.cmake @@ -0,0 +1,23 @@ +# 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_guard: https://cmake.org/cmake/help/latest/command/include_guard.html + +macro(cmake_include_guard) + get_property(INCLUDE_GUARD GLOBAL PROPERTY "_INCLUDE_GUARD_${CMAKE_CURRENT_LIST_FILE}") + if(INCLUDE_GUARD) + return() + endif() + set_property(GLOBAL PROPERTY "_INCLUDE_GUARD_${CMAKE_CURRENT_LIST_FILE}" TRUE) +endmacro() From b102e5ae190ec03b96247483f7f61aea2eb23910 Mon Sep 17 00:00:00 2001 From: Tiny Date: Thu, 1 Nov 2018 16:59:05 +0800 Subject: [PATCH 46/77] add uvc code for test. --- src/mynteye/uvc/utlist_osx.h | 490 +++++++++++++++++++++++++++++ src/mynteye/uvc/uvc-libuvc.cc | 275 ++++++++++++++-- src/mynteye/uvc/uvc_osx_internal.h | 326 +++++++++++++++++++ 3 files changed, 1068 insertions(+), 23 deletions(-) create mode 100644 src/mynteye/uvc/utlist_osx.h create mode 100644 src/mynteye/uvc/uvc_osx_internal.h diff --git a/src/mynteye/uvc/utlist_osx.h b/src/mynteye/uvc/utlist_osx.h new file mode 100644 index 0000000..34c725b --- /dev/null +++ b/src/mynteye/uvc/utlist_osx.h @@ -0,0 +1,490 @@ +/* +Copyright (c) 2007-2010, Troy D. Hanson http://uthash.sourceforge.net +All rights reserved. + +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. + +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. +*/ + +#ifndef UTLIST_H +#define UTLIST_H + +#define UTLIST_VERSION 1.9.1 + +/* + * This file contains macros to manipulate singly and doubly-linked lists. + * + * 1. LL_ macros: singly-linked lists. + * 2. DL_ macros: doubly-linked lists. + * 3. CDL_ macros: circular doubly-linked lists. + * + * To use singly-linked lists, your structure must have a "next" pointer. + * To use doubly-linked lists, your structure must "prev" and "next" pointers. + * Either way, the pointer to the head of the list must be initialized to NULL. + * + * ----------------.EXAMPLE ------------------------- + * struct item { + * int id; + * struct item *prev, *next; + * } + * + * struct item *list = NULL: + * + * int main() { + * struct item *item; + * ... allocate and populate item ... + * DL_APPEND(list, item); + * } + * -------------------------------------------------- + * + * For doubly-linked lists, the append and delete macros are O(1) + * For singly-linked lists, append and delete are O(n) but prepend is O(1) + * The sort macro is O(n log(n)) for all types of single/double/circular lists. + */ + +/* These macros use decltype or the earlier __typeof GNU extension. + As decltype is only available in newer compilers (VS2010 or gcc 4.3+ + when compiling c++ code), this code uses whatever method is needed + or, for VS2008 where neither is available, uses casting workarounds. */ +#ifdef _MSC_VER /* MS compiler */ +#if _MSC_VER >= 1600 && defined(__cplusplus) /* VS2010 or newer in C++ mode */ +#define LDECLTYPE(x) decltype(x) +#else /* VS2008 or older (or VS2010 in C mode) */ +#define NO_DECLTYPE +#define LDECLTYPE(x) char* +#endif +#else /* GNU, Sun and other compilers */ +#define LDECLTYPE(x) __typeof(x) +#endif + +/* for VS2008 we use some workarounds to get around the lack of decltype, + * namely, we always reassign our tmp variable to the list head if we need + * to dereference its prev/next pointers, and save/restore the real head.*/ +#ifdef NO_DECLTYPE +#define _SV(elt,list) _tmp = (char*)(list); {char **_alias = (char**)&(list); *_alias = (elt); } +#define _NEXT(elt,list) ((char*)((list)->next)) +#define _NEXTASGN(elt,list,to) { char **_alias = (char**)&((list)->next); *_alias=(char*)(to); } +#define _PREV(elt,list) ((char*)((list)->prev)) +#define _PREVASGN(elt,list,to) { char **_alias = (char**)&((list)->prev); *_alias=(char*)(to); } +#define _RS(list) { char **_alias = (char**)&(list); *_alias=_tmp; } +#define _CASTASGN(a,b) { char **_alias = (char**)&(a); *_alias=(char*)(b); } +#else +#define _SV(elt,list) +#define _NEXT(elt,list) ((elt)->next) +#define _NEXTASGN(elt,list,to) ((elt)->next)=(to) +#define _PREV(elt,list) ((elt)->prev) +#define _PREVASGN(elt,list,to) ((elt)->prev)=(to) +#define _RS(list) +#define _CASTASGN(a,b) (a)=(b) +#endif + +/****************************************************************************** + * The sort macro is an adaptation of Simon Tatham's O(n log(n)) mergesort * + * Unwieldy variable names used here to avoid shadowing passed-in variables. * + *****************************************************************************/ +#define LL_SORT(list, cmp) \ +do { \ + LDECLTYPE(list) _ls_p; \ + LDECLTYPE(list) _ls_q; \ + LDECLTYPE(list) _ls_e; \ + LDECLTYPE(list) _ls_tail; \ + LDECLTYPE(list) _ls_oldhead; \ + LDECLTYPE(list) _tmp; \ + int _ls_insize, _ls_nmerges, _ls_psize, _ls_qsize, _ls_i, _ls_looping; \ + if (list) { \ + _ls_insize = 1; \ + _ls_looping = 1; \ + while (_ls_looping) { \ + _CASTASGN(_ls_p,list); \ + _CASTASGN(_ls_oldhead,list); \ + list = NULL; \ + _ls_tail = NULL; \ + _ls_nmerges = 0; \ + while (_ls_p) { \ + _ls_nmerges++; \ + _ls_q = _ls_p; \ + _ls_psize = 0; \ + for (_ls_i = 0; _ls_i < _ls_insize; _ls_i++) { \ + _ls_psize++; \ + _SV(_ls_q,list); _ls_q = _NEXT(_ls_q,list); _RS(list); \ + if (!_ls_q) break; \ + } \ + _ls_qsize = _ls_insize; \ + while (_ls_psize > 0 || (_ls_qsize > 0 && _ls_q)) { \ + if (_ls_psize == 0) { \ + _ls_e = _ls_q; _SV(_ls_q,list); _ls_q = _NEXT(_ls_q,list); _RS(list); _ls_qsize--; \ + } else if (_ls_qsize == 0 || !_ls_q) { \ + _ls_e = _ls_p; _SV(_ls_p,list); _ls_p = _NEXT(_ls_p,list); _RS(list); _ls_psize--; \ + } else if (cmp(_ls_p,_ls_q) <= 0) { \ + _ls_e = _ls_p; _SV(_ls_p,list); _ls_p = _NEXT(_ls_p,list); _RS(list); _ls_psize--; \ + } else { \ + _ls_e = _ls_q; _SV(_ls_q,list); _ls_q = _NEXT(_ls_q,list); _RS(list); _ls_qsize--; \ + } \ + if (_ls_tail) { \ + _SV(_ls_tail,list); _NEXTASGN(_ls_tail,list,_ls_e); _RS(list); \ + } else { \ + _CASTASGN(list,_ls_e); \ + } \ + _ls_tail = _ls_e; \ + } \ + _ls_p = _ls_q; \ + } \ + _SV(_ls_tail,list); _NEXTASGN(_ls_tail,list,NULL); _RS(list); \ + if (_ls_nmerges <= 1) { \ + _ls_looping=0; \ + } \ + _ls_insize *= 2; \ + } \ + } else _tmp=NULL; /* quiet gcc unused variable warning */ \ +} while (0) + +#define DL_SORT(list, cmp) \ +do { \ + LDECLTYPE(list) _ls_p; \ + LDECLTYPE(list) _ls_q; \ + LDECLTYPE(list) _ls_e; \ + LDECLTYPE(list) _ls_tail; \ + LDECLTYPE(list) _ls_oldhead; \ + LDECLTYPE(list) _tmp; \ + int _ls_insize, _ls_nmerges, _ls_psize, _ls_qsize, _ls_i, _ls_looping; \ + if (list) { \ + _ls_insize = 1; \ + _ls_looping = 1; \ + while (_ls_looping) { \ + _CASTASGN(_ls_p,list); \ + _CASTASGN(_ls_oldhead,list); \ + list = NULL; \ + _ls_tail = NULL; \ + _ls_nmerges = 0; \ + while (_ls_p) { \ + _ls_nmerges++; \ + _ls_q = _ls_p; \ + _ls_psize = 0; \ + for (_ls_i = 0; _ls_i < _ls_insize; _ls_i++) { \ + _ls_psize++; \ + _SV(_ls_q,list); _ls_q = _NEXT(_ls_q,list); _RS(list); \ + if (!_ls_q) break; \ + } \ + _ls_qsize = _ls_insize; \ + while (_ls_psize > 0 || (_ls_qsize > 0 && _ls_q)) { \ + if (_ls_psize == 0) { \ + _ls_e = _ls_q; _SV(_ls_q,list); _ls_q = _NEXT(_ls_q,list); _RS(list); _ls_qsize--; \ + } else if (_ls_qsize == 0 || !_ls_q) { \ + _ls_e = _ls_p; _SV(_ls_p,list); _ls_p = _NEXT(_ls_p,list); _RS(list); _ls_psize--; \ + } else if (cmp(_ls_p,_ls_q) <= 0) { \ + _ls_e = _ls_p; _SV(_ls_p,list); _ls_p = _NEXT(_ls_p,list); _RS(list); _ls_psize--; \ + } else { \ + _ls_e = _ls_q; _SV(_ls_q,list); _ls_q = _NEXT(_ls_q,list); _RS(list); _ls_qsize--; \ + } \ + if (_ls_tail) { \ + _SV(_ls_tail,list); _NEXTASGN(_ls_tail,list,_ls_e); _RS(list); \ + } else { \ + _CASTASGN(list,_ls_e); \ + } \ + _SV(_ls_e,list); _PREVASGN(_ls_e,list,_ls_tail); _RS(list); \ + _ls_tail = _ls_e; \ + } \ + _ls_p = _ls_q; \ + } \ + _CASTASGN(list->prev, _ls_tail); \ + _SV(_ls_tail,list); _NEXTASGN(_ls_tail,list,NULL); _RS(list); \ + if (_ls_nmerges <= 1) { \ + _ls_looping=0; \ + } \ + _ls_insize *= 2; \ + } \ + } else _tmp=NULL; /* quiet gcc unused variable warning */ \ +} while (0) + +#define CDL_SORT(list, cmp) \ +do { \ + LDECLTYPE(list) _ls_p; \ + LDECLTYPE(list) _ls_q; \ + LDECLTYPE(list) _ls_e; \ + LDECLTYPE(list) _ls_tail; \ + LDECLTYPE(list) _ls_oldhead; \ + LDECLTYPE(list) _tmp; \ + LDECLTYPE(list) _tmp2; \ + int _ls_insize, _ls_nmerges, _ls_psize, _ls_qsize, _ls_i, _ls_looping; \ + if (list) { \ + _ls_insize = 1; \ + _ls_looping = 1; \ + while (_ls_looping) { \ + _CASTASGN(_ls_p,list); \ + _CASTASGN(_ls_oldhead,list); \ + list = NULL; \ + _ls_tail = NULL; \ + _ls_nmerges = 0; \ + while (_ls_p) { \ + _ls_nmerges++; \ + _ls_q = _ls_p; \ + _ls_psize = 0; \ + for (_ls_i = 0; _ls_i < _ls_insize; _ls_i++) { \ + _ls_psize++; \ + _SV(_ls_q,list); \ + if (_NEXT(_ls_q,list) == _ls_oldhead) { \ + _ls_q = NULL; \ + } else { \ + _ls_q = _NEXT(_ls_q,list); \ + } \ + _RS(list); \ + if (!_ls_q) break; \ + } \ + _ls_qsize = _ls_insize; \ + while (_ls_psize > 0 || (_ls_qsize > 0 && _ls_q)) { \ + if (_ls_psize == 0) { \ + _ls_e = _ls_q; _SV(_ls_q,list); _ls_q = _NEXT(_ls_q,list); _RS(list); _ls_qsize--; \ + if (_ls_q == _ls_oldhead) { _ls_q = NULL; } \ + } else if (_ls_qsize == 0 || !_ls_q) { \ + _ls_e = _ls_p; _SV(_ls_p,list); _ls_p = _NEXT(_ls_p,list); _RS(list); _ls_psize--; \ + if (_ls_p == _ls_oldhead) { _ls_p = NULL; } \ + } else if (cmp(_ls_p,_ls_q) <= 0) { \ + _ls_e = _ls_p; _SV(_ls_p,list); _ls_p = _NEXT(_ls_p,list); _RS(list); _ls_psize--; \ + if (_ls_p == _ls_oldhead) { _ls_p = NULL; } \ + } else { \ + _ls_e = _ls_q; _SV(_ls_q,list); _ls_q = _NEXT(_ls_q,list); _RS(list); _ls_qsize--; \ + if (_ls_q == _ls_oldhead) { _ls_q = NULL; } \ + } \ + if (_ls_tail) { \ + _SV(_ls_tail,list); _NEXTASGN(_ls_tail,list,_ls_e); _RS(list); \ + } else { \ + _CASTASGN(list,_ls_e); \ + } \ + _SV(_ls_e,list); _PREVASGN(_ls_e,list,_ls_tail); _RS(list); \ + _ls_tail = _ls_e; \ + } \ + _ls_p = _ls_q; \ + } \ + _CASTASGN(list->prev,_ls_tail); \ + _CASTASGN(_tmp2,list); \ + _SV(_ls_tail,list); _NEXTASGN(_ls_tail,list,_tmp2); _RS(list); \ + if (_ls_nmerges <= 1) { \ + _ls_looping=0; \ + } \ + _ls_insize *= 2; \ + } \ + } else _tmp=NULL; /* quiet gcc unused variable warning */ \ +} while (0) + +/****************************************************************************** + * singly linked list macros (non-circular) * + *****************************************************************************/ +#define LL_PREPEND(head,add) \ +do { \ + (add)->next = head; \ + head = add; \ +} while (0) + +#define LL_APPEND(head,add) \ +do { \ + LDECLTYPE(head) _tmp; \ + (add)->next=NULL; \ + if (head) { \ + _tmp = head; \ + while (_tmp->next) { _tmp = _tmp->next; } \ + _tmp->next=(add); \ + } else { \ + (head)=(add); \ + } \ +} while (0) + +#define LL_DELETE(head,del) \ +do { \ + LDECLTYPE(head) _tmp; \ + if ((head) == (del)) { \ + (head)=(head)->next; \ + } else { \ + _tmp = head; \ + while (_tmp->next && (_tmp->next != (del))) { \ + _tmp = _tmp->next; \ + } \ + if (_tmp->next) { \ + _tmp->next = ((del)->next); \ + } \ + } \ +} while (0) + +/* Here are VS2008 replacements for LL_APPEND and LL_DELETE */ +#define LL_APPEND_VS2008(head,add) \ +do { \ + if (head) { \ + (add)->next = head; /* use add->next as a temp variable */ \ + while ((add)->next->next) { (add)->next = (add)->next->next; } \ + (add)->next->next=(add); \ + } else { \ + (head)=(add); \ + } \ + (add)->next=NULL; \ +} while (0) + +#define LL_DELETE_VS2008(head,del) \ +do { \ + if ((head) == (del)) { \ + (head)=(head)->next; \ + } else { \ + char *_tmp = (char*)(head); \ + while (head->next && (head->next != (del))) { \ + head = head->next; \ + } \ + if (head->next) { \ + head->next = ((del)->next); \ + } \ + { \ + char **_head_alias = (char**)&(head); \ + *_head_alias = _tmp; \ + } \ + } \ +} while (0) +#ifdef NO_DECLTYPE +#undef LL_APPEND +#define LL_APPEND LL_APPEND_VS2008 +#undef LL_DELETE +#define LL_DELETE LL_DELETE_VS2008 +#endif +/* end VS2008 replacements */ + +#define LL_FOREACH(head,el) \ + for(el=head;el;el=el->next) + +#define LL_FOREACH_SAFE(head,el,tmp) \ + for((el)=(head);(el) && (tmp = (el)->next, 1); (el) = tmp) + +#define LL_SEARCH_SCALAR(head,out,field,val) \ +do { \ + LL_FOREACH(head,out) { \ + if ((out)->field == (val)) break; \ + } \ +} while(0) + +#define LL_SEARCH(head,out,elt,cmp) \ +do { \ + LL_FOREACH(head,out) { \ + if ((cmp(out,elt))==0) break; \ + } \ +} while(0) + +/****************************************************************************** + * doubly linked list macros (non-circular) * + *****************************************************************************/ +#define DL_PREPEND(head,add) \ +do { \ + (add)->next = head; \ + if (head) { \ + (add)->prev = (head)->prev; \ + (head)->prev = (add); \ + } else { \ + (add)->prev = (add); \ + } \ + (head) = (add); \ +} while (0) + +#define DL_APPEND(head,add) \ +do { \ + if (head) { \ + (add)->prev = (head)->prev; \ + (head)->prev->next = (add); \ + (head)->prev = (add); \ + (add)->next = NULL; \ + } else { \ + (head)=(add); \ + (head)->prev = (head); \ + (head)->next = NULL; \ + } \ +} while (0); + +#define DL_DELETE(head,del) \ +do { \ + if ((del)->prev == (del)) { \ + (head)=NULL; \ + } else if ((del)==(head)) { \ + (del)->next->prev = (del)->prev; \ + (head) = (del)->next; \ + } else { \ + (del)->prev->next = (del)->next; \ + if ((del)->next) { \ + (del)->next->prev = (del)->prev; \ + } else { \ + (head)->prev = (del)->prev; \ + } \ + } \ +} while (0); + + +#define DL_FOREACH(head,el) \ + for(el=head;el;el=el->next) + +/* this version is safe for deleting the elements during iteration */ +#define DL_FOREACH_SAFE(head,el,tmp) \ + for((el)=(head);(el) && (tmp = (el)->next, 1); (el) = tmp) + +/* these are identical to their singly-linked list counterparts */ +#define DL_SEARCH_SCALAR LL_SEARCH_SCALAR +#define DL_SEARCH LL_SEARCH + +/****************************************************************************** + * circular doubly linked list macros * + *****************************************************************************/ +#define CDL_PREPEND(head,add) \ +do { \ + if (head) { \ + (add)->prev = (head)->prev; \ + (add)->next = (head); \ + (head)->prev = (add); \ + (add)->prev->next = (add); \ + } else { \ + (add)->prev = (add); \ + (add)->next = (add); \ + } \ +(head)=(add); \ +} while (0) + +#define CDL_DELETE(head,del) \ +do { \ + if ( ((head)==(del)) && ((head)->next == (head))) { \ + (head) = 0L; \ + } else { \ + (del)->next->prev = (del)->prev; \ + (del)->prev->next = (del)->next; \ + if ((del) == (head)) (head)=(del)->next; \ + } \ +} while (0); + +#define CDL_FOREACH(head,el) \ + for(el=head;el;el=(el->next==head ? 0L : el->next)) + +#define CDL_FOREACH_SAFE(head,el,tmp1,tmp2) \ + for((el)=(head), ((tmp1)=(head)?((head)->prev):NULL); \ + (el) && ((tmp2)=(el)->next, 1); \ + ((el) = (((el)==(tmp1)) ? 0L : (tmp2)))) + +#define CDL_SEARCH_SCALAR(head,out,field,val) \ +do { \ + CDL_FOREACH(head,out) { \ + if ((out)->field == (val)) break; \ + } \ +} while(0) + +#define CDL_SEARCH(head,out,elt,cmp) \ +do { \ + CDL_FOREACH(head,out) { \ + if ((cmp(out,elt))==0) break; \ + } \ +} while(0) + +#endif /* UTLIST_H */ + diff --git a/src/mynteye/uvc/uvc-libuvc.cc b/src/mynteye/uvc/uvc-libuvc.cc index e5e157b..e359476 100644 --- a/src/mynteye/uvc/uvc-libuvc.cc +++ b/src/mynteye/uvc/uvc-libuvc.cc @@ -11,11 +11,16 @@ // 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 "mynteye/uvc/uvc.h" - -#include +#include +#include +#include +#include #include "mynteye/logger.h" +#include "mynteye/uvc/uvc.h" +#include "libuvc/libuvc.h" + +#include "mynteye/uvc/uvc_osx_internal.h" // #define ENABLE_DEBUG_SPAM @@ -27,6 +32,8 @@ static void check(const char *call, uvc_error_t status) { LOG_IF(FATAL, status < 0) << call << "(...) returned " << uvc_strerror(status); } + +#define CALL_UVC_WITHOUT_CHECK(name, ...) name(__VA_ARGS__) #define CALL_UVC(name, ...) check(#name, name(__VA_ARGS__)) struct context { @@ -44,13 +51,41 @@ struct context { } }; +/** UVC request code (A.8) */ +enum uvc_req_code { + UVC_RC_UNDEFINED = 0x00, + UVC_SET_CUR = 0x01, + UVC_GET_CUR = 0x81, + UVC_GET_MIN = 0x82, + UVC_GET_MAX = 0x83, + UVC_GET_RES = 0x84, + UVC_GET_LEN = 0x85, + UVC_GET_INFO = 0x86, + UVC_GET_DEF = 0x87, + UVC_REQ_TYPE_GET = 0xa1, + UVC_REQ_TYPE_SET = 0x21 +}; + +struct device; + struct device { const std::shared_ptr parent; uvc_device_t *uvcdevice = nullptr; uvc_device_handle_t *handle = nullptr; - + /** Serial number (null if unavailable) */ + std::string serialNumber = ""; + /** Device-reported manufacturer name (or null) */ + std::string manufacturer = ""; + /** Device-reporter product name (or null) */ + std::string product = ""; + uvc_device_info_t info; + int width, height, format, fps; int vid, pid; + video_channel_callback callback = nullptr; + static std::vector s_devices; + + std::mutex _devices_mutex; device(std::shared_ptr parent, uvc_device_t *uvcdevice) : parent(parent), uvcdevice(uvcdevice) { @@ -59,9 +94,16 @@ struct device { uvc_device_descriptor_t *desc; CALL_UVC(uvc_get_device_descriptor, uvcdevice, &desc); + + serialNumber = std::string(desc->serialNumber); + manufacturer = std::string(desc->manufacturer); + product = std::string(desc->product); + vid = desc->idVendor; pid = desc->idProduct; uvc_free_device_descriptor(desc); + std::lock_guard lock(_devices_mutex); + s_devices.push_back(this); } ~device() { @@ -70,14 +112,83 @@ struct device { uvc_close(handle); if (uvcdevice) uvc_unref_device(uvcdevice); + std::lock_guard lock(_devices_mutex); + for(unsigned long i = 0 ; i < s_devices.size() ; i++) { + if(this == s_devices[i]) { + s_devices.erase(s_devices.begin()+i); + } + } } void open() { if (!handle) CALL_UVC(uvc_open, uvcdevice, &handle); } + + void set_format( + int width, int height, int format, int fps, + video_channel_callback callback) { + this->width = width; + this->height = height; + this->format = format; + this->fps = fps; + this->callback = callback; + } + + static void uvc_frame_callback (struct uvc_frame *frame, void *user_ptr) + { + for(unsigned long i = 0 ; i < s_devices.size() ; i++) { + if(user_ptr == (void*)s_devices[i]) { + printf("bingo\n"); + } + } + } + + // int32_t get_data_usb( uvc_req_code action, int control, int unit) const { + // unsigned char buffer[4]; + + // int status = libusb_control_transfer(handle->usb_devh, + // UVC_REQ_TYPE_GET, + // action, + // control << 8, + // unit << 8 | (1),// _interface + // buffer, + // sizeof(int32_t), 0); + // MYNTEYE_UNUSED(status); + // if (status < 0) throw std::runtime_error( + // to_string() << "libusb_control_transfer(...) returned " + // << libusb_error_name(status)); + + // if (status != sizeof(int32_t)) + // throw std::runtime_error("insufficient data read from USB"); + + // return DW_TO_INT(buffer); + // } + + // void set_data_usb( uvc_req_code action, int control, int unit, int value) const { + // unsigned char buffer[4]; + + // INT_TO_DW(value, buffer); + + // int status = libusb_control_transfer(handle->usb_devh, + // UVC_REQ_TYPE_SET, + // action, + // control << 8, + // unit << 8 | (1),// _interface + // buffer, + // sizeof(int32_t), 0); + + // if (status < 0) throw std::runtime_error( + // to_string() << "libusb_control_transfer(...) returned " + // << libusb_error_name(status)); + + // if (status != sizeof(int32_t)) + // throw std::runtime_error("insufficient data writen to USB"); + // } }; +std::vector device::s_devices; + std::shared_ptr create_context() { return std::make_shared(); } @@ -112,17 +223,48 @@ int get_product_id(const device &device) { } std::string get_name(const device &device) { - // TODO(JohnZhao) - MYNTEYE_UNUSED(device) - return ""; + return device.serialNumber + "/" + device.manufacturer + "/" + device.product; } std::string get_video_name(const device &device) { - // TODO(JohnZhao) - MYNTEYE_UNUSED(device) - return ""; + return device.serialNumber + "/" + device.manufacturer + "/" + device.product; } +// class uvc_device +// { +// public: +// virtual void probe_and_commit(stream_profile profile, frame_callback callback, int buffers = DEFAULT_V4L2_FRAME_BUFFERS) = 0; +// virtual void stream_on(std::function error_handler = [](const notification& n){}) = 0; +// virtual void start_callbacks() = 0; +// virtual void stop_callbacks() = 0; +// virtual void close(stream_profile profile) = 0; + +// virtual void set_power_state(power_state state) = 0; +// virtual power_state get_power_state() const = 0; + +// virtual void init_xu(const extension_unit& xu) = 0; +// virtual bool set_xu(const extension_unit& xu, uint8_t ctrl, const uint8_t* data, int len) = 0; +// virtual bool get_xu(const extension_unit& xu, uint8_t ctrl, uint8_t* data, int len) const = 0; +// virtual control_range get_xu_range(const extension_unit& xu, uint8_t ctrl, int len) const = 0; + +// virtual bool get_pu(rs2_option opt, int32_t& value) const = 0; +// virtual bool set_pu(rs2_option opt, int32_t value) = 0; +// virtual control_range get_pu_range(rs2_option opt) const = 0; + +// virtual std::vector get_profiles() const = 0; + +// virtual void lock() const = 0; +// virtual void unlock() const = 0; + +// virtual std::string get_device_location() const = 0; +// virtual usb_spec get_usb_specification() const = 0; + +// virtual ~uvc_device() = default; + +// protected: +// std::function _error_handler; +// }; + bool pu_control_range( const device &device, Option option, int32_t *min, int32_t *max, int32_t *def) { @@ -132,6 +274,7 @@ bool pu_control_range( MYNTEYE_UNUSED(min) MYNTEYE_UNUSED(max) MYNTEYE_UNUSED(def) + // device.uvcdevice -> set_pu(option, *def); return false; } @@ -173,26 +316,112 @@ bool xu_control_query( } void set_device_mode( - device &device, int width, int height, int fourcc, int fps, // NOLINT + device &device, int width, int height, int format, int fps, // NOLINT video_channel_callback callback) { - // TODO(JohnZhao) - MYNTEYE_UNUSED(device) - MYNTEYE_UNUSED(width) - MYNTEYE_UNUSED(height) - MYNTEYE_UNUSED(fourcc) - MYNTEYE_UNUSED(fps) - MYNTEYE_UNUSED(callback) + device.set_format(width, height, format, fps, callback); } void start_streaming(device &device, int num_transfer_bufs) { // NOLINT - // TODO(JohnZhao) - MYNTEYE_UNUSED(device) - MYNTEYE_UNUSED(num_transfer_bufs) + // MYNTEYE_UNUSED(device) + // MYNTEYE_UNUSED(num_transfer_bufs) + +// typedef struct uvc_stream_ctrl { +// uint16_t bmHint; +// uint8_t bFormatIndex; +// uint8_t bFrameIndex; +// uint32_t dwFrameInterval; +// uint16_t wKeyFrameRate; +// uint16_t wPFrameRate; +// uint16_t wCompQuality; +// uint16_t wCompWindowSize; +// uint16_t wDelay; +// uint32_t dwMaxVideoFrameSize; +// uint32_t dwMaxPayloadTransferSize; +// uint32_t dwClockFrequency; +// uint8_t bmFramingInfo; +// uint8_t bPreferredVersion; +// uint8_t bMinVersion; +// uint8_t bMaxVersion; +// uint8_t bInterfaceNumber; +// } uvc_stream_ctrl_t; + + // uvc_error_t uvc_get_stream_ctrl_format_size( + // uvc_device_handle_t *devh, + // uvc_stream_ctrl_t *ctrl, + // enum uvc_frame_format format, + // int width, int height, + // int fps + // ); + + uvc_stream_ctrl_t ctrl_st = {}; + + /** Color coding of stream, transport-independent + * @ingroup streaming + */ +// enum uvc_frame_format { +// UVC_FRAME_FORMAT_UNKNOWN = 0, +// /** Any supported format */ +// UVC_FRAME_FORMAT_ANY = 0, +// UVC_FRAME_FORMAT_UNCOMPRESSED, +// UVC_FRAME_FORMAT_COMPRESSED, +// /** YUYV/YUV2/YUV422: YUV encoding with one luminance value per pixel and +// * one UV (chrominance) pair for every two pixels. +// */ +// UVC_FRAME_FORMAT_YUYV, +// UVC_FRAME_FORMAT_UYVY, +// /** 24-bit RGB */ +// UVC_FRAME_FORMAT_RGB, +// UVC_FRAME_FORMAT_BGR, +// /** Motion-JPEG (or JPEG) encoded images */ +// UVC_FRAME_FORMAT_MJPEG, +// /** Greyscale images */ +// UVC_FRAME_FORMAT_GRAY8, +// UVC_FRAME_FORMAT_GRAY16, +// /* Raw colour mosaic images */ +// UVC_FRAME_FORMAT_BY8, +// UVC_FRAME_FORMAT_BA81, +// UVC_FRAME_FORMAT_SGRBG8, +// UVC_FRAME_FORMAT_SGBRG8, +// UVC_FRAME_FORMAT_SRGGB8, +// UVC_FRAME_FORMAT_SBGGR8, +// /** Number of formats understood */ +// UVC_FRAME_FORMAT_COUNT, +// }; + CALL_UVC(uvc_get_stream_ctrl_format_size, + device.handle, + &ctrl_st, + UVC_FRAME_FORMAT_ANY, // UVC_FRAME_FORMAT_YUYV, //(enum uvc_frame_format)device.format, + device.width, + device.height, + device.fps); + + /** A callback function to handle incoming assembled UVC frames + * @ingroup streaming + */ +// typedef void(uvc_frame_callback_t)(struct uvc_frame *frame, void *user_ptr); + // uvc_frame_callback_t *cb = nullptr; + + CALL_UVC(uvc_start_streaming, + device.handle, + &ctrl_st, + device::uvc_frame_callback, + &device, + num_transfer_bufs); + + printf("begin\n"); + +// uvc_error_t uvc_start_streaming( +// uvc_device_handle_t *devh, +// uvc_stream_ctrl_t *ctrl, +// uvc_frame_callback_t *cb, +// void *user_ptr, +// uint8_t flags); } void stop_streaming(device &device) { // NOLINT - // TODO(JohnZhao) - MYNTEYE_UNUSED(device) + // MYNTEYE_UNUSED(device) + + CALL_UVC_WITHOUT_CHECK(uvc_stop_streaming, device.handle); } } // namespace uvc diff --git a/src/mynteye/uvc/uvc_osx_internal.h b/src/mynteye/uvc/uvc_osx_internal.h new file mode 100644 index 0000000..2f8ccc9 --- /dev/null +++ b/src/mynteye/uvc/uvc_osx_internal.h @@ -0,0 +1,326 @@ +/** @file libuvc_internal.h + * @brief Implementation-specific UVC constants and structures. + * @cond include_hidden + */ +#ifndef UVC_OSX_INTERNAL_H +#define UVC_OSX_INTERNAL_H + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "mynteye/uvc/utlist_osx.h" + +#pragma GCC diagnostic ignored "-Wpedantic" +#include + +/** Converts an unaligned four-byte little-endian integer into an int32 */ +#define DW_TO_INT(p) ((p)[0] | ((p)[1] << 8) | ((p)[2] << 16) | ((p)[3] << 24)) +/** Converts an unaligned two-byte little-endian integer into an int16 */ +#define SW_TO_SHORT(p) ((p)[0] | ((p)[1] << 8)) +/** Converts an unaligned eight-byte little-endian integer into an int64 */ +#define QW_TO_QUAD(p) ((p)[0] | ((p)[1] << 8) | ((p)[2] << 16) | ((p)[3] << 24) | \ + ((p)[4] << 32) |((p)[5] << 40) |((p)[6] << 48) |((p)[7] << 56)) + +/** Converts an int16 into an unaligned two-byte little-endian integer */ +#define SHORT_TO_SW(s, p) \ + (p)[0] = (s); \ + (p)[1] = (s) >> 8; +/** Converts an int32 into an unaligned four-byte little-endian integer */ +#define INT_TO_DW(i, p) \ + (p)[0] = (i); \ + (p)[1] = (i) >> 8; \ + (p)[2] = (i) >> 16; \ + (p)[3] = (i) >> 24; + +/** Converts an int64 into an unaligned eight-byte little-endian integer */ +#define QUAD_TO_QW(i, p) \ + (p)[0] = (i); \ + (p)[1] = (i) >> 8; \ + (p)[2] = (i) >> 16; \ + (p)[3] = (i) >> 24; \ + (p)[4] = (i) >> 32; \ + (p)[5] = (i) >> 40; \ + (p)[6] = (i) >> 48; \ + (p)[7] = (i) >> 56; \ + +/** Selects the nth item in a doubly linked list. n=-1 selects the last item. */ +#define DL_NTH(head, out, n) \ + do { \ + int dl_nth_i = 0; \ + LDECLTYPE(head) dl_nth_p = (head); \ + if ((n) < 0) { \ + while (dl_nth_p && dl_nth_i > (n)) { \ + dl_nth_p = dl_nth_p->prev; \ + dl_nth_i--; \ + } \ + } else { \ + while (dl_nth_p && dl_nth_i < (n)) { \ + dl_nth_p = dl_nth_p->next; \ + dl_nth_i++; \ + } \ + } \ + (out) = dl_nth_p; \ + } while (0); + +#ifdef UVC_DEBUGGING +#include +#define UVC_DEBUG(format, ...) fprintf(stderr, "[%s:%d/%s] " format "\n", basename(__FILE__), __LINE__, __FUNCTION__, ##__VA_ARGS__) +#define UVC_ENTER() fprintf(stderr, "[%s:%d] begin %s\n", basename(__FILE__), __LINE__, __FUNCTION__) +#define UVC_EXIT(code) fprintf(stderr, "[%s:%d] end %s (%d)\n", basename(__FILE__), __LINE__, __FUNCTION__, code) +#define UVC_EXIT_VOID() fprintf(stderr, "[%s:%d] end %s\n", basename(__FILE__), __LINE__, __FUNCTION__) +#else +#define UVC_DEBUG(format, ...) +#define UVC_ENTER() +#define UVC_EXIT_VOID() +#define UVC_EXIT(code) +#endif + +/* http://stackoverflow.com/questions/19452971/array-size-macro-that-rejects-pointers */ +#define IS_INDEXABLE(arg) (sizeof(arg[0])) +#define IS_ARRAY(arg) (IS_INDEXABLE(arg) && (((void *) &arg) == ((void *) arg))) +#define ARRAYSIZE(arr) (sizeof(arr) / (IS_ARRAY(arr) ? sizeof(arr[0]) : 0)) + +/** Video interface subclass code (A.2) */ +enum uvc_int_subclass_code { + UVC_SC_UNDEFINED = 0x00, + UVC_SC_VIDEOCONTROL = 0x01, + UVC_SC_VIDEOSTREAMING = 0x02, + UVC_SC_VIDEO_INTERFACE_COLLECTION = 0x03 +}; + +/** Video interface protocol code (A.3) */ +enum uvc_int_proto_code { + UVC_PC_PROTOCOL_UNDEFINED = 0x00 +}; + +/** VideoControl interface descriptor subtype (A.5) */ +enum uvc_vc_desc_subtype { + UVC_VC_DESCRIPTOR_UNDEFINED = 0x00, + UVC_VC_HEADER = 0x01, + UVC_VC_INPUT_TERMINAL = 0x02, + UVC_VC_OUTPUT_TERMINAL = 0x03, + UVC_VC_SELECTOR_UNIT = 0x04, + UVC_VC_PROCESSING_UNIT = 0x05, + UVC_VC_EXTENSION_UNIT = 0x06 +}; + +/** UVC endpoint descriptor subtype (A.7) */ +enum uvc_ep_desc_subtype { + UVC_EP_UNDEFINED = 0x00, + UVC_EP_GENERAL = 0x01, + UVC_EP_ENDPOINT = 0x02, + UVC_EP_INTERRUPT = 0x03 +}; + +/** VideoControl interface control selector (A.9.1) */ +enum uvc_vc_ctrl_selector { + UVC_VC_CONTROL_UNDEFINED = 0x00, + UVC_VC_VIDEO_POWER_MODE_CONTROL = 0x01, + UVC_VC_REQUEST_ERROR_CODE_CONTROL = 0x02 +}; + +/** Terminal control selector (A.9.2) */ +enum uvc_term_ctrl_selector { + UVC_TE_CONTROL_UNDEFINED = 0x00 +}; + +/** Selector unit control selector (A.9.3) */ +enum uvc_su_ctrl_selector { + UVC_SU_CONTROL_UNDEFINED = 0x00, + UVC_SU_INPUT_SELECT_CONTROL = 0x01 +}; + +/** Extension unit control selector (A.9.6) */ +enum uvc_xu_ctrl_selector { + UVC_XU_CONTROL_UNDEFINED = 0x00 +}; + +/** VideoStreaming interface control selector (A.9.7) */ +enum uvc_vs_ctrl_selector { + UVC_VS_CONTROL_UNDEFINED = 0x00, + UVC_VS_PROBE_CONTROL = 0x01, + UVC_VS_COMMIT_CONTROL = 0x02, + UVC_VS_STILL_PROBE_CONTROL = 0x03, + UVC_VS_STILL_COMMIT_CONTROL = 0x04, + UVC_VS_STILL_IMAGE_TRIGGER_CONTROL = 0x05, + UVC_VS_STREAM_ERROR_CODE_CONTROL = 0x06, + UVC_VS_GENERATE_KEY_FRAME_CONTROL = 0x07, + UVC_VS_UPDATE_FRAME_SEGMENT_CONTROL = 0x08, + UVC_VS_SYNC_DELAY_CONTROL = 0x09 +}; + +/** Status packet type (2.4.2.2) */ +enum uvc_status_type { + UVC_STATUS_TYPE_CONTROL = 1, + UVC_STATUS_TYPE_STREAMING = 2 +}; + +/** Payload header flags (2.4.3.3) */ +#define UVC_STREAM_EOH (1 << 7) +#define UVC_STREAM_ERR (1 << 6) +#define UVC_STREAM_STI (1 << 5) +#define UVC_STREAM_RES (1 << 4) +#define UVC_STREAM_SCR (1 << 3) +#define UVC_STREAM_PTS (1 << 2) +#define UVC_STREAM_EOF (1 << 1) +#define UVC_STREAM_FID (1 << 0) + +/** Control capabilities (4.1.2) */ +#define UVC_CONTROL_CAP_GET (1 << 0) +#define UVC_CONTROL_CAP_SET (1 << 1) +#define UVC_CONTROL_CAP_DISABLED (1 << 2) +#define UVC_CONTROL_CAP_AUTOUPDATE (1 << 3) +#define UVC_CONTROL_CAP_ASYNCHRONOUS (1 << 4) + +struct uvc_streaming_interface; +struct uvc_device_info; + +/** VideoStream interface */ +typedef struct uvc_streaming_interface { + struct uvc_device_info *parent; + struct uvc_streaming_interface *prev, *next; + /** Interface number */ + uint8_t bInterfaceNumber; + /** Video formats that this interface provides */ + struct uvc_format_desc *format_descs; + /** USB endpoint to use when communicating with this interface */ + uint8_t bEndpointAddress; + uint8_t bTerminalLink; +} uvc_streaming_interface_t; + +/** VideoControl interface */ +typedef struct uvc_control_interface { + struct uvc_device_info *parent; + struct uvc_input_terminal *input_term_descs; + // struct uvc_output_terminal *output_term_descs; + struct uvc_selector_unit *selector_unit_descs; + struct uvc_processing_unit *processing_unit_descs; + struct uvc_extension_unit *extension_unit_descs; + uint16_t bcdUVC; + uint32_t dwClockFrequency; + uint8_t bEndpointAddress; + /** Interface number */ + uint8_t bInterfaceNumber; +} uvc_control_interface_t; + +struct uvc_stream_ctrl; + +struct uvc_device { + struct uvc_context *ctx; + int ref; + libusb_device *usb_dev; + int interface; +}; + +typedef struct uvc_device_info { + /** Configuration descriptor for USB device */ + struct libusb_config_descriptor *config; + /** VideoControl interface provided by device */ + uvc_control_interface_t ctrl_if; + /** VideoStreaming interfaces on the device */ + uvc_streaming_interface_t *stream_ifs; + /** Store the interface for multiple UVCs on a single VID/PID device (Intel RealSense, VF200, e.g) */ + int camera_number; +} uvc_device_info_t; + +/* + set a high number of transfer buffers. This uses a lot of ram, but + avoids problems with scheduling delays on slow boards causing missed + transfers. A better approach may be to make the transfer thread FIFO + scheduled (if we have root). + We could/should change this to allow reduce it to, say, 5 by default + and then allow the user to change the number of buffers as required. + */ +#define LIBUVC_NUM_TRANSFER_BUFS 1 + +#define LIBUVC_XFER_BUF_SIZE ( 16 * 1024 * 1024 ) + +struct uvc_stream_handle { + struct uvc_device_handle *devh; + struct uvc_stream_handle *prev, *next; + struct uvc_streaming_interface *stream_if; + + /** if true, stream is running (streaming video to host) */ + std::atomic running; + /** Current control block */ + struct uvc_stream_ctrl cur_ctrl; + + /* listeners may only access hold*, and only when holding a + * lock on cb_mutex (probably signaled with cb_cond) */ + uint8_t fid; + uint32_t seq, hold_seq; + uint32_t pts, hold_pts; + uint32_t last_scr, hold_last_scr; + uint8_t *metadata_buf; + size_t metadata_bytes,metadata_size; + size_t got_bytes, hold_bytes; + uint8_t *outbuf, *holdbuf; + std::mutex cb_mutex; + std::condition_variable cb_cond; + std::thread cb_thread; + uint32_t last_polled_seq; + uvc_frame_callback_t *user_cb; + void *user_ptr; + struct libusb_transfer *transfers[LIBUVC_NUM_TRANSFER_BUFS]; + uint8_t *transfer_bufs[LIBUVC_NUM_TRANSFER_BUFS]; + std::condition_variable transfer_cancel[LIBUVC_NUM_TRANSFER_BUFS]; + struct uvc_frame frame; + enum uvc_frame_format frame_format; +}; + +/** Handle on an open UVC device + * + * @todo move most of this into a uvc_device struct? + */ +struct uvc_device_handle { + struct uvc_device *dev; + struct uvc_device_handle *prev, *next; + /** Underlying USB device handle */ + libusb_device_handle *usb_devh; + struct uvc_device_info *info; + struct libusb_transfer *status_xfer; + uint8_t status_buf[32]; + /** Function to call when we receive status updates from the camera */ + uvc_status_callback_t *status_cb; + void *status_user_ptr; + /** Function to call when we receive button events from the camera */ + uvc_button_callback_t *button_cb; + void *button_user_ptr; + + uvc_stream_handle_t *streams; + /** Whether the camera is an iSight that sends one header per frame */ + uint8_t is_isight; +}; + +/** Context within which we communicate with devices */ +struct uvc_context { + /** Underlying context for USB communication */ + struct libusb_context *usb_ctx; + /** True iff libuvc initialized the underlying USB context */ + uint8_t own_usb_ctx; + /** List of open devices in this context */ + uvc_device_handle_t *open_devices; + std::thread handler_thread; + int kill_handler_thread; +}; + +uvc_error_t uvc_query_stream_ctrl( + uvc_device_handle_t *devh, + uvc_stream_ctrl_t *ctrl, + uint8_t probe, + enum uvc_req_code req); + +void uvc_start_handler_thread(uvc_context_t *ctx); +uvc_error_t uvc_claim_if(uvc_device_handle_t *devh, int idx); +uvc_error_t uvc_release_if(uvc_device_handle_t *devh, int idx); + +#endif // !def(UVC_OSX_INTERNAL_H) +/** @endcond */ + From d44302959919f5e52bebf68d92be381a3494cae0 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Thu, 1 Nov 2018 20:03:23 +0800 Subject: [PATCH 47/77] Add make win pkg target --- CommonDefs.mk | 9 +++++++++ Makefile | 24 +++++++++++++++++++++--- scripts/version.sh | 24 ++++++++++++++++++++++++ scripts/win/winpack.sh | 23 +++++++++++++++++++++++ 4 files changed, 77 insertions(+), 3 deletions(-) create mode 100644 scripts/version.sh create mode 100644 scripts/win/winpack.sh diff --git a/CommonDefs.mk b/CommonDefs.mk index 378b7ff..73187a9 100644 --- a/CommonDefs.mk +++ b/CommonDefs.mk @@ -202,6 +202,15 @@ endif endif +# Package + +PKGVERSION := $(shell ./scripts/version.sh) +PKGNAME := mynteye-$(PKGVERSION)-$(HOST_OS)-$(HOST_ARCH) +ifeq ($(HOST_OS),Linux) + PKGNAME := $(PKGNAME)-gcc$(shell gcc -dumpversion | cut -c 1-1) +endif +PKGNAME := $(call lower,$(PKGNAME)) + # Shell # `sh` is not possible to export a function diff --git a/Makefile b/Makefile index 479c994..2b5cf89 100644 --- a/Makefile +++ b/Makefile @@ -37,6 +37,7 @@ help: @echo " make test build test and run" @echo " make samples build samples" @echo " make tools build tools" + @echo " make pkg package sdk" @echo " make ros build ros wrapper" @echo " make py build python wrapper" @echo " make clean|cleanall clean generated or useless things" @@ -162,14 +163,30 @@ tools: install .PHONY: tools +# pkg + +pkg: clean + @$(call echo,Make $@) +ifeq ($(HOST_OS),Win) + @$(SH) ./scripts/win/winpack.sh +else + $(error "Can't make pkg on $(HOST_OS)") +endif + +cleanpkg: + @$(call echo,Make $@) + @$(call rm_f,$(PKGNAME)*) + +.PHONY: pkg cleanpkg + # ros ros: install @$(call echo,Make $@) -ifeq ($(HOST_OS),Win) - $(error "Can't make ros on win") -else +ifeq ($(HOST_OS),Linux) @cd ./wrappers/ros && catkin_make +else + $(error "Can't make ros on $(HOST_OS)") endif .PHONY: ros @@ -278,6 +295,7 @@ host: @echo BUILD: $(BUILD) @echo LDD: $(LDD) @echo CMAKE: $(CMAKE) + @echo PKGNAME: $(PKGNAME) .PHONY: host diff --git a/scripts/version.sh b/scripts/version.sh new file mode 100644 index 0000000..e3903e1 --- /dev/null +++ b/scripts/version.sh @@ -0,0 +1,24 @@ +#!/usr/bin/env bash +# 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. + +BASE_DIR=$(cd "$(dirname "$0")" && pwd) +ROOT_DIR=$(dirname "$BASE_DIR") +CONFIG_FILE="$ROOT_DIR/CMakeLists.txt" + +version=$(cat "$CONFIG_FILE" | grep -m1 "mynteye VERSION") +version=$(echo "${version%LANGUAGES*}") +version=$(echo "${version#*VERSION}" | tr -d '[:space:]') + +echo "$version" diff --git a/scripts/win/winpack.sh b/scripts/win/winpack.sh new file mode 100644 index 0000000..dbad223 --- /dev/null +++ b/scripts/win/winpack.sh @@ -0,0 +1,23 @@ +#!/usr/bin/env bash +# 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. + +BASE_DIR=$(cd "$(dirname "$0")" && pwd) +ROOT_DIR=$(realpath "$BASE_DIR/../..") +SCRIPTS_DIR=$(realpath "$BASE_DIR/..") + +source "$SCRIPTS_DIR/common/echo.sh" +source "$SCRIPTS_DIR/common/detect.sh" + +_echo_s "winpack.sh" From f9234146607f8a673fcb210aca4e777466505794 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Thu, 1 Nov 2018 20:42:44 +0800 Subject: [PATCH 48/77] Support debug build --- CMakeLists.txt | 4 ++++ CommonDefs.mk | 15 ++++++++++++--- include/mynteye/device/device.h | 8 +++++--- src/mynteye/device/device.cc | 5 +++++ 4 files changed, 26 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 31f7a63..7801c02 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -18,6 +18,10 @@ project(mynteye VERSION 2.2.1 LANGUAGES C CXX) include(cmake/Common.cmake) +if(NOT CMAKE_DEBUG_POSTFIX) + set(CMAKE_DEBUG_POSTFIX d) +endif() + # options include(cmake/Option.cmake) diff --git a/CommonDefs.mk b/CommonDefs.mk index 73187a9..11bc77b 100644 --- a/CommonDefs.mk +++ b/CommonDefs.mk @@ -26,6 +26,16 @@ SINGLE_QUOTE := ' OPEN_PAREN := ( CLOSE_PAREN := ) +# Options +# +# VS_CODE: ignore to auto detect, otherwise specify the version +# 15|2017, 14|2015, 12|2013, 11|2012, 10|2010, 9|2008, 8|2005 +# BUILD_TYPE: Debug|Release +# +# e.g. make [TARGET] VS_CODE=2017 BUILD_TYPE=Debug + +BUILD_TYPE ?= Release + # Host detection ifeq ($(OS),Windows_NT) @@ -124,7 +134,7 @@ ifeq ($(HOST_OS),Win) CC := cl CXX := cl MAKE := make - BUILD := msbuild.exe ALL_BUILD.vcxproj /property:Configuration=Release + BUILD := msbuild.exe ALL_BUILD.vcxproj /property:Configuration=$(BUILD_TYPE) endif else # mac & linux @@ -144,8 +154,7 @@ endif # CMake CMAKE := cmake -# CMAKE := $(CMAKE) -DCMAKE_BUILD_TYPE=Debug -CMAKE := $(CMAKE) -DCMAKE_BUILD_TYPE=Release +CMAKE := $(CMAKE) -DCMAKE_BUILD_TYPE=$(BUILD_TYPE) ifneq ($(CC),) CMAKE := $(CMAKE) -DCMAKE_C_COMPILER=$(CC) endif diff --git a/include/mynteye/device/device.h b/include/mynteye/device/device.h index 2d81632..11ee2fb 100644 --- a/include/mynteye/device/device.h +++ b/include/mynteye/device/device.h @@ -15,7 +15,6 @@ #define MYNTEYE_DEVICE_DEVICE_H_ #pragma once -#include #include #include #include @@ -245,8 +244,11 @@ class MYNTEYE_API Device { /** * Enable cache motion datas. */ - void EnableMotionDatas( - std::size_t max_size = std::numeric_limits::max()); + void EnableMotionDatas(); + /** + * Enable cache motion datas. + */ + void EnableMotionDatas(std::size_t max_size); /** * Get the motion datas. */ diff --git a/src/mynteye/device/device.cc b/src/mynteye/device/device.cc index 32c79ed..3a0e1aa 100644 --- a/src/mynteye/device/device.cc +++ b/src/mynteye/device/device.cc @@ -15,6 +15,7 @@ #include #include +#include #include #include @@ -415,6 +416,10 @@ device::StreamData Device::GetLatestStreamData(const Stream &stream) { return streams_->GetLatestStreamData(stream); } +void Device::EnableMotionDatas() { + EnableMotionDatas(std::numeric_limits::max()); +} + void Device::EnableMotionDatas(std::size_t max_size) { CHECK_NOTNULL(motions_); motions_->EnableMotionDatas(max_size); From f803e3a75badf1f68f43cc8f8d577e0f5719bb68 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Thu, 1 Nov 2018 23:12:36 +0800 Subject: [PATCH 49/77] Update winpack script --- .gitignore | 4 + CMakeLists.txt | 7 + CommonDefs.mk | 2 +- Makefile | 2 +- scripts/common/echo.sh | 10 + .../win/cmake/mynteye-targets-release.cmake | 29 ++ scripts/win/cmake/mynteye-targets.cmake | 102 +++++ scripts/win/nsis/Include/EnvVarUpdate.nsh | 350 ++++++++++++++++++ scripts/win/nsis/mynt.ico | Bin 0 -> 4286 bytes scripts/win/nsis/winpack.nsi.in | 197 ++++++++++ scripts/win/winpack.sh | 77 +++- 11 files changed, 777 insertions(+), 3 deletions(-) create mode 100644 scripts/win/cmake/mynteye-targets-release.cmake create mode 100644 scripts/win/cmake/mynteye-targets.cmake create mode 100644 scripts/win/nsis/Include/EnvVarUpdate.nsh create mode 100644 scripts/win/nsis/mynt.ico create mode 100644 scripts/win/nsis/winpack.nsi.in diff --git a/.gitignore b/.gitignore index 7be8236..478ce28 100644 --- a/.gitignore +++ b/.gitignore @@ -16,6 +16,10 @@ _output/ /plugins/ +/3rdparty/opencv/ +/*.nsi +/*.exe + # ros /wrappers/ros/build diff --git a/CMakeLists.txt b/CMakeLists.txt index 7801c02..2ae3bae 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -83,6 +83,13 @@ configure_file( include/mynteye/mynteye.h @ONLY ) +if(OS_WIN) + configure_file( + scripts/win/nsis/winpack.nsi.in + ${CMAKE_CURRENT_SOURCE_DIR}/winpack.nsi @ONLY + ) +endif() + # targets add_definitions(-DMYNTEYE_EXPORTS) diff --git a/CommonDefs.mk b/CommonDefs.mk index 11bc77b..1df3a94 100644 --- a/CommonDefs.mk +++ b/CommonDefs.mk @@ -214,7 +214,7 @@ endif # Package PKGVERSION := $(shell ./scripts/version.sh) -PKGNAME := mynteye-$(PKGVERSION)-$(HOST_OS)-$(HOST_ARCH) +PKGNAME := mynteye-s-$(PKGVERSION)-$(HOST_OS)-$(HOST_ARCH) ifeq ($(HOST_OS),Linux) PKGNAME := $(PKGNAME)-gcc$(shell gcc -dumpversion | cut -c 1-1) endif diff --git a/Makefile b/Makefile index 2b5cf89..2536152 100644 --- a/Makefile +++ b/Makefile @@ -168,7 +168,7 @@ tools: install pkg: clean @$(call echo,Make $@) ifeq ($(HOST_OS),Win) - @$(SH) ./scripts/win/winpack.sh + @$(SH) ./scripts/win/winpack.sh "$(PKGNAME)" else $(error "Can't make pkg on $(HOST_OS)") endif diff --git a/scripts/common/echo.sh b/scripts/common/echo.sh index 4d9369f..abb90b2 100644 --- a/scripts/common/echo.sh +++ b/scripts/common/echo.sh @@ -27,11 +27,13 @@ ECHO="echo -e" # task colors COLOR_STRONG="1;35" # Magenta COLOR_INFO="1;34" # Blue +COLOR_WARN="1;33" # Yellow COLOR_DONE="1;32" # Green COLOR_ERROR="1;31" # Red # action colors COLOR_STRONG_NORMAL="35" COLOR_INFO_NORMAL="34" +COLOR_WARN_NORMAL="33" COLOR_DONE_NORMAL="32" COLOR_ERROR_NORMAL="31" @@ -59,6 +61,10 @@ _echo_i() { _echo_ "$1" "$COLOR_INFO" } +_echo_w() { + _echo_ "$1" "$COLOR_WARN" +} + _echo_d() { _echo_ "$1" "$COLOR_DONE" } @@ -75,6 +81,10 @@ _echo_in() { _echo_ "$1" "$COLOR_INFO_NORMAL" } +_echo_wn() { + _echo_ "$1" "$COLOR_WARN_NORMAL" +} + _echo_dn() { _echo_ "$1" "$COLOR_DONE_NORMAL" } diff --git a/scripts/win/cmake/mynteye-targets-release.cmake b/scripts/win/cmake/mynteye-targets-release.cmake new file mode 100644 index 0000000..a009b81 --- /dev/null +++ b/scripts/win/cmake/mynteye-targets-release.cmake @@ -0,0 +1,29 @@ +#---------------------------------------------------------------- +# Generated CMake target import file for configuration "Release". +#---------------------------------------------------------------- + +# Commands may need to know the format version. +set(CMAKE_IMPORT_FILE_VERSION 1) + +# Import target "mynteye" for configuration "Release" +set_property(TARGET mynteye APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) +set_target_properties(mynteye PROPERTIES + IMPORTED_IMPLIB_RELEASE "${MYNTEYES_SDK_ROOT}/lib/mynteye.lib" + IMPORTED_LOCATION_RELEASE "${MYNTEYES_SDK_ROOT}/bin/mynteye.dll" + ) + +# Import target "mynteye" for configuration "Debug" +set_property(TARGET mynteye APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) +set_target_properties(mynteye PROPERTIES + IMPORTED_IMPLIB_DEBUG "${MYNTEYES_SDK_ROOT}/lib/mynteyed.lib" + IMPORTED_LOCATION_DEBUG "${MYNTEYES_SDK_ROOT}/bin/mynteyed.dll" + ) + +list(APPEND _IMPORT_CHECK_TARGETS mynteye ) +list(APPEND _IMPORT_CHECK_FILES_FOR_mynteye + "${MYNTEYES_SDK_ROOT}/lib/mynteye.lib" "${MYNTEYES_SDK_ROOT}/bin/mynteye.dll" + "${MYNTEYES_SDK_ROOT}/lib/mynteyed.lib" "${MYNTEYES_SDK_ROOT}/bin/mynteyed.dll" + ) + +# Commands beyond this point should not need to know the version. +set(CMAKE_IMPORT_FILE_VERSION) diff --git a/scripts/win/cmake/mynteye-targets.cmake b/scripts/win/cmake/mynteye-targets.cmake new file mode 100644 index 0000000..dd35c23 --- /dev/null +++ b/scripts/win/cmake/mynteye-targets.cmake @@ -0,0 +1,102 @@ +# Generated by CMake + +if("${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}" LESS 2.5) + message(FATAL_ERROR "CMake >= 2.6.0 required") +endif() +cmake_policy(PUSH) +cmake_policy(VERSION 2.6) +#---------------------------------------------------------------- +# Generated CMake target import file. +#---------------------------------------------------------------- + +# Commands may need to know the format version. +set(CMAKE_IMPORT_FILE_VERSION 1) + +# Protect against multiple inclusion, which would fail when already imported targets are added once more. +set(_targetsDefined) +set(_targetsNotDefined) +set(_expectedTargets) +foreach(_expectedTarget mynteye) + list(APPEND _expectedTargets ${_expectedTarget}) + if(NOT TARGET ${_expectedTarget}) + list(APPEND _targetsNotDefined ${_expectedTarget}) + endif() + if(TARGET ${_expectedTarget}) + list(APPEND _targetsDefined ${_expectedTarget}) + endif() +endforeach() +if("${_targetsDefined}" STREQUAL "${_expectedTargets}") + unset(_targetsDefined) + unset(_targetsNotDefined) + unset(_expectedTargets) + set(CMAKE_IMPORT_FILE_VERSION) + cmake_policy(POP) + return() +endif() +if(NOT "${_targetsDefined}" STREQUAL "") + message(FATAL_ERROR "Some (but not all) targets in this export set were already defined.\nTargets Defined: ${_targetsDefined}\nTargets not yet defined: ${_targetsNotDefined}\n") +endif() +unset(_targetsDefined) +unset(_targetsNotDefined) +unset(_expectedTargets) + + +if(NOT MYNTEYES_SDK_ROOT) + if(DEFINED ENV{MYNTEYES_SDK_ROOT}) + set(MYNTEYES_SDK_ROOT $ENV{MYNTEYES_SDK_ROOT}) + else() + get_filename_component(MYNTEYES_SDK_ROOT "${CMAKE_CURRENT_LIST_DIR}/../../.." ABSOLUTE) + endif() +endif() + +# The installation prefix configured by this project. +set(_IMPORT_PREFIX "${MYNTEYES_SDK_ROOT}") + +# Create imported target mynteye +add_library(mynteye SHARED IMPORTED) + +set_target_properties(mynteye PROPERTIES + INTERFACE_COMPILE_DEFINITIONS "GLOG_NO_ABBREVIATED_SEVERITIES" + INTERFACE_INCLUDE_DIRECTORIES "${_IMPORT_PREFIX}/include" + INTERFACE_LINK_LIBRARIES "opencv_calib3d;opencv_core;opencv_dnn;opencv_features2d;opencv_flann;opencv_highgui;opencv_imgcodecs;opencv_imgproc;opencv_ml;opencv_objdetect;opencv_photo;opencv_shape;opencv_stitching;opencv_superres;opencv_video;opencv_videoio;opencv_videostab;opencv_world" +) + +if(CMAKE_VERSION VERSION_LESS 2.8.12) + message(FATAL_ERROR "This file relies on consumers using CMake 2.8.12 or greater.") +endif() + +# Load information for each installed configuration. +get_filename_component(_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH) +file(GLOB CONFIG_FILES "${_DIR}/mynteye-targets-*.cmake") +foreach(f ${CONFIG_FILES}) + include(${f}) +endforeach() + +# Cleanup temporary variables. +set(_IMPORT_PREFIX) + +# Loop over all imported files and verify that they actually exist +foreach(target ${_IMPORT_CHECK_TARGETS} ) + foreach(file ${_IMPORT_CHECK_FILES_FOR_${target}} ) + if(NOT EXISTS "${file}" ) + message(FATAL_ERROR "The imported target \"${target}\" references the file + \"${file}\" +but this file does not exist. Possible reasons include: +* The file was deleted, renamed, or moved to another location. +* An install or uninstall procedure did not complete successfully. +* The installation package was faulty and contained + \"${CMAKE_CURRENT_LIST_FILE}\" +but not all the files it references. +") + endif() + endforeach() + unset(_IMPORT_CHECK_FILES_FOR_${target}) +endforeach() +unset(_IMPORT_CHECK_TARGETS) + +# This file does not depend on other imported targets which have +# been exported from the same project but in a separate export set. + +# Commands beyond this point should not need to know the version. +set(CMAKE_IMPORT_FILE_VERSION) +cmake_policy(POP) diff --git a/scripts/win/nsis/Include/EnvVarUpdate.nsh b/scripts/win/nsis/Include/EnvVarUpdate.nsh new file mode 100644 index 0000000..8aeba45 --- /dev/null +++ b/scripts/win/nsis/Include/EnvVarUpdate.nsh @@ -0,0 +1,350 @@ +/** + * EnvVarUpdate.nsh + * : Environmental Variables: append, prepend, and remove entries + * + * WARNING: If you use StrFunc.nsh header then include it before this file + * with all required definitions. This is to avoid conflicts + * + * Usage: + * ${EnvVarUpdate} "ResultVar" "EnvVarName" "Action" "RegLoc" "PathString" + * + * Credits: + * Version 1.0 + * * Cal Turney (turnec2) + * * Amir Szekely (KiCHiK) and e-circ for developing the forerunners of this + * function: AddToPath, un.RemoveFromPath, AddToEnvVar, un.RemoveFromEnvVar, + * WriteEnvStr, and un.DeleteEnvStr + * * Diego Pedroso (deguix) for StrTok + * * Kevin English (kenglish_hi) for StrContains + * * Hendri Adriaens (Smile2Me), Diego Pedroso (deguix), and Dan Fuhry + * (dandaman32) for StrReplace + * + * Version 1.1 (compatibility with StrFunc.nsh) + * * techtonik + * + * http://nsis.sourceforge.net/Environmental_Variables:_append%2C_prepend%2C_and_remove_entries + * + */ + + +!ifndef ENVVARUPDATE_FUNCTION +!define ENVVARUPDATE_FUNCTION +!verbose push +!verbose 3 +!include "LogicLib.nsh" +!include "WinMessages.NSH" +!include "StrFunc.nsh" + +; ---- Fix for conflict if StrFunc.nsh is already includes in main file ----------------------- +!macro _IncludeStrFunction StrFuncName + !ifndef ${StrFuncName}_INCLUDED + ${${StrFuncName}} + !endif + !ifndef Un${StrFuncName}_INCLUDED + ${Un${StrFuncName}} + !endif + !define un.${StrFuncName} "${Un${StrFuncName}}" +!macroend + +!insertmacro _IncludeStrFunction StrTok +!insertmacro _IncludeStrFunction StrStr +!insertmacro _IncludeStrFunction StrRep + +; ---------------------------------- Macro Definitions ---------------------------------------- +!macro _EnvVarUpdateConstructor ResultVar EnvVarName Action Regloc PathString + Push "${EnvVarName}" + Push "${Action}" + Push "${RegLoc}" + Push "${PathString}" + Call EnvVarUpdate + Pop "${ResultVar}" +!macroend +!define EnvVarUpdate '!insertmacro "_EnvVarUpdateConstructor"' + +!macro _unEnvVarUpdateConstructor ResultVar EnvVarName Action Regloc PathString + Push "${EnvVarName}" + Push "${Action}" + Push "${RegLoc}" + Push "${PathString}" + Call un.EnvVarUpdate + Pop "${ResultVar}" +!macroend +!define un.EnvVarUpdate '!insertmacro "_unEnvVarUpdateConstructor"' +; ---------------------------------- Macro Definitions end------------------------------------- + +;----------------------------------- EnvVarUpdate start---------------------------------------- +!define hklm_all_users 'HKLM "SYSTEM\CurrentControlSet\Control\Session Manager\Environment"' +!define hkcu_current_user 'HKCU "Environment"' + +!macro EnvVarUpdate UN + +Function ${UN}EnvVarUpdate + + Push $0 + Exch 4 + Exch $1 + Exch 3 + Exch $2 + Exch 2 + Exch $3 + Exch + Exch $4 + Push $5 + Push $6 + Push $7 + Push $8 + Push $9 + Push $R0 + + /* After this point: + ------------------------- + $0 = ResultVar (returned) + $1 = EnvVarName (input) + $2 = Action (input) + $3 = RegLoc (input) + $4 = PathString (input) + $5 = Orig EnvVar (read from registry) + $6 = Len of $0 (temp) + $7 = tempstr1 (temp) + $8 = Entry counter (temp) + $9 = tempstr2 (temp) + $R0 = tempChar (temp) */ + + ; Step 1: Read contents of EnvVarName from RegLoc + ; + ; Check for empty EnvVarName + ${If} $1 == "" + SetErrors + DetailPrint "ERROR: EnvVarName is blank" + Goto EnvVarUpdate_Restore_Vars + ${EndIf} + + ; Check for valid Action + ${If} $2 != "A" + ${AndIf} $2 != "P" + ${AndIf} $2 != "R" + SetErrors + DetailPrint "ERROR: Invalid Action - must be A, P, or R" + Goto EnvVarUpdate_Restore_Vars + ${EndIf} + + ${If} $3 == HKLM + ReadRegStr $5 ${hklm_all_users} $1 ; Get EnvVarName from all users into $5 + ${ElseIf} $3 == HKCU + ReadRegStr $5 ${hkcu_current_user} $1 ; Read EnvVarName from current user into $5 + ${Else} + SetErrors + DetailPrint 'ERROR: Action is [$3] but must be "HKLM" or HKCU"' + Goto EnvVarUpdate_Restore_Vars + ${EndIf} + + ; Check for empty PathString + ${If} $4 == "" + SetErrors + DetailPrint "ERROR: PathString is blank" + Goto EnvVarUpdate_Restore_Vars + ${EndIf} + + ;;khc - here check if length is going to be greater then max string length + ;; and abort if so - also abort if original path empty - may mean + ;; it was too long as well- write message to say set it by hand + Push $6 + Push $7 + Push $8 + StrLen $7 $4 + StrLen $6 $5 + IntOp $8 $6 + $7 + ${If} $5 == "" + ${OrIf} $8 >= ${NSIS_MAX_STRLEN} + SetErrors + DetailPrint "Current $1 length ($6) too long to modify in NSIS; set manually if needed" + Pop $8 + Pop $7 + Pop $6 + Goto EnvVarUpdate_Restore_Vars + ${EndIf} + Pop $8 + Pop $7 + Pop $6 + ;;khc + + ; Make sure we've got some work to do + ${If} $5 == "" + ${AndIf} $2 == "R" + SetErrors + DetailPrint "$1 is empty - Nothing to remove" + Goto EnvVarUpdate_Restore_Vars + ${EndIf} + + ; Step 2: Scrub EnvVar + ; + StrCpy $0 $5 ; Copy the contents to $0 + ; Remove spaces around semicolons (NOTE: spaces before the 1st entry or + ; after the last one are not removed here but instead in Step 3) + ${If} $0 != "" ; If EnvVar is not empty ... + ${Do} + ${${UN}StrStr} $7 $0 " ;" + ${If} $7 == "" + ${ExitDo} + ${EndIf} + ${${UN}StrRep} $0 $0 " ;" ";" ; Remove ';' + ${Loop} + ${Do} + ${${UN}StrStr} $7 $0 "; " + ${If} $7 == "" + ${ExitDo} + ${EndIf} + ${${UN}StrRep} $0 $0 "; " ";" ; Remove ';' + ${Loop} + ${Do} + ${${UN}StrStr} $7 $0 ";;" + ${If} $7 == "" + ${ExitDo} + ${EndIf} + ${${UN}StrRep} $0 $0 ";;" ";" + ${Loop} + + ; Remove a leading or trailing semicolon from EnvVar + StrCpy $7 $0 1 0 + ${If} $7 == ";" + StrCpy $0 $0 "" 1 ; Change ';' to '' + ${EndIf} + StrLen $6 $0 + IntOp $6 $6 - 1 + StrCpy $7 $0 1 $6 + ${If} $7 == ";" + StrCpy $0 $0 $6 ; Change ';' to '' + ${EndIf} + ; DetailPrint "Scrubbed $1: [$0]" ; Uncomment to debug + ${EndIf} + + /* Step 3. Remove all instances of the target path/string (even if "A" or "P") + $6 = bool flag (1 = found and removed PathString) + $7 = a string (e.g. path) delimited by semicolon(s) + $8 = entry counter starting at 0 + $9 = copy of $0 + $R0 = tempChar */ + + ${If} $5 != "" ; If EnvVar is not empty ... + StrCpy $9 $0 + StrCpy $0 "" + StrCpy $8 0 + StrCpy $6 0 + + ${Do} + ${${UN}StrTok} $7 $9 ";" $8 "0" ; $7 = next entry, $8 = entry counter + + ${If} $7 == "" ; If we've run out of entries, + ${ExitDo} ; were done + ${EndIf} ; + + ; Remove leading and trailing spaces from this entry (critical step for Action=Remove) + ${Do} + StrCpy $R0 $7 1 + ${If} $R0 != " " + ${ExitDo} + ${EndIf} + StrCpy $7 $7 "" 1 ; Remove leading space + ${Loop} + ${Do} + StrCpy $R0 $7 1 -1 + ${If} $R0 != " " + ${ExitDo} + ${EndIf} + StrCpy $7 $7 -1 ; Remove trailing space + ${Loop} + ${If} $7 == $4 ; If string matches, remove it by not appending it + StrCpy $6 1 ; Set 'found' flag + ${ElseIf} $7 != $4 ; If string does NOT match + ${AndIf} $0 == "" ; and the 1st string being added to $0, + StrCpy $0 $7 ; copy it to $0 without a prepended semicolon + ${ElseIf} $7 != $4 ; If string does NOT match + ${AndIf} $0 != "" ; and this is NOT the 1st string to be added to $0, + StrCpy $0 $0;$7 ; append path to $0 with a prepended semicolon + ${EndIf} ; + + IntOp $8 $8 + 1 ; Bump counter + ${Loop} ; Check for duplicates until we run out of paths + ${EndIf} + + ; Step 4: Perform the requested Action + ; + ${If} $2 != "R" ; If Append or Prepend + ${If} $6 == 1 ; And if we found the target + DetailPrint "Target is already present in $1. It will be removed and" + ${EndIf} + ${If} $0 == "" ; If EnvVar is (now) empty + StrCpy $0 $4 ; just copy PathString to EnvVar + ${If} $6 == 0 ; If found flag is either 0 + ${OrIf} $6 == "" ; or blank (if EnvVarName is empty) + DetailPrint "$1 was empty and has been updated with the target" + ${EndIf} + ${ElseIf} $2 == "A" ; If Append (and EnvVar is not empty), + StrCpy $0 $0;$4 ; append PathString + ${If} $6 == 1 + DetailPrint "appended to $1" + ${Else} + DetailPrint "Target was appended to $1" + ${EndIf} + ${Else} ; If Prepend (and EnvVar is not empty), + StrCpy $0 $4;$0 ; prepend PathString + ${If} $6 == 1 + DetailPrint "prepended to $1" + ${Else} + DetailPrint "Target was prepended to $1" + ${EndIf} + ${EndIf} + ${Else} ; If Action = Remove + ${If} $6 == 1 ; and we found the target + DetailPrint "Target was found and removed from $1" + ${Else} + DetailPrint "Target was NOT found in $1 (nothing to remove)" + ${EndIf} + ${If} $0 == "" + DetailPrint "$1 is now empty" + ${EndIf} + ${EndIf} + + ; Step 5: Update the registry at RegLoc with the updated EnvVar and announce the change + ; + ClearErrors + ${If} $3 == HKLM + WriteRegExpandStr ${hklm_all_users} $1 $0 ; Write it in all users section + ${ElseIf} $3 == HKCU + WriteRegExpandStr ${hkcu_current_user} $1 $0 ; Write it to current user section + ${EndIf} + + IfErrors 0 +4 + MessageBox MB_OK|MB_ICONEXCLAMATION "Could not write updated $1 to $3" + DetailPrint "Could not write updated $1 to $3" + Goto EnvVarUpdate_Restore_Vars + + ; "Export" our change + SendMessage ${HWND_BROADCAST} ${WM_WININICHANGE} 0 "STR:Environment" /TIMEOUT=5000 + + EnvVarUpdate_Restore_Vars: + ; + ; Restore the user's variables and return ResultVar + Pop $R0 + Pop $9 + Pop $8 + Pop $7 + Pop $6 + Pop $5 + Pop $4 + Pop $3 + Pop $2 + Pop $1 + Push $0 ; Push my $0 (ResultVar) + Exch + Pop $0 ; Restore his $0 + +FunctionEnd + +!macroend ; EnvVarUpdate UN +!insertmacro EnvVarUpdate "" +!insertmacro EnvVarUpdate "un." +;----------------------------------- EnvVarUpdate end---------------------------------------- + +!verbose pop +!endif diff --git a/scripts/win/nsis/mynt.ico b/scripts/win/nsis/mynt.ico new file mode 100644 index 0000000000000000000000000000000000000000..f4d3c3953060ac2104c9157cf57434cb1f29a93a GIT binary patch literal 4286 zcmeI0J!n%=6vt197;&&gq?4FZM2d)mh!pV)2gg!HoQi`uh&U7{5iwar#KA#|h)4$! z73m-j4n>F*hf<1^5=xOmL`0;Biii|7M>oT)mz-5O({^g5U`)bd?zdi#;_xJ6ENqE`ny`oWuG1%5ji#{7+7+l0c zvz%sebUsE}KWHz(+Il(o&%+1swbjnm>$@5s8n0_K=lMM7HL&-(dWNe-)s8u zJ)=esEJU>w4^h8af1hbvH2nB$wWa?EzJqM7&(8q)%4zHRJT&G&TA{XT$u|mqf9O6! z6rb@rX=5Nlr>*Pr(3k;fh1#;^yASUo`wMM|;;+0;+7^xJ z82x+1-hlRo)*(doCmYozb^@e54hLfTO%az?s4ZK*5ts+9ht?rP@rhbpe7oQ&C?2A* z^wjA;5%mkTWh?hC%)(cA8=yH+{LlJhcf!rcAJz?R?duESJ@8rkU-K)?u!iz(gXU1r z0L_EWs#@tNr(asMr{O(>wc>2;x#LmpxhPL#l)kT_^EeE8&*;9CqZ;aW2fAP~cU zF7_nS>7|veb@sJX=LWope4l8?U>|IP%MhoXG^U!G18Mey_Jj7H>Rp2}XpIJ7J)8u; zKaATx? zXjXreJ`KMM5<3O{`4?*GUA4vEZ=;qzyFuqT%$2R@+(4te&`-a0ps{GYIza@u|VzZr0Ku0`h#es(TjaV}SME@RHw3YH3H)x24y!!o68F>6-ZU^die ewz*=KE9&14P|TJxm5xfTny=;;3rmICa=!ueT5qfX literal 0 HcmV?d00001 diff --git a/scripts/win/nsis/winpack.nsi.in b/scripts/win/nsis/winpack.nsi.in new file mode 100644 index 0000000..cc6acf8 --- /dev/null +++ b/scripts/win/nsis/winpack.nsi.in @@ -0,0 +1,197 @@ +; winpack.nsi + +!addincludedir scripts\win\nsis\Include +!include EnvVarUpdate.nsh + +!addplugindir scripts\win\nsis\Plugins + +!include WinMessages.nsh + +!define VERSION "@mynteye_VERSION@" +!define OpenCV_VERSION "@OpenCV_VERSION@" + +!define DSETDIR "$APPDATA" +;!define DSETDIR "$PROGRAMFILES64" + +; HKLM (all users) vs HKCU (current user) defines +!define ENV_HKLM 'HKLM "SYSTEM\CurrentControlSet\Control\Session Manager\Environment"' +!define ENV_HKCU 'HKCU "Environment"' + +;-------------------------------- + +; The name of the installer +Name "MYNTEYE S SDK ${VERSION}" + +; The icon of the installer +Icon "scripts\win\nsis\mynt.ico" + +; The file to write +OutFile "mynteye-s-${VERSION}-win-x64-opencv-${OpenCV_VERSION}.exe" + +; The default installation directory +InstallDir ${DSETDIR}\Slightech\MYNTEYES\SDK\${VERSION} + +; Registry key to check for directory (so if you install again, it will +; overwrite the old one automatically) +InstallDirRegKey HKLM "Software\MYNTEYESSDK" "Install_Dir" + +; Request application privileges for Windows Vista +;RequestExecutionLevel user +RequestExecutionLevel admin + +;-------------------------------- + +; Pages + +Page components +Page directory +Page instfiles + +UninstPage uninstConfirm +UninstPage instfiles + +;-------------------------------- + +; The stuff to install +Section "SDK (required)" + + SectionIn RO + + ; Set output path to the installation directory. + SetOutPath $INSTDIR + + ; Put file there + File /r "mynteye-s-${VERSION}-win-x64\*" + + ; Write the installation path into the registry + WriteRegStr HKLM "SOFTWARE\MYNTEYESSDK" "Install_Dir" "$INSTDIR" + + ; Write the uninstall keys for Windows + WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\MYNTEYESSDK" "DisplayName" "MYNTEYE S SDK" + WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\MYNTEYESSDK" "UninstallString" '"$INSTDIR\uninstall.exe"' + WriteRegDWORD HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\MYNTEYESSDK" "NoModify" 1 + WriteRegDWORD HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\MYNTEYESSDK" "NoRepair" 1 + WriteUninstaller "uninstall.exe" + + ; Set variables for local machine + WriteRegExpandStr ${ENV_HKLM} MYNTEYES_SDK_ROOT "$INSTDIR" + + ;${EnvVarUpdate} $0 "PATH" "P" "HKLM" "%MYNTEYES_SDK_PATH%" + ${EnvVarUpdate} $0 "PATH" "P" "HKLM" "$INSTDIR\bin;$INSTDIR\3rdparty\opencv\build\x64\vc15\bin" + + ; Push "%MYNTEYES_SDK_PATH%" + ; Call AddToPath + + ; Make sure windows knows about the change + SendMessage ${HWND_BROADCAST} ${WM_WININICHANGE} 0 "STR:Environment" /TIMEOUT=5000 + +SectionEnd + +; Optional section (can be disabled by the user) +Section "Desktop Shortcuts" + + CreateShortcut "$DESKTOP\MYNTEYE S SDK ${VERSION}.lnk" "$INSTDIR" "" "$INSTDIR" 0 + +SectionEnd + +Function .onInstSuccess + + ;WriteRegStr "HKLM" "SOFTWARE\Microsoft\Windows\CurrentVersion\RunOnce" "View README" \ + ; "cmd.exe /c start /max notepad.exe $INSTDIR\README" + + MessageBox MB_OKCANCEL "Reboot your system now?" /SD IDOK IDCANCEL NoReboot + Reboot + NoReboot: + +FunctionEnd + +Function .onInstFailed + MessageBox MB_OK "Install failed." +FunctionEnd + +;-------------------------------- + +; Uninstaller + +Section "Uninstall" + + ; Remove registry keys + DeleteRegKey HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\MYNTEYESSDK" + DeleteRegKey HKLM "SOFTWARE\MYNTEYESSDK" + + ; Remove install stuff + RMDir /r "$INSTDIR" + + ; Remove shortcuts, if any + Delete "$DESKTOP\MYNTEYE S SDK ${VERSION}.lnk" + + ; Remove directories used + StrCpy $0 "${DSETDIR}\Slightech\MYNTEYES" + Call un.DeleteDirIfEmpty + StrCpy $0 "${DSETDIR}\Slightech" + Call un.DeleteDirIfEmpty + + RMDir /r "$APPDATA\Slightech\MYNTEYES" + StrCpy $0 "$APPDATA\Slightech" + Call un.DeleteDirIfEmpty + + ; Delete variables + DeleteRegValue ${ENV_HKLM} MYNTEYES_SDK_ROOT + + ;${un.EnvVarUpdate} $0 "PATH" "R" "HKLM" "%MYNTEYES_SDK_PATH%" + ${un.EnvVarUpdate} $0 "PATH" "R" "HKLM" "$INSTDIR\bin" + ${un.EnvVarUpdate} $0 "PATH" "R" "HKLM" "$INSTDIR\3rdparty\opencv\build\x64\vc15\bin" + + ; Push "%MYNTEYES_SDK_PATH%" + ; Call un.RemoveFromPath + + ; Make sure windows knows about the change + SendMessage ${HWND_BROADCAST} ${WM_WININICHANGE} 0 "STR:Environment" /TIMEOUT=5000 + +SectionEnd + +Function un.onUninstSuccess + MessageBox MB_OK "Uninstall success." +FunctionEnd + +Function un.onUninstFailed + MessageBox MB_OK "Uninstall failed." +FunctionEnd + +;-------------------------------- + +; DeleteDirIfEmpty - Delete dir only if empty + +Function un.DeleteDirIfEmpty + FindFirst $R0 $R1 "$0\*.*" + strcmp $R1 "." 0 NoDelete + FindNext $R0 $R1 + strcmp $R1 ".." 0 NoDelete + ClearErrors + FindNext $R0 $R1 + IfErrors 0 NoDelete + FindClose $R0 + Sleep 1000 + RMDir "$0" + NoDelete: + FindClose $R0 +FunctionEnd + +;-------------------------------- + +; Path Manipulation +; http://nsis.sourceforge.net/Path_Manipulation +; Environmental Variables: append, prepend, and remove entries +; http://nsis.sourceforge.net/Environmental_Variables:_append%2C_prepend%2C_and_remove_entries +; Setting Environment Variables +; http://nsis.sourceforge.net/Setting_Environment_Variables +; Setting Environment Variables to Active Installer Process +; http://nsis.sourceforge.net/Setting_Environment_Variables_to_Active_Installer_Process + +; Delete files and subdirectories +; http://nsis.sourceforge.net/Delete_files_and_subdirectories +; Delete dir only if empty +; http://nsis.sourceforge.net/Delete_dir_only_if_empty + +;https://gist.github.com/azalea/deb3c1ed2a984eadf96be77b81dd49b1 +;!include ProcessEnvPrependPath.nsh diff --git a/scripts/win/winpack.sh b/scripts/win/winpack.sh index dbad223..b2c4c5f 100644 --- a/scripts/win/winpack.sh +++ b/scripts/win/winpack.sh @@ -20,4 +20,79 @@ SCRIPTS_DIR=$(realpath "$BASE_DIR/..") source "$SCRIPTS_DIR/common/echo.sh" source "$SCRIPTS_DIR/common/detect.sh" -_echo_s "winpack.sh" +if [ ! -d "$ROOT_DIR/3rdparty/opencv" ]; then + _echo_e "3rdparty/opencv not found, please manually download it to here." + _echo_e + _echo_e " OpenCV Win pack 3.4.3: https://opencv.org/releases.html" + exit 1 +fi + +if ! _detect_cmd makensis; then + _echo_e "makensis not found, please manually download and install it." + _echo_e + _echo_e " NSIS: http://nsis.sourceforge.net" + exit 1 +fi + +export OpenCV_DIR="$ROOT_DIR/3rdparty/opencv/build" + +_rm() { + [ -e "$1" ] && (rm -r "$1" && _echo_in "RM: $1") +} + +_md() { + [ ! -d "$1" ] && (mkdir -p "$1" && _echo_in "MD: $1") +} + +################################################################################ +# build release + +make install + +################################################################################ +# build debug + +rm -r "$ROOT_DIR/_build" +rm -r "$ROOT_DIR/_output" +make build BUILD_TYPE=Debug + +mv "$ROOT_DIR/_output/bin/mynteyed.dll" "$ROOT_DIR/_install/bin/mynteyed.dll" +mv "$ROOT_DIR/_output/lib/mynteyed.lib" "$ROOT_DIR/_install/lib/mynteyed.lib" + +################################################################################ +# copy to _install + +cp -f "$ROOT_DIR/scripts/win/cmake/mynteye-targets.cmake" "$ROOT_DIR/_install/lib/cmake/mynteye/" +cp -f "$ROOT_DIR/scripts/win/cmake/mynteye-targets-release.cmake" "$ROOT_DIR/_install/lib/cmake/mynteye/" + +################################################################################ +# move to _install + +# 3rdparty/opencv +_md "$ROOT_DIR/_install/3rdparty" +mv "$ROOT_DIR/3rdparty/opencv" "$ROOT_DIR/_install/3rdparty/opencv" + +################################################################################ +# archive exe + +_pkgname=$1 +mv "$ROOT_DIR/_install" "$ROOT_DIR/$_pkgname" + +makensis "$ROOT_DIR/winpack.nsi" + +mv "$ROOT_DIR/$_pkgname" "$ROOT_DIR/_install" + +################################################################################ +# move back from _install + +# 3rdparty/opencv +mv "$ROOT_DIR/_install/3rdparty/opencv" "$ROOT_DIR/3rdparty/opencv" + +################################################################################ +# clean build + +_rm "$ROOT_DIR/_build" +_rm "$ROOT_DIR/_output" + + +_echo_d "Win pack success" From 3badd53c4b5b134479b9396d73ace8f7cabfac77 Mon Sep 17 00:00:00 2001 From: John Zhao Date: Thu, 1 Nov 2018 23:34:52 +0800 Subject: [PATCH 50/77] Update pkgname --- .gitignore | 1 + CMakeLists.txt | 4 ++++ cmake/templates/pkginfo.sh.in | 16 ++++++++++++++++ scripts/win/nsis/winpack.nsi.in | 2 +- scripts/win/winpack.sh | 3 ++- 5 files changed, 24 insertions(+), 2 deletions(-) create mode 100644 cmake/templates/pkginfo.sh.in diff --git a/.gitignore b/.gitignore index 478ce28..396e1d4 100644 --- a/.gitignore +++ b/.gitignore @@ -17,6 +17,7 @@ _output/ /plugins/ /3rdparty/opencv/ +/pkginfo.sh /*.nsi /*.exe diff --git a/CMakeLists.txt b/CMakeLists.txt index 2ae3bae..8ab5940 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -83,6 +83,10 @@ configure_file( include/mynteye/mynteye.h @ONLY ) +configure_file( + cmake/templates/pkginfo.sh.in + ${CMAKE_CURRENT_SOURCE_DIR}/pkginfo.sh @ONLY +) if(OS_WIN) configure_file( scripts/win/nsis/winpack.nsi.in diff --git a/cmake/templates/pkginfo.sh.in b/cmake/templates/pkginfo.sh.in new file mode 100644 index 0000000..8778d4e --- /dev/null +++ b/cmake/templates/pkginfo.sh.in @@ -0,0 +1,16 @@ +#!/usr/bin/env bash + +OpenCV_VERSION=@OpenCV_VERSION@ +OpenCV_VERSION_MAJOR=@OpenCV_VERSION_MAJOR@ +OpenCV_VERSION_MINOR=@OpenCV_VERSION_MINOR@ +OpenCV_VERSION_PATCH=@OpenCV_VERSION_PATCH@ +OpenCV_VERSION_STATUS=@OpenCV_VERSION_STATUS@ + +_contains() { + [ `echo $1 | grep -c "$2"` -gt 0 ] +} + +if _contains "@OpenCV_INCLUDE_DIRS@" "/ros/"; then + ROS_VERSION=$(rosversion -d) + OpenCV_VERSION=ros-$ROS_VERSION +fi diff --git a/scripts/win/nsis/winpack.nsi.in b/scripts/win/nsis/winpack.nsi.in index cc6acf8..440a7ab 100644 --- a/scripts/win/nsis/winpack.nsi.in +++ b/scripts/win/nsis/winpack.nsi.in @@ -61,7 +61,7 @@ Section "SDK (required)" SetOutPath $INSTDIR ; Put file there - File /r "mynteye-s-${VERSION}-win-x64\*" + File /r "mynteye-s-${VERSION}-win-x64-opencv-${OpenCV_VERSION}\*" ; Write the installation path into the registry WriteRegStr HKLM "SOFTWARE\MYNTEYESSDK" "Install_Dir" "$INSTDIR" diff --git a/scripts/win/winpack.sh b/scripts/win/winpack.sh index b2c4c5f..b186993 100644 --- a/scripts/win/winpack.sh +++ b/scripts/win/winpack.sh @@ -75,7 +75,8 @@ mv "$ROOT_DIR/3rdparty/opencv" "$ROOT_DIR/_install/3rdparty/opencv" ################################################################################ # archive exe -_pkgname=$1 +source "$ROOT_DIR/pkginfo.sh" +_pkgname=$1-opencv-$OpenCV_VERSION mv "$ROOT_DIR/_install" "$ROOT_DIR/$_pkgname" makensis "$ROOT_DIR/winpack.nsi" From 969cbfd073ba9839806862effe8008093fdf5dc1 Mon Sep 17 00:00:00 2001 From: Tiny Date: Fri, 2 Nov 2018 09:11:01 +0800 Subject: [PATCH 51/77] add macosx demo project in sub dir and change the project platform dir --- CMakeLists.txt | 6 +- src/mynteye/uvc/{ => linux}/uvc-v4l2.cc | 0 src/mynteye/uvc/macosx/Doxyfile | 2382 ++++++++++++ src/mynteye/uvc/macosx/LICENSE.txt | 21 + src/mynteye/uvc/macosx/README.md | 69 + .../uvc/macosx/USBBusProber/APPLE_LICENSE | 372 ++ .../uvc/macosx/USBBusProber/BusProbeClass.h | 55 + .../uvc/macosx/USBBusProber/BusProbeClass.m | 151 + .../uvc/macosx/USBBusProber/BusProbeDevice.h | 82 + .../uvc/macosx/USBBusProber/BusProbeDevice.m | 247 ++ .../uvc/macosx/USBBusProber/BusProber.h | 65 + .../uvc/macosx/USBBusProber/BusProber.m | 611 +++ .../USBBusProber/BusProberSharedFunctions.h | 87 + .../USBBusProber/BusProberSharedFunctions.m | 906 +++++ .../DecodeAudioInterfaceDescriptor.h | 477 +++ .../DecodeAudioInterfaceDescriptor.m | 1475 +++++++ .../macosx/USBBusProber/DecodeBOSDescriptor.h | 35 + .../macosx/USBBusProber/DecodeBOSDescriptor.m | 191 + .../USBBusProber/DecodeCommClassDescriptor.h | 44 + .../USBBusProber/DecodeCommClassDescriptor.m | 123 + .../DecodeConfigurationDescriptor.h | 37 + .../DecodeConfigurationDescriptor.m | 205 + .../USBBusProber/DecodeDeviceDescriptor.h | 36 + .../USBBusProber/DecodeDeviceDescriptor.m | 112 + .../DecodeDeviceQualifierDescriptor.h | 37 + .../DecodeDeviceQualifierDescriptor.m | 52 + .../USBBusProber/DecodeEndpointDescriptor.h | 40 + .../USBBusProber/DecodeEndpointDescriptor.m | 322 ++ .../macosx/USBBusProber/DecodeHIDDescriptor.h | 226 ++ .../macosx/USBBusProber/DecodeHIDDescriptor.m | 730 ++++ .../macosx/USBBusProber/DecodeHubDescriptor.h | 68 + .../macosx/USBBusProber/DecodeHubDescriptor.m | 116 + .../USBBusProber/DecodeInterfaceDescriptor.h | 45 + .../USBBusProber/DecodeInterfaceDescriptor.m | 148 + .../DecodeVideoInterfaceDescriptor.h | 765 ++++ .../DecodeVideoInterfaceDescriptor.m | 1411 +++++++ .../macosx/USBBusProber/DescriptorDecoder.h | 58 + .../macosx/USBBusProber/DescriptorDecoder.m | 152 + .../macosx/USBBusProber/ExtensionSelector.h | 38 + .../macosx/USBBusProber/ExtensionSelector.m | 108 + .../USBBusProber/OutlineViewAdditions.h | 34 + .../USBBusProber/OutlineViewAdditions.m | 78 + .../uvc/macosx/USBBusProber/OutlineViewNode.h | 67 + .../uvc/macosx/USBBusProber/OutlineViewNode.m | 244 ++ .../USBBusProber/TableViewWithCopying.h | 36 + .../USBBusProber/TableViewWithCopying.m | 110 + .../USBBusProber/USBBusProber-Info.plist | 30 + .../USBBusProber/USBBusProber-Prefix.pch | 7 + .../uvc/macosx/USBBusProber/USBBusProber.h | 6 + .../uvc/macosx/USBBusProber/USBVendors.txt | 2226 +++++++++++ .../USBBusProber/en.lproj/InfoPlist.strings | 2 + .../UVC Test App/AVCaptureVideoSource.h | 42 + .../UVC Test App/AVCaptureVideoSource.m | 237 ++ .../uvc/macosx/UVC Test App/AppDelegate.h | 34 + .../uvc/macosx/UVC Test App/AppDelegate.m | 156 + .../uvc/macosx/UVC Test App/CVGLView.h | 16 + .../uvc/macosx/UVC Test App/CVGLView.m | 152 + .../UVC Test App/UVC Test App-Info.plist | 34 + .../UVC Test App/UVC Test App-Prefix.pch | 7 + .../macosx/UVC Test App/en.lproj/Credits.rtf | 29 + .../UVC Test App/en.lproj/InfoPlist.strings | 2 + .../macosx/UVC Test App/en.lproj/MainMenu.xib | 3431 +++++++++++++++++ src/mynteye/uvc/macosx/UVC Test App/main.m | 14 + .../UVCXcodeProject.xcodeproj/project.pbxproj | 880 +++++ .../contents.xcworkspacedata | 7 + .../UserInterfaceState.xcuserstate | Bin 0 -> 88860 bytes .../xcschemes/UVC Test App.xcscheme | 93 + .../xcschemes/xcschememanagement.plist | 34 + .../VVUVCKit/UVCXcodeProject-Info.plist | 30 + .../VVUVCKit/UVCXcodeProject-Prefix.pch | 7 + .../uvc/macosx/VVUVCKit/VVUVCController.h | 405 ++ .../uvc/macosx/VVUVCKit/VVUVCController.m | 1674 ++++++++ .../uvc/macosx/VVUVCKit/VVUVCController.xib | 237 ++ src/mynteye/uvc/macosx/VVUVCKit/VVUVCKit.h | 4 + .../macosx/VVUVCKit/VVUVCKitStringAdditions.h | 7 + .../macosx/VVUVCKit/VVUVCKitStringAdditions.m | 15 + .../uvc/macosx/VVUVCKit/VVUVCUIController.h | 44 + .../uvc/macosx/VVUVCKit/VVUVCUIController.m | 344 ++ .../uvc/macosx/VVUVCKit/VVUVCUIElement.h | 36 + .../uvc/macosx/VVUVCKit/VVUVCUIElement.m | 145 + .../VVUVCKit/en.lproj/InfoPlist.strings | 2 + src/mynteye/uvc/{ => macosx}/utlist_osx.h | 0 src/mynteye/uvc/{ => macosx}/uvc-libuvc.cc | 2 +- .../uvc/{ => macosx}/uvc_osx_internal.h | 2 +- src/mynteye/uvc/{ => win}/uvc-wmf.cc | 0 85 files changed, 23062 insertions(+), 5 deletions(-) rename src/mynteye/uvc/{ => linux}/uvc-v4l2.cc (100%) create mode 100644 src/mynteye/uvc/macosx/Doxyfile create mode 100644 src/mynteye/uvc/macosx/LICENSE.txt create mode 100644 src/mynteye/uvc/macosx/README.md create mode 100644 src/mynteye/uvc/macosx/USBBusProber/APPLE_LICENSE create mode 100644 src/mynteye/uvc/macosx/USBBusProber/BusProbeClass.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/BusProbeClass.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/BusProbeDevice.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/BusProbeDevice.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/BusProber.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/BusProber.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/BusProberSharedFunctions.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/BusProberSharedFunctions.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeAudioInterfaceDescriptor.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeAudioInterfaceDescriptor.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeBOSDescriptor.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeBOSDescriptor.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeCommClassDescriptor.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeCommClassDescriptor.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeConfigurationDescriptor.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeConfigurationDescriptor.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeDeviceDescriptor.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeDeviceDescriptor.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeDeviceQualifierDescriptor.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeDeviceQualifierDescriptor.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeEndpointDescriptor.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeEndpointDescriptor.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeHIDDescriptor.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeHIDDescriptor.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeHubDescriptor.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeHubDescriptor.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeInterfaceDescriptor.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeInterfaceDescriptor.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeVideoInterfaceDescriptor.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DecodeVideoInterfaceDescriptor.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DescriptorDecoder.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/DescriptorDecoder.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/ExtensionSelector.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/ExtensionSelector.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/OutlineViewAdditions.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/OutlineViewAdditions.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/OutlineViewNode.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/OutlineViewNode.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/TableViewWithCopying.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/TableViewWithCopying.m create mode 100644 src/mynteye/uvc/macosx/USBBusProber/USBBusProber-Info.plist create mode 100644 src/mynteye/uvc/macosx/USBBusProber/USBBusProber-Prefix.pch create mode 100644 src/mynteye/uvc/macosx/USBBusProber/USBBusProber.h create mode 100644 src/mynteye/uvc/macosx/USBBusProber/USBVendors.txt create mode 100644 src/mynteye/uvc/macosx/USBBusProber/en.lproj/InfoPlist.strings create mode 100644 src/mynteye/uvc/macosx/UVC Test App/AVCaptureVideoSource.h create mode 100644 src/mynteye/uvc/macosx/UVC Test App/AVCaptureVideoSource.m create mode 100644 src/mynteye/uvc/macosx/UVC Test App/AppDelegate.h create mode 100644 src/mynteye/uvc/macosx/UVC Test App/AppDelegate.m create mode 100644 src/mynteye/uvc/macosx/UVC Test App/CVGLView.h create mode 100644 src/mynteye/uvc/macosx/UVC Test App/CVGLView.m create mode 100644 src/mynteye/uvc/macosx/UVC Test App/UVC Test App-Info.plist create mode 100644 src/mynteye/uvc/macosx/UVC Test App/UVC Test App-Prefix.pch create mode 100644 src/mynteye/uvc/macosx/UVC Test App/en.lproj/Credits.rtf create mode 100644 src/mynteye/uvc/macosx/UVC Test App/en.lproj/InfoPlist.strings create mode 100644 src/mynteye/uvc/macosx/UVC Test App/en.lproj/MainMenu.xib create mode 100644 src/mynteye/uvc/macosx/UVC Test App/main.m create mode 100644 src/mynteye/uvc/macosx/UVCXcodeProject.xcodeproj/project.pbxproj create mode 100644 src/mynteye/uvc/macosx/UVCXcodeProject.xcodeproj/project.xcworkspace/contents.xcworkspacedata create mode 100644 src/mynteye/uvc/macosx/UVCXcodeProject.xcodeproj/project.xcworkspace/xcuserdata/tiny.xcuserdatad/UserInterfaceState.xcuserstate create mode 100644 src/mynteye/uvc/macosx/UVCXcodeProject.xcodeproj/xcshareddata/xcschemes/UVC Test App.xcscheme create mode 100644 src/mynteye/uvc/macosx/UVCXcodeProject.xcodeproj/xcuserdata/tiny.xcuserdatad/xcschemes/xcschememanagement.plist create mode 100644 src/mynteye/uvc/macosx/VVUVCKit/UVCXcodeProject-Info.plist create mode 100644 src/mynteye/uvc/macosx/VVUVCKit/UVCXcodeProject-Prefix.pch create mode 100644 src/mynteye/uvc/macosx/VVUVCKit/VVUVCController.h create mode 100644 src/mynteye/uvc/macosx/VVUVCKit/VVUVCController.m create mode 100644 src/mynteye/uvc/macosx/VVUVCKit/VVUVCController.xib create mode 100644 src/mynteye/uvc/macosx/VVUVCKit/VVUVCKit.h create mode 100644 src/mynteye/uvc/macosx/VVUVCKit/VVUVCKitStringAdditions.h create mode 100644 src/mynteye/uvc/macosx/VVUVCKit/VVUVCKitStringAdditions.m create mode 100644 src/mynteye/uvc/macosx/VVUVCKit/VVUVCUIController.h create mode 100644 src/mynteye/uvc/macosx/VVUVCKit/VVUVCUIController.m create mode 100644 src/mynteye/uvc/macosx/VVUVCKit/VVUVCUIElement.h create mode 100644 src/mynteye/uvc/macosx/VVUVCKit/VVUVCUIElement.m create mode 100644 src/mynteye/uvc/macosx/VVUVCKit/en.lproj/InfoPlist.strings rename src/mynteye/uvc/{ => macosx}/utlist_osx.h (100%) rename src/mynteye/uvc/{ => macosx}/uvc-libuvc.cc (99%) rename src/mynteye/uvc/{ => macosx}/uvc_osx_internal.h (99%) rename src/mynteye/uvc/{ => win}/uvc-wmf.cc (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 31f7a63..ffd7c78 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -111,16 +111,16 @@ if(NOT WITH_GLOG AND NOT OS_WIN) endif() if(OS_WIN) - set(UVC_SRC src/mynteye/uvc/uvc-wmf.cc) + set(UVC_SRC src/mynteye/uvc/win/uvc-wmf.cc) elseif(OS_MAC) - set(UVC_SRC src/mynteye/uvc/uvc-libuvc.cc) + set(UVC_SRC src/mynteye/uvc/macosx/uvc-libuvc.cc) find_package(libuvc REQUIRED) set(UVC_LIB ${libuvc_LIBRARIES}) include_directories(${libuvc_INCLUDE_DIRS}) elseif(OS_LINUX) - set(UVC_SRC src/mynteye/uvc/uvc-v4l2.cc) + set(UVC_SRC src/mynteye/uvc/linux/uvc-v4l2.cc) else() message(FATAL_ERROR "Unsupported OS.") endif() diff --git a/src/mynteye/uvc/uvc-v4l2.cc b/src/mynteye/uvc/linux/uvc-v4l2.cc similarity index 100% rename from src/mynteye/uvc/uvc-v4l2.cc rename to src/mynteye/uvc/linux/uvc-v4l2.cc diff --git a/src/mynteye/uvc/macosx/Doxyfile b/src/mynteye/uvc/macosx/Doxyfile new file mode 100644 index 0000000..a7717fd --- /dev/null +++ b/src/mynteye/uvc/macosx/Doxyfile @@ -0,0 +1,2382 @@ +# Doxyfile 1.8.7 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project. +# +# All text after a double hash (##) is considered a comment and is placed in +# front of the TAG it is preceding. +# +# All text after a single hash (#) is considered a comment and will be ignored. +# The format is: +# TAG = value [value, ...] +# For lists, items can also be appended using: +# TAG += value [value, ...] +# Values that contain spaces should be placed between quotes (\" \"). + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- + +# This tag specifies the encoding used for all characters in the config file +# that follow. The default is UTF-8 which is also the encoding used for all text +# before the first occurrence of this tag. Doxygen uses libiconv (or the iconv +# built into libc) for the transcoding. See http://www.gnu.org/software/libiconv +# for the list of possible encodings. +# The default value is: UTF-8. + +DOXYFILE_ENCODING = UTF-8 + +# The PROJECT_NAME tag is a single word (or a sequence of words surrounded by +# double-quotes, unless you are using Doxywizard) that should identify the +# project for which the documentation is generated. This name is used in the +# title of most generated pages and in a few other places. +# The default value is: My Project. + +PROJECT_NAME = VVUVCKit + +# The PROJECT_NUMBER tag can be used to enter a project or revision number. This +# could be handy for archiving the generated documentation or if some version +# control system is used. + +PROJECT_NUMBER = + +# 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 +# quick idea about the purpose of the project. Keep the description short. + +PROJECT_BRIEF = + +# With the PROJECT_LOGO tag one can specify an logo or icon that is included in +# the documentation. The maximum height of the logo should not exceed 55 pixels +# and the maximum width should not exceed 200 pixels. Doxygen will copy the logo +# to the output directory. + +PROJECT_LOGO = + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path +# into which the generated documentation will be written. If a relative path is +# entered, it will be relative to the location where doxygen was started. If +# left blank the current directory will be used. + +OUTPUT_DIRECTORY = ./ + +# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create 4096 sub- +# directories (in 2 levels) under the output directory of each output format and +# will distribute the generated files over these directories. Enabling this +# option can be useful when feeding doxygen a huge amount of source files, where +# putting all generated files in the same directory would otherwise causes +# performance problems for the file system. +# The default value is: NO. + +CREATE_SUBDIRS = NO + +# If the ALLOW_UNICODE_NAMES tag is set to YES, doxygen will allow non-ASCII +# characters to appear in the names of generated files. If set to NO, non-ASCII +# characters will be escaped, for example _xE3_x81_x84 will be used for Unicode +# U+3044. +# The default value is: NO. + +ALLOW_UNICODE_NAMES = NO + +# The OUTPUT_LANGUAGE tag is used to specify the language in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all constant output in the proper language. +# Possible values are: Afrikaans, Arabic, Armenian, Brazilian, Catalan, Chinese, +# Chinese-Traditional, Croatian, Czech, Danish, Dutch, English (United States), +# Esperanto, Farsi (Persian), Finnish, French, German, Greek, Hungarian, +# Indonesian, Italian, Japanese, Japanese-en (Japanese with English messages), +# Korean, Korean-en (Korean with English messages), Latvian, Lithuanian, +# Macedonian, Norwegian, Persian (Farsi), Polish, Portuguese, Romanian, Russian, +# Serbian, Serbian-Cyrillic, Slovak, Slovene, Spanish, Swedish, Turkish, +# Ukrainian and Vietnamese. +# The default value is: English. + +OUTPUT_LANGUAGE = English + +# If the BRIEF_MEMBER_DESC tag is set to YES doxygen will include brief member +# descriptions after the members that are listed in the file and class +# documentation (similar to Javadoc). Set to NO to disable this. +# The default value is: YES. + +BRIEF_MEMBER_DESC = YES + +# If the REPEAT_BRIEF tag is set to YES doxygen will prepend the brief +# description of a member or function before the detailed description +# +# Note: If both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the +# brief descriptions will be completely suppressed. +# The default value is: YES. + +REPEAT_BRIEF = YES + +# This tag implements a quasi-intelligent brief description abbreviator that is +# used to form the text in various listings. Each string in this list, if found +# as the leading text of the brief description, will be stripped from the text +# and the result, after processing the whole list, is used as the annotated +# text. Otherwise, the brief description is used as-is. If left blank, the +# following values are used ($name is automatically replaced with the name of +# the entity):The $name class, The $name widget, The $name file, is, provides, +# specifies, contains, represents, a, an and the. + +ABBREVIATE_BRIEF = "The $name class" \ + "The $name widget" \ + "The $name file" \ + is \ + provides \ + specifies \ + contains \ + represents \ + a \ + an \ + the + +# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then +# doxygen will generate a detailed section even if there is only a brief +# description. +# The default value is: NO. + +ALWAYS_DETAILED_SEC = NO + +# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all +# inherited members of a class in the documentation of that class as if those +# members were ordinary class members. Constructors, destructors and assignment +# operators of the base classes will not be shown. +# The default value is: NO. + +INLINE_INHERITED_MEMB = NO + +# If the FULL_PATH_NAMES tag is set to YES doxygen will prepend the full path +# before files name in the file list and in the header files. If set to NO the +# shortest path that makes the file name unique will be used +# The default value is: YES. + +FULL_PATH_NAMES = YES + +# The STRIP_FROM_PATH tag can be used to strip a user-defined part of the path. +# Stripping is only done if one of the specified strings matches the left-hand +# part of the path. The tag can be used to show relative paths in the file list. +# If left blank the directory from which doxygen is run is used as the path to +# strip. +# +# Note that you can specify absolute paths here, but also relative paths, which +# will be relative from the directory where doxygen is started. +# This tag requires that the tag FULL_PATH_NAMES is set to YES. + +STRIP_FROM_PATH = + +# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of the +# path mentioned in the documentation of a class, which tells the reader which +# header file to include in order to use a class. If left blank only the name of +# the header file containing the class definition is used. Otherwise one should +# specify the list of include paths that are normally passed to the compiler +# using the -I flag. + +STRIP_FROM_INC_PATH = + +# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter (but +# less readable) file names. This can be useful is your file systems doesn't +# support long names like on DOS, Mac, or CD-ROM. +# The default value is: NO. + +SHORT_NAMES = NO + +# If the JAVADOC_AUTOBRIEF tag is set to YES then doxygen will interpret the +# first line (until the first dot) of a Javadoc-style comment as the brief +# description. If set to NO, the Javadoc-style will behave just like regular Qt- +# style comments (thus requiring an explicit @brief command for a brief +# description.) +# The default value is: NO. + +JAVADOC_AUTOBRIEF = NO + +# If the QT_AUTOBRIEF tag is set to YES then doxygen will interpret the first +# line (until the first dot) of a Qt-style comment as the brief description. If +# set to NO, the Qt-style will behave just like regular Qt-style comments (thus +# requiring an explicit \brief command for a brief description.) +# The default value is: NO. + +QT_AUTOBRIEF = NO + +# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make doxygen treat a +# multi-line C++ special comment block (i.e. a block of //! or /// comments) as +# a brief description. This used to be the default behavior. The new default is +# to treat a multi-line C++ comment block as a detailed description. Set this +# tag to YES if you prefer the old behavior instead. +# +# Note that setting this tag to YES also means that rational rose comments are +# not recognized any more. +# The default value is: NO. + +MULTILINE_CPP_IS_BRIEF = NO + +# If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the +# documentation from any documented member that it re-implements. +# The default value is: YES. + +INHERIT_DOCS = YES + +# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce a +# new page for each member. If set to NO, the documentation of a member will be +# part of the file/class/namespace that contains it. +# The default value is: NO. + +SEPARATE_MEMBER_PAGES = NO + +# The TAB_SIZE tag can be used to set the number of spaces in a tab. Doxygen +# uses this value to replace tabs by spaces in code fragments. +# Minimum value: 1, maximum value: 16, default value: 4. + +TAB_SIZE = 4 + +# This tag can be used to specify a number of aliases that act as commands in +# the documentation. An alias has the form: +# name=value +# For example adding +# "sideeffect=@par Side Effects:\n" +# will allow you to put the command \sideeffect (or @sideeffect) in the +# documentation, which will result in a user-defined paragraph with heading +# "Side Effects:". You can put \n's in the value part of an alias to insert +# newlines. + +ALIASES = + +# This tag can be used to specify a number of word-keyword mappings (TCL only). +# A mapping has the form "name=value". For example adding "class=itcl::class" +# will allow you to use the command class in the itcl::class meaning. + +TCL_SUBST = + +# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources +# only. Doxygen will then generate output that is more tailored for C. For +# instance, some of the names that are used will be different. The list of all +# members will be omitted, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_FOR_C = YES + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java or +# Python sources only. Doxygen will then generate output that is more tailored +# for that language. For instance, namespaces will be presented as packages, +# qualified scopes will look different, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_JAVA = NO + +# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran +# sources. Doxygen will then generate output that is tailored for Fortran. +# The default value is: NO. + +OPTIMIZE_FOR_FORTRAN = NO + +# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL +# sources. Doxygen will then generate output that is tailored for VHDL. +# The default value is: NO. + +OPTIMIZE_OUTPUT_VHDL = NO + +# Doxygen selects the parser to use depending on the extension of the files it +# parses. With this tag you can assign which parser to use for a given +# extension. Doxygen has a built-in mapping, but you can override or extend it +# using this tag. The format is ext=language, where ext is a file extension, and +# language is one of the parsers supported by doxygen: IDL, Java, Javascript, +# C#, C, C++, D, PHP, Objective-C, Python, Fortran (fixed format Fortran: +# FortranFixed, free formatted Fortran: FortranFree, unknown formatted Fortran: +# Fortran. In the later case the parser tries to guess whether the code is fixed +# or free formatted code, this is the default for Fortran type files), VHDL. For +# instance to make doxygen treat .inc files as Fortran files (default is PHP), +# and .f files as C (default is Fortran), use: inc=Fortran f=C. +# +# Note For files without extension you can use no_extension as a placeholder. +# +# Note that for custom extensions you also need to set FILE_PATTERNS otherwise +# the files are not read by doxygen. + +EXTENSION_MAPPING = + +# If the MARKDOWN_SUPPORT tag is enabled then doxygen pre-processes all comments +# according to the Markdown format, which allows for more readable +# documentation. See http://daringfireball.net/projects/markdown/ for details. +# The output of markdown processing is further processed by doxygen, so you can +# mix doxygen, HTML, and XML commands with Markdown formatting. Disable only in +# case of backward compatibilities issues. +# The default value is: YES. + +MARKDOWN_SUPPORT = YES + +# When enabled doxygen tries to link words that correspond to documented +# classes, or namespaces to their corresponding documentation. Such a link can +# be prevented in individual cases by by putting a % sign in front of the word +# or globally by setting AUTOLINK_SUPPORT to NO. +# The default value is: YES. + +AUTOLINK_SUPPORT = YES + +# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want +# to include (a tag file for) the STL sources as input, then you should set this +# tag to YES in order to let doxygen match functions declarations and +# definitions whose arguments contain STL classes (e.g. func(std::string); +# versus func(std::string) {}). This also make the inheritance and collaboration +# diagrams that involve STL classes more complete and accurate. +# The default value is: NO. + +BUILTIN_STL_SUPPORT = NO + +# If you use Microsoft's C++/CLI language, you should set this option to YES to +# enable parsing support. +# The default value is: NO. + +CPP_CLI_SUPPORT = NO + +# Set the SIP_SUPPORT tag to YES if your project consists of sip (see: +# http://www.riverbankcomputing.co.uk/software/sip/intro) sources only. Doxygen +# will parse them like normal C++ but will assume all classes use public instead +# of private inheritance when no explicit protection keyword is present. +# The default value is: NO. + +SIP_SUPPORT = NO + +# For Microsoft's IDL there are propget and propput attributes to indicate +# getter and setter methods for a property. Setting this option to YES will make +# doxygen to replace the get and set methods by a property in the documentation. +# This will only work if the methods are indeed getting or setting a simple +# type. If this is not the case, or you want to show the methods anyway, you +# should set this option to NO. +# The default value is: YES. + +IDL_PROPERTY_SUPPORT = YES + +# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC +# tag is set to YES, then doxygen will reuse the documentation of the first +# member in the group (if any) for the other members of the group. By default +# all members of a group must be documented explicitly. +# The default value is: NO. + +DISTRIBUTE_GROUP_DOC = NO + +# Set the SUBGROUPING tag to YES to allow class member groups of the same type +# (for instance a group of public functions) to be put as a subgroup of that +# type (e.g. under the Public Functions section). Set it to NO to prevent +# subgrouping. Alternatively, this can be done per class using the +# \nosubgrouping command. +# The default value is: YES. + +SUBGROUPING = YES + +# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and unions +# are shown inside the group in which they are included (e.g. using \ingroup) +# instead of on a separate page (for HTML and Man pages) or section (for LaTeX +# and RTF). +# +# Note that this feature does not work in combination with +# SEPARATE_MEMBER_PAGES. +# The default value is: NO. + +INLINE_GROUPED_CLASSES = NO + +# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and unions +# with only public data fields or simple typedef fields will be shown inline in +# the documentation of the scope in which they are defined (i.e. file, +# namespace, or group documentation), provided this scope is documented. If set +# to NO, structs, classes, and unions are shown on a separate page (for HTML and +# Man pages) or section (for LaTeX and RTF). +# The default value is: NO. + +INLINE_SIMPLE_STRUCTS = NO + +# When TYPEDEF_HIDES_STRUCT tag is enabled, a typedef of a struct, union, or +# enum is documented as struct, union, or enum with the name of the typedef. So +# typedef struct TypeS {} TypeT, will appear in the documentation as a struct +# with name TypeT. When disabled the typedef will appear as a member of a file, +# namespace, or class. And the struct will be named TypeS. This can typically be +# useful for C code in case the coding convention dictates that all compound +# types are typedef'ed and only the typedef is referenced, never the tag name. +# The default value is: NO. + +TYPEDEF_HIDES_STRUCT = NO + +# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This +# cache is used to resolve symbols given their name and scope. Since this can be +# an expensive process and often the same symbol appears multiple times in the +# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small +# doxygen will become slower. If the cache is too large, memory is wasted. The +# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range +# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536 +# symbols. At the end of a run doxygen will report the cache usage and suggest +# the optimal cache size from a speed point of view. +# Minimum value: 0, maximum value: 9, default value: 0. + +LOOKUP_CACHE_SIZE = 0 + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in +# documentation are documented, even if no documentation was available. Private +# class members and static file members will be hidden unless the +# EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES. +# Note: This will also disable the warnings about undocumented members that are +# normally produced when WARNINGS is set to YES. +# The default value is: NO. + +EXTRACT_ALL = NO + +# If the EXTRACT_PRIVATE tag is set to YES all private members of a class will +# be included in the documentation. +# The default value is: NO. + +EXTRACT_PRIVATE = NO + +# If the EXTRACT_PACKAGE tag is set to YES all members with package or internal +# scope will be included in the documentation. +# The default value is: NO. + +EXTRACT_PACKAGE = NO + +# If the EXTRACT_STATIC tag is set to YES all static members of a file will be +# included in the documentation. +# The default value is: NO. + +EXTRACT_STATIC = NO + +# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) defined +# locally in source files will be included in the documentation. If set to NO +# only classes defined in header files are included. Does not have any effect +# for Java sources. +# The default value is: YES. + +EXTRACT_LOCAL_CLASSES = NO + +# This flag is only useful for Objective-C code. When set to YES local methods, +# which are defined in the implementation section but not in the interface are +# included in the documentation. If set to NO only methods in the interface are +# included. +# The default value is: NO. + +EXTRACT_LOCAL_METHODS = NO + +# If this flag is set to YES, the members of anonymous namespaces will be +# extracted and appear in the documentation as a namespace called +# 'anonymous_namespace{file}', where file will be replaced with the base name of +# the file that contains the anonymous namespace. By default anonymous namespace +# are hidden. +# The default value is: NO. + +EXTRACT_ANON_NSPACES = NO + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, doxygen will hide all +# undocumented members inside documented classes or files. If set to NO these +# members will be included in the various overviews, but no documentation +# section is generated. This option has no effect if EXTRACT_ALL is enabled. +# The default value is: NO. + +HIDE_UNDOC_MEMBERS = YES + +# If the HIDE_UNDOC_CLASSES tag is set to YES, doxygen will hide all +# undocumented classes that are normally visible in the class hierarchy. If set +# to NO these classes will be included in the various overviews. This option has +# no effect if EXTRACT_ALL is enabled. +# The default value is: NO. + +HIDE_UNDOC_CLASSES = YES + +# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, doxygen will hide all friend +# (class|struct|union) declarations. If set to NO these declarations will be +# included in the documentation. +# The default value is: NO. + +HIDE_FRIEND_COMPOUNDS = NO + +# If the HIDE_IN_BODY_DOCS tag is set to YES, doxygen will hide any +# documentation blocks found inside the body of a function. If set to NO these +# blocks will be appended to the function's detailed documentation block. +# The default value is: NO. + +HIDE_IN_BODY_DOCS = NO + +# The INTERNAL_DOCS tag determines if documentation that is typed after a +# \internal command is included. If the tag is set to NO then the documentation +# will be excluded. Set it to YES to include the internal documentation. +# The default value is: NO. + +INTERNAL_DOCS = NO + +# If the CASE_SENSE_NAMES tag is set to NO then doxygen will only generate file +# names in lower-case letters. If set to YES upper-case letters are also +# allowed. This is useful if you have classes or files whose names only differ +# in case and if your file system supports case sensitive file names. Windows +# and Mac users are advised to set this option to NO. +# The default value is: system dependent. + +CASE_SENSE_NAMES = NO + +# If the HIDE_SCOPE_NAMES tag is set to NO then doxygen will show members with +# their full class and namespace scopes in the documentation. If set to YES the +# scope will be hidden. +# The default value is: NO. + +HIDE_SCOPE_NAMES = YES + +# If the SHOW_INCLUDE_FILES tag is set to YES then doxygen will put a list of +# the files that are included by a file in the documentation of that file. +# The default value is: YES. + +SHOW_INCLUDE_FILES = YES + +# If the SHOW_GROUPED_MEMB_INC tag is set to YES then Doxygen will add for each +# grouped member an include statement to the documentation, telling the reader +# which file to include in order to use the member. +# The default value is: NO. + +SHOW_GROUPED_MEMB_INC = NO + +# If the FORCE_LOCAL_INCLUDES tag is set to YES then doxygen will list include +# files with double quotes in the documentation rather than with sharp brackets. +# The default value is: NO. + +FORCE_LOCAL_INCLUDES = NO + +# If the INLINE_INFO tag is set to YES then a tag [inline] is inserted in the +# documentation for inline members. +# The default value is: YES. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES then doxygen will sort the +# (detailed) documentation of file and class members alphabetically by member +# name. If set to NO the members will appear in declaration order. +# The default value is: YES. + +SORT_MEMBER_DOCS = YES + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the brief +# descriptions of file, namespace and class members alphabetically by member +# name. If set to NO the members will appear in declaration order. Note that +# this will also influence the order of the classes in the class list. +# The default value is: NO. + +SORT_BRIEF_DOCS = NO + +# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the +# (brief and detailed) documentation of class members so that constructors and +# destructors are listed first. If set to NO the constructors will appear in the +# respective orders defined by SORT_BRIEF_DOCS and SORT_MEMBER_DOCS. +# Note: If SORT_BRIEF_DOCS is set to NO this option is ignored for sorting brief +# member documentation. +# Note: If SORT_MEMBER_DOCS is set to NO this option is ignored for sorting +# detailed member documentation. +# The default value is: NO. + +SORT_MEMBERS_CTORS_1ST = NO + +# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the hierarchy +# of group names into alphabetical order. If set to NO the group names will +# appear in their defined order. +# The default value is: NO. + +SORT_GROUP_NAMES = NO + +# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be sorted by +# fully-qualified names, including namespaces. If set to NO, the class list will +# be sorted only by class name, not including the namespace part. +# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. +# Note: This option applies only to the class list, not to the alphabetical +# list. +# The default value is: NO. + +SORT_BY_SCOPE_NAME = NO + +# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to do proper +# type resolution of all parameters of a function it will reject a match between +# the prototype and the implementation of a member function even if there is +# only one candidate or it is obvious which candidate to choose by doing a +# simple string match. By disabling STRICT_PROTO_MATCHING doxygen will still +# accept a match between prototype and implementation in such cases. +# The default value is: NO. + +STRICT_PROTO_MATCHING = NO + +# The GENERATE_TODOLIST tag can be used to enable ( YES) or disable ( NO) the +# todo list. This list is created by putting \todo commands in the +# documentation. +# The default value is: YES. + +GENERATE_TODOLIST = YES + +# The GENERATE_TESTLIST tag can be used to enable ( YES) or disable ( NO) the +# test list. This list is created by putting \test commands in the +# documentation. +# The default value is: YES. + +GENERATE_TESTLIST = YES + +# The GENERATE_BUGLIST tag can be used to enable ( YES) or disable ( NO) the bug +# list. This list is created by putting \bug commands in the documentation. +# The default value is: YES. + +GENERATE_BUGLIST = YES + +# The GENERATE_DEPRECATEDLIST tag can be used to enable ( YES) or disable ( NO) +# the deprecated list. This list is created by putting \deprecated commands in +# the documentation. +# The default value is: YES. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional documentation +# sections, marked by \if ... \endif and \cond +# ... \endcond blocks. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines that the +# initial value of a variable or macro / define can have for it to appear in the +# documentation. If the initializer consists of more lines than specified here +# it will be hidden. Use a value of 0 to hide initializers completely. The +# appearance of the value of individual variables and macros / defines can be +# controlled using \showinitializer or \hideinitializer command in the +# documentation regardless of this setting. +# Minimum value: 0, maximum value: 10000, default value: 30. + +MAX_INITIALIZER_LINES = 30 + +# Set the SHOW_USED_FILES tag to NO to disable the list of files generated at +# the bottom of the documentation of classes and structs. If set to YES the list +# will mention the files that were used to generate the documentation. +# The default value is: YES. + +SHOW_USED_FILES = YES + +# Set the SHOW_FILES tag to NO to disable the generation of the Files page. This +# will remove the Files entry from the Quick Index and from the Folder Tree View +# (if specified). +# The default value is: YES. + +SHOW_FILES = YES + +# Set the SHOW_NAMESPACES tag to NO to disable the generation of the Namespaces +# page. This will remove the Namespaces entry from the Quick Index and from the +# Folder Tree View (if specified). +# The default value is: YES. + +SHOW_NAMESPACES = YES + +# The FILE_VERSION_FILTER tag can be used to specify a program or script that +# doxygen should invoke to get the current version for each file (typically from +# the version control system). Doxygen will invoke the program by executing (via +# popen()) the command command input-file, where command is the value of the +# FILE_VERSION_FILTER tag, and input-file is the name of an input file provided +# by doxygen. Whatever the program writes to standard output is used as the file +# version. For an example see the documentation. + +FILE_VERSION_FILTER = + +# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed +# by doxygen. The layout file controls the global structure of the generated +# output files in an output format independent way. To create the layout file +# that represents doxygen's defaults, run doxygen with the -l option. You can +# optionally specify a file name after the option, if omitted DoxygenLayout.xml +# will be used as the name of the layout file. +# +# Note that if you run doxygen from a directory containing a file called +# DoxygenLayout.xml, doxygen will parse it automatically even if the LAYOUT_FILE +# tag is left empty. + +LAYOUT_FILE = + +# The CITE_BIB_FILES tag can be used to specify one or more bib files containing +# the reference definitions. This must be a list of .bib files. The .bib +# extension is automatically appended if omitted. This requires the bibtex tool +# to be installed. See also http://en.wikipedia.org/wiki/BibTeX for more info. +# For LaTeX the style of the bibliography can be controlled using +# LATEX_BIB_STYLE. To use this feature you need bibtex and perl available in the +# search path. Do not use file names with spaces, bibtex cannot handle them. See +# also \cite for info how to create references. + +CITE_BIB_FILES = + +#--------------------------------------------------------------------------- +# Configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated to +# standard output by doxygen. If QUIET is set to YES this implies that the +# messages are off. +# The default value is: NO. + +QUIET = NO + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated to standard error ( stderr) by doxygen. If WARNINGS is set to YES +# this implies that the warnings are on. +# +# Tip: Turn warnings on while writing the documentation. +# The default value is: YES. + +WARNINGS = YES + +# If the WARN_IF_UNDOCUMENTED tag is set to YES, then doxygen will generate +# warnings for undocumented members. If EXTRACT_ALL is set to YES then this flag +# will automatically be disabled. +# The default value is: YES. + +WARN_IF_UNDOCUMENTED = YES + +# If the WARN_IF_DOC_ERROR tag is set to YES, doxygen will generate warnings for +# potential errors in the documentation, such as not documenting some parameters +# in a documented function, or documenting parameters that don't exist or using +# markup commands wrongly. +# The default value is: YES. + +WARN_IF_DOC_ERROR = YES + +# This WARN_NO_PARAMDOC option can be enabled to get warnings for functions that +# are documented, but have no documentation for their parameters or return +# value. If set to NO doxygen will only warn about wrong or incomplete parameter +# documentation, but not about the absence of documentation. +# The default value is: NO. + +WARN_NO_PARAMDOC = NO + +# The WARN_FORMAT tag determines the format of the warning messages that doxygen +# can produce. The string should contain the $file, $line, and $text tags, which +# will be replaced by the file and line number from which the warning originated +# and the warning text. Optionally the format may contain $version, which will +# be replaced by the version of the file (if it could be obtained via +# FILE_VERSION_FILTER) +# The default value is: $file:$line: $text. + +WARN_FORMAT = "$file:$line: $text" + +# The WARN_LOGFILE tag can be used to specify a file to which warning and error +# messages should be written. If left blank the output is written to standard +# error (stderr). + +WARN_LOGFILE = + +#--------------------------------------------------------------------------- +# Configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag is used to specify the files and/or directories that contain +# documented source files. You may enter file names like myfile.cpp or +# directories like /usr/src/myproject. Separate the files or directories with +# spaces. +# Note: If this tag is empty the current directory is searched. + +INPUT = ./VVUVCKit \ + ./README.md \ + ./USBBusProber/APPLE_LICENSE + +# This tag can be used to specify the character encoding of the source files +# that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses +# libiconv (or the iconv built into libc) for the transcoding. See the libiconv +# documentation (see: http://www.gnu.org/software/libiconv) for the list of +# possible encodings. +# The default value is: UTF-8. + +INPUT_ENCODING = UTF-8 + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard patterns (like *.cpp and +# *.h) to filter out the source-files in the directories. If left blank the +# following patterns are tested:*.c, *.cc, *.cxx, *.cpp, *.c++, *.java, *.ii, +# *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h, *.hh, *.hxx, *.hpp, +# *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc, *.m, *.markdown, +# *.md, *.mm, *.dox, *.py, *.f90, *.f, *.for, *.tcl, *.vhd, *.vhdl, *.ucf, +# *.qsf, *.as and *.js. + +FILE_PATTERNS = *.c \ + *.cc \ + *.cxx \ + *.cpp \ + *.c++ \ + *.java \ + *.ii \ + *.ixx \ + *.ipp \ + *.i++ \ + *.inl \ + *.idl \ + *.ddl \ + *.odl \ + *.h \ + *.hh \ + *.hxx \ + *.hpp \ + *.h++ \ + *.cs \ + *.d \ + *.php \ + *.php4 \ + *.php5 \ + *.phtml \ + *.inc \ + *.m \ + *.markdown \ + *.md \ + *.mm \ + *.dox \ + *.py \ + *.f90 \ + *.f \ + *.for \ + *.tcl \ + *.vhd \ + *.vhdl \ + *.ucf \ + *.qsf \ + *.as \ + *.js + +# The RECURSIVE tag can be used to specify whether or not subdirectories should +# be searched for input files as well. +# The default value is: NO. + +RECURSIVE = YES + +# The EXCLUDE tag can be used to specify files and/or directories that should be +# excluded from the INPUT source files. This way you can easily exclude a +# subdirectory from a directory tree whose root is specified with the INPUT tag. +# +# Note that relative paths are relative to the directory from which doxygen is +# run. + +EXCLUDE = + +# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or +# directories that are symbolic links (a Unix file system feature) are excluded +# from the input. +# The default value is: NO. + +EXCLUDE_SYMLINKS = NO + +# If the value of the INPUT tag contains directories, you can use the +# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude +# certain files from those directories. +# +# Note that the wildcards are matched against the file with absolute path, so to +# exclude all test directories for example use the pattern */test/* + +EXCLUDE_PATTERNS = + +# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names +# (namespaces, classes, functions, etc.) that should be excluded from the +# output. The symbol name can be a fully qualified name, a word, or if the +# wildcard * is used, a substring. Examples: ANamespace, AClass, +# AClass::ANamespace, ANamespace::*Test +# +# Note that the wildcards are matched against the file with absolute path, so to +# exclude all test directories use the pattern */test/* + +EXCLUDE_SYMBOLS = + +# The EXAMPLE_PATH tag can be used to specify one or more files or directories +# that contain example code fragments that are included (see the \include +# command). + +EXAMPLE_PATH = + +# If the value of the EXAMPLE_PATH tag contains directories, you can use the +# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp and +# *.h) to filter out the source-files in the directories. If left blank all +# files are included. + +EXAMPLE_PATTERNS = * + +# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be +# searched for input files to be used with the \include or \dontinclude commands +# irrespective of the value of the RECURSIVE tag. +# The default value is: NO. + +EXAMPLE_RECURSIVE = NO + +# The IMAGE_PATH tag can be used to specify one or more files or directories +# that contain images that are to be included in the documentation (see the +# \image command). + +IMAGE_PATH = + +# The INPUT_FILTER tag can be used to specify a program that doxygen should +# invoke to filter for each input file. Doxygen will invoke the filter program +# by executing (via popen()) the command: +# +# +# +# where is the value of the INPUT_FILTER tag, and is the +# name of an input file. Doxygen will then use the output that the filter +# program writes to standard output. If FILTER_PATTERNS is specified, this tag +# will be ignored. +# +# Note that the filter must not add or remove lines; it is applied before the +# code is scanned, but not when the output code is generated. If lines are added +# or removed, the anchors will not be placed correctly. + +INPUT_FILTER = + +# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern +# basis. Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. The filters are a list of the form: pattern=filter +# (like *.cpp=my_cpp_filter). See INPUT_FILTER for further information on how +# filters are used. If the FILTER_PATTERNS tag is empty or if none of the +# patterns match the file name, INPUT_FILTER is applied. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER ) will also be used to filter the input files that are used for +# producing the source files to browse (i.e. when SOURCE_BROWSER is set to YES). +# The default value is: NO. + +FILTER_SOURCE_FILES = NO + +# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file +# pattern. A pattern will override the setting for FILTER_PATTERN (if any) and +# it is also possible to disable source filtering for a specific pattern using +# *.ext= (so without naming a filter). +# This tag requires that the tag FILTER_SOURCE_FILES is set to YES. + +FILTER_SOURCE_PATTERNS = + +# If the USE_MDFILE_AS_MAINPAGE tag refers to the name of a markdown file that +# is part of the input, its contents will be placed on the main page +# (index.html). This can be useful if you have a project on for instance GitHub +# and want to reuse the introduction page also for the doxygen output. + +USE_MDFILE_AS_MAINPAGE = + +#--------------------------------------------------------------------------- +# Configuration options related to source browsing +#--------------------------------------------------------------------------- + +# If the SOURCE_BROWSER tag is set to YES then a list of source files will be +# generated. Documented entities will be cross-referenced with these sources. +# +# Note: To get rid of all source code in the generated output, make sure that +# also VERBATIM_HEADERS is set to NO. +# The default value is: NO. + +SOURCE_BROWSER = NO + +# Setting the INLINE_SOURCES tag to YES will include the body of functions, +# classes and enums directly into the documentation. +# The default value is: NO. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES will instruct doxygen to hide any +# special comment blocks from generated source code fragments. Normal C, C++ and +# Fortran comments will always remain visible. +# The default value is: YES. + +STRIP_CODE_COMMENTS = YES + +# If the REFERENCED_BY_RELATION tag is set to YES then for each documented +# function all documented functions referencing it will be listed. +# The default value is: NO. + +REFERENCED_BY_RELATION = NO + +# If the REFERENCES_RELATION tag is set to YES then for each documented function +# all documented entities called/used by that function will be listed. +# The default value is: NO. + +REFERENCES_RELATION = NO + +# If the REFERENCES_LINK_SOURCE tag is set to YES and SOURCE_BROWSER tag is set +# to YES, then the hyperlinks from functions in REFERENCES_RELATION and +# REFERENCED_BY_RELATION lists will link to the source code. Otherwise they will +# link to the documentation. +# The default value is: YES. + +REFERENCES_LINK_SOURCE = YES + +# If SOURCE_TOOLTIPS is enabled (the default) then hovering a hyperlink in the +# source code will show a tooltip with additional information such as prototype, +# brief description and links to the definition and documentation. Since this +# will make the HTML file larger and loading of large files a bit slower, you +# can opt to disable this feature. +# The default value is: YES. +# This tag requires that the tag SOURCE_BROWSER is set to YES. + +SOURCE_TOOLTIPS = YES + +# If the USE_HTAGS tag is set to YES then the references to source code will +# point to the HTML generated by the htags(1) tool instead of doxygen built-in +# source browser. The htags tool is part of GNU's global source tagging system +# (see http://www.gnu.org/software/global/global.html). You will need version +# 4.8.6 or higher. +# +# To use it do the following: +# - Install the latest version of global +# - Enable SOURCE_BROWSER and USE_HTAGS in the config file +# - Make sure the INPUT points to the root of the source tree +# - Run doxygen as normal +# +# Doxygen will invoke htags (and that will in turn invoke gtags), so these +# tools must be available from the command line (i.e. in the search path). +# +# The result: instead of the source browser generated by doxygen, the links to +# source code will now point to the output of htags. +# The default value is: NO. +# This tag requires that the tag SOURCE_BROWSER is set to YES. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set the YES then doxygen will generate a +# verbatim copy of the header file for each class for which an include is +# specified. Set to NO to disable this. +# See also: Section \class. +# The default value is: YES. + +VERBATIM_HEADERS = YES + +# If the CLANG_ASSISTED_PARSING tag is set to YES, then doxygen will use the +# clang parser (see: http://clang.llvm.org/) for more accurate parsing at the +# cost of reduced performance. This can be particularly helpful with template +# rich C++ code for which doxygen's built-in parser lacks the necessary type +# information. +# Note: The availability of this option depends on whether or not doxygen was +# compiled with the --with-libclang option. +# The default value is: NO. + +CLANG_ASSISTED_PARSING = NO + +# If clang assisted parsing is enabled you can provide the compiler with command +# line options that you would normally use when invoking the compiler. Note that +# the include paths will already be set by doxygen for the files and directories +# specified with INPUT and INCLUDE_PATH. +# This tag requires that the tag CLANG_ASSISTED_PARSING is set to YES. + +CLANG_OPTIONS = + +#--------------------------------------------------------------------------- +# Configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index of all +# compounds will be generated. Enable this if the project contains a lot of +# classes, structs, unions or interfaces. +# The default value is: YES. + +ALPHABETICAL_INDEX = YES + +# The COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns in +# which the alphabetical index list will be split. +# Minimum value: 1, maximum value: 20, default value: 5. +# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. + +COLS_IN_ALPHA_INDEX = 5 + +# In case all classes in a project start with a common prefix, all classes will +# be put under the same header in the alphabetical index. The IGNORE_PREFIX tag +# can be used to specify a prefix (or a list of prefixes) that should be ignored +# while generating the index headers. +# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES doxygen will generate HTML output +# The default value is: YES. + +GENERATE_HTML = YES + +# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. If a +# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of +# it. +# The default directory is: html. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_OUTPUT = html + +# The HTML_FILE_EXTENSION tag can be used to specify the file extension for each +# generated HTML page (for example: .htm, .php, .asp). +# The default value is: .html. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a user-defined HTML header file for +# each generated HTML page. If the tag is left blank doxygen will generate a +# standard header. +# +# To get valid HTML the header file that includes any scripts and style sheets +# that doxygen needs, which is dependent on the configuration options used (e.g. +# the setting GENERATE_TREEVIEW). It is highly recommended to start with a +# default header using +# doxygen -w html new_header.html new_footer.html new_stylesheet.css +# YourConfigFile +# and then modify the file new_header.html. See also section "Doxygen usage" +# for information on how to generate the default header that doxygen normally +# uses. +# Note: The header is subject to change so you typically have to regenerate the +# default header when upgrading to a newer version of doxygen. For a description +# of the possible markers and block names see the documentation. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_HEADER = + +# The HTML_FOOTER tag can be used to specify a user-defined HTML footer for each +# generated HTML page. If the tag is left blank doxygen will generate a standard +# footer. See HTML_HEADER for more information on how to generate a default +# footer and what special commands can be used inside the footer. See also +# section "Doxygen usage" for information on how to generate the default footer +# that doxygen normally uses. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FOOTER = + +# The HTML_STYLESHEET tag can be used to specify a user-defined cascading style +# sheet that is used by each HTML page. It can be used to fine-tune the look of +# the HTML output. If left blank doxygen will generate a default style sheet. +# See also section "Doxygen usage" for information on how to generate the style +# sheet that doxygen normally uses. +# Note: It is recommended to use HTML_EXTRA_STYLESHEET instead of this tag, as +# it is more robust and this tag (HTML_STYLESHEET) will in the future become +# obsolete. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_STYLESHEET = + +# The HTML_EXTRA_STYLESHEET tag can be used to specify an additional user- +# defined cascading style sheet that is included after the standard style sheets +# created by doxygen. Using this option one can overrule certain style aspects. +# This is preferred over using HTML_STYLESHEET since it does not replace the +# standard style sheet and is therefor more robust against future updates. +# Doxygen will copy the style sheet file to the output directory. For an example +# see the documentation. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_EXTRA_STYLESHEET = + +# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or +# other source files which should be copied to the HTML output directory. Note +# that these files will be copied to the base HTML output directory. Use the +# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these +# files. In the HTML_STYLESHEET file, use the file name only. Also note that the +# files will be copied as-is; there are no commands or markers available. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_EXTRA_FILES = + +# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen +# will adjust the colors in the stylesheet and background images according to +# this color. Hue is specified as an angle on a colorwheel, see +# http://en.wikipedia.org/wiki/Hue for more information. For instance the value +# 0 represents red, 60 is yellow, 120 is green, 180 is cyan, 240 is blue, 300 +# purple, and 360 is red again. +# Minimum value: 0, maximum value: 359, default value: 220. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_HUE = 220 + +# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of the colors +# in the HTML output. For a value of 0 the output will use grayscales only. A +# value of 255 will produce the most vivid colors. +# Minimum value: 0, maximum value: 255, default value: 100. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_SAT = 100 + +# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to the +# luminance component of the colors in the HTML output. Values below 100 +# gradually make the output lighter, whereas values above 100 make the output +# darker. The value divided by 100 is the actual gamma applied, so 80 represents +# a gamma of 0.8, The value 220 represents a gamma of 2.2, and 100 does not +# change the gamma. +# Minimum value: 40, maximum value: 240, default value: 80. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_GAMMA = 80 + +# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML +# page will contain the date and time when the page was generated. Setting this +# to NO can help when comparing the output of multiple runs. +# The default value is: YES. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_TIMESTAMP = YES + +# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML +# documentation will contain sections that can be hidden and shown after the +# page has loaded. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_DYNAMIC_SECTIONS = NO + +# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of entries +# shown in the various tree structured indices initially; the user can expand +# and collapse entries dynamically later on. Doxygen will expand the tree to +# such a level that at most the specified number of entries are visible (unless +# a fully collapsed tree already exceeds this amount). So setting the number of +# entries 1 will produce a full collapsed tree by default. 0 is a special value +# representing an infinite number of entries and will result in a full expanded +# tree by default. +# Minimum value: 0, maximum value: 9999, default value: 100. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_INDEX_NUM_ENTRIES = 100 + +# If the GENERATE_DOCSET tag is set to YES, additional index files will be +# generated that can be used as input for Apple's Xcode 3 integrated development +# environment (see: http://developer.apple.com/tools/xcode/), introduced with +# OSX 10.5 (Leopard). To create a documentation set, doxygen will generate a +# Makefile in the HTML output directory. Running make will produce the docset in +# that directory and running make install will install the docset in +# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at +# startup. See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html +# for more information. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_DOCSET = NO + +# This tag determines the name of the docset feed. A documentation feed provides +# an umbrella under which multiple documentation sets from a single provider +# (such as a company or product suite) can be grouped. +# The default value is: Doxygen generated docs. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_FEEDNAME = "Doxygen generated docs" + +# This tag specifies a string that should uniquely identify the documentation +# set bundle. This should be a reverse domain-name style string, e.g. +# com.mycompany.MyDocSet. Doxygen will append .docset to the name. +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_BUNDLE_ID = org.doxygen.Project + +# The DOCSET_PUBLISHER_ID tag specifies a string that should uniquely identify +# the documentation publisher. This should be a reverse domain-name style +# string, e.g. com.mycompany.MyDocSet.documentation. +# The default value is: org.doxygen.Publisher. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_PUBLISHER_ID = org.doxygen.Publisher + +# The DOCSET_PUBLISHER_NAME tag identifies the documentation publisher. +# The default value is: Publisher. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_PUBLISHER_NAME = Publisher + +# If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three +# additional HTML index files: index.hhp, index.hhc, and index.hhk. The +# index.hhp is a project file that can be read by Microsoft's HTML Help Workshop +# (see: http://www.microsoft.com/en-us/download/details.aspx?id=21138) on +# Windows. +# +# The HTML Help Workshop contains a compiler that can convert all HTML output +# generated by doxygen into a single compiled HTML file (.chm). Compiled HTML +# files are now used as the Windows 98 help format, and will replace the old +# Windows help format (.hlp) on all Windows platforms in the future. Compressed +# HTML files also contain an index, a table of contents, and you can search for +# words in the documentation. The HTML workshop also contains a viewer for +# compressed HTML files. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_HTMLHELP = NO + +# The CHM_FILE tag can be used to specify the file name of the resulting .chm +# file. You can add a path in front of the file if the result should not be +# written to the html output directory. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +CHM_FILE = + +# The HHC_LOCATION tag can be used to specify the location (absolute path +# including file name) of the HTML help compiler ( hhc.exe). If non-empty +# doxygen will try to run the HTML help compiler on the generated index.hhp. +# The file has to be specified with full path. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +HHC_LOCATION = + +# The GENERATE_CHI flag controls if a separate .chi index file is generated ( +# YES) or that it should be included in the master .chm file ( NO). +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +GENERATE_CHI = NO + +# The CHM_INDEX_ENCODING is used to encode HtmlHelp index ( hhk), content ( hhc) +# and project file content. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +CHM_INDEX_ENCODING = + +# The BINARY_TOC flag controls whether a binary table of contents is generated ( +# YES) or a normal table of contents ( NO) in the .chm file. Furthermore it +# enables the Previous and Next buttons. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members to +# the table of contents of the HTML help documentation and to the tree view. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +TOC_EXPAND = NO + +# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and +# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated that +# can be used as input for Qt's qhelpgenerator to generate a Qt Compressed Help +# (.qch) of the generated HTML documentation. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_QHP = NO + +# If the QHG_LOCATION tag is specified, the QCH_FILE tag can be used to specify +# the file name of the resulting .qch file. The path specified is relative to +# the HTML output folder. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QCH_FILE = + +# The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help +# Project output. For more information please see Qt Help Project / Namespace +# (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#namespace). +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_NAMESPACE = org.doxygen.Project + +# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt +# Help Project output. For more information please see Qt Help Project / Virtual +# Folders (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#virtual- +# folders). +# The default value is: doc. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_VIRTUAL_FOLDER = doc + +# If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom +# filter to add. For more information please see Qt Help Project / Custom +# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom- +# filters). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_CUST_FILTER_NAME = + +# The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the +# custom filter to add. For more information please see Qt Help Project / Custom +# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom- +# filters). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_CUST_FILTER_ATTRS = + +# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this +# project's filter section matches. Qt Help Project / Filter Attributes (see: +# http://qt-project.org/doc/qt-4.8/qthelpproject.html#filter-attributes). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_SECT_FILTER_ATTRS = + +# The QHG_LOCATION tag can be used to specify the location of Qt's +# qhelpgenerator. If non-empty doxygen will try to run qhelpgenerator on the +# generated .qhp file. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHG_LOCATION = + +# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files will be +# generated, together with the HTML files, they form an Eclipse help plugin. To +# install this plugin and make it available under the help contents menu in +# Eclipse, the contents of the directory containing the HTML and XML files needs +# to be copied into the plugins directory of eclipse. The name of the directory +# within the plugins directory should be the same as the ECLIPSE_DOC_ID value. +# After copying Eclipse needs to be restarted before the help appears. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_ECLIPSEHELP = NO + +# A unique identifier for the Eclipse help plugin. When installing the plugin +# the directory name containing the HTML and XML files should also have this +# name. Each documentation set should have its own identifier. +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_ECLIPSEHELP is set to YES. + +ECLIPSE_DOC_ID = org.doxygen.Project + +# If you want full control over the layout of the generated HTML pages it might +# be necessary to disable the index and replace it with your own. The +# DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) at top +# of each HTML page. A value of NO enables the index and the value YES disables +# it. Since the tabs in the index contain the same information as the navigation +# tree, you can set this option to YES if you also set GENERATE_TREEVIEW to YES. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +DISABLE_INDEX = NO + +# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index +# structure should be generated to display hierarchical information. If the tag +# value is set to YES, a side panel will be generated containing a tree-like +# index structure (just like the one that is generated for HTML Help). For this +# to work a browser that supports JavaScript, DHTML, CSS and frames is required +# (i.e. any modern browser). Windows users are probably better off using the +# HTML help feature. Via custom stylesheets (see HTML_EXTRA_STYLESHEET) one can +# further fine-tune the look of the index. As an example, the default style +# sheet generated by doxygen has an example that shows how to put an image at +# the root of the tree instead of the PROJECT_NAME. Since the tree basically has +# the same information as the tab index, you could consider setting +# DISABLE_INDEX to YES when enabling this option. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_TREEVIEW = NO + +# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values that +# doxygen will group on one line in the generated HTML documentation. +# +# Note that a value of 0 will completely suppress the enum values from appearing +# in the overview section. +# Minimum value: 0, maximum value: 20, default value: 4. +# This tag requires that the tag GENERATE_HTML is set to YES. + +ENUM_VALUES_PER_LINE = 4 + +# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be used +# to set the initial width (in pixels) of the frame in which the tree is shown. +# Minimum value: 0, maximum value: 1500, default value: 250. +# This tag requires that the tag GENERATE_HTML is set to YES. + +TREEVIEW_WIDTH = 250 + +# When the EXT_LINKS_IN_WINDOW option is set to YES doxygen will open links to +# external symbols imported via tag files in a separate window. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +EXT_LINKS_IN_WINDOW = NO + +# Use this tag to change the font size of LaTeX formulas included as images in +# the HTML documentation. When you change the font size after a successful +# doxygen run you need to manually remove any form_*.png images from the HTML +# output directory to force them to be regenerated. +# Minimum value: 8, maximum value: 50, default value: 10. +# This tag requires that the tag GENERATE_HTML is set to YES. + +FORMULA_FONTSIZE = 10 + +# Use the FORMULA_TRANPARENT tag to determine whether or not the images +# generated for formulas are transparent PNGs. Transparent PNGs are not +# supported properly for IE 6.0, but are supported on all modern browsers. +# +# Note that when changing this option you need to delete any form_*.png files in +# the HTML output directory before the changes have effect. +# The default value is: YES. +# This tag requires that the tag GENERATE_HTML is set to YES. + +FORMULA_TRANSPARENT = YES + +# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see +# http://www.mathjax.org) which uses client side Javascript for the rendering +# instead of using prerendered bitmaps. Use this if you do not have LaTeX +# installed or if you want to formulas look prettier in the HTML output. When +# enabled you may also need to install MathJax separately and configure the path +# to it using the MATHJAX_RELPATH option. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +USE_MATHJAX = NO + +# When MathJax is enabled you can set the default output format to be used for +# the MathJax output. See the MathJax site (see: +# http://docs.mathjax.org/en/latest/output.html) for more details. +# Possible values are: HTML-CSS (which is slower, but has the best +# compatibility), NativeMML (i.e. MathML) and SVG. +# The default value is: HTML-CSS. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_FORMAT = HTML-CSS + +# When MathJax is enabled you need to specify the location relative to the HTML +# output directory using the MATHJAX_RELPATH option. The destination directory +# should contain the MathJax.js script. For instance, if the mathjax directory +# is located at the same level as the HTML output directory, then +# MATHJAX_RELPATH should be ../mathjax. The default value points to the MathJax +# Content Delivery Network so you can quickly see the result without installing +# MathJax. However, it is strongly recommended to install a local copy of +# MathJax from http://www.mathjax.org before deployment. +# The default value is: http://cdn.mathjax.org/mathjax/latest. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest + +# The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax +# extension names that should be enabled during MathJax rendering. For example +# MATHJAX_EXTENSIONS = TeX/AMSmath TeX/AMSsymbols +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_EXTENSIONS = + +# The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces +# of code that will be used on startup of the MathJax code. See the MathJax site +# (see: http://docs.mathjax.org/en/latest/output.html) for more details. For an +# example see the documentation. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_CODEFILE = + +# When the SEARCHENGINE tag is enabled doxygen will generate a search box for +# the HTML output. The underlying search engine uses javascript and DHTML and +# should work on any modern browser. Note that when using HTML help +# (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets (GENERATE_DOCSET) +# there is already a search function so this one should typically be disabled. +# For large projects the javascript based search engine can be slow, then +# enabling SERVER_BASED_SEARCH may provide a better solution. It is possible to +# search using the keyboard; to jump to the search box use + S +# (what the is depends on the OS and browser, but it is typically +# , /