Fix the conflict
5
.gitignore
vendored
|
@ -16,6 +16,11 @@ _output/
|
|||
|
||||
/plugins/
|
||||
|
||||
/3rdparty/opencv/
|
||||
/pkginfo.sh
|
||||
/*.nsi
|
||||
/*.exe
|
||||
|
||||
# ros
|
||||
|
||||
/wrappers/ros/build
|
||||
|
|
198
CMakeLists.txt
|
@ -14,10 +14,14 @@
|
|||
|
||||
cmake_minimum_required(VERSION 3.0)
|
||||
|
||||
project(mynteye VERSION 2.0.0 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)
|
||||
|
@ -55,23 +59,6 @@ macro(target_link_threads NAME)
|
|||
endif()
|
||||
endmacro()
|
||||
|
||||
if(WITH_API)
|
||||
include(cmake/DetectOpenCV.cmake)
|
||||
endif()
|
||||
|
||||
find_package(Boost COMPONENTS filesystem)
|
||||
if(Boost_FOUND)
|
||||
set(WITH_BOOST_FILESYSTEM true)
|
||||
add_definitions(-DWITH_FILESYSTEM)
|
||||
add_definitions(-DWITH_BOOST_FILESYSTEM)
|
||||
message(STATUS "With boost filesystem: ${Boost_VERSION}")
|
||||
#message(STATUS " Boost_LIBRARIES: ${Boost_LIBRARIES}")
|
||||
elseif(OS_WIN)
|
||||
add_definitions(-DWITH_FILESYSTEM)
|
||||
add_definitions(-DWITH_NATIVE_FILESYSTEM)
|
||||
message(STATUS "With native filesystem")
|
||||
endif()
|
||||
|
||||
LIST(APPEND CMAKE_MODULE_PATH cmake)
|
||||
|
||||
include(CMakePackageConfigHelpers)
|
||||
|
@ -96,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)
|
||||
|
@ -107,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)
|
||||
add_executable(main src/main.cc)
|
||||
|
@ -124,11 +117,16 @@ endif()
|
|||
|
||||
## libmynteye
|
||||
|
||||
<<<<<<< HEAD
|
||||
if(NOT WITH_GLOG)
|
||||
=======
|
||||
if(NOT WITH_GLOG AND NOT OS_WIN)
|
||||
>>>>>>> origin/develop
|
||||
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)
|
||||
<<<<<<< HEAD
|
||||
endif()
|
||||
|
||||
set(MYNTEYE_PUBLIC_H
|
||||
|
@ -150,6 +148,8 @@ if(WITH_API)
|
|||
${CMAKE_CURRENT_SOURCE_DIR}/src/api/plugin.h
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/src/api/processor/object.h
|
||||
)
|
||||
=======
|
||||
>>>>>>> origin/develop
|
||||
endif()
|
||||
if(NOT WITH_GLOG)
|
||||
list(APPEND MYNTEYE_PUBLIC_H
|
||||
|
@ -158,50 +158,54 @@ if(NOT WITH_GLOG)
|
|||
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)
|
||||
<<<<<<< HEAD
|
||||
list(APPEND MYNTEYE_SRCS src/public/miniglog.cc)
|
||||
=======
|
||||
list(APPEND MYNTEYE_SRCS src/mynteye/miniglog.cc)
|
||||
>>>>>>> origin/develop
|
||||
endif()
|
||||
|
||||
set(MYNTEYE_LINKLIBS ${UVC_LIB})
|
||||
|
@ -218,7 +222,11 @@ endif()
|
|||
|
||||
add_library(${MYNTEYE_NAME} SHARED ${MYNTEYE_SRCS})
|
||||
target_link_libraries(${MYNTEYE_NAME} ${MYNTEYE_LINKLIBS})
|
||||
<<<<<<< HEAD
|
||||
option(WITH_GLOG "Include glog support" OFF)
|
||||
=======
|
||||
target_link_threads(${MYNTEYE_NAME})
|
||||
>>>>>>> origin/develop
|
||||
|
||||
if(OS_WIN)
|
||||
target_compile_definitions(${MYNTEYE_NAME}
|
||||
|
@ -230,27 +238,78 @@ target_include_directories(${MYNTEYE_NAME} PUBLIC
|
|||
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
|
||||
"$<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}/include>"
|
||||
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src>"
|
||||
"$<INSTALL_INTERFACE:${MYNTEYE_CMAKE_INCLUDE_DIR}>"
|
||||
"$<INSTALL_INTERFACE:include>"
|
||||
)
|
||||
|
||||
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}
|
||||
|
@ -278,32 +337,7 @@ install(EXPORT ${MYNTEYE_NAME}-targets
|
|||
|
||||
## build.info
|
||||
|
||||
macro(set_default_value VARIABLE DEFAULT)
|
||||
if(NOT ${VARIABLE})
|
||||
set(${VARIABLE} ${DEFAULT})
|
||||
endif()
|
||||
endmacro()
|
||||
|
||||
macro(set_version_values VARIABLE)
|
||||
string(REPLACE "." ";" __version_list "${${VARIABLE}}")
|
||||
list(LENGTH __version_list __len)
|
||||
if(${__len} GREATER 0)
|
||||
list(GET __version_list 0 ${VARIABLE}_MAJOR)
|
||||
endif()
|
||||
if(${__len} GREATER 1)
|
||||
list(GET __version_list 1 ${VARIABLE}_MINOR)
|
||||
endif()
|
||||
if(${__len} GREATER 2)
|
||||
list(GET __version_list 2 ${VARIABLE}_PATCH)
|
||||
endif()
|
||||
if(${__len} GREATER 3)
|
||||
list(GET __version_list 3 ${VARIABLE}_TWEAK)
|
||||
endif()
|
||||
endmacro()
|
||||
|
||||
find_package(CUDA QUIET)
|
||||
|
||||
set_version_values(CMAKE_CXX_COMPILER_VERSION)
|
||||
# set default int values for yaml file (build.info)
|
||||
set_default_value(CMAKE_CXX_COMPILER_VERSION_MAJOR 0)
|
||||
set_default_value(CMAKE_CXX_COMPILER_VERSION_MINOR 0)
|
||||
set_default_value(CMAKE_CXX_COMPILER_VERSION_PATCH 0)
|
||||
|
|
|
@ -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
|
||||
|
|
103
Jenkinsfile
vendored
Normal file
|
@ -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'
|
||||
}
|
||||
}
|
||||
}
|
68
Makefile
|
@ -16,6 +16,14 @@ include CommonDefs.mk
|
|||
MKFILE_PATH := $(abspath $(lastword $(MAKEFILE_LIST)))
|
||||
MKFILE_DIR := $(patsubst %/,%,$(dir $(MKFILE_PATH)))
|
||||
|
||||
# CMAKE_INSTALL_PREFIX:
|
||||
# https://cmake.org/cmake/help/latest/variable/CMAKE_INSTALL_PREFIX.html
|
||||
#
|
||||
# UNIX: /usr/local
|
||||
# Windows: c:/Program Files/${PROJECT_NAME}
|
||||
|
||||
SUDO ?= sudo
|
||||
|
||||
.DEFAULT_GOAL := all
|
||||
|
||||
help:
|
||||
|
@ -29,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"
|
||||
|
@ -43,7 +52,8 @@ all: init samples tools ros
|
|||
|
||||
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
|
||||
|
@ -54,19 +64,26 @@ opendoc: apidoc
|
|||
[ -f "$$html" ] && $(SH) ./scripts/open.sh $$html; \
|
||||
done
|
||||
|
||||
.PHONY: apidoc opendoc
|
||||
cleandoc:
|
||||
@$(call rm,./doc/_output/)
|
||||
|
||||
.PHONY: apidoc opendoc cleandoc
|
||||
|
||||
# deps
|
||||
|
||||
submodules:
|
||||
@git submodule update --init
|
||||
<<<<<<< HEAD
|
||||
=======
|
||||
|
||||
>>>>>>> origin/develop
|
||||
.PHONY: submodules
|
||||
|
||||
# init
|
||||
|
||||
init:
|
||||
@$(call echo,Make $@)
|
||||
@$(SH) ./scripts/init.sh
|
||||
@$(SH) ./scripts/init.sh $(INIT_OPTIONS)
|
||||
|
||||
.PHONY: init
|
||||
|
||||
|
@ -74,7 +91,11 @@ init:
|
|||
|
||||
build:
|
||||
@$(call echo,Make $@)
|
||||
ifeq ($(HOST_OS),Win)
|
||||
@$(call cmake_build,./_build,..,-DCMAKE_INSTALL_PREFIX=$(MKFILE_DIR)/_install)
|
||||
else
|
||||
@$(call cmake_build,./_build,..)
|
||||
endif
|
||||
|
||||
.PHONY: build
|
||||
|
||||
|
@ -108,12 +129,27 @@ ifneq ($(HOST_NAME),MinGW)
|
|||
else
|
||||
@cd ./_build; make install
|
||||
endif
|
||||
else
|
||||
ifeq ($(HOST_OS),Linux)
|
||||
@cd ./_build; $(SUDO) make install
|
||||
else
|
||||
@cd ./_build; make install
|
||||
endif
|
||||
endif
|
||||
|
||||
.PHONY: install
|
||||
|
||||
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
|
||||
|
@ -130,14 +166,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
|
||||
|
@ -219,8 +271,7 @@ cleanlog:
|
|||
@$(call rm_f,*ERROR*)
|
||||
@$(call rm_f,*FATAL*)
|
||||
|
||||
cleanall: clean
|
||||
@$(call rm,./doc/_output/)
|
||||
cleanall: clean cleandoc
|
||||
@$(call rm,./test/gtest/_build/)
|
||||
@$(call rm,./third_party/glog/_build/)
|
||||
@$(FIND) . -type f -name ".DS_Store" -print0 | xargs -0 rm -f
|
||||
|
@ -247,6 +298,7 @@ host:
|
|||
@echo BUILD: $(BUILD)
|
||||
@echo LDD: $(LDD)
|
||||
@echo CMAKE: $(CMAKE)
|
||||
@echo PKGNAME: $(PKGNAME)
|
||||
|
||||
.PHONY: host
|
||||
|
||||
|
|
27
README.md
|
@ -1,10 +1,10 @@
|
|||
# MYNT® EYE SDK
|
||||
# MYNT® EYE S SDK
|
||||
|
||||
[![](https://img.shields.io/badge/MYNT%20EYE%20SDK-2.0.0--rc-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,19 +16,20 @@ 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.
|
||||
* zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2083629/mynt-eye-sdk-apidoc-2.0.0-rc-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2/files/2083631/mynt-eye-sdk-apidoc-2.0.0-rc-html-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-SDK-2/)
|
||||
* [Guide Doc](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/releases): How to install and start using the SDK.
|
||||
* zh-Hans: [![](https://img.shields.io/badge/Download-PDF-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2083740/mynt-eye-sdk-guide-2.0.0-rc-zh-Hans.pdf) [![](https://img.shields.io/badge/Download-HTML-blue.svg?style=flat)](https://github.com/slightech/MYNT-EYE-SDK-2-Guide/files/2083745/mynt-eye-sdk-guide-2.0.0-rc-html-zh-Hans.zip) [![](https://img.shields.io/badge/Online-HTML-blue.svg?style=flat)](https://slightech.github.io/MYNT-EYE-SDK-2-Guide/)
|
||||
* [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/2598115/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/2598116/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/2598117/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/2598119/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: `zh-Hans`.
|
||||
> Supported languages: `en`, `zh-Hans`.
|
||||
|
||||
## Firmwares
|
||||
|
||||
[Google Drive]: https://drive.google.com/drive/folders/1tdFCcTBMNcImEGZ39tdOZmlX2SHKCr2f
|
||||
[百度网盘]: https://pan.baidu.com/s/1yPQDp2r0x4jvNwn2UjlMUQ
|
||||
[MYNTEYE_BOX]: http://doc.myntai.com/mynteye/s/download
|
||||
|
||||
Get firmwares from our online disks: [Google Drive][], [百度网盘][]. The latest version is `2.0.0-rc`.
|
||||
Get firmwares from our online disks: [MYNTEYE_BOX][]. The latest version is `2.2.2`.
|
||||
|
||||
## Usage
|
||||
|
||||
|
@ -60,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.
|
||||
|
|
|
@ -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")
|
||||
|
|
|
@ -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()
|
||||
|
|
|
@ -12,11 +12,141 @@
|
|||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
option(WITH_API "Build with API layer, need OpenCV" ON)
|
||||
include(${CMAKE_CURRENT_LIST_DIR}/IncludeGuard.cmake)
|
||||
cmake_include_guard()
|
||||
|
||||
message(STATUS "Options:")
|
||||
message(STATUS " WITH_API: ${WITH_API}")
|
||||
include(${CMAKE_CURRENT_LIST_DIR}/Utils.cmake)
|
||||
|
||||
|
||||
# build components
|
||||
|
||||
option(WITH_API "Build with API layer, need OpenCV" ON)
|
||||
option(WITH_DEVICE_INFO_REQUIRED "Build with device info required" ON)
|
||||
|
||||
# 3rdparty components
|
||||
|
||||
option(WITH_BOOST "Include Boost support" ON)
|
||||
|
||||
# How to install glog?
|
||||
# Ubuntu: `sudo apt-get install libgoogle-glog-dev`
|
||||
option(WITH_GLOG "Include glog support" OFF)
|
||||
|
||||
# packages
|
||||
|
||||
if(WITH_API)
|
||||
include(${CMAKE_CURRENT_LIST_DIR}/DetectOpenCV.cmake)
|
||||
endif()
|
||||
|
||||
if(WITH_DEVICE_INFO_REQUIRED)
|
||||
add_definitions(-DWITH_DEVICE_INFO_REQUIRED)
|
||||
endif()
|
||||
|
||||
if(WITH_BOOST)
|
||||
find_package(Boost COMPONENTS filesystem)
|
||||
if(Boost_FOUND)
|
||||
set(Boost_VERSION_STRING "${Boost_MAJOR_VERSION}.${Boost_MINOR_VERSION}.${Boost_SUBMINOR_VERSION}")
|
||||
set(WITH_FILESYSTEM TRUE)
|
||||
set(WITH_BOOST_FILESYSTEM TRUE)
|
||||
add_definitions(-DWITH_FILESYSTEM)
|
||||
add_definitions(-DWITH_BOOST_FILESYSTEM)
|
||||
endif()
|
||||
endif()
|
||||
|
||||
if(NOT WITH_FILESYSTEM)
|
||||
if(MSVC OR MSYS OR MINGW) # win
|
||||
set(WITH_FILESYSTEM TRUE)
|
||||
set(WITH_NATIVE_FILESYSTEM TRUE)
|
||||
add_definitions(-DWITH_FILESYSTEM)
|
||||
add_definitions(-DWITH_NATIVE_FILESYSTEM)
|
||||
endif()
|
||||
endif()
|
||||
|
||||
if(WITH_GLOG)
|
||||
include(${CMAKE_CURRENT_LIST_DIR}/DetectGLog.cmake)
|
||||
endif()
|
||||
|
||||
find_package(CUDA QUIET)
|
||||
|
||||
# summary
|
||||
|
||||
set_version_values(CMAKE_CXX_COMPILER_VERSION)
|
||||
|
||||
status("")
|
||||
status("Platform:")
|
||||
status(" HOST_OS: ${HOST_OS}")
|
||||
status(" HOST_NAME: ${HOST_NAME}")
|
||||
status(" HOST_ARCH: ${HOST_ARCH}")
|
||||
status(" HOST_COMPILER: ${CMAKE_CXX_COMPILER_ID}")
|
||||
status(" COMPILER_VERSION: ${CMAKE_CXX_COMPILER_VERSION}")
|
||||
status(" COMPILER_VERSION_MAJOR: ${CMAKE_CXX_COMPILER_VERSION_MAJOR}")
|
||||
status(" COMPILER_VERSION_MINOR: ${CMAKE_CXX_COMPILER_VERSION_MINOR}")
|
||||
status(" COMPILER_VERSION_PATCH: ${CMAKE_CXX_COMPILER_VERSION_PATCH}")
|
||||
status(" COMPILER_VERSION_TWEAK: ${CMAKE_CXX_COMPILER_VERSION_TWEAK}")
|
||||
if(CUDA_FOUND)
|
||||
status(" CUDA_VERSION: ${CUDA_VERSION}")
|
||||
status(" CUDA_VERSION_MAJOR: ${CUDA_VERSION_MAJOR}")
|
||||
status(" CUDA_VERSION_MINOR: ${CUDA_VERSION_MINOR}")
|
||||
status(" CUDA_VERSION_STRING: ${CUDA_VERSION_STRING}")
|
||||
endif()
|
||||
if(OpenCV_FOUND)
|
||||
status(" OpenCV_VERSION: ${OpenCV_VERSION}")
|
||||
status(" OpenCV_VERSION_MAJOR: ${OpenCV_VERSION_MAJOR}")
|
||||
status(" OpenCV_VERSION_MINOR: ${OpenCV_VERSION_MINOR}")
|
||||
status(" OpenCV_VERSION_PATCH: ${OpenCV_VERSION_PATCH}")
|
||||
status(" OpenCV_VERSION_TWEAK: ${OpenCV_VERSION_TWEAK}")
|
||||
status(" OpenCV_VERSION_STATUS: ${OpenCV_VERSION_STATUS}")
|
||||
status(" OpenCV_WITH_WORLD: ${WITH_OPENCV_WORLD}")
|
||||
endif()
|
||||
if(mynteye_VERSION)
|
||||
status(" MYNTEYE_VERSION: ${mynteye_VERSION}")
|
||||
status(" MYNTEYE_VERSION_MAJOR: ${mynteye_VERSION_MAJOR}")
|
||||
status(" MYNTEYE_VERSION_MINOR: ${mynteye_VERSION_MINOR}")
|
||||
status(" MYNTEYE_VERSION_PATCH: ${mynteye_VERSION_PATCH}")
|
||||
status(" MYNTEYE_VERSION_TWEAK: ${mynteye_VERSION_TWEAK}")
|
||||
endif()
|
||||
|
||||
status("")
|
||||
status("Options:")
|
||||
status(" WITH_API: ${WITH_API}")
|
||||
if(WITH_API)
|
||||
if(OpenCV_FOUND)
|
||||
status(" OpenCV: YES")
|
||||
status(" OpenCV_VERSION: ${OpenCV_VERSION}")
|
||||
status(" OpenCV_WORLD: " IF WITH_OPENCV_WORLD "YES" ELSE "NO")
|
||||
else()
|
||||
status(" OpenCV: NO")
|
||||
endif()
|
||||
endif()
|
||||
|
||||
status(" WITH_DEVICE_INFO_REQUIRED: ${WITH_DEVICE_INFO_REQUIRED}")
|
||||
|
||||
status(" WITH_BOOST: ${WITH_BOOST}")
|
||||
if(WITH_BOOST)
|
||||
if(Boost_FOUND)
|
||||
status(" Boost: YES")
|
||||
status(" Boost_VERSION: ${Boost_VERSION_STRING}")
|
||||
#status(" Boost_LIBRARIES: ${Boost_LIBRARIES}")
|
||||
else()
|
||||
status(" Boost: NO")
|
||||
endif()
|
||||
endif()
|
||||
|
||||
status(" WITH_GLOG: ${WITH_GLOG}")
|
||||
if(WITH_GLOG)
|
||||
if(glog_FOUND)
|
||||
status(" glog: YES")
|
||||
status(" glog_VERSION: ${glog_VERSION}")
|
||||
else()
|
||||
status(" glog: NO")
|
||||
endif()
|
||||
endif()
|
||||
|
||||
status("")
|
||||
status("Features:")
|
||||
status(" Filesystem: "
|
||||
IF WITH_BOOST_FILESYSTEM "boost"
|
||||
ELIF WITH_NATIVE_FILESYSTEM "native"
|
||||
ELSE "none"
|
||||
)
|
||||
|
||||
status("")
|
||||
|
|
|
@ -49,3 +49,88 @@ macro(make_executable NAME)
|
|||
endif()
|
||||
endif()
|
||||
endmacro()
|
||||
|
||||
# set_default_value(VARIABLE DEFAULT)
|
||||
macro(set_default_value VARIABLE DEFAULT)
|
||||
if(NOT ${VARIABLE})
|
||||
set(${VARIABLE} ${DEFAULT})
|
||||
endif()
|
||||
endmacro()
|
||||
|
||||
# set_version_values(VARIABLE)
|
||||
macro(set_version_values VARIABLE)
|
||||
string(REPLACE "." ";" __version_list "${${VARIABLE}}")
|
||||
list(LENGTH __version_list __len)
|
||||
if(${__len} GREATER 0)
|
||||
list(GET __version_list 0 ${VARIABLE}_MAJOR)
|
||||
endif()
|
||||
if(${__len} GREATER 1)
|
||||
list(GET __version_list 1 ${VARIABLE}_MINOR)
|
||||
endif()
|
||||
if(${__len} GREATER 2)
|
||||
list(GET __version_list 2 ${VARIABLE}_PATCH)
|
||||
endif()
|
||||
if(${__len} GREATER 3)
|
||||
list(GET __version_list 3 ${VARIABLE}_TWEAK)
|
||||
endif()
|
||||
endmacro()
|
||||
|
||||
# status(TEXT [IF cond text [ELIF cond text] [ELSE cond text]])
|
||||
macro(status TEXT)
|
||||
set(options)
|
||||
set(oneValueArgs)
|
||||
set(multiValueArgs IF ELIF ELSE)
|
||||
cmake_parse_arguments(THIS "${options}" "${oneValueArgs}"
|
||||
"${multiValueArgs}" ${ARGN})
|
||||
|
||||
#message(STATUS "TEXT: ${TEXT}")
|
||||
#message(STATUS "THIS_IF: ${THIS_IF}")
|
||||
#message(STATUS "THIS_ELIF: ${THIS_ELIF}")
|
||||
#message(STATUS "THIS_ELSE: ${THIS_ELSE}")
|
||||
|
||||
set(__msg_list "${TEXT}")
|
||||
set(__continue TRUE)
|
||||
|
||||
if(__continue AND DEFINED THIS_IF)
|
||||
#message(STATUS "-- THIS_IF: ${THIS_IF}")
|
||||
list(LENGTH THIS_IF __if_len)
|
||||
if(${__if_len} GREATER 1)
|
||||
list(GET THIS_IF 0 __if_cond)
|
||||
if(${__if_cond})
|
||||
list(REMOVE_AT THIS_IF 0)
|
||||
list(APPEND __msg_list ${THIS_IF})
|
||||
set(__continue FALSE)
|
||||
endif()
|
||||
else()
|
||||
message(FATAL_ERROR "status() IF must have cond and text, >= 2 items")
|
||||
endif()
|
||||
endif()
|
||||
|
||||
if(__continue AND DEFINED THIS_ELIF)
|
||||
#message(STATUS "-- THIS_ELIF: ${THIS_ELIF}")
|
||||
list(LENGTH THIS_ELIF __elif_len)
|
||||
if(${__elif_len} GREATER 1)
|
||||
list(GET THIS_ELIF 0 __elif_cond)
|
||||
if(${__elif_cond})
|
||||
list(REMOVE_AT THIS_ELIF 0)
|
||||
list(APPEND __msg_list ${THIS_ELIF})
|
||||
set(__continue FALSE)
|
||||
endif()
|
||||
else()
|
||||
message(FATAL_ERROR "status() ELIF must have cond and text, >= 2 items")
|
||||
endif()
|
||||
endif()
|
||||
|
||||
if(__continue AND DEFINED THIS_ELSE)
|
||||
#message(STATUS "-- THIS_ELSE: ${THIS_ELSE}")
|
||||
list(LENGTH THIS_ELSE __else_len)
|
||||
if(${__else_len} GREATER 0)
|
||||
list(APPEND __msg_list ${THIS_ELSE})
|
||||
else()
|
||||
message(FATAL_ERROR "status() ELSE must have text, >= 1 items")
|
||||
endif()
|
||||
endif()
|
||||
|
||||
string(REPLACE ";" "" __msg_list "${__msg_list}")
|
||||
message(STATUS "${__msg_list}")
|
||||
endmacro()
|
||||
|
|
16
cmake/templates/pkginfo.sh.in
Normal file
|
@ -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
|
|
@ -1,10 +0,0 @@
|
|||
%YAML:1.0
|
||||
---
|
||||
device_name: MYNT-EYE-S210A
|
||||
serial_number: "07C624160009071F"
|
||||
firmware_version: "0.1"
|
||||
hardware_version: "1.0"
|
||||
spec_version: "1.1"
|
||||
lens_type: "0000"
|
||||
imu_type: "0000"
|
||||
nominal_baseline: 0
|
|
@ -1,53 +0,0 @@
|
|||
%YAML:1.0
|
||||
---
|
||||
version: "1.1"
|
||||
in_left_map:
|
||||
-
|
||||
width: 640
|
||||
height: 400
|
||||
fx: 1.9739641213416058e+02
|
||||
fy: 1.9772337597617189e+02
|
||||
cx: 3.2611983633916327e+02
|
||||
cy: 1.9986969132833946e+02
|
||||
model: 0
|
||||
coeffs: [ 1.2135236310725651e-01, -8.5442776049177036e-02,
|
||||
2.4914898631983504e-03, -3.7752063658256863e-03, 0. ]
|
||||
-
|
||||
width: 1280
|
||||
height: 800
|
||||
fx: 1.9739641213416058e+02
|
||||
fy: 1.9772337597617189e+02
|
||||
cx: 3.2611983633916327e+02
|
||||
cy: 1.9986969132833946e+02
|
||||
model: 0
|
||||
coeffs: [ 1.2135236310725651e-01, -8.5442776049177036e-02,
|
||||
2.4914898631983504e-03, -3.7752063658256863e-03, 0. ]
|
||||
in_right_map:
|
||||
-
|
||||
width: 640
|
||||
height: 400
|
||||
fx: 2.0335498653655989e+02
|
||||
fy: 2.0453858622699008e+02
|
||||
cx: 3.1589962248180814e+02
|
||||
cy: 2.1871688038954812e+02
|
||||
model: 0
|
||||
coeffs: [ 2.2904330559241560e-02, -2.9561990079971841e-02,
|
||||
3.9725942760981507e-03, -3.9689073214945591e-03, 0. ]
|
||||
-
|
||||
width: 1280
|
||||
height: 800
|
||||
fx: 2.0335498653655989e+02
|
||||
fy: 2.0453858622699008e+02
|
||||
cx: 3.1589962248180814e+02
|
||||
cy: 2.1871688038954812e+02
|
||||
model: 0
|
||||
coeffs: [ 2.2904330559241560e-02, -2.9561990079971841e-02,
|
||||
3.9725942760981507e-03, -3.9689073214945591e-03, 0. ]
|
||||
ex_left_to_right:
|
||||
rotation: [ 9.9998850083695123e-01, -1.9263678722299450e-03,
|
||||
-4.3917309443490191e-03, 1.8166060642710027e-03,
|
||||
9.9968925981619028e-01, -2.4861290203142431e-02,
|
||||
4.4382582477776426e-03, 2.4853026274046636e-02,
|
||||
9.9968126367795229e-01 ]
|
||||
translation: [ -8.2270200890555529e+01, -1.9535144360069059e+00,
|
||||
2.2588034344482368e+00 ]
|
|
@ -1,15 +0,0 @@
|
|||
%YAML:1.0
|
||||
---
|
||||
in_accel:
|
||||
scale: [ 0., 0., 0., 0., 0., 0., 0., 0., 0. ]
|
||||
drift: [ 0., 0., 0. ]
|
||||
noise: [ 0., 0., 0. ]
|
||||
bias: [ 0., 0., 0. ]
|
||||
in_gyro:
|
||||
scale: [ 0., 0., 0., 0., 0., 0., 0., 0., 0. ]
|
||||
drift: [ 0., 0., 0. ]
|
||||
noise: [ 0., 0., 0. ]
|
||||
bias: [ 0., 0., 0. ]
|
||||
ex_left_to_imu:
|
||||
rotation: [ 0., 0., 0., 0., 0., 0., 0., 0., 0. ]
|
||||
translation: [ 0., 0., 0. ]
|
25
doc/build.sh
|
@ -40,8 +40,8 @@ OUTPUT="$BASE_DIR/_output"
|
|||
_texcjk() {
|
||||
tex="$1"; shift;
|
||||
_echo_in "add cjk to $tex"
|
||||
sed -i "" -e $'s/^\\\\begin{document}$/\\\\usepackage{CJKutf8}\\\n\\\\begin{document}\\\n\\\\begin{CJK}{UTF8}{gbsn}/g' $tex
|
||||
sed -i "" -e $'s/^\\\\end{document}$/\\\\end{CJK}\\\n\\\\end{document}/g' $tex
|
||||
sed -i "" -E $'s/^\\\\begin{document}$/\\\\usepackage{CJKutf8}\\\n\\\\begin{document}\\\n\\\\begin{CJK}{UTF8}{gbsn}/g' $tex
|
||||
sed -i "" -E $'s/^\\\\end{document}$/\\\\end{CJK}\\\n\\\\end{document}/g' $tex
|
||||
}
|
||||
|
||||
for lang in "${LANGS[@]}"; do
|
||||
|
@ -52,11 +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"
|
||||
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" "../mynteye-apidoc.pdf"
|
||||
[ -f "refman.pdf" ] && mv "refman.pdf" "../$filename"
|
||||
fi
|
||||
|
||||
_echo_d "doxygen completed"
|
||||
else
|
||||
_echo_e "$DOXYFILE not found"
|
||||
|
|
2495
doc/en/api.doxyfile
Normal file
11
doc/en/mainpage.md
Normal file
|
@ -0,0 +1,11 @@
|
|||
# MYNT EYE S SDK {#mainpage}
|
||||
|
||||
* <a class="el" href="annotated.html">API Classes</a>
|
||||
* <a class="el" href="modules.html">API Modules</a>
|
||||
* \link enumerations Enumerations\endlink
|
||||
* \link datatypes Datatypes\endlink
|
||||
* \link utils Utiliities\endlink
|
||||
* \link calibration Intrinsics & Extrinsics\endlink
|
||||
* <span style="font-weight:bold">Device Specifications</span>
|
||||
* @subpage specs_data
|
||||
* @subpage specs_ctrl
|
26
doc/en/spec_control_api.md
Normal file
|
@ -0,0 +1,26 @@
|
|||
# Control Protocols {#spec_control_api}
|
||||
|
||||
There are two control modes, one is through UVC standard protocol, the other is through UVC custom protocol with extension unit.
|
||||
|
||||
## Standard Protocol
|
||||
|
||||
| Name | Field | Bytes | Default | Min | Max | Stored | Flash Address | Note |
|
||||
| :--- | :---- | :---- | :------ | :-- | :-- | :----- | :------------ | :--- |
|
||||
| Gain | gain | 2 | 24 | 0 | 48 | √ | 0x12 | valid if manual-exposure |
|
||||
| Brightness | brightness/exposure_time | 2 | 120 | 0 | 240 | √ | 0x14 | valid if manual-exposure |
|
||||
| Contrast | contrast/black_level_calibration | 2 | 127 | 0 | 255 | √ | 0x10 | valid if manual-exposure |
|
||||
|
||||
## Custom Protocol
|
||||
|
||||
| Name | Field | Bytes | Default | Min | Max | Stored | Flash Address | Channel | Note |
|
||||
| :--- | :---- | :---- | :------ | :-- | :-- | :----- | :------------ | :------ | :----- |
|
||||
| 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 |
|
||||
| Max exposure time | max_exposure_time | 2 | 240 | 0 | 240 | √ | 0x1B | XU_CAM_CTRL | valid if auto-exposure |
|
||||
| Desired brightness | desired_brightness | 2 | 192 | 0 | 255 | √ | 0x19 | XU_CAM_CTRL | valid if auto-exposure |
|
||||
| IR control | ir_control | 1 | 0 | 0 | 160 | × | - | XU_CAM_CTRL | |
|
||||
| HDR mode | hdr_mode | 1 | 0 | 0 | 1 | √ | 0x1F | XU_CAM_CTRL | 0: 10-bit; 1: 12-bit |
|
||||
| Zero drift calibration | zero_drift_calibration | | - | - | - | × | - | XU_HALF_DUPLEX | |
|
||||
| Erase chip | erase_chip | | - | - | - | × | - | XU_HALF_DUPLEX | |
|
53
doc/en/spec_control_channel.md
Normal file
|
@ -0,0 +1,53 @@
|
|||
# Control Channels {#spec_control_channel}
|
||||
|
||||
| Name | Field | Address | Bandwidth | Node |
|
||||
| :----- | :----- | :----- | :----- | :----- |
|
||||
| Camera control channel | XU_CAM_CTRL_CHANNEL | 1 | 3 | |
|
||||
| Half-Duplex channel | XU_HALF_DUPLEX_CHANNEL | 2 | 20 | |
|
||||
| IMU write channel | XU_IMUDATA_WRITE_CHANNEL | 3 | 5 | |
|
||||
| IMU read channel | XU_IMUDATA_READ_CHANNEL | 4 | 2000 | |
|
||||
| File channel | XU_FILE_CHANNEL | 5 | 2000 | |
|
||||
|
||||
## Camera Control Channel
|
||||
|
||||
The channel provides get, set and query (min, max, default).
|
||||
|
||||
## Half-Duplex Channel
|
||||
|
||||
The channel only provides set, such as zero drift correction.
|
||||
|
||||
## IMU Channel
|
||||
|
||||
The channel is used to request and response IMU data, see @ref spec_imu_data.
|
||||
|
||||
## File Channel
|
||||
|
||||
The channel is used to read and write device information, image params, and IMU params.
|
||||
|
||||
| Name | Header | Size | File | Checksum |
|
||||
| :--- | :- | :--- | :--- | :-------- |
|
||||
| Bytes | 1 | 2 | - | 1 |
|
||||
| Type | uint8_t | uint16_t | - | uint8_t |
|
||||
| Description | Flags | Content size | Content data | Checksum, XOR of all content bytes |
|
||||
|
||||
| Header Bit Subscript | Description |
|
||||
| :------------------- | :---------- |
|
||||
| 0 | Device information |
|
||||
| 1 | Image params |
|
||||
| 2 | IMU params |
|
||||
| 3~6 | Undefined |
|
||||
| 7 | 0: Get; 1: Set |
|
||||
|
||||
### File Content Packet
|
||||
|
||||
| Name | ID | Size | Content |
|
||||
| :--- | :- | :--- | :------ |
|
||||
| Bytes | 1 | 2 | - |
|
||||
| Type | uint8_t | uint16_t | - |
|
||||
| Description | Content ID | Content size | Content data |
|
||||
|
||||
| File | ID | Max Size |
|
||||
| :--- | :- | :------- |
|
||||
| Device information | 1 | 250 |
|
||||
| Image params | 2 | 250 |
|
||||
| IMU params | 4 | 500 |
|
14
doc/en/spec_hardware_info.md
Normal file
|
@ -0,0 +1,14 @@
|
|||
# Device Information {#spec_hardware_info}
|
||||
|
||||
| Name | Field | Fixed Value | USB Descriptor | UVC Extension Unit | Bytes | Note |
|
||||
| :----- | :----- | :-------- | :-------------- | :----------------- | :-------- | :----- |
|
||||
| VID | vid | 0x04B4 | √ | × | 2 | |
|
||||
| PID | pid | 0x00F9 | √ | × | 2 | |
|
||||
| Device name | name | MYNT-EYE-? | √ | √ Get | 16 | MYNT-EYE-S1000 |
|
||||
| Serial number | serial_number | - | √ | √ Get | 16 | |
|
||||
| Firmware version | firmware_version | - | √ | √ Get | 2 | major,minor |
|
||||
| Hardware version | hardware_version | - | × | √ Get | 3 | major,minor,flag |
|
||||
| Spec version | spec_version | - | × | √ Get | 2 | major,minor |
|
||||
| Lens type | lens_type | - | × | √ Get/Set | 4 | vendor(2),product(2); default: 0 |
|
||||
| IMU type | imu_type | - | × | √ Get/Set | 4 | vendor(2),product(2); default: 0 |
|
||||
| Nominal baseline | nominal_baseline | - | × | √ Get/Set | 2 | unit: mm; default: 0 |
|
20
doc/en/spec_image_data.md
Normal file
|
@ -0,0 +1,20 @@
|
|||
# Image Data {#spec_image_data}
|
||||
|
||||
| Name | Field | Unit | Bytes | Note |
|
||||
| :----- | :----- | :----- | :-------- | :----- |
|
||||
| Frame ID | frame_id | - | 2 | uint16_t; [0,65535] |
|
||||
| Timestamp | timestamp | 10 us | 4 | uint32_t |
|
||||
| Exposure Time | exposure_time | 10 us | 2 | uint16_t |
|
||||
|
||||
## Image Packet
|
||||
|
||||
| Name | Header | Size | Frame ID | Timestamp | Exposure Time | Checksum |
|
||||
| :--- | :----- | :--- | :------- | :-------- | :------------ | :------- |
|
||||
| Bytes | 1 | 1 | 2 | 4 | 2 | 1 |
|
||||
| Type | uint8_t | uint8_t | uint16_t | uint32_t | uint16_t | uint8_t |
|
||||
| Description | 0x3B | 0x08, content size | Frame ID | Timestamp | Exposure time | Checksum, XOR of all content bytes |
|
||||
|
||||
* The image packet will be dropped, if checksum is incorrect.
|
||||
* The accuracy of the time unit: 0.01 ms / 10 us.
|
||||
* The timestamp could indicate 11.9 hours, it will accumulate again after overflow.
|
||||
* The timestamp accumulation starts from the time of power-on, instead of opening.
|
23
doc/en/spec_image_params.md
Normal file
|
@ -0,0 +1,23 @@
|
|||
# Image Params {#spec_image_params}
|
||||
|
||||
## Image Intrinsics
|
||||
|
||||
| Name | Field | Unit | Bytes | Note |
|
||||
| :----- | :----- | :----- | :-------- | :----- |
|
||||
| Image width | width | px | 2 | uint16_t; [0,65535] |
|
||||
| Image height | height | px | 2 | uint16_t; [0,65535] |
|
||||
| Focal length | fx | - | 8 | double |
|
||||
| ^ | fy | - | 8 | double |
|
||||
| Principal point | cx | - | 8 | double |
|
||||
| ^ | cy | - | 8 | double |
|
||||
| Distortion model | model | - | 1 | uint8_t; pinhole,... |
|
||||
| Distortion coefficients | coeffs[5] | - | 40 | double; k1,k2,p1,p2,k3 |
|
||||
|
||||
## Image Extrinsics
|
||||
|
||||
Transformation matrix from left image to right image.
|
||||
|
||||
| Name | Field | Unit | Bytes | Note |
|
||||
| :----- | :----- | :----- | :-------- | :----- |
|
||||
| Rotation matrix | rotation[3][3] | - | 72 | double |
|
||||
| Translation vector | translation[3] | - | 24 | double |
|
42
doc/en/spec_imu_data.md
Normal file
|
@ -0,0 +1,42 @@
|
|||
# IMU Data {#spec_imu_data}
|
||||
|
||||
## IMU Request Packet
|
||||
|
||||
| Name | Header | Serial Number |
|
||||
| :--- | :----- | :------------ |
|
||||
| Bytes | 1 | 4 |
|
||||
| Type | uint8_t | uint32_t |
|
||||
| Description | 0x5A | First request should be 0, otherwise the last one |
|
||||
|
||||
## IMU Response Packet
|
||||
|
||||
The IMU response packet contains multiple IMU packets, and each IMU packet contains multiple IMU segments.
|
||||
|
||||
| Name | Header | State | Size | IMU Packets | Checksum |
|
||||
| :--- | :----- | :---- | :--- | :---------- | :------- |
|
||||
| Bytes | 1 | 1 | 2 | ... | 1 |
|
||||
| Type | uint8_t | uint8_t | uint16_t | - | uint8_t |
|
||||
| Description | 0x5B | 0 is success, others are failed | Content size | IMU packets | Checksum, XOR of all content bytes |
|
||||
|
||||
### IMU Packet
|
||||
|
||||
The IMU packet is an array of IMU datas.
|
||||
|
||||
| Name | Serial Number | Timestamp | Count | IMU Datas |
|
||||
| :--- | :------------ | :-------- | :---- | :-------- |
|
||||
| Bytes | 4 | 4 | 1 | ... |
|
||||
| Type | uint32_t | uint32_t | uint8_t | - |
|
||||
| Description | Serial number | IMU basic timestamp | The number of IMU datas | IMU datas |
|
||||
|
||||
### IMU Segment
|
||||
|
||||
| Name | Offset | Frame ID | Accelerometer | Temperature | Gyroscope |
|
||||
| :--- | :----- | :------- | :------------ | :---------- | :-------- |
|
||||
| Bytes | 2 | 2 | 6 | 2 | 6 |
|
||||
| Type | int16_t | uint16_t | int16_t * 3 | int16_t | int16_t * 3 |
|
||||
| Description | The timestamp offset | Image frame ID | Accel x,y,z values | IMU temperature | Gyro x,y,z values |
|
||||
|
||||
* Formula for converting the accel & gyro values to real ones: **real = data * range / 0x10000** .
|
||||
* ``accel`` default ``range`` is **8 g**, ``gyro`` default ``range`` is **1000 deg/s**.
|
||||
* Formula for converting the temperature to real value: **real = data / ratio + offset** .
|
||||
* default ``ratio`` is **326.8**, default ``offset`` is **25℃**.
|
23
doc/en/spec_imu_params.md
Normal file
|
@ -0,0 +1,23 @@
|
|||
# IMU Params {#spec_imu_params}
|
||||
|
||||
## IMU Intrinsics
|
||||
|
||||
| Name | Field | Unit | Bytes | Note |
|
||||
| :----- | :----- | :----- | :-------- | :----- |
|
||||
| Scale matrix | acc_scale[3][3] | - | 72 | double |
|
||||
| ^ | gyro_scale[3][3] | - | 72 | double |
|
||||
| Zero-drift | acc_drift[3] | - | 24 | double |
|
||||
| ^ | gyro_drift[3] | - | 24 | double |
|
||||
| Noise density | acc_noise[3] | - | 24 | double |
|
||||
| ^ | gyro_noise[3] | - | 24 | double |
|
||||
| Random walk | acc_bias[3] | - | 24 | double |
|
||||
| ^ | gyro_bias[3] | - | 24 | double |
|
||||
|
||||
## IMU Extrinsics
|
||||
|
||||
Transformation matrix from left image to IMU.
|
||||
|
||||
| Name | Field | Unit | Bytes | Note |
|
||||
| :----- | :----- | :----- | :-------- | :----- |
|
||||
| Rotation matrix | rotation[3][3] | - | 72 | double |
|
||||
| Translation vector | translation[3] | - | 24 | double |
|
4
doc/en/specs_ctrl.md
Normal file
|
@ -0,0 +1,4 @@
|
|||
# Device Control Specification {#specs_ctrl}
|
||||
|
||||
* @subpage spec_control_api
|
||||
* @subpage spec_control_channel
|
7
doc/en/specs_data.md
Normal file
|
@ -0,0 +1,7 @@
|
|||
# Device Data Specification {#specs_data}
|
||||
|
||||
* @subpage spec_hardware_info
|
||||
* @subpage spec_image_params
|
||||
* @subpage spec_imu_params
|
||||
* @subpage spec_image_data
|
||||
* @subpage spec_imu_data
|
|
@ -1,4 +1,4 @@
|
|||
# Doxyfile 1.8.13
|
||||
# Doxyfile 1.8.14
|
||||
|
||||
# This file describes the settings to be used by the documentation system
|
||||
# doxygen (www.doxygen.org) for a project.
|
||||
|
@ -20,8 +20,8 @@
|
|||
# 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.
|
||||
# built into libc) for the transcoding. See
|
||||
# https://www.gnu.org/software/libiconv/ for the list of possible encodings.
|
||||
# The default value is: UTF-8.
|
||||
|
||||
DOXYFILE_ENCODING = UTF-8
|
||||
|
@ -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.0-rc
|
||||
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
|
||||
|
@ -236,7 +236,8 @@ TAB_SIZE = 2
|
|||
# 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.
|
||||
# newlines (in the resulting output). You can put ^^ in the value part of an
|
||||
# alias to insert a newline as if a physical newline was in the original file.
|
||||
|
||||
ALIASES =
|
||||
|
||||
|
@ -337,7 +338,7 @@ BUILTIN_STL_SUPPORT = 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
|
||||
# https://www.riverbankcomputing.com/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.
|
||||
|
@ -708,7 +709,7 @@ 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.
|
||||
# to be installed. See also https://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. See also \cite for info how to create references.
|
||||
|
@ -791,14 +792,6 @@ WARN_LOGFILE =
|
|||
# Note: If this tag is empty the current directory is searched.
|
||||
|
||||
INPUT = mainpage.md \
|
||||
guides.md \
|
||||
guide_build_linux.md \
|
||||
guide_build_win.md \
|
||||
guide_samples.md \
|
||||
guide_tools.md \
|
||||
guide_log.md \
|
||||
guide_opencv.md \
|
||||
guide_ros.md \
|
||||
specs_data.md \
|
||||
spec_hardware_info.md \
|
||||
spec_image_params.md \
|
||||
|
@ -808,12 +801,12 @@ 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
|
||||
# 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
|
||||
# documentation (see: https://www.gnu.org/software/libiconv/) for the list of
|
||||
# possible encodings.
|
||||
# The default value is: UTF-8.
|
||||
|
||||
|
@ -891,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
|
||||
|
@ -1061,7 +1055,7 @@ 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
|
||||
# (see https://www.gnu.org/software/global/global.html). You will need version
|
||||
# 4.8.6 or higher.
|
||||
#
|
||||
# To use it do the following:
|
||||
|
@ -1206,7 +1200,7 @@ HTML_EXTRA_FILES =
|
|||
# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen
|
||||
# will adjust the colors in the style sheet 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
|
||||
# https://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.
|
||||
|
@ -1242,6 +1236,17 @@ HTML_COLORSTYLE_GAMMA = 80
|
|||
|
||||
HTML_TIMESTAMP = NO
|
||||
|
||||
# If the HTML_DYNAMIC_MENUS tag is set to YES then the generated HTML
|
||||
# documentation will contain a main index with vertical navigation menus that
|
||||
# are dynamically created via Javascript. If disabled, the navigation index will
|
||||
# consists of multiple levels of tabs that are statically embedded in every HTML
|
||||
# page. Disable this option to support browsers that do not have Javascript,
|
||||
# like the Qt help browser.
|
||||
# The default value is: YES.
|
||||
# This tag requires that the tag GENERATE_HTML is set to YES.
|
||||
|
||||
HTML_DYNAMIC_MENUS = 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.
|
||||
|
@ -1265,12 +1270,12 @@ 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
|
||||
# environment (see: https://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
|
||||
# startup. See https://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.
|
||||
|
@ -1305,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
|
||||
|
@ -1386,7 +1391,7 @@ 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).
|
||||
# (see: http://doc.qt.io/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.
|
||||
|
||||
|
@ -1394,8 +1399,7 @@ QHP_NAMESPACE = com.slightech.mynteye
|
|||
|
||||
# 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).
|
||||
# Folders (see: http://doc.qt.io/qt-4.8/qthelpproject.html#virtual-folders).
|
||||
# The default value is: doc.
|
||||
# This tag requires that the tag GENERATE_QHP is set to YES.
|
||||
|
||||
|
@ -1403,23 +1407,21 @@ 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).
|
||||
# Filters (see: http://doc.qt.io/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).
|
||||
# Filters (see: http://doc.qt.io/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).
|
||||
# http://doc.qt.io/qt-4.8/qthelpproject.html#filter-attributes).
|
||||
# This tag requires that the tag GENERATE_QHP is set to YES.
|
||||
|
||||
QHP_SECT_FILTER_ATTRS =
|
||||
|
@ -1512,7 +1514,7 @@ EXT_LINKS_IN_WINDOW = NO
|
|||
|
||||
FORMULA_FONTSIZE = 10
|
||||
|
||||
# Use the FORMULA_TRANPARENT tag to determine whether or not the images
|
||||
# Use the FORMULA_TRANSPARENT 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.
|
||||
#
|
||||
|
@ -1524,7 +1526,7 @@ FORMULA_FONTSIZE = 10
|
|||
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
|
||||
# https://www.mathjax.org) which uses client side Javascript for the rendering
|
||||
# instead of using pre-rendered 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
|
||||
|
@ -1551,11 +1553,11 @@ MATHJAX_FORMAT = HTML-CSS
|
|||
# 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.
|
||||
# MathJax from https://www.mathjax.org before deployment.
|
||||
# The default value is: https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.2/.
|
||||
# This tag requires that the tag USE_MATHJAX is set to YES.
|
||||
|
||||
MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest
|
||||
MATHJAX_RELPATH = https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.2/
|
||||
|
||||
# The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax
|
||||
# extension names that should be enabled during MathJax rendering. For example
|
||||
|
@ -1613,7 +1615,7 @@ SERVER_BASED_SEARCH = NO
|
|||
#
|
||||
# Doxygen ships with an example indexer (doxyindexer) and search engine
|
||||
# (doxysearch.cgi) which are based on the open source search engine library
|
||||
# Xapian (see: http://xapian.org/).
|
||||
# Xapian (see: https://xapian.org/).
|
||||
#
|
||||
# See the section "External Indexing and Searching" for details.
|
||||
# The default value is: NO.
|
||||
|
@ -1626,7 +1628,7 @@ EXTERNAL_SEARCH = NO
|
|||
#
|
||||
# Doxygen ships with an example indexer (doxyindexer) and search engine
|
||||
# (doxysearch.cgi) which are based on the open source search engine library
|
||||
# Xapian (see: http://xapian.org/). See the section "External Indexing and
|
||||
# Xapian (see: https://xapian.org/). See the section "External Indexing and
|
||||
# Searching" for details.
|
||||
# This tag requires that the tag SEARCHENGINE is set to YES.
|
||||
|
||||
|
@ -1815,7 +1817,7 @@ LATEX_SOURCE_CODE = NO
|
|||
|
||||
# The LATEX_BIB_STYLE tag can be used to specify the style to use for the
|
||||
# bibliography, e.g. plainnat, or ieeetr. See
|
||||
# http://en.wikipedia.org/wiki/BibTeX and \cite for more info.
|
||||
# https://en.wikipedia.org/wiki/BibTeX and \cite for more info.
|
||||
# The default value is: plain.
|
||||
# This tag requires that the tag GENERATE_LATEX is set to YES.
|
||||
|
||||
|
@ -1998,9 +2000,9 @@ DOCBOOK_PROGRAMLISTING = NO
|
|||
#---------------------------------------------------------------------------
|
||||
|
||||
# If the GENERATE_AUTOGEN_DEF tag is set to YES, doxygen will generate an
|
||||
# AutoGen Definitions (see http://autogen.sf.net) file that captures the
|
||||
# structure of the code including all documentation. Note that this feature is
|
||||
# still experimental and incomplete at the moment.
|
||||
# AutoGen Definitions (see http://autogen.sourceforge.net/) file that captures
|
||||
# the structure of the code including all documentation. Note that this feature
|
||||
# is still experimental and incomplete at the moment.
|
||||
# The default value is: NO.
|
||||
|
||||
GENERATE_AUTOGEN_DEF = NO
|
||||
|
|
|
@ -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
|
||||
```
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -1,9 +1,11 @@
|
|||
# MYNT EYE SDK {#mainpage}
|
||||
# MYNT EYE S SDK {#mainpage}
|
||||
|
||||
* API 模块
|
||||
* <a class="el" href="annotated.html">API 类</a>
|
||||
* <a class="el" href="modules.html">API 模块</a>
|
||||
* \link enumerations 枚举类型\endlink
|
||||
* \link datatypes 数据类型\endlink
|
||||
* \link utils 工具函数\endlink
|
||||
* \link calibration 内参与外参\endlink
|
||||
* 设备说明
|
||||
* <span style="font-weight:bold">设备说明</span>
|
||||
* @subpage specs_data
|
||||
* @subpage specs_ctrl
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
# 控制 API 说明 {#spec_contorl_api}
|
||||
# 控制 API 说明 {#spec_control_api}
|
||||
|
||||
控制有两种实现方式,一是通过 UVC 标准协议,二是通过 UVC 拓展通道自定义协议。
|
||||
|
||||
|
@ -24,3 +24,4 @@
|
|||
| 陀螺仪量程 | gyroscope_range | 2 | 1000 | 250 | 4000 | √ | - | XU_CAM_CTRL | 0x0100 | |
|
||||
| 加速度计低通滤波 | accelerometer_low_pass_filter | 2 | 2 | 0 | 2 | √ | - | XU_CAM_CTRL | 0x0100 | |
|
||||
| 陀螺仪低通滤波 | gyroscope__low_pass_filter | 2 | 64 | 23 | 64 | √ | - | XU_CAM_CTRL | 0x0100 | |
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
# 拓展通道说明 {#spec_contorl_channel}
|
||||
# 拓展通道说明 {#spec_control_channel}
|
||||
|
||||
| 名称 | 字段 | 地址 | 带宽 | 说明 |
|
||||
| :----- | :----- | :----- | :----- | :----- |
|
||||
|
@ -14,7 +14,7 @@
|
|||
|
||||
## 半双工通道
|
||||
|
||||
半双工通道是那些仅需 Get 或 Set 的控制通道,如请求零漂矫正。
|
||||
半双工通道是那些仅需 Set 的控制通道,如请求零漂矫正。
|
||||
|
||||
## IMU 通道
|
||||
|
||||
|
@ -25,18 +25,18 @@
|
|||
用来读写硬件信息、图像参数、 IMU 参数的通道。
|
||||
|
||||
| Name | Header | Size | File | Checksum |
|
||||
| :--- | :- | :--- | :--- | :-------- |
|
||||
| :--- | :----- | :--- | :--- | :-------- |
|
||||
| 字节数 | 1 | 2 | - | 1 |
|
||||
| 类型 | uint8_t | uint16_t | - | uint8_t |
|
||||
| 描述 | 标识 | 文件内容大小 | 文件内容 | 校验码(文件内容所有字节异或) |
|
||||
|
||||
| Header bit | Description |
|
||||
| :--------- | :---------- |
|
||||
| 0 | 0: Get; 1: Set |
|
||||
| 1~4 | 未定义 |
|
||||
| 5 | IMU 参数 |
|
||||
| 6 | 图像参数 |
|
||||
| 7 | 硬件信息 |
|
||||
| Header Bit Subscript | Description |
|
||||
| :------------------- | :---------- |
|
||||
| 0 | 硬件信息 |
|
||||
| 1 | 图像参数 |
|
||||
| 2 | IMU 参数 |
|
||||
| 3~6 | 未定义 |
|
||||
| 7 | 0: Get; 1: Set |
|
||||
|
||||
### 文件内容包
|
||||
|
||||
|
|
|
@ -13,7 +13,7 @@
|
|||
| 畸变模型 | model | - | 1 | uint8_t; pinhole,... |
|
||||
| 畸变参数 | coeffs[5] | - | 40 | double; k1,k2,p1,p2,k3 |
|
||||
|
||||
> 图像内参不同分辨率会不同。如果多分辨率的话,就会有多个。
|
||||
> 图像分辨率不同,内参不同。多分辨率的话,需有多个内参。
|
||||
|
||||
## 图像外参
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
# 设备控制说明 {#specs_ctrl}
|
||||
|
||||
* @subpage spec_contorl_api
|
||||
* @subpage spec_contorl_channel
|
||||
* @subpage spec_control_api
|
||||
* @subpage spec_control_channel
|
||||
|
|
1
include/deprecated/mynteye/api.h
Normal file
|
@ -0,0 +1 @@
|
|||
#include "mynteye/api/api.h"
|
1
include/deprecated/mynteye/callbacks.h
Normal file
|
@ -0,0 +1 @@
|
|||
#include "mynteye/device/callbacks.h"
|
1
include/deprecated/mynteye/context.h
Normal file
|
@ -0,0 +1 @@
|
|||
#include "mynteye/device/context.h"
|
1
include/deprecated/mynteye/device.h
Normal file
|
@ -0,0 +1 @@
|
|||
#include "mynteye/device/device.h"
|
1
include/deprecated/mynteye/files.h
Normal file
|
@ -0,0 +1 @@
|
|||
#include "mynteye/util/files.h"
|
1
include/deprecated/mynteye/glog_init.h
Normal file
|
@ -0,0 +1 @@
|
|||
#include "mynteye/logger.h"
|
1
include/deprecated/mynteye/object.h
Normal file
|
@ -0,0 +1 @@
|
|||
#include "mynteye/api/object.h"
|
1
include/deprecated/mynteye/plugin.h
Normal file
|
@ -0,0 +1 @@
|
|||
#include "mynteye/api/plugin.h"
|
1
include/deprecated/mynteye/strings.h
Normal file
|
@ -0,0 +1 @@
|
|||
#include "mynteye/util/strings.h"
|
1
include/deprecated/mynteye/times.h
Normal file
|
@ -0,0 +1 @@
|
|||
#include "mynteye/util/times.h"
|
1
include/deprecated/mynteye/utils.h
Normal file
|
@ -0,0 +1 @@
|
|||
#include "mynteye/device/utils.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 <opencv2/core/core.hpp>
|
||||
|
||||
#include <limits>
|
||||
#include <memory>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
#include <opencv2/core/core.hpp>
|
||||
|
||||
#include "mynteye/mynteye.h"
|
||||
#include "mynteye/types.h"
|
||||
|
||||
|
@ -49,6 +49,8 @@ struct MYNTEYE_API StreamData {
|
|||
cv::Mat frame;
|
||||
/** Raw frame. */
|
||||
std::shared_ptr<device::Frame> frame_raw;
|
||||
/** Frame ID. */
|
||||
std::uint16_t frame_id;
|
||||
|
||||
bool operator==(const StreamData &other) const {
|
||||
if (img && other.img) {
|
||||
|
@ -292,4 +294,4 @@ class MYNTEYE_API API {
|
|||
|
||||
MYNTEYE_END_NAMESPACE
|
||||
|
||||
#endif // MYNTEYE_API_H_ NOLINT
|
||||
#endif // MYNTEYE_API_API_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 <opencv2/core/core.hpp>
|
||||
|
||||
#include <memory>
|
||||
|
||||
#include <opencv2/core/core.hpp>
|
||||
|
||||
#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<ImgData> &data)
|
||||
: value(value), id(id), data(data) {}
|
||||
|
||||
/** The value */
|
||||
cv::Mat value;
|
||||
/** The id **/
|
||||
std::uint16_t id;
|
||||
/** The data **/
|
||||
std::shared_ptr<ImgData> 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<ImgData> &first_data,
|
||||
const cv::Mat &second, std::uint16_t second_id,
|
||||
const std::shared_ptr<ImgData> &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<ImgData> first_data;
|
||||
|
||||
/** The second value */
|
||||
cv::Mat second;
|
||||
/** The second id **/
|
||||
std::uint16_t second_id;
|
||||
/** The second data **/
|
||||
std::shared_ptr<ImgData> 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_
|
|
@ -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 <opencv2/core/core.hpp>
|
||||
|
||||
#include <cstdint>
|
||||
|
||||
#include <opencv2/core/core.hpp>
|
||||
|
||||
#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_
|
|
@ -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 <cstdint>
|
||||
|
@ -113,6 +113,8 @@ struct MYNTEYE_API StreamData {
|
|||
std::shared_ptr<ImgData> img;
|
||||
/** Frame. */
|
||||
std::shared_ptr<Frame> frame;
|
||||
/** Frame ID. */
|
||||
std::uint16_t frame_id;
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -131,4 +133,4 @@ using MotionCallback = std::function<void(const MotionData &data)>;
|
|||
|
||||
MYNTEYE_END_NAMESPACE
|
||||
|
||||
#endif // MYNTEYE_CALLBACKS_H_ NOLINT
|
||||
#endif // 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_CONTEXT_H_ // NOLINT
|
||||
#define MYNTEYE_CONTEXT_H_
|
||||
#ifndef MYNTEYE_DEVICE_CONTEXT_H_
|
||||
#define MYNTEYE_DEVICE_CONTEXT_H_
|
||||
#pragma once
|
||||
|
||||
#include <memory>
|
||||
|
@ -53,4 +53,4 @@ class MYNTEYE_API Context {
|
|||
|
||||
MYNTEYE_END_NAMESPACE
|
||||
|
||||
#endif // MYNTEYE_CONTEXT_H_ NOLINT
|
||||
#endif // MYNTEYE_DEVICE_CONTEXT_H_
|
|
@ -11,21 +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 <limits>
|
||||
#include <map>
|
||||
#include <memory>
|
||||
#include <mutex>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
#include "internal/channels.h"
|
||||
#include "mynteye/callbacks.h"
|
||||
#include "mynteye/mynteye.h"
|
||||
#include "mynteye/types.h"
|
||||
#include "mynteye/device/callbacks.h"
|
||||
|
||||
MYNTEYE_BEGIN_NAMESPACE
|
||||
|
||||
|
@ -253,8 +251,11 @@ class MYNTEYE_API Device {
|
|||
/**
|
||||
* Enable cache motion datas.
|
||||
*/
|
||||
void EnableMotionDatas(
|
||||
std::size_t max_size = std::numeric_limits<std::size_t>::max());
|
||||
void EnableMotionDatas();
|
||||
/**
|
||||
* Enable cache motion datas.
|
||||
*/
|
||||
void EnableMotionDatas(std::size_t max_size);
|
||||
/**
|
||||
* Get the motion datas.
|
||||
*/
|
||||
|
@ -339,4 +340,4 @@ class MYNTEYE_API Device {
|
|||
|
||||
MYNTEYE_END_NAMESPACE
|
||||
|
||||
#endif // MYNTEYE_DEVICE_H_ NOLINT
|
||||
#endif // MYNTEYE_DEVICE_DEVICE_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 <memory>
|
||||
#include <string>
|
||||
|
||||
#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_
|
|
@ -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 <TargetConditionals.h>
|
||||
#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)
|
||||
#if defined(MYNTEYE_OS_WIN) && !defined(MYNTEYE_OS_MINGW) && \
|
||||
!defined(MYNTEYE_OS_CYGWIN)
|
||||
#define MYNTEYE_OS_SEP "\\"
|
||||
#else
|
||||
#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 <typename... T>
|
||||
void unused(T &&...) {}
|
||||
#define MYNTEYE_UNUSED(x) (void)x;
|
||||
|
||||
#endif // MYNTEYE_GLOBAL_H_
|
||||
|
|
|
@ -103,7 +103,7 @@
|
|||
#include "mynteye/mynteye.h"
|
||||
|
||||
#ifdef MYNTEYE_OS_ANDROID
|
||||
#include <android/log.h>
|
||||
# include <android/log.h>
|
||||
#endif // ANDROID
|
||||
|
||||
// Log severity level constants.
|
||||
|
@ -144,10 +144,13 @@ const int INFO = ::INFO;
|
|||
class MYNTEYE_API LogSink {
|
||||
public:
|
||||
virtual ~LogSink() {}
|
||||
virtual void send(
|
||||
LogSeverity severity, const char *full_filename,
|
||||
const char *base_filename, int line, const struct tm *tm_time,
|
||||
const char *message, size_t message_len) = 0;
|
||||
virtual void send(LogSeverity severity,
|
||||
const char* full_filename,
|
||||
const char* base_filename,
|
||||
int line,
|
||||
const struct tm* tm_time,
|
||||
const char* message,
|
||||
size_t message_len) = 0;
|
||||
virtual void WaitTillSent() = 0;
|
||||
};
|
||||
|
||||
|
@ -157,7 +160,7 @@ MYNTEYE_API extern std::set<LogSink *> log_sinks_global;
|
|||
// 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*/) {
|
||||
inline void InitGoogleLogging(char */*argv*/) {
|
||||
// Do nothing; this is ignored.
|
||||
}
|
||||
|
||||
|
@ -205,8 +208,8 @@ class MYNTEYE_API MessageLogger {
|
|||
|
||||
// Bound the logging level.
|
||||
const int kMaxVerboseLevel = 2;
|
||||
int android_level_index =
|
||||
std::min(std::max(FATAL, severity_), kMaxVerboseLevel) - FATAL;
|
||||
int android_level_index = std::min(std::max(FATAL, severity_),
|
||||
kMaxVerboseLevel) - FATAL;
|
||||
int android_log_level = android_log_levels[android_level_index];
|
||||
|
||||
// Output the log string the Android log at the appropriate level.
|
||||
|
@ -214,7 +217,9 @@ class MYNTEYE_API MessageLogger {
|
|||
|
||||
// Indicate termination if needed.
|
||||
if (severity_ == FATAL) {
|
||||
__android_log_write(ANDROID_LOG_FATAL, tag_.c_str(), "terminating.\n");
|
||||
__android_log_write(ANDROID_LOG_FATAL,
|
||||
tag_.c_str(),
|
||||
"terminating.\n");
|
||||
}
|
||||
#else
|
||||
// If not building on Android, log all output to std::cerr.
|
||||
|
@ -232,24 +237,21 @@ class MYNTEYE_API MessageLogger {
|
|||
}
|
||||
|
||||
// Return the stream associated with the logger object.
|
||||
std::stringstream &stream() {
|
||||
return stream_;
|
||||
}
|
||||
std::stringstream &stream() { return stream_; }
|
||||
|
||||
private:
|
||||
void LogToSinks(int severity) {
|
||||
time_t rawtime;
|
||||
struct tm *timeinfo;
|
||||
struct tm* timeinfo;
|
||||
|
||||
time(&rawtime);
|
||||
time (&rawtime);
|
||||
timeinfo = localtime(&rawtime);
|
||||
std::set<google::LogSink *>::iterator iter;
|
||||
std::set<google::LogSink*>::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());
|
||||
(*iter)->send(severity, file_.c_str(), filename_only_.c_str(), line_,
|
||||
timeinfo, stream_.str().c_str(), stream_.str().size());
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -305,19 +307,17 @@ class MYNTEYE_API MessageLogger {
|
|||
// is not used" and "statement has no effect".
|
||||
class MYNTEYE_API LoggerVoidify {
|
||||
public:
|
||||
LoggerVoidify() {}
|
||||
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) \
|
||||
(static_cast<int>(severity) > google::log_severity_global || !(condition)) \
|
||||
? (void)0 \
|
||||
: LoggerVoidify() & \
|
||||
MessageLogger((char *)__FILE__, __LINE__, "native", severity) \
|
||||
.stream()
|
||||
(static_cast<int>(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))
|
||||
|
@ -326,23 +326,23 @@ class MYNTEYE_API LoggerVoidify {
|
|||
// google3 code is discouraged and the following shortcut exists for
|
||||
// backward compatibility with existing code.
|
||||
#ifdef MYNTEYE_MAX_LOG_LEVEL
|
||||
#define LOG(n) LOG_IF(n, (n <= MYNTEYE_MAX_LOG_LEVEL))
|
||||
#define VLOG(n) LOG_IF(n, (n <= MYNTEYE_MAX_LOG_LEVEL))
|
||||
#define LG LOG_IF(INFO, (INFO <= MYNTEYE_MAX_LOG_LEVEL))
|
||||
#define VLOG_IF(n, condition) \
|
||||
# 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) 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)
|
||||
# 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 MYNTEYE_MAX_LOG_LEVEL.
|
||||
#ifndef MYNTEYE_MAX_LOG_LEVEL
|
||||
#define VLOG_IS_ON(x) (1)
|
||||
# define VLOG_IS_ON(x) (1)
|
||||
#else
|
||||
#define VLOG_IS_ON(x) (x <= MYNTEYE_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)
|
||||
|
@ -351,34 +351,32 @@ class MYNTEYE_API LoggerVoidify {
|
|||
#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)
|
||||
# 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)
|
||||
# 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)
|
||||
# define VLOG_IS_ON(x) (1+2)
|
||||
#else
|
||||
#define VLOG_IS_ON(x) (x + 2 <= MYNTEYE_MAX_LOG_LEVEL)
|
||||
# define VLOG_IS_ON(x) (x+2 <= MYNTEYE_MAX_LOG_LEVEL)
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#ifndef NDEBUG
|
||||
#define DLOG LOG
|
||||
# define DLOG LOG
|
||||
#else
|
||||
#define DLOG(severity) \
|
||||
true ? (void)0 \
|
||||
: LoggerVoidify() & \
|
||||
MessageLogger((char *)__FILE__, __LINE__, "native", severity) \
|
||||
.stream()
|
||||
# define DLOG(severity) true ? (void) 0 : LoggerVoidify() & \
|
||||
MessageLogger((char *)__FILE__, __LINE__, "native", severity).stream()
|
||||
#endif
|
||||
|
||||
|
||||
// Log a message and terminate.
|
||||
template <class T>
|
||||
template<class T>
|
||||
void LogMessageFatal(const char *file, int line, const T &message) {
|
||||
MessageLogger(file, line, "native", FATAL).stream() << message;
|
||||
}
|
||||
|
@ -386,26 +384,24 @@ void LogMessageFatal(const char *file, int line, const T &message) {
|
|||
// ---------------------------- CHECK macros ---------------------------------
|
||||
|
||||
// Check for a given boolean condition.
|
||||
#define CHECK(condition) \
|
||||
LOG_IF_FALSE(FATAL, condition) << "Check failed: " #condition " "
|
||||
#define CHECK(condition) LOG_IF_FALSE(FATAL, condition) \
|
||||
<< "Check failed: " #condition " "
|
||||
|
||||
#ifndef NDEBUG
|
||||
// Debug only version of CHECK
|
||||
#define DCHECK(condition) \
|
||||
LOG_IF_FALSE(FATAL, condition) << "Check failed: " #condition " "
|
||||
# define DCHECK(condition) LOG_IF_FALSE(FATAL, condition) \
|
||||
<< "Check failed: " #condition " "
|
||||
#else
|
||||
// Optimized version - generates no code.
|
||||
#define DCHECK(condition) \
|
||||
if (false) \
|
||||
LOG_IF_FALSE(FATAL, condition) << "Check failed: " #condition " "
|
||||
# define DCHECK(condition) if (false) LOG_IF_FALSE(FATAL, condition) \
|
||||
<< "Check failed: " #condition " "
|
||||
#endif // NDEBUG
|
||||
|
||||
// ------------------------- CHECK_OP macros ---------------------------------
|
||||
|
||||
// Generic binary operator check macro. This should not be directly invoked,
|
||||
// instead use the binary comparison macros defined below.
|
||||
#define CHECK_OP(val1, val2, op) \
|
||||
LOG_IF_FALSE(FATAL, (val1 op val2)) \
|
||||
#define CHECK_OP(val1, val2, op) LOG_IF_FALSE(FATAL, (val1 op val2)) \
|
||||
<< "Check failed: " #val1 " " #op " " #val2 " "
|
||||
|
||||
// Check_op macro definitions
|
||||
|
@ -418,32 +414,20 @@ void LogMessageFatal(const char *file, int line, const T &message) {
|
|||
|
||||
#ifndef NDEBUG
|
||||
// Debug only versions of CHECK_OP macros.
|
||||
#define DCHECK_EQ(val1, val2) CHECK_OP(val1, val2, ==)
|
||||
#define DCHECK_NE(val1, val2) CHECK_OP(val1, val2, !=)
|
||||
#define DCHECK_LE(val1, val2) CHECK_OP(val1, val2, <=)
|
||||
#define DCHECK_LT(val1, val2) CHECK_OP(val1, val2, <)
|
||||
#define DCHECK_GE(val1, val2) CHECK_OP(val1, val2, >=)
|
||||
#define DCHECK_GT(val1, val2) CHECK_OP(val1, val2, >)
|
||||
# define DCHECK_EQ(val1, val2) CHECK_OP(val1, val2, ==)
|
||||
# define DCHECK_NE(val1, val2) CHECK_OP(val1, val2, !=)
|
||||
# define DCHECK_LE(val1, val2) CHECK_OP(val1, val2, <=)
|
||||
# define DCHECK_LT(val1, val2) CHECK_OP(val1, val2, <)
|
||||
# define DCHECK_GE(val1, val2) CHECK_OP(val1, val2, >=)
|
||||
# define DCHECK_GT(val1, val2) CHECK_OP(val1, val2, >)
|
||||
#else
|
||||
// These versions generate no code in optimized mode.
|
||||
#define DCHECK_EQ(val1, val2) \
|
||||
if (false) \
|
||||
CHECK_OP(val1, val2, ==)
|
||||
#define DCHECK_NE(val1, val2) \
|
||||
if (false) \
|
||||
CHECK_OP(val1, val2, !=)
|
||||
#define DCHECK_LE(val1, val2) \
|
||||
if (false) \
|
||||
CHECK_OP(val1, val2, <=)
|
||||
#define DCHECK_LT(val1, val2) \
|
||||
if (false) \
|
||||
CHECK_OP(val1, val2, <)
|
||||
#define DCHECK_GE(val1, val2) \
|
||||
if (false) \
|
||||
CHECK_OP(val1, val2, >=)
|
||||
#define DCHECK_GT(val1, val2) \
|
||||
if (false) \
|
||||
CHECK_OP(val1, val2, >)
|
||||
# define DCHECK_EQ(val1, val2) if (false) CHECK_OP(val1, val2, ==)
|
||||
# define DCHECK_NE(val1, val2) if (false) CHECK_OP(val1, val2, !=)
|
||||
# define DCHECK_LE(val1, val2) if (false) CHECK_OP(val1, val2, <=)
|
||||
# define DCHECK_LT(val1, val2) if (false) CHECK_OP(val1, val2, <)
|
||||
# define DCHECK_GE(val1, val2) if (false) CHECK_OP(val1, val2, >=)
|
||||
# define DCHECK_GT(val1, val2) if (false) CHECK_OP(val1, val2, >)
|
||||
#endif // NDEBUG
|
||||
|
||||
// ---------------------------CHECK_NOTNULL macros ---------------------------
|
||||
|
@ -451,7 +435,7 @@ void LogMessageFatal(const char *file, int line, const T &message) {
|
|||
// Helpers for CHECK_NOTNULL(). Two are necessary to support both raw pointers
|
||||
// and smart pointers.
|
||||
template <typename T>
|
||||
T &CheckNotNullCommon(const char *file, int line, const char *names, T &t) {
|
||||
T& CheckNotNullCommon(const char *file, int line, const char *names, T& t) {
|
||||
if (t == NULL) {
|
||||
LogMessageFatal(file, line, std::string(names));
|
||||
}
|
||||
|
@ -459,12 +443,12 @@ T &CheckNotNullCommon(const char *file, int line, const char *names, T &t) {
|
|||
}
|
||||
|
||||
template <typename T>
|
||||
T *CheckNotNull(const char *file, int line, const char *names, T *t) {
|
||||
T* CheckNotNull(const char *file, int line, const char *names, T* t) {
|
||||
return CheckNotNullCommon(file, line, names, t);
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
T &CheckNotNull(const char *file, int line, const char *names, T &t) {
|
||||
T& CheckNotNull(const char *file, int line, const char *names, T& t) {
|
||||
return CheckNotNullCommon(file, line, names, t);
|
||||
}
|
||||
|
||||
|
@ -478,8 +462,7 @@ T &CheckNotNull(const char *file, int line, const char *names, T &t) {
|
|||
CheckNotNull(__FILE__, __LINE__, "'" #val "' Must be non NULL", (val))
|
||||
#else
|
||||
// Optimized version - generates no code.
|
||||
#define DCHECK_NOTNULL(val) \
|
||||
if (false) \
|
||||
#define DCHECK_NOTNULL(val) if (false)\
|
||||
CheckNotNull(__FILE__, __LINE__, "'" #val "' Must be non NULL", (val))
|
||||
#endif // NDEBUG
|
||||
|
||||
|
|
|
@ -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)
|
||||
|
@ -58,7 +58,14 @@ MYNTEYE_API_VERSION_CHECK( \
|
|||
# define MYNTEYE_USE_NAMESPACE
|
||||
#endif
|
||||
|
||||
constexpr char MYNTEYE_SDK_ROOT_DIR[] = "@MYNTEYE_SDK_ROOT_DIR@";
|
||||
constexpr char MYNTEYE_SDK_INSTALL_DIR[] = "@MYNTEYE_SDK_INSTALL_DIR@";
|
||||
const char MYNTEYE_SDK_ROOT_DIR[] = "@MYNTEYE_SDK_ROOT_DIR@";
|
||||
const char MYNTEYE_SDK_INSTALL_DIR[] = "@MYNTEYE_SDK_INSTALL_DIR@";
|
||||
|
||||
MYNTEYE_BEGIN_NAMESPACE
|
||||
|
||||
template <typename... T>
|
||||
void UNUSED(T &&...) {}
|
||||
|
||||
MYNTEYE_END_NAMESPACE
|
||||
|
||||
#endif // MYNTEYE_MYNTEYE_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
|
||||
|
||||
|
@ -198,6 +198,7 @@ enum class Option : std::uint8_t {
|
|||
/** Erase chip */
|
||||
ERASE_CHIP,
|
||||
/**
|
||||
<<<<<<< HEAD
|
||||
* min exposure time, valid if auto-exposure
|
||||
*
|
||||
* range: [0,1000], default: 0
|
||||
|
@ -207,11 +208,17 @@ enum class Option : std::uint8_t {
|
|||
* The range of accelerometer
|
||||
*
|
||||
* values: {6,12,24,48}, default: 6
|
||||
=======
|
||||
* The range of accelerometer
|
||||
*
|
||||
* values: {4,8,16,32}, default: 8
|
||||
>>>>>>> origin/develop
|
||||
*/
|
||||
ACCELEROMETER_RANGE,
|
||||
/**
|
||||
* The range of gyroscope
|
||||
*
|
||||
<<<<<<< HEAD
|
||||
* values: {250,500,1000,2000,4000}, default: 1000
|
||||
*/
|
||||
GYROSCOPE_RANGE,
|
||||
|
@ -227,6 +234,11 @@ enum class Option : std::uint8_t {
|
|||
* values: {23,64}, default: 64
|
||||
*/
|
||||
GYROSCOPE_LOW_PASS_FILTER,
|
||||
=======
|
||||
* values: {500,1000,2000,4000}, default: 1000
|
||||
*/
|
||||
GYROSCOPE_RANGE,
|
||||
>>>>>>> origin/develop
|
||||
/** Last guard */
|
||||
LAST
|
||||
};
|
||||
|
@ -601,4 +613,4 @@ std::ostream &operator<<(std::ostream &os, const OptionInfo &info);
|
|||
|
||||
MYNTEYE_END_NAMESPACE
|
||||
|
||||
#endif // MYNTEYE_TYPES_H_ NOLINT
|
||||
#endif // MYNTEYE_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_FILES_H_ // NOLINT
|
||||
#define MYNTEYE_INTERNAL_FILES_H_
|
||||
#ifndef MYNTEYE_UTIL_FILES_H_
|
||||
#define MYNTEYE_UTIL_FILES_H_
|
||||
#pragma once
|
||||
|
||||
#include <string>
|
||||
|
@ -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_
|
|
@ -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 <stdexcept>
|
||||
|
@ -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_
|
|
@ -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 <chrono>
|
||||
|
@ -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_
|
|
@ -16,4 +16,7 @@
|
|||
set(mynteye_WITH_API @WITH_API@)
|
||||
set(mynteye_WITH_GLOG @WITH_GLOG@)
|
||||
|
||||
set(mynteye_WITH_API @WITH_API@)
|
||||
set(mynteye_WITH_GLOG @WITH_GLOG@)
|
||||
|
||||
include("${CMAKE_CURRENT_LIST_DIR}/mynteye-targets.cmake")
|
||||
|
|
76
platforms/projects/vs2017/README.md
Normal file
|
@ -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.
|
||||
|
||||
<!--
|
||||
![](images/10_path.png)
|
||||
-->
|
BIN
platforms/projects/vs2017/images/10_path.png
Normal file
After Width: | Height: | Size: 42 KiB |
BIN
platforms/projects/vs2017/images/1_new_pro.png
Normal file
After Width: | Height: | Size: 27 KiB |
BIN
platforms/projects/vs2017/images/2_new_pro.png
Normal file
After Width: | Height: | Size: 25 KiB |
BIN
platforms/projects/vs2017/images/3_new_pro.png
Normal file
After Width: | Height: | Size: 30 KiB |
BIN
platforms/projects/vs2017/images/4_config.png
Normal file
After Width: | Height: | Size: 22 KiB |
BIN
platforms/projects/vs2017/images/5_config_include.png
Normal file
After Width: | Height: | Size: 39 KiB |
BIN
platforms/projects/vs2017/images/6_config_lib_dir.png
Normal file
After Width: | Height: | Size: 42 KiB |
BIN
platforms/projects/vs2017/images/7_config_lib.png
Normal file
After Width: | Height: | Size: 32 KiB |
BIN
platforms/projects/vs2017/images/8_config_debug_lib.png
Normal file
After Width: | Height: | Size: 33 KiB |
BIN
platforms/projects/vs2017/images/9_run_x64.png
Normal file
After Width: | Height: | Size: 60 KiB |
4
platforms/projects/vs2017/mynteyes_demo/.gitignore
vendored
Normal file
|
@ -0,0 +1,4 @@
|
|||
/.vs/
|
||||
/x64/
|
||||
/mynteyes_demo/x64/
|
||||
/mynteyes_demo/*.user
|
31
platforms/projects/vs2017/mynteyes_demo/mynteyes_demo.sln
Normal file
|
@ -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
|
|
@ -0,0 +1,177 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<Project DefaultTargets="Build" ToolsVersion="15.0" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
|
||||
<ItemGroup Label="ProjectConfigurations">
|
||||
<ProjectConfiguration Include="Debug|Win32">
|
||||
<Configuration>Debug</Configuration>
|
||||
<Platform>Win32</Platform>
|
||||
</ProjectConfiguration>
|
||||
<ProjectConfiguration Include="Release|Win32">
|
||||
<Configuration>Release</Configuration>
|
||||
<Platform>Win32</Platform>
|
||||
</ProjectConfiguration>
|
||||
<ProjectConfiguration Include="Debug|x64">
|
||||
<Configuration>Debug</Configuration>
|
||||
<Platform>x64</Platform>
|
||||
</ProjectConfiguration>
|
||||
<ProjectConfiguration Include="Release|x64">
|
||||
<Configuration>Release</Configuration>
|
||||
<Platform>x64</Platform>
|
||||
</ProjectConfiguration>
|
||||
</ItemGroup>
|
||||
<PropertyGroup Label="Globals">
|
||||
<VCProjectVersion>15.0</VCProjectVersion>
|
||||
<ProjectGuid>{49798F84-3EA3-4CB5-A873-6163DB4B4A43}</ProjectGuid>
|
||||
<Keyword>Win32Proj</Keyword>
|
||||
<RootNamespace>mynteyesdemo</RootNamespace>
|
||||
<WindowsTargetPlatformVersion>10.0.17134.0</WindowsTargetPlatformVersion>
|
||||
</PropertyGroup>
|
||||
<Import Project="$(VCTargetsPath)\Microsoft.Cpp.Default.props" />
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'" Label="Configuration">
|
||||
<ConfigurationType>Application</ConfigurationType>
|
||||
<UseDebugLibraries>true</UseDebugLibraries>
|
||||
<PlatformToolset>v141</PlatformToolset>
|
||||
<CharacterSet>Unicode</CharacterSet>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Release|Win32'" Label="Configuration">
|
||||
<ConfigurationType>Application</ConfigurationType>
|
||||
<UseDebugLibraries>false</UseDebugLibraries>
|
||||
<PlatformToolset>v141</PlatformToolset>
|
||||
<WholeProgramOptimization>true</WholeProgramOptimization>
|
||||
<CharacterSet>Unicode</CharacterSet>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|x64'" Label="Configuration">
|
||||
<ConfigurationType>Application</ConfigurationType>
|
||||
<UseDebugLibraries>true</UseDebugLibraries>
|
||||
<PlatformToolset>v141</PlatformToolset>
|
||||
<CharacterSet>Unicode</CharacterSet>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Release|x64'" Label="Configuration">
|
||||
<ConfigurationType>Application</ConfigurationType>
|
||||
<UseDebugLibraries>false</UseDebugLibraries>
|
||||
<PlatformToolset>v141</PlatformToolset>
|
||||
<WholeProgramOptimization>true</WholeProgramOptimization>
|
||||
<CharacterSet>Unicode</CharacterSet>
|
||||
</PropertyGroup>
|
||||
<Import Project="$(VCTargetsPath)\Microsoft.Cpp.props" />
|
||||
<ImportGroup Label="ExtensionSettings">
|
||||
</ImportGroup>
|
||||
<ImportGroup Label="Shared">
|
||||
</ImportGroup>
|
||||
<ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
|
||||
<Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
|
||||
</ImportGroup>
|
||||
<ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
|
||||
<Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
|
||||
</ImportGroup>
|
||||
<ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Debug|x64'">
|
||||
<Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
|
||||
</ImportGroup>
|
||||
<ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Release|x64'">
|
||||
<Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
|
||||
</ImportGroup>
|
||||
<PropertyGroup Label="UserMacros" />
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
|
||||
<LinkIncremental>true</LinkIncremental>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|x64'">
|
||||
<LinkIncremental>true</LinkIncremental>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
|
||||
<LinkIncremental>false</LinkIncremental>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Release|x64'">
|
||||
<LinkIncremental>false</LinkIncremental>
|
||||
</PropertyGroup>
|
||||
<ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
|
||||
<ClCompile>
|
||||
<PrecompiledHeader>Use</PrecompiledHeader>
|
||||
<WarningLevel>Level3</WarningLevel>
|
||||
<Optimization>Disabled</Optimization>
|
||||
<SDLCheck>true</SDLCheck>
|
||||
<PreprocessorDefinitions>WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions)</PreprocessorDefinitions>
|
||||
<ConformanceMode>true</ConformanceMode>
|
||||
<AdditionalIncludeDirectories>$(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\include;$(MYNTEYES_SDK_ROOT)\include;%(AdditionalIncludeDirectories)</AdditionalIncludeDirectories>
|
||||
</ClCompile>
|
||||
<Link>
|
||||
<SubSystem>Console</SubSystem>
|
||||
<GenerateDebugInformation>true</GenerateDebugInformation>
|
||||
<AdditionalLibraryDirectories>$(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\x64\vc15\lib;$(MYNTEYES_SDK_ROOT)\lib;%(AdditionalLibraryDirectories)</AdditionalLibraryDirectories>
|
||||
<AdditionalDependencies>mynteyed.lib;opencv_world343d.lib;%(AdditionalDependencies)</AdditionalDependencies>
|
||||
</Link>
|
||||
</ItemDefinitionGroup>
|
||||
<ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Debug|x64'">
|
||||
<ClCompile>
|
||||
<PrecompiledHeader>Use</PrecompiledHeader>
|
||||
<WarningLevel>Level3</WarningLevel>
|
||||
<Optimization>Disabled</Optimization>
|
||||
<SDLCheck>true</SDLCheck>
|
||||
<PreprocessorDefinitions>_DEBUG;_CONSOLE;%(PreprocessorDefinitions)</PreprocessorDefinitions>
|
||||
<ConformanceMode>true</ConformanceMode>
|
||||
<AdditionalIncludeDirectories>$(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\include;$(MYNTEYES_SDK_ROOT)\include;%(AdditionalIncludeDirectories)</AdditionalIncludeDirectories>
|
||||
</ClCompile>
|
||||
<Link>
|
||||
<SubSystem>Console</SubSystem>
|
||||
<GenerateDebugInformation>true</GenerateDebugInformation>
|
||||
<AdditionalLibraryDirectories>$(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\x64\vc15\lib;$(MYNTEYES_SDK_ROOT)\lib;%(AdditionalLibraryDirectories)</AdditionalLibraryDirectories>
|
||||
<AdditionalDependencies>mynteyed.lib;opencv_world343d.lib;%(AdditionalDependencies)</AdditionalDependencies>
|
||||
</Link>
|
||||
</ItemDefinitionGroup>
|
||||
<ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
|
||||
<ClCompile>
|
||||
<PrecompiledHeader>Use</PrecompiledHeader>
|
||||
<WarningLevel>Level3</WarningLevel>
|
||||
<Optimization>MaxSpeed</Optimization>
|
||||
<FunctionLevelLinking>true</FunctionLevelLinking>
|
||||
<IntrinsicFunctions>true</IntrinsicFunctions>
|
||||
<SDLCheck>true</SDLCheck>
|
||||
<PreprocessorDefinitions>WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions)</PreprocessorDefinitions>
|
||||
<ConformanceMode>true</ConformanceMode>
|
||||
<AdditionalIncludeDirectories>$(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\include;$(MYNTEYES_SDK_ROOT)\include;%(AdditionalIncludeDirectories)</AdditionalIncludeDirectories>
|
||||
</ClCompile>
|
||||
<Link>
|
||||
<SubSystem>Console</SubSystem>
|
||||
<EnableCOMDATFolding>true</EnableCOMDATFolding>
|
||||
<OptimizeReferences>true</OptimizeReferences>
|
||||
<GenerateDebugInformation>true</GenerateDebugInformation>
|
||||
<AdditionalLibraryDirectories>$(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\x64\vc15\lib;$(MYNTEYES_SDK_ROOT)\lib;%(AdditionalLibraryDirectories)</AdditionalLibraryDirectories>
|
||||
<AdditionalDependencies>mynteye.lib;opencv_world343.lib;%(AdditionalDependencies)</AdditionalDependencies>
|
||||
</Link>
|
||||
</ItemDefinitionGroup>
|
||||
<ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Release|x64'">
|
||||
<ClCompile>
|
||||
<PrecompiledHeader>Use</PrecompiledHeader>
|
||||
<WarningLevel>Level3</WarningLevel>
|
||||
<Optimization>MaxSpeed</Optimization>
|
||||
<FunctionLevelLinking>true</FunctionLevelLinking>
|
||||
<IntrinsicFunctions>true</IntrinsicFunctions>
|
||||
<SDLCheck>true</SDLCheck>
|
||||
<PreprocessorDefinitions>NDEBUG;_CONSOLE;%(PreprocessorDefinitions)</PreprocessorDefinitions>
|
||||
<ConformanceMode>true</ConformanceMode>
|
||||
<AdditionalIncludeDirectories>$(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\include;$(MYNTEYES_SDK_ROOT)\include;%(AdditionalIncludeDirectories)</AdditionalIncludeDirectories>
|
||||
</ClCompile>
|
||||
<Link>
|
||||
<SubSystem>Console</SubSystem>
|
||||
<EnableCOMDATFolding>true</EnableCOMDATFolding>
|
||||
<OptimizeReferences>true</OptimizeReferences>
|
||||
<GenerateDebugInformation>true</GenerateDebugInformation>
|
||||
<AdditionalLibraryDirectories>$(MYNTEYES_SDK_ROOT)\3rdparty\opencv\build\x64\vc15\lib;$(MYNTEYES_SDK_ROOT)\lib;%(AdditionalLibraryDirectories)</AdditionalLibraryDirectories>
|
||||
<AdditionalDependencies>mynteye.lib;opencv_world343.lib;%(AdditionalDependencies)</AdditionalDependencies>
|
||||
</Link>
|
||||
</ItemDefinitionGroup>
|
||||
<ItemGroup>
|
||||
<ClInclude Include="stdafx.h" />
|
||||
<ClInclude Include="targetver.h" />
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<ClCompile Include="mynteyes_demo.cpp" />
|
||||
<ClCompile Include="stdafx.cpp">
|
||||
<PrecompiledHeader Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">Create</PrecompiledHeader>
|
||||
<PrecompiledHeader Condition="'$(Configuration)|$(Platform)'=='Debug|x64'">Create</PrecompiledHeader>
|
||||
<PrecompiledHeader Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">Create</PrecompiledHeader>
|
||||
<PrecompiledHeader Condition="'$(Configuration)|$(Platform)'=='Release|x64'">Create</PrecompiledHeader>
|
||||
</ClCompile>
|
||||
</ItemGroup>
|
||||
<Import Project="$(VCTargetsPath)\Microsoft.Cpp.targets" />
|
||||
<ImportGroup Label="ExtensionTargets">
|
||||
</ImportGroup>
|
||||
</Project>
|
|
@ -0,0 +1,33 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<Project ToolsVersion="4.0" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
|
||||
<ItemGroup>
|
||||
<Filter Include="Source Files">
|
||||
<UniqueIdentifier>{4FC737F1-C7A5-4376-A066-2A32D752A2FF}</UniqueIdentifier>
|
||||
<Extensions>cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx</Extensions>
|
||||
</Filter>
|
||||
<Filter Include="Header Files">
|
||||
<UniqueIdentifier>{93995380-89BD-4b04-88EB-625FBE52EBFB}</UniqueIdentifier>
|
||||
<Extensions>h;hh;hpp;hxx;hm;inl;inc;ipp;xsd</Extensions>
|
||||
</Filter>
|
||||
<Filter Include="Resource Files">
|
||||
<UniqueIdentifier>{67DA6AB6-F800-4c08-8B7A-83BB121AAD01}</UniqueIdentifier>
|
||||
<Extensions>rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms</Extensions>
|
||||
</Filter>
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<ClInclude Include="stdafx.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="targetver.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<ClCompile Include="stdafx.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="mynteyes_demo.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
</ItemGroup>
|
||||
</Project>
|
BIN
platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/stdafx.cpp
Normal file
BIN
platforms/projects/vs2017/mynteyes_demo/mynteyes_demo/stdafx.h
Normal file
176
platforms/win/README.txt
Normal file
|
@ -0,0 +1,176 @@
|
|||
# MYNT® EYE S SDK
|
||||
|
||||
################################################################################
|
||||
Language: 简体中文
|
||||
################################################################################
|
||||
|
||||
## 如何开始使用 SDK
|
||||
|
||||
1) 运行样例程序
|
||||
|
||||
安装完 SDK 的 exe 安装包后,桌面会生成 SDK 根目录的快捷方式。
|
||||
|
||||
进入 "<SDK_ROOT_DIR>\bin\samples\tutorials" 目录,双击 "get_stereo.exe" 运行,即可看到双目实时画面。
|
||||
|
||||
2)生成样例工程
|
||||
|
||||
首先,安装好 Visual Studio 2017 <https://visualstudio.microsoft.com/> 和 CMake <https://cmake.org/> 。
|
||||
|
||||
接着,进入 "<SDK_ROOT_DIR>\samples" 目录, 双击 "generate.bat" 即可生成样例工程。
|
||||
|
||||
p.s. 样例教程,可见 https://slightech.github.io/MYNT-EYE-S-SDK/ 主页给出的 Guide 文档。
|
||||
|
||||
p.p.s. 运行结果,参考下方英文内容。
|
||||
|
||||
3)如何于 Visual Studio 2017 下使用 SDK
|
||||
|
||||
进入 "<SDK_ROOT_DIR>\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 "<SDK_ROOT_DIR>\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 <https://visualstudio.microsoft.com/> and CMake <https://cmake.org/>.
|
||||
|
||||
Second, goto the "<SDK_ROOT_DIR>\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 "<SDK_ROOT_DIR>\projects\vs2017", see the "README.md".
|
|
@ -47,7 +47,6 @@ message(STATUS "CXX_FLAGS: ${CMAKE_CXX_FLAGS}")
|
|||
|
||||
# packages
|
||||
|
||||
|
||||
LIST(APPEND CMAKE_PREFIX_PATH ${PRO_DIR}/_install/lib/cmake)
|
||||
find_package(mynteye REQUIRED)
|
||||
message(STATUS "Found mynteye: ${mynteye_VERSION}")
|
||||
|
@ -80,4 +79,6 @@ add_subdirectory(uvc)
|
|||
|
||||
# tutorials
|
||||
|
||||
add_subdirectory(tutorials)
|
||||
if(WITH_API)
|
||||
add_subdirectory(tutorials)
|
||||
endif()
|
||||
|
|
|
@ -13,9 +13,9 @@
|
|||
// limitations under the License.
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
#include "mynteye/api.h"
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/times.h"
|
||||
#include "mynteye/api/api.h"
|
||||
#include "mynteye/util/times.h"
|
||||
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
|
|
|
@ -14,10 +14,7 @@
|
|||
#include <opencv2/highgui/highgui.hpp>
|
||||
#include <opencv2/imgproc/imgproc.hpp>
|
||||
|
||||
#include "mynteye/api.h"
|
||||
|
||||
#define WIN_FLAGS \
|
||||
cv::WINDOW_AUTOSIZE | cv::WINDOW_KEEPRATIO | cv::WINDOW_GUI_NORMAL
|
||||
#include "mynteye/api/api.h"
|
||||
|
||||
namespace {
|
||||
|
||||
|
@ -32,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;
|
||||
}
|
||||
|
@ -157,14 +154,14 @@ int main(int argc, char *argv[]) {
|
|||
|
||||
api->Start(Source::VIDEO_STREAMING);
|
||||
|
||||
cv::namedWindow("frame", WIN_FLAGS);
|
||||
cv::namedWindow("depth", WIN_FLAGS);
|
||||
cv::namedWindow("region", WIN_FLAGS);
|
||||
cv::namedWindow("frame");
|
||||
cv::namedWindow("depth");
|
||||
cv::namedWindow("region");
|
||||
|
||||
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";
|
||||
|
@ -187,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);
|
||||
|
|
|
@ -15,11 +15,17 @@
|
|||
#include <opencv2/imgproc/imgproc.hpp>
|
||||
|
||||
#include "mynteye/logger.h"
|
||||
<<<<<<< HEAD
|
||||
|
||||
#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"
|
||||
>>>>>>> origin/develop
|
||||
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
|
|
|
@ -64,7 +64,7 @@ macro(make_executable2 NAME)
|
|||
endif()
|
||||
endmacro()
|
||||
|
||||
if(WITH_API)
|
||||
# packages
|
||||
|
||||
# If you install PCL to different directory, please set CMAKE_PREFIX_PATH to find it.
|
||||
#LIST(APPEND CMAKE_PREFIX_PATH /usr/local/share)
|
||||
|
@ -115,6 +115,7 @@ make_executable2(get_with_plugin SRCS data/get_with_plugin.cc WITH_OPENCV)
|
|||
## control
|
||||
|
||||
make_executable2(ctrl_framerate SRCS control/framerate.cc WITH_OPENCV)
|
||||
make_executable2(ctrl_imu_range SRCS control/imu_range.cc WITH_OPENCV)
|
||||
make_executable2(ctrl_auto_exposure
|
||||
SRCS control/auto_exposure.cc util/cv_painter.cc
|
||||
WITH_OPENCV
|
||||
|
@ -125,8 +126,6 @@ make_executable2(ctrl_manual_exposure
|
|||
)
|
||||
make_executable2(ctrl_infrared SRCS control/infrared.cc WITH_OPENCV)
|
||||
|
||||
endif()
|
||||
|
||||
# intermediate level
|
||||
|
||||
make_executable2(get_all_device_info SRCS intermediate/get_all_device_info.cc WITH_OPENCV)
|
||||
|
|
|
@ -13,8 +13,13 @@
|
|||
// limitations under the License.
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
<<<<<<< HEAD
|
||||
#include "mynteye/api.h"
|
||||
#include "mynteye/logger.h"
|
||||
=======
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/api/api.h"
|
||||
>>>>>>> origin/develop
|
||||
|
||||
#include "util/cv_painter.h"
|
||||
|
||||
|
|
|
@ -11,6 +11,7 @@
|
|||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
// See the License for the specific language governing permissions and
|
||||
// limitations under the License.
|
||||
<<<<<<< HEAD
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
#include <atomic>
|
||||
|
@ -18,6 +19,15 @@
|
|||
#include "mynteye/api.h"
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/times.h"
|
||||
=======
|
||||
#include <atomic>
|
||||
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/api/api.h"
|
||||
#include "mynteye/util/times.h"
|
||||
>>>>>>> origin/develop
|
||||
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
|
|
89
samples/tutorials/control/imu_range.cc
Normal file
|
@ -0,0 +1,89 @@
|
|||
// Copyright 2018 Slightech Co., Ltd. All rights reserved.
|
||||
//
|
||||
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||
// you may not use this file except in compliance with the License.
|
||||
// You may obtain a copy of the License at
|
||||
//
|
||||
// http://www.apache.org/licenses/LICENSE-2.0
|
||||
//
|
||||
// Unless required by applicable law or agreed to in writing, software
|
||||
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
// See the License for the specific language governing permissions and
|
||||
// limitations under the License.
|
||||
#include <atomic>
|
||||
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/api/api.h"
|
||||
#include "mynteye/util/times.h"
|
||||
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
int main(int argc, char *argv[]) {
|
||||
auto &&api = API::Create(argc, argv);
|
||||
if (!api)
|
||||
return 1;
|
||||
|
||||
// ACCELEROMETER_RANGE values: 4, 8, 16, 32
|
||||
api->SetOptionValue(Option::ACCELEROMETER_RANGE, 8);
|
||||
// GYROSCOPE_RANGE values: 500, 1000, 2000, 4000
|
||||
api->SetOptionValue(Option::GYROSCOPE_RANGE, 1000);
|
||||
|
||||
LOG(INFO) << "Set ACCELEROMETER_RANGE to "
|
||||
<< api->GetOptionValue(Option::ACCELEROMETER_RANGE);
|
||||
LOG(INFO) << "Set GYROSCOPE_RANGE to "
|
||||
<< api->GetOptionValue(Option::GYROSCOPE_RANGE);
|
||||
|
||||
// Count img
|
||||
std::atomic_uint img_count(0);
|
||||
api->SetStreamCallback(
|
||||
Stream::LEFT, [&img_count](const api::StreamData &data) {
|
||||
CHECK_NOTNULL(data.img);
|
||||
++img_count;
|
||||
});
|
||||
|
||||
// Count imu
|
||||
std::atomic_uint imu_count(0);
|
||||
api->SetMotionCallback([&imu_count](const api::MotionData &data) {
|
||||
CHECK_NOTNULL(data.imu);
|
||||
++imu_count;
|
||||
});
|
||||
|
||||
api->Start(Source::ALL);
|
||||
|
||||
cv::namedWindow("frame");
|
||||
|
||||
auto &&time_beg = times::now();
|
||||
while (true) {
|
||||
api->WaitForStreams();
|
||||
|
||||
auto &&left_data = api->GetStreamData(Stream::LEFT);
|
||||
auto &&right_data = api->GetStreamData(Stream::RIGHT);
|
||||
|
||||
cv::Mat img;
|
||||
cv::hconcat(left_data.frame, right_data.frame, img);
|
||||
cv::imshow("frame", img);
|
||||
|
||||
char key = static_cast<char>(cv::waitKey(1));
|
||||
if (key == 27 || key == 'q' || key == 'Q') { // ESC/Q
|
||||
break;
|
||||
}
|
||||
}
|
||||
auto &&time_end = times::now();
|
||||
|
||||
api->Stop(Source::ALL);
|
||||
|
||||
// Calculate img fps and imu hz
|
||||
float elapsed_ms =
|
||||
times::count<times::microseconds>(time_end - time_beg) * 0.001f;
|
||||
LOG(INFO) << "Time beg: " << times::to_local_string(time_beg)
|
||||
<< ", end: " << times::to_local_string(time_end)
|
||||
<< ", cost: " << elapsed_ms << "ms";
|
||||
LOG(INFO) << "Img count: " << img_count
|
||||
<< ", fps: " << (1000.f * img_count / elapsed_ms);
|
||||
LOG(INFO) << "Imu count: " << imu_count
|
||||
<< ", hz: " << (1000.f * imu_count / elapsed_ms);
|
||||
return 0;
|
||||
}
|
|
@ -13,8 +13,13 @@
|
|||
// limitations under the License.
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
<<<<<<< HEAD
|
||||
#include "mynteye/api.h"
|
||||
#include "mynteye/logger.h"
|
||||
=======
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/api/api.h"
|
||||
>>>>>>> origin/develop
|
||||
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
|
|
|
@ -13,8 +13,13 @@
|
|||
// limitations under the License.
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
<<<<<<< HEAD
|
||||
#include "mynteye/api.h"
|
||||
#include "mynteye/logger.h"
|
||||
=======
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/api/api.h"
|
||||
>>>>>>> origin/develop
|
||||
|
||||
#include "util/cv_painter.h"
|
||||
|
||||
|
|
|
@ -13,8 +13,12 @@
|
|||
// limitations under the License.
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
<<<<<<< HEAD
|
||||
#include "mynteye/api.h"
|
||||
#include "mynteye/logger.h"
|
||||
=======
|
||||
#include "mynteye/api/api.h"
|
||||
>>>>>>> origin/develop
|
||||
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
|
|
|
@ -11,8 +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.
|
||||
<<<<<<< HEAD
|
||||
#include "mynteye/api.h"
|
||||
#include "mynteye/logger.h"
|
||||
=======
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/api/api.h"
|
||||
>>>>>>> origin/develop
|
||||
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
|
|
|
@ -13,9 +13,13 @@
|
|||
// limitations under the License.
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
<<<<<<< HEAD
|
||||
|
||||
#include "mynteye/api.h"
|
||||
#include "mynteye/logger.h"
|
||||
=======
|
||||
#include "mynteye/api/api.h"
|
||||
>>>>>>> origin/develop
|
||||
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
|
|
|
@ -11,15 +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.
|
||||
<<<<<<< HEAD
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
=======
|
||||
>>>>>>> origin/develop
|
||||
#include <atomic>
|
||||
#include <memory>
|
||||
#include <mutex>
|
||||
#include <sstream>
|
||||
|
||||
<<<<<<< HEAD
|
||||
#include "mynteye/api.h"
|
||||
#include "mynteye/logger.h"
|
||||
=======
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/api/api.h"
|
||||
>>>>>>> origin/develop
|
||||
|
||||
#include "util/cv_painter.h"
|
||||
|
||||
|
@ -52,7 +62,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<std::mutex> _(depth_mtx);
|
||||
|
|
|
@ -11,8 +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.
|
||||
<<<<<<< HEAD
|
||||
#include "mynteye/api.h"
|
||||
#include "mynteye/logger.h"
|
||||
=======
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/api/api.h"
|
||||
>>>>>>> origin/develop
|
||||
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
|
@ -24,8 +29,8 @@ int main(int argc, char *argv[]) {
|
|||
LOG(INFO) << "Intrinsics left: {" << api->GetIntrinsics(Stream::LEFT) << "}";
|
||||
LOG(INFO) << "Intrinsics right: {" << api->GetIntrinsics(Stream::RIGHT)
|
||||
<< "}";
|
||||
LOG(INFO) << "Extrinsics left to right: {"
|
||||
<< api->GetExtrinsics(Stream::LEFT, Stream::RIGHT) << "}";
|
||||
LOG(INFO) << "Extrinsics right to left: {"
|
||||
<< api->GetExtrinsics(Stream::RIGHT, Stream::LEFT) << "}";
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -13,8 +13,13 @@
|
|||
// limitations under the License.
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
<<<<<<< HEAD
|
||||
#include "mynteye/api.h"
|
||||
#include "mynteye/logger.h"
|
||||
=======
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/api/api.h"
|
||||
>>>>>>> origin/develop
|
||||
|
||||
#include "util/cv_painter.h"
|
||||
|
||||
|
|
|
@ -11,8 +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.
|
||||
<<<<<<< HEAD
|
||||
#include "mynteye/api.h"
|
||||
#include "mynteye/logger.h"
|
||||
=======
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/api/api.h"
|
||||
>>>>>>> origin/develop
|
||||
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
|
|
|
@ -13,8 +13,12 @@
|
|||
// limitations under the License.
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
<<<<<<< HEAD
|
||||
#include "mynteye/api.h"
|
||||
#include "mynteye/logger.h"
|
||||
=======
|
||||
#include "mynteye/api/api.h"
|
||||
>>>>>>> origin/develop
|
||||
|
||||
#include "util/pc_viewer.h"
|
||||
|
||||
|
|
|
@ -13,8 +13,12 @@
|
|||
// limitations under the License.
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
<<<<<<< HEAD
|
||||
#include "mynteye/api.h"
|
||||
#include "mynteye/logger.h"
|
||||
=======
|
||||
#include "mynteye/api/api.h"
|
||||
>>>>>>> origin/develop
|
||||
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
|
|
|
@ -13,8 +13,12 @@
|
|||
// limitations under the License.
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
<<<<<<< HEAD
|
||||
#include "mynteye/api.h"
|
||||
#include "mynteye/logger.h"
|
||||
=======
|
||||
#include "mynteye/api/api.h"
|
||||
>>>>>>> origin/develop
|
||||
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
|
|