diff --git a/.gitignore b/.gitignore index 7be8236..396e1d4 100644 --- a/.gitignore +++ b/.gitignore @@ -16,6 +16,11 @@ _output/ /plugins/ +/3rdparty/opencv/ +/pkginfo.sh +/*.nsi +/*.exe + # ros /wrappers/ros/build diff --git a/CMakeLists.txt b/CMakeLists.txt index 9305000..2172b5f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,10 +14,14 @@ cmake_minimum_required(VERSION 3.0) -project(mynteye VERSION 2.0.1 LANGUAGES C CXX) +project(mynteye VERSION 2.2.2 LANGUAGES C CXX) include(cmake/Common.cmake) +if(NOT CMAKE_DEBUG_POSTFIX) + set(CMAKE_DEBUG_POSTFIX d) +endif() + # options include(cmake/Option.cmake) @@ -79,6 +83,17 @@ 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 + ${CMAKE_CURRENT_SOURCE_DIR}/winpack.nsi @ONLY + ) +endif() + # targets add_definitions(-DMYNTEYE_EXPORTS) @@ -90,11 +105,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) @@ -108,84 +118,58 @@ 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}") 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/win/uvc-wmf.cc) elseif(OS_MAC) - set(UVC_SRC src/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/uvc/uvc-v4l2.cc) + set(UVC_SRC src/mynteye/uvc/linux/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 +198,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/CommonDefs.mk b/CommonDefs.mk index 378b7ff..1df3a94 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 @@ -202,6 +211,15 @@ endif endif +# Package + +PKGVERSION := $(shell ./scripts/version.sh) +PKGNAME := mynteye-s-$(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/Jenkinsfile b/Jenkinsfile new file mode 100644 index 0000000..619ee8e --- /dev/null +++ b/Jenkinsfile @@ -0,0 +1,103 @@ +pipeline { + agent { + // docker { image 'ros:kinetic-ros-base-xenial' } + docker { image 'joinaero/kinetic-ros-opencv-xenial' } + } + + /* + environment { + // FindOpenCV.cmake + OpenCV_DIR = '/opt/ros/kinetic/share/OpenCV-3.3.1-dev' + } + */ + + stages { + stage('Prepare') { + steps { + echo "WORKSPACE: ${env.WORKSPACE}" + echo 'apt-get ..' + sh 'apt-get update' + } + } + stage('Init') { + 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 '. /opt/ros/kinetic/setup.sh; make build' + } + } + stage('Install') { + steps { + echo 'make install ..' + sh '. /opt/ros/kinetic/setup.sh; make install SUDO=' + } + } + stage('Test') { + steps { + echo 'make test ..' + sh '. /opt/ros/kinetic/setup.sh; make test SUDO=' + } + } + stage('Samples') { + steps { + echo 'make samples ..' + sh '. /opt/ros/kinetic/setup.sh; make samples SUDO=' + } + } + stage('Tools') { + steps { + echo 'make tools ..' + 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= + ''' + } + } + /* + 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-ci@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' + } + } +} diff --git a/Makefile b/Makefile index 974617f..fc7c86d 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: @@ -35,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" @@ -49,7 +52,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 @@ -76,7 +80,7 @@ submodules: init: submodules @$(call echo,Make $@) - @$(SH) ./scripts/init.sh + @$(SH) ./scripts/init.sh $(INIT_OPTIONS) .PHONY: init @@ -123,11 +127,26 @@ else @cd ./_build; make install endif else - @cd ./_build; sudo make install +ifeq ($(HOST_OS),Linux) + @cd ./_build; $(SUDO) make install +else + @cd ./_build; make install +endif 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 @@ -144,14 +163,30 @@ tools: install .PHONY: tools +# pkg + +pkg: clean + @$(call echo,Make $@) +ifeq ($(HOST_OS),Win) + @$(SH) ./scripts/win/winpack.sh "$(PKGNAME)" +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") +ifeq ($(HOST_OS),Linux) + @cd ./wrappers/ros && catkin_make -DCMAKE_BUILD_TYPE=$(BUILD_TYPE) else - @cd ./wrappers/ros && catkin_make + $(error "Can't make ros on $(HOST_OS)") endif .PHONY: ros @@ -260,6 +295,7 @@ host: @echo BUILD: $(BUILD) @echo LDD: $(LDD) @echo CMAKE: $(CMAKE) + @echo PKGNAME: $(PKGNAME) .PHONY: host diff --git a/README.md b/README.md index 762044c..85235c1 100644 --- a/README.md +++ b/README.md @@ -1,10 +1,10 @@ -# MYNT® EYE SDK +# MYNT® EYE S 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%20S%20SDK-2.2.2--rc0-brightgreen.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK) ## Overview -MYNT® EYE SDK 2.0 is a cross-platform library for MYNT® EYE cameras. +MYNT® EYE S SDK is a cross-platform library for MYNT® EYE Standard cameras. The following platforms have been tested: @@ -16,13 +16,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/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/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) - +* [API Doc](https://github.com/slightech/MYNT-EYE-S-SDK/releases): API reference, some guides and data spec. + * en: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2562294/mynt-eye-s-sdk-apidoc-2.2.2-rc0-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2562296/mynt-eye-s-sdk-apidoc-2.2.2-rc0-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-S-SDK/) + * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2562297/mynt-eye-s-sdk-apidoc-2.2.2-rc0-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK/files/2562298/mynt-eye-s-sdk-apidoc-2.2.2-rc0-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/api/mynt-eye-s-sdk-apidoc-2.2.2-rc0-zh-Hans/mynt-eye-s-sdk-apidoc-2.2.2-rc0-zh-Hans/index.html) +* [Guide Doc](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/releases): How to install and start using the SDK. + * en: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2562348/mynt-eye-s-sdk-guide-2.2.2-rc0-en.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2562352/mynt-eye-s-sdk-guide-2.2.2-rc0-en.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-S-SDK-Guide/) + * zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2562353/mynt-eye-s-sdk-guide-2.2.2-rc0-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2562356/mynt-eye-s-sdk-guide-2.2.2-rc0-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](http://doc.myntai.com/resource/sdk/mynt-eye-s-sdk-guide-2.2.2-rc0-zh-Hans/mynt-eye-s-sdk-guide-2.2.2-rc0-zh-Hans/index.html) > Supported languages: `en`, `zh-Hans`. @@ -30,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.2`. ## Usage @@ -62,8 +61,8 @@ make samples ## Mirrors -国内镜像:[码云](https://gitee.com/mynt/MYNT-EYE-SDK-2)。 +国内镜像:[码云](https://gitee.com/mynt/MYNT-EYE-S-SDK)。 ## License -This project is licensed under the Apache License, Version 2.0. Copyright 2018 Slightech Co., Ltd. +This project is licensed under the [Apache License, Version 2.0](LICENSE). Copyright 2018 Slightech Co., Ltd. diff --git a/cmake/Common.cmake b/cmake/Common.cmake index ab14b08..8526d9a 100755 --- a/cmake/Common.cmake +++ b/cmake/Common.cmake @@ -70,7 +70,9 @@ macro(set_outdir ARCHIVE_OUTPUT_DIRECTORY LIBRARY_OUTPUT_DIRECTORY RUNTIME_OUTPU endforeach() endmacro() -set(__exe2bat_relative_path false) +if(NOT __exe2bat_relative_path) + set(__exe2bat_relative_path false) +endif() macro(exe2bat exe_name exe_dir dll_search_paths) message(STATUS "Generating ${exe_name}.bat") diff --git a/cmake/DetectOpenCV.cmake b/cmake/DetectOpenCV.cmake index 4673876..e82e546 100644 --- a/cmake/DetectOpenCV.cmake +++ b/cmake/DetectOpenCV.cmake @@ -15,14 +15,25 @@ 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) +if(OpenCV_FIND_QUIET) + find_package(OpenCV QUIET) else() - add_definitions(-DUSE_OPENCV4) + find_package(OpenCV REQUIRED) +endif() + +if(OpenCV_FOUND) + +#message(STATUS "Found OpenCV: ${OpenCV_VERSION}") + +set(WITH_OPENCV TRUE) +add_definitions(-DWITH_OPENCV) + +if(OpenCV_VERSION VERSION_LESS 3.0) + add_definitions(-DWITH_OPENCV2) +elseif(OpenCV_VERSION VERSION_LESS 4.0) + add_definitions(-DWITH_OPENCV3) +else() + add_definitions(-DWITH_OPENCV4) endif() list(FIND OpenCV_LIBS "opencv_world" __index) @@ -35,3 +46,9 @@ if(MSVC OR MSYS OR MINGW) else() set(OpenCV_LIB_SEARCH_PATH "${OpenCV_LIB_PATH}") endif() + +else() + +set(WITH_OPENCV FALSE) + +endif() 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/doc/build.sh b/doc/build.sh index c2f368c..5160c61 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-s-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"; \ + filename="mynt-eye-s-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 c4dcd32..9f69ae2 100644 --- a/doc/en/api.doxyfile +++ b/doc/en/api.doxyfile @@ -32,19 +32,19 @@ DOXYFILE_ENCODING = UTF-8 # title of most generated pages and in a few other places. # The default value is: My Project. -PROJECT_NAME = "MYNT EYE SDK" +PROJECT_NAME = "MYNT EYE S SDK" # 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 = 2.0.1-rc1 +PROJECT_NUMBER = 2.2.2-rc0 # 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 = http://www.myntai.com/camera +PROJECT_BRIEF = http://www.myntai.com/mynteye/standard # With the PROJECT_LOGO tag one can specify a logo or an icon that is included # in the documentation. The maximum height of the logo should not exceed 55 @@ -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 @@ -1309,7 +1310,7 @@ DOCSET_PUBLISHER_ID = com.slightech.mynteye.documentation # The default value is: Publisher. # This tag requires that the tag GENERATE_DOCSET is set to YES. -DOCSET_PUBLISHER_NAME = MYNT EYE SDK +DOCSET_PUBLISHER_NAME = MYNT EYE S SDK # 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 diff --git a/doc/en/mainpage.md b/doc/en/mainpage.md index 487ef06..47a2dda 100644 --- a/doc/en/mainpage.md +++ b/doc/en/mainpage.md @@ -1,4 +1,4 @@ -# MYNT EYE SDK {#mainpage} +# MYNT EYE S SDK {#mainpage} * API Classes * API Modules diff --git a/doc/en/spec_control_api.md b/doc/en/spec_control_api.md index 46d2366..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} | +| 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 ac8ccb5..a30690b 100644 --- a/doc/zh-Hans/api.doxyfile +++ b/doc/zh-Hans/api.doxyfile @@ -32,19 +32,19 @@ DOXYFILE_ENCODING = UTF-8 # title of most generated pages and in a few other places. # The default value is: My Project. -PROJECT_NAME = "MYNT EYE SDK" +PROJECT_NAME = "MYNT EYE S SDK" # 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 = 2.0.1-rc1 +PROJECT_NUMBER = 2.2.2-rc0 # 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 = http://www.myntai.com/camera +PROJECT_BRIEF = http://www.myntai.com/mynteye/standard # With the PROJECT_LOGO tag one can specify a logo or an icon that is included # in the documentation. The maximum height of the logo should not exceed 55 @@ -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 @@ -1309,7 +1310,7 @@ DOCSET_PUBLISHER_ID = com.slightech.mynteye.documentation # The default value is: Publisher. # This tag requires that the tag GENERATE_DOCSET is set to YES. -DOCSET_PUBLISHER_NAME = MYNT EYE SDK +DOCSET_PUBLISHER_NAME = MYNT EYE S SDK # 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 diff --git a/doc/zh-Hans/guide_build_linux.md b/doc/zh-Hans/guide_build_linux.md index a1bbda0..8e2bc38 100644 --- a/doc/zh-Hans/guide_build_linux.md +++ b/doc/zh-Hans/guide_build_linux.md @@ -5,13 +5,13 @@ ## 获取代码 ```bash -git clone https://github.com/slightech/MYNT-EYE-SDK-2.git +git clone https://github.com/slightech/MYNT-EYE-S-SDK.git ``` ## 准备依赖 ```bash -cd mynt-eye-sdk-2/ +cd mynt-eye-s-sdk/ make init ``` diff --git a/doc/zh-Hans/guide_build_win.md b/doc/zh-Hans/guide_build_win.md index 8f7a279..30370bc 100644 --- a/doc/zh-Hans/guide_build_win.md +++ b/doc/zh-Hans/guide_build_win.md @@ -72,13 +72,13 @@ GNU Make 4.2.1 ## 获取代码 ```cmd ->git clone https://github.com/slightech/MYNT-EYE-SDK-2.git +>git clone https://github.com/slightech/MYNT-EYE-S-SDK.git ``` ## 准备依赖 ```cmd ->cd mynt-eye-sdk-2 +>cd mynt-eye-s-sdk >make init Make init Init deps diff --git a/doc/zh-Hans/mainpage.md b/doc/zh-Hans/mainpage.md index 3097ef4..6b45b5a 100644 --- a/doc/zh-Hans/mainpage.md +++ b/doc/zh-Hans/mainpage.md @@ -1,4 +1,4 @@ -# MYNT EYE SDK {#mainpage} +# MYNT EYE S SDK {#mainpage} * API 类 * API 模块 diff --git a/doc/zh-Hans/spec_control_api.md b/doc/zh-Hans/spec_control_api.md index 9c3bea1..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} | +| 图像帧率 | 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 | 开始自动曝光,可设定的阈值 | 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 a7f0ff8..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" @@ -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) { @@ -280,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 66% rename from src/api/processor/object.h rename to include/mynteye/api/object.h index 808b150..5dd6d82 100644 --- a/src/api/processor/object.h +++ b/include/mynteye/api/object.h @@ -11,18 +11,20 @@ // 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 +struct ImgData; + /** * Input & output object. */ @@ -56,14 +58,22 @@ 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, + const std::shared_ptr &data) + : value(value), id(id), data(data) {} /** The value */ cv::Mat value; + /** The id **/ + std::uint16_t id; + /** The data **/ + std::shared_ptr data; Object *Clone() const { ObjMat *mat = new ObjMat; mat->value = value.clone(); + mat->id = id; + mat->data = data; return mat; } @@ -77,19 +87,35 @@ 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 std::shared_ptr &first_data, + const cv::Mat &second, std::uint16_t second_id, + const std::shared_ptr &second_data) + : first(first), first_id(first_id), first_data(first_data), + second(second), second_id(second_id), second_data(second_data) {} /** The first value */ cv::Mat first; + /** The first id **/ + std::uint16_t first_id; + /** The first data **/ + std::shared_ptr first_data; /** The second value */ cv::Mat second; + /** The second id **/ + std::uint16_t second_id; + /** The second data **/ + std::shared_ptr second_data; Object *Clone() const { ObjMat2 *mat2 = new ObjMat2; mat2->first = first.clone(); + mat2->first_id = first_id; + mat2->first_data = first_data; mat2->second = second.clone(); + mat2->second_id = second_id; + mat2->second_data = second_data; return mat2; } @@ -100,4 +126,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 89% rename from src/api/plugin.h rename to include/mynteye/api/plugin.h index 325f6bf..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 @@ -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; } @@ -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 94% rename from include/mynteye/callbacks.h rename to include/mynteye/device/callbacks.h index d1f2c0c..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 @@ -113,6 +113,8 @@ struct MYNTEYE_API StreamData { std::shared_ptr img; /** Frame. */ std::shared_ptr frame; + /** Frame ID. */ + std::uint16_t frame_id; }; /** @@ -131,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 96% rename from src/device/device.h rename to include/mynteye/device/device.h index 6d11cd2..11ee2fb 100644 --- a/src/device/device.h +++ b/include/mynteye/device/device.h @@ -11,20 +11,19 @@ // 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 #include #include #include #include #include -#include "mynteye/callbacks.h" #include "mynteye/mynteye.h" #include "mynteye/types.h" +#include "mynteye/device/callbacks.h" MYNTEYE_BEGIN_NAMESPACE @@ -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. */ @@ -322,4 +324,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 82% rename from include/mynteye/utils.h rename to include/mynteye/device/utils.h index 8f210f7..0b64ce1 100644 --- a/include/mynteye/utils.h +++ b/include/mynteye/device/utils.h @@ -11,11 +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. -#ifndef MYNTEYE_UTILS_H_ // NOLINT -#define MYNTEYE_UTILS_H_ +#ifndef MYNTEYE_DEVICE_UTILS_H_ +#define MYNTEYE_DEVICE_UTILS_H_ #pragma once #include +#include #include "mynteye/mynteye.h" @@ -55,8 +56,22 @@ namespace utils { MYNTEYE_API float get_real_exposure_time( std::int32_t frame_rate, std::uint16_t exposure_time); +/** + * @ingroup utils + * + * Get sdk root dir. + */ +MYNTEYE_API std::string get_sdk_root_dir(); + +/** + * @ingroup utils + * + * Get sdk install dir. + */ +MYNTEYE_API std::string get_sdk_install_dir(); + } // namespace utils MYNTEYE_END_NAMESPACE -#endif // MYNTEYE_UTILS_H_ NOLINT +#endif // MYNTEYE_DEVICE_UTILS_H_ 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..02d377a 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: @@ -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,34 +100,48 @@ #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] --------------------------------- +#include "mynteye/mynteye.h" + +#ifdef MYNTEYE_OS_ANDROID +# include +#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; +#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, @@ -149,9 +155,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. } @@ -174,20 +183,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"; -#ifdef ANDROID +#ifdef MYNTEYE_OS_ANDROID static const int android_log_levels[] = { ANDROID_LOG_FATAL, // LOG(FATAL) ANDROID_LOG_ERROR, // LOG(ERROR) @@ -213,34 +222,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(); @@ -258,23 +242,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()); } } @@ -291,8 +268,8 @@ class CERES_EXPORT 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 { @@ -302,34 +279,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_; @@ -343,18 +305,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)) @@ -362,23 +325,46 @@ 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 -# 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 -// 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 + +#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 @@ -392,8 +378,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 --------------------------------- @@ -416,7 +401,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 @@ -427,15 +412,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, ==) @@ -444,8 +420,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, ==) @@ -454,8 +428,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 --------------------------- @@ -494,42 +466,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/include/mynteye/mynteye.h.in b/include/mynteye/mynteye.h.in index c2c8eff..ee58cdf 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 @@ -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) @@ -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/include/mynteye/types.h b/include/mynteye/types.h index 51a8e40..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 @@ -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, /** @@ -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 266973a..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 @@ -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; @@ -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/platforms/projects/vs2017/README.md b/platforms/projects/vs2017/README.md new file mode 100644 index 0000000..982839b --- /dev/null +++ b/platforms/projects/vs2017/README.md @@ -0,0 +1,76 @@ +# How to use MYNT® EYE S SDK with Visual Studio 2017 + +This tutorial will create a project with Visual Studio 2017 to start using MYNT® EYE S SDK. + +## Preparation + +Install the win pack of MYNT® EYE S SDK. + +## Create Project + +Open Visual Studio 2017, then `File > New > Project`, + +![](images/1_new_pro.png) + +Select "Windows Console Application", set the project's name and location, click "OK", + +![](images/2_new_pro.png) + +Finally, you will see the new project like this, + +![](images/3_new_pro.png) + +## Config Properties + +Right click the project, and open its "Properties" window, + +![](images/4_config.png) + +Change "Configuration" to "All Configurations", then add the following paths to "Additional Include Directories", + +```bash +$(MYNTEYES_SDK_ROOT)\include +$(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\include +``` + +![](images/5_config_include.png) + +Add the following paths to "Additional Library Directories", + +```bash +$(MYNTEYES_SDK_ROOT)\lib +$(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\x64\vc15\lib +``` + +![](images/6_config_lib_dir.png) + + +Add the following libs to "Additional Dependencies", + +```bash +mynteye.lib +opencv_world343.lib +``` + +![](images/7_config_lib.png) + +If you wanna debug, could change "Configuration" to "Debug" and add these debug libs, + +```bash +mynteyed.lib +opencv_world343d.lib +``` + +![](images/8_config_debug_lib.png) + +## Start using SDK + +Include the headers of SDK and start using its APIs, + +![](images/9_run_x64.png) + +Select "Release x64" or "Debug x64" to run the project. + + diff --git a/platforms/projects/vs2017/images/10_path.png b/platforms/projects/vs2017/images/10_path.png new file mode 100644 index 0000000..7254149 Binary files /dev/null and b/platforms/projects/vs2017/images/10_path.png differ diff --git a/platforms/projects/vs2017/images/1_new_pro.png b/platforms/projects/vs2017/images/1_new_pro.png new file mode 100644 index 0000000..2c50214 Binary files /dev/null and b/platforms/projects/vs2017/images/1_new_pro.png differ diff --git a/platforms/projects/vs2017/images/2_new_pro.png b/platforms/projects/vs2017/images/2_new_pro.png new file mode 100644 index 0000000..f46d196 Binary files /dev/null and b/platforms/projects/vs2017/images/2_new_pro.png differ diff --git a/platforms/projects/vs2017/images/3_new_pro.png b/platforms/projects/vs2017/images/3_new_pro.png new file mode 100644 index 0000000..8e80228 Binary files /dev/null and b/platforms/projects/vs2017/images/3_new_pro.png differ diff --git a/platforms/projects/vs2017/images/4_config.png b/platforms/projects/vs2017/images/4_config.png new file mode 100644 index 0000000..29f4a9c Binary files /dev/null and b/platforms/projects/vs2017/images/4_config.png differ diff --git a/platforms/projects/vs2017/images/5_config_include.png b/platforms/projects/vs2017/images/5_config_include.png new file mode 100644 index 0000000..9a8aa35 Binary files /dev/null and b/platforms/projects/vs2017/images/5_config_include.png differ diff --git a/platforms/projects/vs2017/images/6_config_lib_dir.png b/platforms/projects/vs2017/images/6_config_lib_dir.png new file mode 100644 index 0000000..b9518ba Binary files /dev/null and b/platforms/projects/vs2017/images/6_config_lib_dir.png differ diff --git a/platforms/projects/vs2017/images/7_config_lib.png b/platforms/projects/vs2017/images/7_config_lib.png new file mode 100644 index 0000000..1336081 Binary files /dev/null and b/platforms/projects/vs2017/images/7_config_lib.png differ diff --git a/platforms/projects/vs2017/images/8_config_debug_lib.png b/platforms/projects/vs2017/images/8_config_debug_lib.png new file mode 100644 index 0000000..f4ec94f Binary files /dev/null and b/platforms/projects/vs2017/images/8_config_debug_lib.png differ diff --git a/platforms/projects/vs2017/images/9_run_x64.png b/platforms/projects/vs2017/images/9_run_x64.png new file mode 100644 index 0000000..9ff0e51 Binary files /dev/null and b/platforms/projects/vs2017/images/9_run_x64.png differ diff --git a/platforms/projects/vs2017/mynteyes_demo/.gitignore b/platforms/projects/vs2017/mynteyes_demo/.gitignore new file mode 100644 index 0000000..9d0a5a9 --- /dev/null +++ b/platforms/projects/vs2017/mynteyes_demo/.gitignore @@ -0,0 +1,4 @@ +/.vs/ +/x64/ +/mynteyes_demo/x64/ +/mynteyes_demo/*.user diff --git a/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo.sln b/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo.sln new file mode 100644 index 0000000..9a23cf5 --- /dev/null +++ b/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo.sln @@ -0,0 +1,31 @@ + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Visual Studio 15 +VisualStudioVersion = 15.0.27703.2018 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "mynteyes_demo", "mynteyes_demo\mynteyes_demo.vcxproj", "{49798F84-3EA3-4CB5-A873-6163DB4B4A43}" +EndProject +Global + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|x64 = Debug|x64 + Debug|x86 = Debug|x86 + Release|x64 = Release|x64 + Release|x86 = Release|x86 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {49798F84-3EA3-4CB5-A873-6163DB4B4A43}.Debug|x64.ActiveCfg = Debug|x64 + {49798F84-3EA3-4CB5-A873-6163DB4B4A43}.Debug|x64.Build.0 = Debug|x64 + {49798F84-3EA3-4CB5-A873-6163DB4B4A43}.Debug|x86.ActiveCfg = Debug|Win32 + {49798F84-3EA3-4CB5-A873-6163DB4B4A43}.Debug|x86.Build.0 = Debug|Win32 + {49798F84-3EA3-4CB5-A873-6163DB4B4A43}.Release|x64.ActiveCfg = Release|x64 + {49798F84-3EA3-4CB5-A873-6163DB4B4A43}.Release|x64.Build.0 = Release|x64 + {49798F84-3EA3-4CB5-A873-6163DB4B4A43}.Release|x86.ActiveCfg = Release|Win32 + {49798F84-3EA3-4CB5-A873-6163DB4B4A43}.Release|x86.Build.0 = Release|Win32 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection + GlobalSection(ExtensibilityGlobals) = postSolution + SolutionGuid = {F6C50224-4EC6-46EB-AA63-7E32FC6F0648} + EndGlobalSection +EndGlobal diff --git a/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/mynteyes_demo.cpp b/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/mynteyes_demo.cpp new file mode 100644 index 0000000..02233b7 Binary files /dev/null and b/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/mynteyes_demo.cpp differ diff --git a/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/mynteyes_demo.vcxproj b/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/mynteyes_demo.vcxproj new file mode 100644 index 0000000..9ad85b5 --- /dev/null +++ b/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/mynteyes_demo.vcxproj @@ -0,0 +1,177 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + 15.0 + {49798F84-3EA3-4CB5-A873-6163DB4B4A43} + Win32Proj + mynteyesdemo + 10.0.17134.0 + + + + Application + true + v141 + Unicode + + + Application + false + v141 + true + Unicode + + + Application + true + v141 + Unicode + + + Application + false + v141 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + + + true + + + false + + + false + + + + Use + Level3 + Disabled + true + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + $(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\include;$(MYNTEYES_SDK_ROOT)\include;%(AdditionalIncludeDirectories) + + + Console + true + $(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\x64\vc15\lib;$(MYNTEYES_SDK_ROOT)\lib;%(AdditionalLibraryDirectories) + mynteyed.lib;opencv_world343d.lib;%(AdditionalDependencies) + + + + + Use + Level3 + Disabled + true + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + $(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\include;$(MYNTEYES_SDK_ROOT)\include;%(AdditionalIncludeDirectories) + + + Console + true + $(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\x64\vc15\lib;$(MYNTEYES_SDK_ROOT)\lib;%(AdditionalLibraryDirectories) + mynteyed.lib;opencv_world343d.lib;%(AdditionalDependencies) + + + + + Use + Level3 + MaxSpeed + true + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + $(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\include;$(MYNTEYES_SDK_ROOT)\include;%(AdditionalIncludeDirectories) + + + Console + true + true + true + $(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\x64\vc15\lib;$(MYNTEYES_SDK_ROOT)\lib;%(AdditionalLibraryDirectories) + mynteye.lib;opencv_world343.lib;%(AdditionalDependencies) + + + + + Use + Level3 + MaxSpeed + true + true + true + NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + $(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\include;$(MYNTEYES_SDK_ROOT)\include;%(AdditionalIncludeDirectories) + + + Console + true + true + true + $(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\x64\vc15\lib;$(MYNTEYES_SDK_ROOT)\lib;%(AdditionalLibraryDirectories) + mynteye.lib;opencv_world343.lib;%(AdditionalDependencies) + + + + + + + + + + Create + Create + Create + Create + + + + + + \ No newline at end of file diff --git a/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/mynteyes_demo.vcxproj.filters b/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/mynteyes_demo.vcxproj.filters new file mode 100644 index 0000000..182978b --- /dev/null +++ b/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/mynteyes_demo.vcxproj.filters @@ -0,0 +1,33 @@ + + + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;ipp;xsd + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + + + Header Files + + + Header Files + + + + + Source Files + + + Source Files + + + \ No newline at end of file diff --git a/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/stdafx.cpp b/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/stdafx.cpp new file mode 100644 index 0000000..d289662 Binary files /dev/null and b/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/stdafx.cpp differ diff --git a/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/stdafx.h b/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/stdafx.h new file mode 100644 index 0000000..94d4ed8 Binary files /dev/null and b/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/stdafx.h differ diff --git a/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/targetver.h b/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/targetver.h new file mode 100644 index 0000000..567cd34 Binary files /dev/null and b/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/targetver.h differ diff --git a/platforms/win/README.txt b/platforms/win/README.txt new file mode 100644 index 0000000..7969b73 --- /dev/null +++ b/platforms/win/README.txt @@ -0,0 +1,176 @@ +# MYNT® EYE S SDK + +################################################################################ +Language: 简体中文 +################################################################################ + +## 如何开始使用 SDK + +1) 运行样例程序 + +安装完 SDK 的 exe 安装包后,桌面会生成 SDK 根目录的快捷方式。 + +进入 "\bin\samples\tutorials" 目录,双击 "get_stereo.exe" 运行,即可看到双目实时画面。 + +2)生成样例工程 + +首先,安装好 Visual Studio 2017 和 CMake 。 + +接着,进入 "\samples" 目录, 双击 "generate.bat" 即可生成样例工程。 + +p.s. 样例教程,可见 https://slightech.github.io/MYNT-EYE-S-SDK/ 主页给出的 Guide 文档。 + +p.p.s. 运行结果,参考下方英文内容。 + +3)如何于 Visual Studio 2017 下使用 SDK + +进入 "\projects\vs2017" ,见 "README.md" 说明。 + +################################################################################ +Language: English +################################################################################ + +## How to start using SDK + +1) Run the prebuilt samples, ensure the SDK works well. + +After you install the win pack of SDK, there will be a shortcut to the SDK root directory on your desktop. + +First, you should plug the MYNT® EYE camera in a USB 3.0 port. + +Second, goto the "\bin\samples\tutorials" directory and click "get_stereo.exe" to run. + +Finally, you will see the window that display the realtime frame of the camera. + +2) Generate samples project of Visual Studio 2017. + +First, you should install Visual Studio 2017 and CMake . + +Second, goto the "\samples" directory and click "generate.bat" to run. + +Finally, you could click `_build\mynteye_samples.sln` to open the samples project. + +p.s. The tutorials of samples are here: https://slightech.github.io/MYNT-EYE-S-SDK-Guide/src/data/contents.html. + +p.p.s. The example result of "generate.bat", + +```cmd +-- The C compiler identification is MSVC 19.14.26429.4 +-- The CXX compiler identification is MSVC 19.14.26429.4 +-- Check for working C compiler: C:/Program Files (x86)/Microsoft Visual Studio/2017/Community/VC/Tools/MSVC/14.14.26428/bin/Hostx86/x64/cl.exe +-- Check for working C compiler: C:/Program Files (x86)/Microsoft Visual Studio/2017/Community/VC/Tools/MSVC/14.14.26428/bin/Hostx86/x64/cl.exe -- works +-- Detecting C compiler ABI info +-- Detecting C compiler ABI info - done +-- Check for working CXX compiler: C:/Program Files (x86)/Microsoft Visual Studio/2017/Community/VC/Tools/MSVC/14.14.26428/bin/Hostx86/x64/cl.exe +-- Check for working CXX compiler: C:/Program Files (x86)/Microsoft Visual Studio/2017/Community/VC/Tools/MSVC/14.14.26428/bin/Hostx86/x64/cl.exe -- works +-- Detecting CXX compiler ABI info +-- Detecting CXX compiler ABI info - done +-- Detecting CXX compile features +-- Detecting CXX compile features - done +-- HOST_ARCH: x86_64 +-- OpenCV ARCH: x64 +-- OpenCV RUNTIME: vc15 +-- OpenCV STATIC: OFF +-- Found OpenCV: C:/Users/John/AppData/Roaming/Slightech/MYNTEYES/SDK/2.2.1/3rdparty/opencv/build (found version "3.4.3") +-- Found OpenCV 3.4.3 in C:/Users/John/AppData/Roaming/Slightech/MYNTEYES/SDK/2.2.1/3rdparty/opencv/build/x64/vc15/lib +-- You might need to add C:\Users\John\AppData\Roaming\Slightech\MYNTEYES\SDK\2.2.1\3rdparty\opencv\build\x64\vc15\bin to your PATH to be able to run your applications. +-- Found OpenCV: 3.4.3 +CMake Warning at C:/Program Files/CMake/share/cmake-3.10/Modules/FindBoost.cmake:567 (message): + Imported targets and dependency information not available for Boost version + (all versions older than 1.33) +Call Stack (most recent call first): + C:/Program Files/CMake/share/cmake-3.10/Modules/FindBoost.cmake:907 (_Boost_COMPONENT_DEPENDENCIES) + C:/Program Files/CMake/share/cmake-3.10/Modules/FindBoost.cmake:1542 (_Boost_MISSING_DEPENDENCIES) + C:/Users/John/AppData/Roaming/Slightech/MYNTEYES/SDK/2.2.1/cmake/Option.cmake:47 (find_package) + CMakeLists.txt:26 (include) + + +-- Could NOT find Boost +-- +-- Platform: +-- HOST_OS: Win +-- HOST_NAME: Win +-- HOST_ARCH: x86_64 +-- HOST_COMPILER: MSVC +-- COMPILER_VERSION: 19.14.26429.4 +-- COMPILER_VERSION_MAJOR: 19 +-- COMPILER_VERSION_MINOR: 14 +-- COMPILER_VERSION_PATCH: 26429 +-- COMPILER_VERSION_TWEAK: 4 +-- CUDA_VERSION: 9.2 +-- CUDA_VERSION_MAJOR: 9 +-- CUDA_VERSION_MINOR: 2 +-- CUDA_VERSION_STRING: 9.2 +-- OpenCV_VERSION: 3.4.3 +-- OpenCV_VERSION_MAJOR: 3 +-- OpenCV_VERSION_MINOR: 4 +-- OpenCV_VERSION_PATCH: 3 +-- OpenCV_VERSION_TWEAK: 0 +-- OpenCV_VERSION_STATUS: +-- OpenCV_WITH_WORLD: TRUE +-- +-- Options: +-- WITH_API: ON +-- OpenCV: YES +-- OpenCV_VERSION: 3.4.3 +-- OpenCV_WORLD: YES +-- WITH_DEVICE_INFO_REQUIRED: ON +-- WITH_BOOST: ON +-- Boost: NO +-- WITH_GLOG: OFF +-- +-- Features: +-- Filesystem: native +-- +-- Visual Studio >= 2010, MSVC >= 10.0 +-- C_FLAGS: /DWIN32 /D_WINDOWS /W3 -Wall -march=native +-- CXX_FLAGS: /DWIN32 /D_WINDOWS /W3 /GR /EHsc -Wall -march=native +-- Found mynteye: 2.2.1 +-- Generating camera_a.bat +-- Generating get_depth_with_region.bat +-- Generating camera_d.bat +-- Generating camera_u.bat +CMake Warning at tutorials/CMakeLists.txt:70 (find_package): + By not providing "FindPCL.cmake" in CMAKE_MODULE_PATH this project has + asked CMake to find a package configuration file provided by "PCL", but + CMake did not find one. + + Could not find a package configuration file provided by "PCL" with any of + the following names: + + PCLConfig.cmake + pcl-config.cmake + + Add the installation prefix of "PCL" to CMAKE_PREFIX_PATH or set "PCL_DIR" + to a directory containing one of the above files. If "PCL" provides a + separate development package or SDK, be sure it has been installed. + + +CMake Warning at tutorials/CMakeLists.txt:86 (message): + PCL not found :( + + +-- Generating get_device_info.bat +-- Generating get_img_params.bat +-- Generating get_imu_params.bat +-- Generating get_stereo.bat +-- Generating get_stereo_rectified.bat +-- Generating get_disparity.bat +-- Generating get_depth.bat +-- Generating get_imu.bat +-- Generating get_from_callbacks.bat +-- Generating get_with_plugin.bat +-- Generating ctrl_framerate.bat +-- Generating ctrl_auto_exposure.bat +-- Generating ctrl_manual_exposure.bat +-- Generating ctrl_infrared.bat +-- Generating get_all_device_info.bat +-- Configuring done +-- Generating done +-- Build files have been written to: C:/Users/John/AppData/Roaming/Slightech/MYNTEYES/SDK/2.2.1/samples/_build +Press any key to continue . . . +``` + +3) Start using MYNT® EYE S SDK with Visual Studio 2017 + +Goto the "\projects\vs2017", see the "README.md". 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 5a1091b..560b279 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 { @@ -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"; @@ -184,7 +184,7 @@ int main(int argc, char *argv[]) { // Show disparity instead of depth, but show depth values in region. auto &&depth_frame = disp_data.frame; -#ifdef USE_OPENCV3 +#ifdef WITH_OPENCV3 // ColormapTypes // http://docs.opencv.org/master/d3/d50/group__imgproc__colormap.html#ga9a805d8262bcbe273f16be9ea2055a65 cv::applyColorMap(depth_frame, depth_frame, cv::COLORMAP_JET); 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 6a16a19..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 @@ -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/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 d38b7ae..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" @@ -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/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 03391f5..5761c62 100644 --- a/samples/tutorials/intermediate/get_depth_and_points.cc +++ b/samples/tutorials/intermediate/get_depth_and_points.cc @@ -14,7 +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" @@ -32,7 +33,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 +165,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"; @@ -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); @@ -193,7 +196,7 @@ int main(int argc, char *argv[]) { // Show disparity instead of depth, but show depth values in region. auto &&depth_frame = disp_data.frame; -#ifdef USE_OPENCV3 +#ifdef WITH_OPENCV3 // ColormapTypes // http://docs.opencv.org/master/d3/d50/group__imgproc__colormap.html#ga9a805d8262bcbe273f16be9ea2055a65 cv::applyColorMap(depth_frame, depth_frame, cv::COLORMAP_JET); @@ -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/samples/tutorials/util/cv_painter.cc b/samples/tutorials/util/cv_painter.cc index eaa7d8a..d5344b5 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 @@ -178,7 +178,7 @@ cv::Rect CVPainter::DrawText( y += offset_y; cv::Point org(x, y); -#ifdef USE_OPENCV2 +#ifdef WITH_OPENCV2 cv::putText( const_cast(img), text, org, FONT_FACE, FONT_SCALE, FONT_COLOR, THICKNESS); 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 4b36b44..2a92930 100644 --- a/samples/uvc/camera.cc +++ b/samples/uvc/camera.cc @@ -11,19 +11,19 @@ // 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" -#include "uvc/uvc.h" +#include "mynteye/uvc/uvc.h" struct frame { const void *data = nullptr; @@ -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/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/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 diff --git a/scripts/version.sh b/scripts/version.sh new file mode 100755 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/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/generate.bat b/scripts/win/generate.bat new file mode 100644 index 0000000..71d5e8d --- /dev/null +++ b/scripts/win/generate.bat @@ -0,0 +1,20 @@ +@echo off +setlocal +set _MY_DIR=%~dp0 + +set _VS_GEN="Visual Studio 15 2017 Win64" +REM set _VS_GEN="Visual Studio 14 2015 Win64" + +cd %_MY_DIR% + +mkdir _build +cd _build/ + +cmake -DCMAKE_BUILD_TYPE=Release ^ +-DCMAKE_PREFIX_PATH="%_MY_DIR%/../lib/cmake" ^ +-DOpenCV_DIR="%_MY_DIR%/../3rdparty/opencv/build" ^ +-G %_VS_GEN% ^ +.. + +cd %_MY_DIR% +pause 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 0000000..f4d3c39 Binary files /dev/null and b/scripts/win/nsis/mynt.ico differ diff --git a/scripts/win/nsis/winpack.nsi.in b/scripts/win/nsis/winpack.nsi.in new file mode 100644 index 0000000..b70cd3d --- /dev/null +++ b/scripts/win/nsis/winpack.nsi.in @@ -0,0 +1,198 @@ +; 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-opencv-${OpenCV_VERSION}\*" + + ; 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 MYNTEYES README.txt" \ + "cmd.exe /c start /max notepad.exe $INSTDIR\README.txt" + + 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 new file mode 100644 index 0000000..e081ac9 --- /dev/null +++ b/scripts/win/winpack.sh @@ -0,0 +1,179 @@ +#!/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" + +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_i "RM: $1") +} + +_md() { + [ ! -d "$1" ] && (mkdir -p "$1" && _echo_i "MD: $1") +} + +# _mv_subs [sub1 sub2 ...] +_mv_subs() { + _src_dir="$1"; shift; _dst_dir="$1"; shift; _subs="$@"; + if [ -z "$_subs" ]; then + _subs=`ls $_src_dir` + fi + for _sub in $_subs; do + _src="$_src_dir/$_sub" + [ ! -e "$_src" ] && (_echo_i "Not exist: $_src") && continue + _dst= + [ -f "$_src" ] && _dst="$_dst_dir" + [ -d "$_src" ] && _dst="$_dst_dir/$_sub" + [ -z "$_dst" ] && continue + # _echo "_src: $_src" + # _echo "_dst: $_dst" + mv "$_src" "$_dst" + done +} + +################################################################################ +# build release + +make samples tools + +################################################################################ +# 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" + +################################################################################ +# move to _install + +# 3rdparty/opencv +_md "$ROOT_DIR/_install/3rdparty" +mv "$ROOT_DIR/3rdparty/opencv" "$ROOT_DIR/_install/3rdparty/opencv" + +# cmake +mv "$ROOT_DIR/cmake" "$ROOT_DIR/_install/cmake" + +# samples +mv "$ROOT_DIR/samples/_output/bin" "$ROOT_DIR/_install/bin/samples" +mv "$ROOT_DIR/samples/_output/lib" "$ROOT_DIR/_install/lib/samples" +_rm "$ROOT_DIR/samples/_build" +_rm "$ROOT_DIR/samples/_output" +mv "$ROOT_DIR/samples" "$ROOT_DIR/_install/samples" + +# tools +mv "$ROOT_DIR/tools/_output/bin" "$ROOT_DIR/_install/bin/tools" +mv "$ROOT_DIR/tools/_output/lib" "$ROOT_DIR/_install/lib/tools" +_rm "$ROOT_DIR/tools/_build" +_rm "$ROOT_DIR/tools/_output" +mv "$ROOT_DIR/tools/linter" "$ROOT_DIR/3rdparty/linter" +mv "$ROOT_DIR/tools" "$ROOT_DIR/_install/tools" + +# platforms/win +mv "$ROOT_DIR/platforms/win/README.txt" "$ROOT_DIR/_install" + +_rm "$ROOT_DIR/platforms/projects/vs2017/mynteyes_demo/.vs" +_rm "$ROOT_DIR/platforms/projects/vs2017/mynteyes_demo/x64" +_rm "$ROOT_DIR/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/x64" +_rm "$ROOT_DIR/platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/mynteyes_demo.vcxproj.user" +mv "$ROOT_DIR/platforms/projects" "$ROOT_DIR/_install/projects" + +################################################################################ +# 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/" + +cp -f "$ROOT_DIR/scripts/win/generate.bat" "$ROOT_DIR/_install/samples/" +cp -f "$ROOT_DIR/scripts/win/generate.bat" "$ROOT_DIR/_install/tools/" + +################################################################################ +# archive exe + +source "$ROOT_DIR/pkginfo.sh" +_pkgname="$1-opencv-$OpenCV_VERSION" + +_rm "$ROOT_DIR/$_pkgname.exe" +mv "$ROOT_DIR/_install" "$ROOT_DIR/$_pkgname" + +makensis "$ROOT_DIR/winpack.nsi" + +if _detect_cmd git; then + _git_branch=`git symbolic-ref --short -q HEAD` + if [ "$_git_branch" == "develop" ]; then + _git_hash=`git rev-parse --short HEAD` + mv "$ROOT_DIR/$_pkgname.exe" "$ROOT_DIR/$_pkgname-dev-$_git_hash.exe" + fi +fi + +mv "$ROOT_DIR/$_pkgname" "$ROOT_DIR/_install" + +################################################################################ +# remove from _install + +_rm "$ROOT_DIR/_install/samples/generate.bat" +_rm "$ROOT_DIR/_install/tools/generate.bat" + +################################################################################ +# move back from _install + +# 3rdparty/opencv +mv "$ROOT_DIR/_install/3rdparty/opencv" "$ROOT_DIR/3rdparty/opencv" + +# cmake +mv "$ROOT_DIR/_install/cmake" "$ROOT_DIR/cmake" + +# samples +mv "$ROOT_DIR/_install/samples" "$ROOT_DIR/samples" + +# tools +mv "$ROOT_DIR/_install/tools" "$ROOT_DIR/tools" +mv "$ROOT_DIR/3rdparty/linter" "$ROOT_DIR/tools/linter" + +# platforms/win +mv "$ROOT_DIR/_install/README.txt" "$ROOT_DIR/platforms/win" + +mv "$ROOT_DIR/_install/projects" "$ROOT_DIR/platforms/projects" + +################################################################################ +# clean build + +_rm "$ROOT_DIR/_build" +_rm "$ROOT_DIR/_output" + + +_echo_d "Win pack success" diff --git a/src/api/api.cc b/src/mynteye/api/api.cc similarity index 94% rename from src/api/api.cc rename to src/mynteye/api/api.cc index 8fb98bb..631f014 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,16 +22,15 @@ #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(OS_WIN) +#if defined(MYNTEYE_OS_WIN) #include #endif #endif @@ -68,7 +67,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()); @@ -89,8 +88,8 @@ bool dir_exists(const std::string &p) { #endif 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"); + std::string info_path = utils::get_sdk_install_dir(); + 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()) { @@ -184,16 +183,17 @@ std::vector get_plugin_paths() { } plats.push_back(host_os + "-" + host_arch); - std::vector dirs{MYNTEYE_SDK_ROOT_DIR, MYNTEYE_SDK_INSTALL_DIR}; + std::vector dirs{ + utils::get_sdk_root_dir(), utils::get_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); @@ -226,7 +226,7 @@ API::API(std::shared_ptr device) : device_(device) { "to write the image params. If you update the SDK from " "1.x, the `SN*.conf` is the file contains them. Besides, " "you could also calibrate them by yourself. Read the guide " - "doc (https://github.com/slightech/MYNT-EYE-SDK-2-Guide) " + "doc (https://github.com/slightech/MYNT-EYE-S-SDK-Guide) " "to learn more."; } } diff --git a/src/internal/dl.cc b/src/mynteye/api/dl.cc similarity index 85% rename from src/internal/dl.cc rename to src/mynteye/api/dl.cc index 2de8150..d7559b6 100644 --- a/src/internal/dl.cc +++ b/src/mynteye/api/dl.cc @@ -11,13 +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 "internal/dl.h" +#include "mynteye/api/dl.h" #include "mynteye/logger.h" 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/mynteye/api/dl.h similarity index 83% rename from src/internal/dl.h rename to src/mynteye/api/dl.h index 901608a..be0c05b 100644 --- a/src/internal/dl.h +++ b/src/mynteye/api/dl.h @@ -11,13 +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_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" -#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 *; @@ -66,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 91% rename from src/api/processor/depth_processor.cc rename to src/mynteye/api/processor/depth_processor.cc index 433e47d..aaaf610 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"; @@ -40,12 +40,14 @@ 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()*/]; cv::split(input->value, channels); channels[2].convertTo(output->value, CV_16UC1); + output->id = input->id; + output->data = input->data; return true; } 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 91% rename from src/api/processor/disparity_normalized_processor.cc rename to src/mynteye/api/processor/disparity_normalized_processor.cc index 6c24c6b..9a629e8 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 @@ -44,11 +44,13 @@ 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); // cv::normalize maybe return empty == + output->id = input->id; + output->data = input->data; return !output->value.empty(); } 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 95% rename from src/api/processor/disparity_processor.cc rename to src/mynteye/api/processor/disparity_processor.cc index 041e246..c22232c 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 @@ -29,7 +29,7 @@ DisparityProcessor::DisparityProcessor(std::int32_t proc_period) int sgbmWinSize = 3; int numberOfDisparities = 64; -#ifdef USE_OPENCV2 +#ifdef WITH_OPENCV2 // StereoSGBM // http://docs.opencv.org/2.4/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html?#stereosgbm sgbm_ = cv::Ptr( @@ -74,12 +74,12 @@ 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); cv::Mat disparity; -#ifdef USE_OPENCV2 +#ifdef WITH_OPENCV2 // StereoSGBM::operator() // http://docs.opencv.org/2.4/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html#stereosgbm-operator // Output disparity map. It is a 16-bit signed single-channel image of the @@ -99,6 +99,8 @@ bool DisparityProcessor::OnProcess( sgbm_->compute(input->first, input->second, disparity); #endif output->value = disparity / 16 + 1; + output->id = input->first_id; + output->data = input->first_data; return true; } 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 91% rename from src/api/processor/points_processor.cc rename to src/mynteye/api/processor/points_processor.cc index 02a70b2..7d2b6d4 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 @@ -42,10 +42,12 @@ 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); + output->id = input->id; + output->data = input->data; return true; } 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 92% rename from src/api/processor/rectify_processor.cc rename to src/mynteye/api/processor/rectify_processor.cc index 9a45b0f..9c570f0 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 @@ -49,11 +48,15 @@ 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); cv::remap(input->second, output->second, map21, map22, cv::INTER_LINEAR); + output->first_id = input->first_id; + output->first_data = input->first_data; + output->second_id = input->second_id; + output->second_data = input->second_data; return true; } 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 87% rename from src/api/synthetic.cc rename to src/mynteye/api/synthetic.cc index a1a3730..3c7e298 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 @@ -46,7 +45,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 +164,10 @@ api::StreamData Synthetic::GetStreamData(const Stream &stream) { } if (output != nullptr) { if (stream == Stream::LEFT_RECTIFIED) { - return {nullptr, output->first, nullptr}; + return {output->first_data, output->first, nullptr, output->first_id}; } else { - return {nullptr, output->second, nullptr}; + return {output->second_data, 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 {output->data, 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 {output->data, 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 {output->data, 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 {output->data, output->value, nullptr, output->id}; } VLOG(2) << "Depth not ready now"; } break; @@ -456,7 +456,9 @@ 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, left_data.img, + right_data.frame, right_data.frame_id, right_data.img}); } return; } @@ -471,25 +473,30 @@ void Synthetic::ProcessNativeStream( if (left_rect_data.img && right_rect_data.img && 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}); + processor_, RectifyProcessor::NAME, ObjMat2{ + left_rect_data.frame, left_rect_data.frame_id, left_rect_data.img, + right_rect_data.frame, right_rect_data.frame_id, + right_rect_data.img}); } 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, data.img}); } break; case Stream::DISPARITY_NORMALIZED: { - process_childs( - processor_, DisparityNormalizedProcessor::NAME, ObjMat{data.frame}); + process_childs(processor_, DisparityNormalizedProcessor::NAME, + ObjMat{data.frame, data.frame_id, data.img}); } break; case Stream::POINTS: { - process_childs(processor_, PointsProcessor::NAME, ObjMat{data.frame}); + process_childs(processor_, PointsProcessor::NAME, + ObjMat{data.frame, data.frame_id, data.img}); } break; case Stream::DEPTH: { - process_childs(processor_, DepthProcessor::NAME, ObjMat{data.frame}); + process_childs(processor_, DepthProcessor::NAME, + ObjMat{data.frame, data.frame_id, data.img}); } break; default: break; @@ -498,7 +505,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 +515,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 +524,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 +533,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 +542,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; } @@ -546,18 +553,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}); + {output->first_data, output->first, nullptr, output->first_id}); } if (HasStreamCallback(Stream::RIGHT_RECTIFIED)) { stream_callbacks_.at(Stream::RIGHT_RECTIFIED)( - {nullptr, output->second, nullptr}); + {output->second_data, 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)( + {output->data, output->value, nullptr, output->id}); } } @@ -565,21 +573,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}); + {output->data, 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)( + {output->data, 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)( + {output->data, output->value, nullptr, output->id}); } } 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 98% rename from src/internal/channels.cc rename to src/mynteye/device/channels.cc index 679fe61..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 @@ -224,7 +223,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; @@ -453,7 +452,7 @@ std::size_t from_data( } i += 40; - UNUSED(spec_version) + MYNTEYE_UNUSED(spec_version) return i; } @@ -484,7 +483,7 @@ std::size_t from_data( } i += 24; - UNUSED(spec_version) + MYNTEYE_UNUSED(spec_version) return i; } @@ -505,7 +504,7 @@ std::size_t from_data( } i += 24; - UNUSED(spec_version) + MYNTEYE_UNUSED(spec_version) return i; } @@ -684,7 +683,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 +724,7 @@ std::size_t to_data( } i += 40; - UNUSED(spec_version) + MYNTEYE_UNUSED(spec_version) return i; } @@ -756,7 +755,7 @@ std::size_t to_data( } i += 24; - UNUSED(spec_version) + MYNTEYE_UNUSED(spec_version) return i; } @@ -777,7 +776,7 @@ std::size_t to_data( } i += 24; - UNUSED(spec_version) + MYNTEYE_UNUSED(spec_version) return i; } 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..3a0e1aa 100644 --- a/src/device/device.cc +++ b/src/mynteye/device/device.cc @@ -11,25 +11,25 @@ // 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 +#include #include #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 @@ -416,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); 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 95% rename from src/internal/motions.cc rename to src/mynteye/device/motions.cc index 27d3c67..7a2bcd4 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 @@ -37,7 +36,6 @@ void Motions::SetMotionCallback(motion_callback_t callback) { if (motion_callback_) { channels_->SetImuCallback([this](const ImuPacket &packet) { if (!motion_callback_ && !motion_datas_enabled_) { - LOG(WARNING) << ""; return; } for (auto &&seg : packet.segments) { @@ -58,7 +56,9 @@ void Motions::SetMotionCallback(motion_callback_t callback) { std::lock_guard _(mtx_datas_); motion_data_t data = {imu}; - motion_datas_.push_back(data); + if (motion_datas_enabled_) { + motion_datas_.push_back(data); + } motion_callback_(data); } 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 97% rename from src/internal/streams.cc rename to src/mynteye/device/streams.cc index 1f9fe64..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 @@ -147,10 +146,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 +268,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 +285,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); } 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 78% rename from src/public/utils.cc rename to src/mynteye/device/utils.cc index 36ba8ff..c178676 100644 --- a/src/public/utils.cc +++ b/src/mynteye/device/utils.cc @@ -11,12 +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 "mynteye/utils.h" +#include "mynteye/device/utils.h" + +#include #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 @@ -100,6 +102,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; @@ -107,6 +112,24 @@ float get_real_exposure_time( return exposure_time * real_max / 480.f; } +std::string get_sdk_root_dir() { + if (const char* root = std::getenv("MYNTEYES_SDK_ROOT")) { + // LOG(INFO) << "Environment variable MYNTEYES_SDK_ROOT found: " << root; + return std::string(root); + } else { + return std::string(MYNTEYE_SDK_ROOT_DIR); + } +} + +std::string get_sdk_install_dir() { + if (const char* root = std::getenv("MYNTEYES_SDK_ROOT")) { + // LOG(INFO) << "Environment variable MYNTEYES_SDK_ROOT found: " << root; + return std::string(root); + } else { + return std::string(MYNTEYE_SDK_INSTALL_DIR); + } +} + } // namespace utils MYNTEYE_END_NAMESPACE diff --git a/src/public/miniglog.cc b/src/mynteye/miniglog.cc similarity index 93% rename from src/public/miniglog.cc rename to src/mynteye/miniglog.cc index 23a2c32..0bda4be 100644 --- a/src/public/miniglog.cc +++ b/src/mynteye/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/mynteye/miniglog.readme b/src/mynteye/miniglog.readme new file mode 100644 index 0000000..e10b189 --- /dev/null +++ b/src/mynteye/miniglog.readme @@ -0,0 +1,3 @@ +miniglog: + * https://github.com/arpg/miniglog + * https://github.com/tzutalin/miniglog 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 82% rename from src/internal/files.cc rename to src/mynteye/util/files.cc index 556d5c9..2e87b3b 100644 --- a/src/internal/files.cc +++ b/src/mynteye/util/files.cc @@ -11,26 +11,27 @@ // 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" -#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 #endif -#include "internal/strings.h" +#include "mynteye/util/strings.h" 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/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 72% rename from src/uvc/README.md rename to src/mynteye/uvc/README.md index f8676b9..6427918 100644 --- a/src/uvc/README.md +++ b/src/mynteye/uvc/README.md @@ -8,3 +8,8 @@ * [Media Foundation](https://msdn.microsoft.com/en-us/library/ms694197(VS.85).aspx) * [USB Video Class Driver](https://docs.microsoft.com/en-us/windows-hardware/drivers/stream/usb-video-class-driver) + +## `uvc-vvuvckit.cc` + +* [VVUVCKit](https://github.com/mrRay/VVUVCKit.git) +* [osx IOUSBFamily-190](https://opensource.apple.com/source/IOUSBFamily/IOUSBFamily-190.4.1/) diff --git a/src/uvc/uvc-v4l2.cc b/src/mynteye/uvc/linux/uvc-v4l2.cc similarity index 99% rename from src/uvc/uvc-v4l2.cc rename to src/mynteye/uvc/linux/uvc-v4l2.cc index 292804c..bbb5cff 100755 --- a/src/uvc/uvc-v4l2.cc +++ b/src/mynteye/uvc/linux/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/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 +# , /