17 Commits

Author SHA1 Message Date
John Zhao
d5bdce4f75 Update README.md 2018-06-08 16:45:24 +08:00
John Zhao
7ed11b01ff Update doc version 2018-06-08 16:13:28 +08:00
John Zhao
9caf979d4c Merge branch 'feature/one-thread-read' into develop 2018-06-08 12:17:13 +08:00
John Zhao
9b91304f0b Get stream & motion datas in one thread 2018-06-07 11:19:58 +08:00
John Zhao
0286da50c6 Add intermediate tutorials 2018-06-05 15:28:10 +08:00
John Zhao
3e96e56d8b Detect OpenCV 4.x 2018-06-05 15:00:44 +08:00
John Zhao
9451fdd90c Fix view points rotation 2018-06-05 14:42:39 +08:00
John Zhao
9bb99499a2 Update TargetArch.cmake 2016-02-12 01:52:59 +08:00
John Zhao
ddb5cb46b7 Update enable plugin log info 2018-06-08 00:49:07 +08:00
John Zhao
0af640015b Detect opencv with world 2018-06-08 00:48:25 +08:00
John Zhao
064b536822 Update tutorials with opencv 2018-06-08 00:22:59 +08:00
John Zhao
209617dd24 Get compiler version values 2018-06-07 23:47:01 +08:00
John Zhao
ac88a68ebc Update build.info and support native system on win 2018-06-07 23:32:36 +08:00
John Zhao
ee6d9f5a3b Use absolute paths in bat 2018-06-07 21:40:41 +08:00
John Zhao
09fb4c04df Obtain raw frame in api stream data 2018-06-07 17:39:51 +08:00
John Zhao
22ea971407 Fix default int value in build.info 2018-06-07 16:23:38 +08:00
John Zhao
87458482d9 Update default topics 2018-06-07 12:45:23 +08:00
29 changed files with 635 additions and 175 deletions

View File

@@ -57,8 +57,12 @@ if(Boost_FOUND)
set(WITH_BOOST_FILESYSTEM true)
add_definitions(-DWITH_FILESYSTEM)
add_definitions(-DWITH_BOOST_FILESYSTEM)
message(STATUS "Found boost filesystem: ${Boost_VERSION}")
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)
@@ -72,8 +76,13 @@ set(MYNTEYE_NAME ${PROJECT_NAME})
set(MYNTEYE_NAMESPACE "mynteye")
message(STATUS "Namespace: ${MYNTEYE_NAMESPACE}")
if(MSVC)
string(REPLACE "/" "\\\\" MYNTEYE_SDK_ROOT_DIR "${CMAKE_CURRENT_SOURCE_DIR}")
string(REPLACE "/" "\\\\" MYNTEYE_SDK_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}")
else()
file(TO_NATIVE_PATH "${CMAKE_CURRENT_SOURCE_DIR}" MYNTEYE_SDK_ROOT_DIR)
file(TO_NATIVE_PATH "${CMAKE_INSTALL_PREFIX}" MYNTEYE_SDK_INSTALL_DIR)
endif()
configure_file(
include/mynteye/mynteye.h.in
@@ -243,8 +252,49 @@ install(EXPORT ${MYNTEYE_NAME}-targets
DESTINATION ${MYNTEYE_CMAKE_INSTALLDIR}
)
## 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_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)
set_default_value(CMAKE_CXX_COMPILER_VERSION_TWEAK 0)
set_default_value(CUDA_VERSION_MAJOR 0)
set_default_value(CUDA_VERSION_MINOR 0)
set_default_value(OpenCV_VERSION_MAJOR 0)
set_default_value(OpenCV_VERSION_MINOR 0)
set_default_value(OpenCV_VERSION_PATCH 0)
set_default_value(OpenCV_VERSION_TWEAK 0)
set_default_value(${PROJECT_NAME}_VERSION_MAJOR 0)
set_default_value(${PROJECT_NAME}_VERSION_MINOR 0)
set_default_value(${PROJECT_NAME}_VERSION_PATCH 0)
set_default_value(${PROJECT_NAME}_VERSION_TWEAK 0)
configure_file(
cmake/templates/build.info.in
build.info @ONLY

View File

@@ -24,7 +24,7 @@ Please follow the guide doc to install the SDK on different platforms.
[Google Drive]: https://drive.google.com/drive/folders/1tdFCcTBMNcImEGZ39tdOZmlX2SHKCr2f
[百度网盘]: https://pan.baidu.com/s/1yPQDp2r0x4jvNwn2UjlMUQ
Get firmwares from our online disks: [Google Drive][], [百度网盘][]. The latest version is `2.0.0-rc2`.
Get firmwares from our online disks: [Google Drive][], [百度网盘][]. The latest version is `2.0.0-rc`.
## Usage

View File

@@ -50,15 +50,10 @@ include(${CMAKE_CURRENT_LIST_DIR}/TargetArch.cmake)
target_architecture(HOST_ARCH)
message(STATUS "HOST_ARCH: ${HOST_ARCH}")
if(CMAKE_COMPILER_IS_GNUCC)
execute_process(COMMAND gcc -dumpversion COMMAND cut -c 1-3 COMMAND tr -d '\n' OUTPUT_VARIABLE GCC_VERSION)
string(REGEX MATCHALL "[0-9]+" GCC_VERSION_COMPONMENTS ${GCC_VERSION})
list(GET GCC_VERSION_COMPONMENTS 0 GCC_VERSION_MAJOR)
list(GET GCC_VERSION_COMPONMENTS 1 GCC_VERSION_MINOR)
message(STATUS "GCC_VERSION: ${GCC_VERSION}")
#message(STATUS "GCC_VERSION_MAJOR: ${GCC_VERSION_MAJOR}")
#message(STATUS "GCC_VERSION_MINOR: ${GCC_VERSION_MINOR}")
endif()
# CMAKE_CXX_COMPILER_ID
# https://cmake.org/cmake/help/latest/variable/CMAKE_LANG_COMPILER_ID.html
# CMAKE_CXX_COMPILER_VERSION
# https://cmake.org/cmake/help/latest/variable/CMAKE_LANG_COMPILER_VERSION.html
# set_outdir(ARCHIVE_OUTPUT_DIRECTORY
# LIBRARY_OUTPUT_DIRECTORY
@@ -75,17 +70,27 @@ macro(set_outdir ARCHIVE_OUTPUT_DIRECTORY LIBRARY_OUTPUT_DIRECTORY RUNTIME_OUTPU
endforeach()
endmacro()
set(__exe2bat_relative_path false)
macro(exe2bat exe_name exe_dir dll_search_paths)
message(STATUS "Generating ${exe_name}.bat")
set(__exe_name ${exe_name})
if(__exe2bat_relative_path)
set(__dll_relative_search_paths "")
foreach(path ${dll_search_paths})
file(RELATIVE_PATH __relative_path "${exe_dir}" "${path}")
file(TO_NATIVE_PATH ${__relative_path} __relative_path)
list(APPEND __dll_relative_search_paths ${__relative_path})
endforeach()
#message(STATUS __dll_relative_search_paths: "${__dll_relative_search_paths}")
set(__dll_search_paths "${__dll_relative_search_paths}")
else()
set(__dll_native_search_paths "")
foreach(path ${dll_search_paths})
file(TO_NATIVE_PATH ${path} __native_path)
list(APPEND __dll_native_search_paths ${__native_path})
endforeach()
set(__dll_search_paths "${__dll_native_search_paths}")
endif()
configure_file(
"${CUR_DIR}/templates/exe.bat.in"
"${exe_dir}/${__exe_name}.bat"

View File

@@ -19,8 +19,15 @@ find_package(OpenCV REQUIRED)
message(STATUS "Found OpenCV: ${OpenCV_VERSION}")
if(OpenCV_VERSION VERSION_LESS 3.0)
add_definitions(-DUSE_OPENCV2)
else()
elseif(OpenCV_VERSION VERSION_LESS 4.0)
add_definitions(-DUSE_OPENCV3)
else()
add_definitions(-DUSE_OPENCV4)
endif()
list(FIND OpenCV_LIBS "opencv_world" __index)
if(${__index} GREATER -1)
set(WITH_OPENCV_WORLD TRUE)
endif()
if(MSVC OR MSYS OR MINGW)

View File

@@ -1,33 +1,66 @@
# Based on the Qt 5 processor detection code, so should be very accurate
# https://qt.gitorious.org/qt/qtbase/blobs/master/src/corelib/global/qprocessordetection.h
# Currently handles arm (v5, v6, v7), x86 (32/64), ia64, and ppc (32/64)
# http://code.qt.io/cgit/qt/qtbase.git/tree/src/corelib/global/qprocessordetection.h
# Currently handles arm (v5, v6, v7, v8), x86 (32/64), ia64, and ppc (32/64)
# Regarding POWER/PowerPC, just as is noted in the Qt source,
# "There are many more known variants/revisions that we do not handle/detect."
set(archdetect_c_code "
#if defined(__arm__) || defined(__TARGET_ARCH_ARM)
#if defined(__ARM_ARCH_7__) \\
#if defined(__arm__) || defined(__TARGET_ARCH_ARM) || defined(_M_ARM) \\
|| defined(__aarch64__) || defined(__ARM64__)
#if defined(__aarch64__) || defined(__ARM64__)
#define cmake_ARM_64
#else
#define cmake_ARM_32
#endif
#if defined(__ARM_ARCH) && __ARM_ARCH > 1
#define cmake_ARM __ARM_ARCH
#elif defined(__TARGET_ARCH_ARM) && __TARGET_ARCH_ARM > 1
#define cmake_ARM __TARGET_ARCH_ARM
#elif defined(_M_ARM) && _M_ARM > 1
#define cmake_ARM _M_ARM
#elif defined(__ARM64_ARCH_8__) \\
|| defined(__aarch64__) \\
|| defined(__ARMv8__) \\
|| defined(__ARMv8_A__)
#define cmake_ARM 8
#elif defined(__ARM_ARCH_7__) \\
|| defined(__ARM_ARCH_7A__) \\
|| defined(__ARM_ARCH_7R__) \\
|| defined(__ARM_ARCH_7M__) \\
|| (defined(__TARGET_ARCH_ARM) && __TARGET_ARCH_ARM-0 >= 7)
#error cmake_ARCH armv7
|| defined(__ARM_ARCH_7S__) \\
|| defined(_ARM_ARCH_7) \\
|| defined(__CORE_CORTEXA__)
#define cmake_ARM 7
#elif defined(__ARM_ARCH_6__) \\
|| defined(__ARM_ARCH_6J__) \\
|| defined(__ARM_ARCH_6T2__) \\
|| defined(__ARM_ARCH_6Z__) \\
|| defined(__ARM_ARCH_6K__) \\
|| defined(__ARM_ARCH_6ZK__) \\
|| defined(__ARM_ARCH_6M__) \\
|| (defined(__TARGET_ARCH_ARM) && __TARGET_ARCH_ARM-0 >= 6)
#error cmake_ARCH armv6
|| defined(__ARM_ARCH_6M__)
#define cmake_ARM 6
#elif defined(__ARM_ARCH_5TEJ__) \\
|| (defined(__TARGET_ARCH_ARM) && __TARGET_ARCH_ARM-0 >= 5)
|| defined(__ARM_ARCH_5TE__)
#define cmake_ARM 5
#else
#define cmake_ARM 0
#endif
#if cmake_ARM >= 8
#error cmake_ARCH armv8
#elif cmake_ARM >= 7
#error cmake_ARCH armv7
#elif cmake_ARM >= 6
#error cmake_ARCH armv6
#elif cmake_ARM >= 5
#error cmake_ARCH armv5
#else
#if defined(cmake_ARM_64)
#error cmake_ARCH arm64
#else
#error cmake_ARCH arm
#endif
#endif
#elif defined(__i386) || defined(__i386__) || defined(_M_IX86)
#error cmake_ARCH i386
#elif defined(__x86_64) || defined(__x86_64__) || defined(__amd64) || defined(_M_X64)

View File

@@ -3,9 +3,12 @@
HOST_OS: "@HOST_OS@"
HOST_NAME: "@HOST_NAME@"
HOST_ARCH: "@HOST_ARCH@"
GCC_VERSION: "@GCC_VERSION@"
GCC_VERSION_MAJOR: @GCC_VERSION_MAJOR@
GCC_VERSION_MINOR: @GCC_VERSION_MINOR@
HOST_COMPILER: "@CMAKE_CXX_COMPILER_ID@"
COMPILER_VERSION: "@CMAKE_CXX_COMPILER_VERSION@"
COMPILER_VERSION_MAJOR: @CMAKE_CXX_COMPILER_VERSION_MAJOR@
COMPILER_VERSION_MINOR: @CMAKE_CXX_COMPILER_VERSION_MINOR@
COMPILER_VERSION_PATCH: @CMAKE_CXX_COMPILER_VERSION_PATCH@
COMPILER_VERSION_TWEAK: @CMAKE_CXX_COMPILER_VERSION_TWEAK@
CUDA_VERSION: "@CUDA_VERSION@"
CUDA_VERSION_MAJOR: @CUDA_VERSION_MAJOR@
CUDA_VERSION_MINOR: @CUDA_VERSION_MINOR@
@@ -16,6 +19,7 @@ OpenCV_VERSION_MINOR: @OpenCV_VERSION_MINOR@
OpenCV_VERSION_PATCH: @OpenCV_VERSION_PATCH@
OpenCV_VERSION_TWEAK: @OpenCV_VERSION_TWEAK@
OpenCV_VERSION_STATUS: "@OpenCV_VERSION_STATUS@"
OpenCV_WITH_WORLD: "@WITH_OPENCV_WORLD@"
MYNTEYE_VERSION: "@mynteye_VERSION@"
MYNTEYE_VERSION_MAJOR: @mynteye_VERSION_MAJOR@
MYNTEYE_VERSION_MINOR: @mynteye_VERSION_MINOR@

View File

@@ -7,7 +7,7 @@ if "%MY_PATH_SET_@__exe_name@%"=="" (
set "PATH=@__dll_search_paths@;%PATH%"
)
cd "%MY_DIR%"
::cd "%MY_DIR%"
"%MY_DIR%@__exe_name@.exe" %*
cd "%MY_PWD%"
::cd "%MY_PWD%"
::pause >nul

View File

@@ -38,7 +38,7 @@ PROJECT_NAME = "MYNT EYE SDK"
# could be handy for archiving the generated documentation or if some version
# control system is used.
PROJECT_NUMBER = 2.0.0-rc2
PROJECT_NUMBER = 2.0.0-rc
# Using the PROJECT_BRIEF tag one can provide an optional one line description
# for a project that appears at the top of each page and should give viewer a

View File

@@ -30,8 +30,12 @@ make_executable(camera_a
## get_depth_with_region
if(OpenCV_VERSION VERSION_LESS 4.0)
make_executable(get_depth_with_region
SRCS get_depth_with_region.cc
LINK_LIBS mynteye ${OpenCV_LIBS}
DLL_SEARCH_PATHS ${PRO_DIR}/_install/bin ${OpenCV_LIB_SEARCH_PATH}
)
endif()

View File

@@ -86,11 +86,13 @@ else()
message(WARNING "PCL not found :(")
endif()
# data
# beginner level
make_executable2(get_device_info SRCS data/get_device_info.cc)
make_executable2(get_img_params SRCS data/get_img_params.cc)
make_executable2(get_imu_params SRCS data/get_imu_params.cc)
## data
make_executable2(get_device_info SRCS data/get_device_info.cc WITH_OPENCV)
make_executable2(get_img_params SRCS data/get_img_params.cc WITH_OPENCV)
make_executable2(get_imu_params SRCS data/get_imu_params.cc WITH_OPENCV)
make_executable2(get_stereo SRCS data/get_stereo.cc WITH_OPENCV)
make_executable2(get_stereo_rectified SRCS data/get_stereo_rectified.cc WITH_OPENCV)
@@ -109,7 +111,7 @@ make_executable2(get_from_callbacks
)
make_executable2(get_with_plugin SRCS data/get_with_plugin.cc WITH_OPENCV)
# control
## control
make_executable2(ctrl_framerate SRCS control/framerate.cc WITH_OPENCV)
make_executable2(ctrl_auto_exposure
@@ -123,3 +125,20 @@ make_executable2(ctrl_manual_exposure
make_executable2(ctrl_infrared SRCS control/infrared.cc WITH_OPENCV)
endif()
# intermediate level
if(PCL_FOUND)
if(OpenCV_VERSION VERSION_LESS 4.0)
make_executable2(get_depth_and_points
SRCS intermediate/get_depth_and_points.cc util/cv_painter.cc util/pc_viewer.cc
WITH_OPENCV WITH_PCL
)
endif()
endif()
# advanced level

View File

@@ -0,0 +1,244 @@
// 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 <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <glog/logging.h>
#include "mynteye/api.h"
#include "util/cv_painter.h"
#include "util/pc_viewer.h"
#define WIN_FLAGS \
cv::WINDOW_AUTOSIZE | cv::WINDOW_KEEPRATIO | cv::WINDOW_GUI_NORMAL
namespace {
class DepthRegion {
public:
explicit DepthRegion(std::uint32_t n)
: n_(std::move(n)), show_(false), selected_(false), point_(0, 0) {}
~DepthRegion() = default;
/**
* 鼠标事件:默认不选中区域,随鼠标移动而显示。单击后,则会选中区域来显示。你可以再单击已选中区域或双击未选中区域,取消选中。
*/
void OnMouse(const int &event, const int &x, const int &y, const int &flags) {
UNUSED(flags)
if (event != CV_EVENT_MOUSEMOVE && event != CV_EVENT_LBUTTONDOWN) {
return;
}
show_ = true;
if (event == CV_EVENT_MOUSEMOVE) {
if (!selected_) {
point_.x = x;
point_.y = y;
}
} else if (event == CV_EVENT_LBUTTONDOWN) {
if (selected_) {
if (x >= static_cast<int>(point_.x - n_) &&
x <= static_cast<int>(point_.x + n_) &&
y >= static_cast<int>(point_.y - n_) &&
y <= static_cast<int>(point_.y + n_)) {
selected_ = false;
}
} else {
selected_ = true;
}
point_.x = x;
point_.y = y;
}
}
template <typename T>
void ShowElems(
const cv::Mat &depth,
std::function<std::string(const T &elem)> elem2string,
int elem_space = 40,
std::function<std::string(
const cv::Mat &depth, const cv::Point &point, const std::uint32_t &n)>
getinfo = nullptr) {
if (!show_)
return;
int space = std::move(elem_space);
int n = 2 * n_ + 1;
cv::Mat im(space * n, space * n, CV_8UC3, cv::Scalar(255, 255, 255));
int x, y;
std::string str;
int baseline = 0;
for (int i = -n_; i <= n; ++i) {
x = point_.x + i;
if (x < 0 || x >= depth.cols)
continue;
for (int j = -n_; j <= n; ++j) {
y = point_.y + j;
if (y < 0 || y >= depth.rows)
continue;
str = elem2string(depth.at<T>(y, x));
cv::Scalar color(0, 0, 0);
if (i == 0 && j == 0)
color = cv::Scalar(0, 0, 255);
cv::Size sz =
cv::getTextSize(str, cv::FONT_HERSHEY_PLAIN, 1, 1, &baseline);
cv::putText(
im, str, cv::Point(
(i + n_) * space + (space - sz.width) / 2,
(j + n_) * space + (space + sz.height) / 2),
cv::FONT_HERSHEY_PLAIN, 1, color, 1);
}
}
if (getinfo) {
std::string info = getinfo(depth, point_, n_);
if (!info.empty()) {
cv::Size sz =
cv::getTextSize(info, cv::FONT_HERSHEY_PLAIN, 1, 1, &baseline);
cv::putText(
im, info, cv::Point(5, 5 + sz.height), cv::FONT_HERSHEY_PLAIN, 1,
cv::Scalar(255, 0, 255), 1);
}
}
cv::imshow("region", im);
}
void DrawRect(cv::Mat &image) { // NOLINT
if (!show_)
return;
std::uint32_t n = (n_ > 1) ? n_ : 1;
n += 1; // outside the region
cv::rectangle(
image, cv::Point(point_.x - n, point_.y - n),
cv::Point(point_.x + n, point_.y + n),
selected_ ? cv::Scalar(0, 255, 0) : cv::Scalar(0, 0, 255), 1);
}
private:
std::uint32_t n_;
bool show_;
bool selected_;
cv::Point point_;
};
void OnDepthMouseCallback(int event, int x, int y, int flags, void *userdata) {
DepthRegion *region = reinterpret_cast<DepthRegion *>(userdata);
region->OnMouse(event, x, y, flags);
}
} // namespace
MYNTEYE_USE_NAMESPACE
int main(int argc, char *argv[]) {
auto &&api = API::Create(argc, argv);
if (!api)
return 1;
api->SetOptionValue(Option::IR_CONTROL, 80);
api->EnableStreamData(Stream::DISPARITY_NORMALIZED);
api->EnableStreamData(Stream::DEPTH);
api->Start(Source::VIDEO_STREAMING);
cv::namedWindow("frame", WIN_FLAGS);
cv::namedWindow("depth", WIN_FLAGS);
cv::namedWindow("region", WIN_FLAGS);
DepthRegion depth_region(3);
auto depth_info = [](
const cv::Mat &depth, const cv::Point &point, const std::uint32_t &n) {
UNUSED(depth)
std::ostringstream os;
os << "depth pos: [" << point.y << ", " << point.x << "]"
<< "±" << n << ", unit: mm";
return os.str();
};
CVPainter painter;
PCViewer pcviewer;
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);
painter.DrawImgData(img, *left_data.img);
cv::imshow("frame", img);
auto &&disp_data = api->GetStreamData(Stream::DISPARITY_NORMALIZED);
auto &&depth_data = api->GetStreamData(Stream::DEPTH);
if (!disp_data.frame.empty() && !depth_data.frame.empty()) {
// Show disparity instead of depth, but show depth values in region.
auto &&depth_frame = disp_data.frame;
#ifdef USE_OPENCV3
// ColormapTypes
// http://docs.opencv.org/master/d3/d50/group__imgproc__colormap.html#ga9a805d8262bcbe273f16be9ea2055a65
cv::applyColorMap(depth_frame, depth_frame, cv::COLORMAP_JET);
#endif
cv::setMouseCallback("depth", OnDepthMouseCallback, &depth_region);
// Note: DrawRect will change some depth values to show the rect.
depth_region.DrawRect(depth_frame);
cv::imshow("depth", depth_frame);
depth_region.ShowElems<ushort>(
depth_data.frame,
[](const ushort &elem) {
if (elem >= 10000) {
// Filter errors, or limit to valid range.
//
// reprojectImageTo3D(), missing values will set to 10000
// https://docs.opencv.org/master/d9/d0c/group__calib3d.html#ga1bc1152bd57d63bc524204f21fde6e02
return std::string("invalid");
}
return std::to_string(elem);
},
80, depth_info);
}
auto &&points_data = api->GetStreamData(Stream::POINTS);
if (!points_data.frame.empty()) {
pcviewer.Update(points_data.frame);
}
char key = static_cast<char>(cv::waitKey(1));
if (key == 27 || key == 'q' || key == 'Q') { // ESC/Q
break;
}
if (pcviewer.WasStopped()) {
break;
}
}
api->Stop(Source::VIDEO_STREAMING);
return 0;
}

View File

@@ -35,7 +35,7 @@ std::shared_ptr<pcl::visualization::PCLVisualizer> CustomColorVis(
// viewer->addCoordinateSystem(1.0);
viewer->addCoordinateSystem(1000.0);
viewer->initCameraParameters();
viewer->setCameraPosition(0, 0, -150, 0, 1, 0);
viewer->setCameraPosition(0, 0, -150, 0, -1, 0);
return (viewer);
}

View File

@@ -31,13 +31,19 @@
#include "device/device.h"
#include "internal/dl.h"
#if defined(WITH_FILESYSTEM) && defined(WITH_NATIVE_FILESYSTEM)
#if defined(OS_WIN)
#include <windows.h>
#endif
#endif
MYNTEYE_BEGIN_NAMESPACE
namespace {
#ifdef WITH_FILESYSTEM
#if defined(WITH_FILESYSTEM)
#ifdef WITH_BOOST_FILESYSTEM
#if defined(WITH_BOOST_FILESYSTEM)
namespace fs = boost::filesystem;
@@ -61,6 +67,24 @@ bool dir_exists(const fs::path &p) {
}
}
#elif defined(WITH_NATIVE_FILESYSTEM)
#if defined(OS_WIN)
bool file_exists(const std::string &p) {
DWORD attrs = GetFileAttributes(p.c_str());
return (attrs != INVALID_FILE_ATTRIBUTES && !(attrs & FILE_ATTRIBUTE_DIRECTORY));
}
bool dir_exists(const std::string &p) {
DWORD attrs = GetFileAttributes(p.c_str());
return (attrs != INVALID_FILE_ATTRIBUTES && (attrs & FILE_ATTRIBUTE_DIRECTORY));
}
#else
#error "Unsupported native filesystem"
#endif
#endif
std::vector<std::string> get_plugin_paths() {
@@ -69,7 +93,7 @@ std::vector<std::string> get_plugin_paths() {
cv::FileStorage fs(info_path, cv::FileStorage::READ);
if (!fs.isOpened()) {
// LOG(ERROR) << "build.info not found";
LOG(WARNING) << "build.info not found: " << info_path;
return {};
}
@@ -83,19 +107,29 @@ std::vector<std::string> get_plugin_paths() {
to_lower(host_name);
std::string host_arch = fs["HOST_ARCH"];
to_lower(host_arch);
// std::string gcc_version = fs["GCC_VERSION"];
int gcc_version_major = fs["GCC_VERSION_MAJOR"];
// int gcc_version_minor = fs["GCC_VERSION_MINOR"];
std::string host_compiler = fs["HOST_COMPILER"];
to_lower(host_compiler);
// std::string compiler_version = fs["COMPILER_VERSION"];
int compiler_version_major = fs["COMPILER_VERSION_MAJOR"];
// int compiler_version_minor = fs["COMPILER_VERSION_MINOR"];
// int compiler_version_patch = fs["COMPILER_VERSION_PATCH"];
// int compiler_version_tweak = fs["COMPILER_VERSION_TWEAK"];
std::string cuda_version = fs["CUDA_VERSION"];
// int cuda_version_major = fs["CUDA_VERSION_MAJOR"];
// int cuda_version_minor = fs["CUDA_VERSION_MINOR"];
// std::string cuda_version_string = fs["CUDA_VERSION_STRING"];
std::string opencv_version = fs["OpenCV_VERSION"];
// int opencv_version_major = fs["OpenCV_VERSION_MAJOR"];
// int opencv_version_minor = fs["OpenCV_VERSION_MINOR"];
// int opencv_version_patch = fs["OpenCV_VERSION_PATCH"];
// int opencv_version_tweak = fs["OpenCV_VERSION_TWEAK"];
// std::string opencv_version_status = fs["OpenCV_VERSION_STATUS"];
std::string opencv_with_world = fs["OpenCV_WITH_WORLD"];
to_lower(opencv_with_world);
std::string mynteye_version = fs["MYNTEYE_VERSION"];
// int mynteye_version_major = fs["MYNTEYE_VERSION_MAJOR"];
// int mynteye_version_minor = fs["MYNTEYE_VERSION_MINOR"];
@@ -107,7 +141,7 @@ std::vector<std::string> get_plugin_paths() {
std::string lib_prefix;
std::string lib_suffix;
if (host_os == "linux") {
if (gcc_version_major < 5)
if (host_compiler != "gnu" || compiler_version_major < 5)
return {};
lib_prefix = "lib";
lib_suffix = ".so";
@@ -127,10 +161,13 @@ std::vector<std::string> get_plugin_paths() {
// lib_prefix + "plugin_b_ocl" + ocl_version,
lib_prefix + "plugin_g_cuda" + cuda_version,
};
std::string opencv_name("_opencv" + opencv_version);
if (opencv_with_world == "true") {
opencv_name.append("-world");
}
for (auto &&prefix : prefixes) {
names.push_back(
prefix + "_opencv" + opencv_version + "_mynteye" + mynteye_version);
names.push_back(prefix + "_opencv" + opencv_version);
names.push_back(prefix + opencv_name + "_mynteye" + mynteye_version);
names.push_back(prefix + opencv_name);
names.push_back(prefix);
}
for (auto &&name : names) {
@@ -301,10 +338,14 @@ void API::Start(const Source &source) {
if (source == Source::VIDEO_STREAMING) {
#ifdef WITH_FILESYSTEM
if (!synthetic_->HasPlugin()) {
try {
auto &&plugin_paths = get_plugin_paths();
if (plugin_paths.size() > 0) {
EnablePlugin(plugin_paths[0]);
}
} catch (...) {
LOG(WARNING) << "Incorrect yaml format: build.info";
}
}
#endif
synthetic_->StartVideoStreaming();
@@ -371,7 +412,9 @@ void API::EnablePlugin(const std::string &path) {
plugin_version_code_t *plugin_version_code =
dl.Sym<plugin_version_code_t>("plugin_version_code");
LOG(INFO) << "Enable plugin, version code: " << plugin_version_code();
LOG(INFO) << "Enable plugin success";
LOG(INFO) << " version code: " << plugin_version_code();
LOG(INFO) << " path: " << path;
plugin_create_t *plugin_create = dl.Sym<plugin_create_t>("plugin_create");
plugin_destroy_t *plugin_destroy = dl.Sym<plugin_destroy_t>("plugin_destroy");

View File

@@ -30,6 +30,12 @@ MYNTEYE_BEGIN_NAMESPACE
class Device;
class Synthetic;
namespace device {
class Frame;
} // namespace device
namespace api {
/**
@@ -41,6 +47,8 @@ struct MYNTEYE_API StreamData {
std::shared_ptr<ImgData> img;
/** Frame. */
cv::Mat frame;
/** Raw frame. */
std::shared_ptr<device::Frame> frame_raw;
bool operator==(const StreamData &other) const {
if (img && other.img) {

View File

@@ -46,7 +46,7 @@ cv::Mat frame2mat(const std::shared_ptr<device::Frame> &frame) {
}
api::StreamData data2api(const device::StreamData &data) {
return {data.img, frame2mat(data.frame)};
return {data.img, frame2mat(data.frame), data.frame};
}
} // namespace
@@ -152,7 +152,7 @@ api::StreamData Synthetic::GetStreamData(const Stream &stream) {
Object *out = processor->GetOutput();
if (out != nullptr) {
ObjMat2 *output = Object::Cast<ObjMat2>(out);
return {nullptr, output->first};
return {nullptr, output->first, nullptr};
}
VLOG(2) << "Rectify not ready now";
} break;
@@ -161,7 +161,7 @@ api::StreamData Synthetic::GetStreamData(const Stream &stream) {
Object *out = processor->GetOutput();
if (out != nullptr) {
ObjMat2 *output = Object::Cast<ObjMat2>(out);
return {nullptr, output->second};
return {nullptr, output->second, nullptr};
}
VLOG(2) << "Rectify not ready now";
} break;
@@ -170,7 +170,7 @@ api::StreamData Synthetic::GetStreamData(const Stream &stream) {
Object *out = processor->GetOutput();
if (out != nullptr) {
ObjMat *output = Object::Cast<ObjMat>(out);
return {nullptr, output->value};
return {nullptr, output->value, nullptr};
}
VLOG(2) << "Disparity not ready now";
} break;
@@ -180,7 +180,7 @@ api::StreamData Synthetic::GetStreamData(const Stream &stream) {
Object *out = processor->GetOutput();
if (out != nullptr) {
ObjMat *output = Object::Cast<ObjMat>(out);
return {nullptr, output->value};
return {nullptr, output->value, nullptr};
}
VLOG(2) << "Disparity normalized not ready now";
} break;
@@ -189,7 +189,7 @@ api::StreamData Synthetic::GetStreamData(const Stream &stream) {
Object *out = processor->GetOutput();
if (out != nullptr) {
ObjMat *output = Object::Cast<ObjMat>(out);
return {nullptr, output->value};
return {nullptr, output->value, nullptr};
}
VLOG(2) << "Points not ready now";
} break;
@@ -198,7 +198,7 @@ api::StreamData Synthetic::GetStreamData(const Stream &stream) {
Object *out = processor->GetOutput();
if (out != nullptr) {
ObjMat *output = Object::Cast<ObjMat>(out);
return {nullptr, output->value};
return {nullptr, output->value, nullptr};
}
VLOG(2) << "Depth not ready now";
} break;
@@ -546,17 +546,19 @@ bool Synthetic::OnDepthProcess(
void Synthetic::OnRectifyPostProcess(Object *const out) {
const ObjMat2 *output = Object::Cast<ObjMat2>(out);
if (HasStreamCallback(Stream::LEFT_RECTIFIED)) {
stream_callbacks_.at(Stream::LEFT_RECTIFIED)({nullptr, output->first});
stream_callbacks_.at(Stream::LEFT_RECTIFIED)(
{nullptr, output->first, nullptr});
}
if (HasStreamCallback(Stream::RIGHT_RECTIFIED)) {
stream_callbacks_.at(Stream::RIGHT_RECTIFIED)({nullptr, output->second});
stream_callbacks_.at(Stream::RIGHT_RECTIFIED)(
{nullptr, output->second, nullptr});
}
}
void Synthetic::OnDisparityPostProcess(Object *const out) {
const ObjMat *output = Object::Cast<ObjMat>(out);
if (HasStreamCallback(Stream::DISPARITY)) {
stream_callbacks_.at(Stream::DISPARITY)({nullptr, output->value});
stream_callbacks_.at(Stream::DISPARITY)({nullptr, output->value, nullptr});
}
}
@@ -564,21 +566,21 @@ void Synthetic::OnDisparityNormalizedPostProcess(Object *const out) {
const ObjMat *output = Object::Cast<ObjMat>(out);
if (HasStreamCallback(Stream::DISPARITY_NORMALIZED)) {
stream_callbacks_.at(Stream::DISPARITY_NORMALIZED)(
{nullptr, output->value});
{nullptr, output->value, nullptr});
}
}
void Synthetic::OnPointsPostProcess(Object *const out) {
const ObjMat *output = Object::Cast<ObjMat>(out);
if (HasStreamCallback(Stream::POINTS)) {
stream_callbacks_.at(Stream::POINTS)({nullptr, output->value});
stream_callbacks_.at(Stream::POINTS)({nullptr, output->value, nullptr});
}
}
void Synthetic::OnDepthPostProcess(Object *const out) {
const ObjMat *output = Object::Cast<ObjMat>(out);
if (HasStreamCallback(Stream::DEPTH)) {
stream_callbacks_.at(Stream::DEPTH)({nullptr, output->value});
stream_callbacks_.at(Stream::DEPTH)({nullptr, output->value, nullptr});
}
}

View File

@@ -434,6 +434,7 @@ void Device::StartVideoStreaming() {
}
}
continuation();
OnStereoStreamUpdate();
// VLOG(2) << "Stereo video callback cost "
// << times::count<times::milliseconds>(times::now() - time_beg)
// << " ms";
@@ -465,7 +466,7 @@ void Device::StartMotionTracking() {
}
motions_->SetMotionCallback(
std::bind(&Device::CallbackMotionData, this, std::placeholders::_1));
motions_->StartMotionTracking();
// motions_->StartMotionTracking();
motion_tracking_ = true;
}
@@ -474,10 +475,12 @@ void Device::StopMotionTracking() {
LOG(WARNING) << "Cannot stop motion tracking without first starting it";
return;
}
motions_->StopMotionTracking();
// motions_->StopMotionTracking();
motion_tracking_ = false;
}
void Device::OnStereoStreamUpdate() {}
void Device::ReadAllInfos() {
device_info_ = std::make_shared<DeviceInfo>();

View File

@@ -239,6 +239,18 @@ class MYNTEYE_API Device {
return device_;
}
std::shared_ptr<Streams> streams() const {
return streams_;
}
std::shared_ptr<Channels> channels() const {
return channels_;
}
std::shared_ptr<Motions> motions() const {
return motions_;
}
const StreamRequest &GetStreamRequest(const Capabilities &capability);
virtual void StartVideoStreaming();
@@ -247,6 +259,8 @@ class MYNTEYE_API Device {
virtual void StartMotionTracking();
virtual void StopMotionTracking();
virtual void OnStereoStreamUpdate();
virtual std::vector<Stream> GetKeyStreams() const = 0;
bool video_streaming_;
@@ -284,10 +298,6 @@ class MYNTEYE_API Device {
void CallbackPushedStreamData(const Stream &stream);
void CallbackMotionData(const device::MotionData &data);
std::shared_ptr<Channels> channels() {
return channels_;
}
friend API;
friend tools::DeviceWriter;
};

View File

@@ -15,6 +15,8 @@
#include <glog/logging.h>
#include "internal/motions.h"
MYNTEYE_BEGIN_NAMESPACE
StandardDevice::StandardDevice(std::shared_ptr<uvc::device> device)
@@ -30,4 +32,11 @@ std::vector<Stream> StandardDevice::GetKeyStreams() const {
return {Stream::LEFT, Stream::RIGHT};
}
void StandardDevice::OnStereoStreamUpdate() {
if (motion_tracking_) {
auto &&motions = this->motions();
motions->DoMotionTrack();
}
}
MYNTEYE_END_NAMESPACE

View File

@@ -28,6 +28,8 @@ class StandardDevice : public Device {
virtual ~StandardDevice();
std::vector<Stream> GetKeyStreams() const override;
void OnStereoStreamUpdate() override;
};
MYNTEYE_END_NAMESPACE

View File

@@ -31,7 +31,12 @@ MYNTEYE_BEGIN_NAMESPACE
namespace {
const uvc::xu mynteye_xu = {3, 2, {0x947a6d9f, 0x8a2f, 0x418d, {0x85, 0x9e, 0x6c, 0x9a, 0xa0, 0x38, 0x10, 0x14}}};
const uvc::xu mynteye_xu = {3,
2,
{0x947a6d9f,
0x8a2f,
0x418d,
{0x85, 0x9e, 0x6c, 0x9a, 0xa0, 0x38, 0x10, 0x14}}};
int XuCamCtrlId(Option option) {
switch (option) {
@@ -276,6 +281,47 @@ void Channels::SetImuCallback(imu_callback_t callback) {
imu_callback_ = callback;
}
void Channels::DoImuTrack() {
static ImuReqPacket req_packet{0};
static ImuResPacket res_packet;
req_packet.serial_number = imu_sn_;
if (!XuImuWrite(req_packet)) {
return;
}
if (!XuImuRead(&res_packet)) {
return;
}
if (res_packet.packets.size() == 0) {
return;
}
VLOG(2) << "Imu req sn: " << imu_sn_ << ", res count: " << []() {
std::size_t n = 0;
for (auto &&packet : res_packet.packets) {
n += packet.count;
}
return n;
}();
auto &&sn = res_packet.packets.back().serial_number;
if (imu_sn_ == sn) {
VLOG(2) << "New imu not ready, dropped";
return;
}
imu_sn_ = sn;
if (imu_callback_) {
for (auto &&packet : res_packet.packets) {
imu_callback_(packet);
}
}
res_packet.packets.clear();
}
void Channels::StartImuTracking(imu_callback_t callback) {
if (is_imu_tracking_) {
LOG(WARNING) << "Start imu tracking failed, is tracking already";
@@ -287,8 +333,6 @@ void Channels::StartImuTracking(imu_callback_t callback) {
is_imu_tracking_ = true;
imu_track_thread_ = std::thread([this]() {
imu_sn_ = 0;
ImuReqPacket req_packet{imu_sn_};
ImuResPacket res_packet;
auto sleep = [](const times::system_clock::time_point &time_beg) {
auto &&time_elapsed_ms =
times::count<times::milliseconds>(times::now() - time_beg);
@@ -301,48 +345,7 @@ void Channels::StartImuTracking(imu_callback_t callback) {
};
while (!imu_track_stop_) {
auto &&time_beg = times::now();
req_packet.serial_number = imu_sn_;
if (!XuImuWrite(req_packet)) {
sleep(time_beg);
continue;
}
if (!XuImuRead(&res_packet)) {
sleep(time_beg);
continue;
}
if (res_packet.packets.size() == 0) {
sleep(time_beg);
continue;
}
VLOG(2) << "Imu req sn: " << imu_sn_
<< ", res count: " << [&res_packet]() {
std::size_t n = 0;
for (auto &&packet : res_packet.packets) {
n += packet.count;
}
return n;
}();
auto &&sn = res_packet.packets.back().serial_number;
if (imu_sn_ == sn) {
VLOG(2) << "New imu not ready, dropped";
sleep(time_beg);
continue;
}
imu_sn_ = sn;
if (imu_callback_) {
for (auto &&packet : res_packet.packets) {
imu_callback_(packet);
}
}
res_packet.packets.clear();
DoImuTrack();
sleep(time_beg);
}
});
@@ -870,7 +873,8 @@ bool Channels::PuControlQuery(
}
bool Channels::XuControlRange(
channel_t channel, uint8_t id, int32_t *min, int32_t *max, int32_t *def) const {
channel_t channel, uint8_t id, int32_t *min, int32_t *max,
int32_t *def) const {
return XuControlRange(mynteye_xu, channel, id, min, max, def);
}
@@ -1016,7 +1020,8 @@ Channels::control_info_t Channels::XuControlInfo(Option option) const {
int id = XuCamCtrlId(option);
int32_t min = 0, max = 0, def = 0;
if (!XuControlRange(CHANNEL_CAM_CTRL, static_cast<std::uint8_t>(id), &min, &max, &def)) {
if (!XuControlRange(
CHANNEL_CAM_CTRL, static_cast<std::uint8_t>(id), &min, &max, &def)) {
LOG(WARNING) << "Get XuControlInfo of " << option << " failed";
}
return {min, max, def};

View File

@@ -95,6 +95,8 @@ class MYNTEYE_API Channels {
bool RunControlAction(const Option &option) const;
void SetImuCallback(imu_callback_t callback);
void DoImuTrack();
void StartImuTracking(imu_callback_t callback = nullptr);
void StopImuTracking();
@@ -111,10 +113,11 @@ class MYNTEYE_API Channels {
bool PuControlQuery(Option option, uvc::pu_query query, int32_t *value) const;
bool XuControlRange(
channel_t channel, uint8_t id, int32_t *min, int32_t *max, int32_t *def) const;
bool XuControlRange(
const uvc::xu &xu, uint8_t selector, uint8_t id, int32_t *min, int32_t *max,
channel_t channel, uint8_t id, int32_t *min, int32_t *max,
int32_t *def) const;
bool XuControlRange(
const uvc::xu &xu, uint8_t selector, uint8_t id, int32_t *min,
int32_t *max, int32_t *def) const;
bool XuControlQuery(
channel_t channel, uvc::xu_query query, uint16_t size,

View File

@@ -34,11 +34,8 @@ Motions::~Motions() {
void Motions::SetMotionCallback(motion_callback_t callback) {
motion_callback_ = callback;
}
void Motions::StartMotionTracking() {
if (!is_imu_tracking) {
channels_->StartImuTracking([this](const ImuPacket &packet) {
if (motion_callback_) {
channels_->SetImuCallback([this](const ImuPacket &packet) {
if (!motion_callback_ && !motion_datas_enabled_) {
LOG(WARNING) << "";
return;
@@ -62,11 +59,22 @@ void Motions::StartMotionTracking() {
std::lock_guard<std::mutex> _(mtx_datas_);
motion_data_t data = {imu};
motion_datas_.push_back(data);
if (motion_callback_) {
motion_callback_(data);
}
}
});
} else {
channels_->SetImuCallback(nullptr);
}
}
void Motions::DoMotionTrack() {
channels_->DoImuTrack();
}
void Motions::StartMotionTracking() {
if (!is_imu_tracking) {
channels_->StartImuTracking();
is_imu_tracking = true;
} else {
LOG(WARNING) << "Imu is tracking already";

View File

@@ -37,6 +37,7 @@ class Motions {
~Motions();
void SetMotionCallback(motion_callback_t callback);
void DoMotionTrack();
void StartMotionTracking();
void StopMotionTracking();

View File

@@ -69,7 +69,7 @@ roslaunch mynt_eye_ros_wrapper mynteye.launch
```
```bash
rosbag record -O mynteye.bag /mynteye/left /mynteye/imu /mynteye/temp
rosbag record -O mynteye.bag /mynteye/left/image_raw /mynteye/imu/data_raw /mynteye/temp/data_raw
```
## Analytics data (rosbag)

View File

@@ -650,8 +650,8 @@ def _main():
else:
dataset = ROSBag(
path,
topic_imu='/mynteye/imu',
topic_temp='/mynteye/temp')
topic_imu='/mynteye/imu/data_raw',
topic_temp='/mynteye/temp/data_raw')
return dataset
if args.binary:

View File

@@ -334,8 +334,8 @@ def _main():
sys.exit('Error: dataset model not supported {}'.format(model))
else:
dataset = ROSBag(path,
topic_img_left='/mynteye/left',
topic_imu='/mynteye/imu')
topic_img_left='/mynteye/left/image_raw',
topic_imu='/mynteye/imu/data_raw')
return dataset
dataset = BinDataset(dataset_path, dataset_creator)

View File

@@ -3,7 +3,7 @@ dataset: "mynteye"
# rosbag config
rosbag:
topic_img_left: "/mynteye/left"
topic_img_right: "/mynteye/right"
topic_imu: "/mynteye/imu"
topic_temp: "/mynteye/temp"
topic_img_left: "/mynteye/left/image_raw"
topic_img_right: "/mynteye/right/image_raw"
topic_imu: "/mynteye/imu/data_raw"
topic_temp: "/mynteye/temp/data_raw"

View File

@@ -4,17 +4,17 @@
<!-- node params -->
<arg name="left_topic" default="left" />
<arg name="right_topic" default="right" />
<arg name="left_rect_topic" default="left_rect" />
<arg name="right_rect_topic" default="right_rect" />
<arg name="disparity_topic" default="disparity" />
<arg name="disparity_norm_topic" default="disparity_norm" />
<arg name="points_topic" default="points" />
<arg name="depth_topic" default="depth" />
<arg name="left_topic" default="left/image_raw" />
<arg name="right_topic" default="right/image_raw" />
<arg name="left_rect_topic" default="left/image_rect" />
<arg name="right_rect_topic" default="right/image_rect" />
<arg name="disparity_topic" default="disparity/image_raw" />
<arg name="disparity_norm_topic" default="disparity/image_norm" />
<arg name="depth_topic" default="depth/image_raw" />
<arg name="points_topic" default="points/data_raw" />
<arg name="imu_topic" default="imu" />
<arg name="temp_topic" default="temp" />
<arg name="imu_topic" default="imu/data_raw" />
<arg name="temp_topic" default="temp/data_raw" />
<arg name="base_frame_id" default="$(arg mynteye)_link" />
<arg name="left_frame_id" default="$(arg mynteye)_left_frame" />

View File

@@ -55,7 +55,7 @@ Visualization Manager:
Displays:
- Class: rviz/Image
Enabled: true
Image Topic: /mynteye/left
Image Topic: /mynteye/left/image_raw
Max Value: 1
Median window: 5
Min Value: 0
@@ -67,7 +67,7 @@ Visualization Manager:
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /mynteye/right
Image Topic: /mynteye/right/image_raw
Max Value: 1
Median window: 5
Min Value: 0
@@ -81,7 +81,7 @@ Visualization Manager:
Displays:
- Class: rviz/Image
Enabled: true
Image Topic: /mynteye/left_rect
Image Topic: /mynteye/left/image_rect
Max Value: 1
Median window: 5
Min Value: 0
@@ -93,7 +93,7 @@ Visualization Manager:
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /mynteye/right_rect
Image Topic: /mynteye/right/image_rect
Max Value: 1
Median window: 5
Min Value: 0
@@ -111,7 +111,7 @@ Visualization Manager:
Displays:
- Class: rviz/Image
Enabled: true
Image Topic: /mynteye/disparity
Image Topic: /mynteye/disparity/image_raw
Max Value: 1
Median window: 5
Min Value: 0
@@ -123,7 +123,7 @@ Visualization Manager:
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /mynteye/disparity_norm
Image Topic: /mynteye/disparity/image_norm
Max Value: 1
Median window: 5
Min Value: 0
@@ -137,7 +137,7 @@ Visualization Manager:
Name: Disparity
- Class: rviz/Image
Enabled: true
Image Topic: /mynteye/depth
Image Topic: /mynteye/depth/image_raw
Max Value: 1
Median window: 5
Min Value: 0
@@ -157,7 +157,7 @@ Visualization Manager:
Channel Name: intensity
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: ""
Color Transformer: RGB8
Decay Time: 0
Enabled: true
Invert Rainbow: false
@@ -166,13 +166,13 @@ Visualization Manager:
Min Color: 0; 0; 0
Min Intensity: 0
Name: Points
Position Transformer: ""
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.00999999978
Style: Flat Squares
Topic: /mynteye/points
Topic: /mynteye/points/data_raw
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
@@ -183,7 +183,7 @@ Visualization Manager:
Enabled: false
History Length: 1
Name: Imu
Topic: /mynteye/imu
Topic: /mynteye/imu/data_raw
Unreliable: false
Value: false
Enabled: true
@@ -247,7 +247,7 @@ Window Geometry:
collapsed: false
LeftRect:
collapsed: false
QMainWindow State: 000000ff00000000fd00000004000000000000016a00000396fc020000000ffb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000396000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000008004c00650066007403000001bd000000860000024e00000190fb0000000a00520069006700680074030000040c000000860000025000000190fb00000010004c006500660074005200650063007402000001bd000002170000024e00000190fb00000012005200690067006800740052006500630074020000040c000002170000024f00000190fb0000000a0044006500700074006803000001bc000002170000024f00000190fb0000001200440069007300700061007200690074007902000001bd000002170000024e0000018ffb0000001a004400690073007000610072006900740079004e006f0072006d020000040c000002170000025100000190000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000396000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000004ba0000039600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
QMainWindow State: 000000ff00000000fd00000004000000000000017e00000396fc020000000ffb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000396000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000008004c00650066007403000001bd000000860000024e00000190fb0000000a00520069006700680074030000040c000000860000025000000190fb00000010004c006500660074005200650063007402000001bd000002170000024e00000190fb00000012005200690067006800740052006500630074020000040c000002170000024f00000190fb0000000a0044006500700074006803000001bc000002170000024f00000190fb0000001200440069007300700061007200690074007902000001bd000002170000024e0000018ffb0000001a004400690073007000610072006900740079004e006f0072006d020000040c000002170000025100000190000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000396000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000004a60000039600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Right:
collapsed: false
RightRect: