Merge branch 'develop' of https://github.com/slightech/MYNT-EYE-SDK-2 into develop

This commit is contained in:
Tiny 2018-11-02 09:11:13 +08:00
commit 8d12fc8f14
9 changed files with 261 additions and 45 deletions

11
Jenkinsfile vendored
View File

@ -1,7 +1,7 @@
pipeline { pipeline {
agent { agent {
// docker { image 'ros:kinetic-ros-core-xenial' } // docker { image 'ros:kinetic-ros-base-xenial' }
docker { image 'ros:kinetic-ros-base-xenial' } docker { image 'joinaero/kinetic-ros-opencv-xenial' }
} }
/* /*
@ -16,10 +16,7 @@ pipeline {
steps { steps {
echo "WORKSPACE: ${env.WORKSPACE}" echo "WORKSPACE: ${env.WORKSPACE}"
echo 'apt-get ..' echo 'apt-get ..'
sh ''' sh 'apt-get update'
apt-get update
apt-get install -y ros-kinetic-opencv3
'''
} }
} }
stage('Init') { stage('Init') {
@ -91,7 +88,7 @@ pipeline {
} }
failure { failure {
echo 'This will run only if failed' echo 'This will run only if failed'
mail to: 'mynteye@slightech.com', mail to: 'mynteye-ci@slightech.com',
subject: "Failed Pipeline: ${currentBuild.fullDisplayName}", subject: "Failed Pipeline: ${currentBuild.fullDisplayName}",
body: "Something is wrong with ${env.BUILD_URL}" body: "Something is wrong with ${env.BUILD_URL}"
} }

View File

@ -27,3 +27,9 @@ make_executable(record
LINK_LIBS mynteye ${OpenCV_LIBS} LINK_LIBS mynteye ${OpenCV_LIBS}
DLL_SEARCH_PATHS ${PRO_DIR}/_install/bin ${OpenCV_LIB_SEARCH_PATH} DLL_SEARCH_PATHS ${PRO_DIR}/_install/bin ${OpenCV_LIB_SEARCH_PATH}
) )
make_executable(record2
SRCS record2.cc dataset.cc
LINK_LIBS mynteye ${OpenCV_LIBS}
DLL_SEARCH_PATHS ${PRO_DIR}/_install/bin ${OpenCV_LIB_SEARCH_PATH}
)

View File

@ -87,6 +87,34 @@ void Dataset::SaveMotionData(const device::MotionData &data) {
++motion_count_; ++motion_count_;
} }
void Dataset::SaveStreamData(
const Stream &stream, const api::StreamData &data) {
auto &&writer = GetStreamWriter(stream);
auto seq = stream_counts_[stream];
writer->ofs << seq << ", " << data.img->frame_id << ", "
<< data.img->timestamp << ", " << data.img->exposure_time
<< std::endl;
if (!data.frame.empty()) {
std::stringstream ss;
ss << writer->outdir << MYNTEYE_OS_SEP << std::dec
<< std::setw(IMAGE_FILENAME_WIDTH) << std::setfill('0') << seq << ".png";
cv::imwrite(ss.str(), data.frame);
}
++stream_counts_[stream];
}
void Dataset::SaveMotionData(const api::MotionData &data) {
auto &&writer = GetMotionWriter();
auto seq = motion_count_;
writer->ofs << seq << ", " << data.imu->frame_id << ", "
<< data.imu->timestamp << ", " << data.imu->accel[0] << ", "
<< data.imu->accel[1] << ", " << data.imu->accel[2] << ", "
<< data.imu->gyro[0] << ", " << data.imu->gyro[1] << ", "
<< data.imu->gyro[2] << ", " << data.imu->temperature
<< std::endl;
++motion_count_;
}
Dataset::writer_t Dataset::GetStreamWriter(const Stream &stream) { Dataset::writer_t Dataset::GetStreamWriter(const Stream &stream) {
try { try {
return stream_writers_.at(stream); return stream_writers_.at(stream);

View File

@ -21,6 +21,7 @@
#include <string> #include <string>
#include "mynteye/mynteye.h" #include "mynteye/mynteye.h"
#include "mynteye/api/api.h"
#include "mynteye/device/callbacks.h" #include "mynteye/device/callbacks.h"
MYNTEYE_BEGIN_NAMESPACE MYNTEYE_BEGIN_NAMESPACE
@ -43,6 +44,9 @@ class Dataset {
void SaveStreamData(const Stream &stream, const device::StreamData &data); void SaveStreamData(const Stream &stream, const device::StreamData &data);
void SaveMotionData(const device::MotionData &data); void SaveMotionData(const device::MotionData &data);
void SaveStreamData(const Stream &stream, const api::StreamData &data);
void SaveMotionData(const api::MotionData &data);
private: private:
writer_t GetStreamWriter(const Stream &stream); writer_t GetStreamWriter(const Stream &stream);
writer_t GetMotionWriter(); writer_t GetMotionWriter();

View File

@ -15,8 +15,7 @@
#include <opencv2/imgproc/imgproc.hpp> #include <opencv2/imgproc/imgproc.hpp>
#include "mynteye/logger.h" #include "mynteye/logger.h"
#include "mynteye/device/device.h" #include "mynteye/api/api.h"
#include "mynteye/device/utils.h"
#include "mynteye/util/times.h" #include "mynteye/util/times.h"
#include "dataset/dataset.h" #include "dataset/dataset.h"
@ -24,33 +23,31 @@
MYNTEYE_USE_NAMESPACE MYNTEYE_USE_NAMESPACE
int main(int argc, char *argv[]) { int main(int argc, char *argv[]) {
glog_init _(argc, argv); auto &&api = API::Create(argc, argv);
if (!api)
auto &&device = device::select();
if (!device)
return 1; return 1;
/* /*
{ // auto-exposure { // auto-exposure
device->SetOptionValue(Option::EXPOSURE_MODE, 0); api->SetOptionValue(Option::EXPOSURE_MODE, 0);
device->SetOptionValue(Option::MAX_GAIN, 40); // [0.48] api->SetOptionValue(Option::MAX_GAIN, 40); // [0.48]
device->SetOptionValue(Option::MAX_EXPOSURE_TIME, 120); // [0,240] api->SetOptionValue(Option::MAX_EXPOSURE_TIME, 120); // [0,240]
device->SetOptionValue(Option::DESIRED_BRIGHTNESS, 200); // [0,255] api->SetOptionValue(Option::DESIRED_BRIGHTNESS, 200); // [0,255]
} }
{ // manual-exposure { // manual-exposure
device->SetOptionValue(Option::EXPOSURE_MODE, 1); api->SetOptionValue(Option::EXPOSURE_MODE, 1);
device->SetOptionValue(Option::GAIN, 20); // [0.48] api->SetOptionValue(Option::GAIN, 20); // [0.48]
device->SetOptionValue(Option::BRIGHTNESS, 20); // [0,240] api->SetOptionValue(Option::BRIGHTNESS, 20); // [0,240]
device->SetOptionValue(Option::CONTRAST, 20); // [0,255] api->SetOptionValue(Option::CONTRAST, 20); // [0,255]
} }
device->SetOptionValue(Option::IR_CONTROL, 80); api->SetOptionValue(Option::IR_CONTROL, 80);
device->SetOptionValue(Option::FRAME_RATE, 25); api->SetOptionValue(Option::FRAME_RATE, 25);
device->SetOptionValue(Option::IMU_FREQUENCY, 500); api->SetOptionValue(Option::IMU_FREQUENCY, 500);
*/ */
device->LogOptionInfos(); api->LogOptionInfos();
// Enable this will cache the motion datas until you get them. // Enable this will cache the motion datas until you get them.
device->EnableMotionDatas(); api->EnableMotionDatas();
device->Start(Source::ALL); api->Start(Source::ALL);
const char *outdir; const char *outdir;
if (argc >= 2) { if (argc >= 2) {
@ -66,22 +63,17 @@ int main(int argc, char *argv[]) {
std::size_t imu_count = 0; std::size_t imu_count = 0;
auto &&time_beg = times::now(); auto &&time_beg = times::now();
while (true) { while (true) {
device->WaitForStreams(); api->WaitForStreams();
auto &&left_datas = device->GetStreamDatas(Stream::LEFT); auto &&left_datas = api->GetStreamDatas(Stream::LEFT);
auto &&right_datas = device->GetStreamDatas(Stream::RIGHT); auto &&right_datas = api->GetStreamDatas(Stream::RIGHT);
img_count += left_datas.size(); img_count += left_datas.size();
auto &&motion_datas = device->GetMotionDatas(); auto &&motion_datas = api->GetMotionDatas();
imu_count += motion_datas.size(); imu_count += motion_datas.size();
auto &&left_frame = left_datas.back().frame; auto &&left_img = left_datas.back().frame;
auto &&right_frame = right_datas.back().frame; auto &&right_img = right_datas.back().frame;
cv::Mat left_img(
left_frame->height(), left_frame->width(), CV_8UC1, left_frame->data());
cv::Mat right_img(
right_frame->height(), right_frame->width(), CV_8UC1,
right_frame->data());
cv::Mat img; cv::Mat img;
cv::hconcat(left_img, right_img, img); cv::hconcat(left_img, right_img, img);
@ -111,7 +103,7 @@ int main(int argc, char *argv[]) {
std::cout << " to " << outdir << std::endl; std::cout << " to " << outdir << std::endl;
auto &&time_end = times::now(); auto &&time_end = times::now();
device->Stop(Source::ALL); api->Stop(Source::ALL);
float elapsed_ms = float elapsed_ms =
times::count<times::microseconds>(time_end - time_beg) * 0.001f; times::count<times::microseconds>(time_end - time_beg) * 0.001f;

126
tools/dataset/record2.cc Normal file
View File

@ -0,0 +1,126 @@
// Copyright 2018 Slightech Co., Ltd. All rights reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include "mynteye/logger.h"
#include "mynteye/device/device.h"
#include "mynteye/device/utils.h"
#include "mynteye/util/times.h"
#include "dataset/dataset.h"
MYNTEYE_USE_NAMESPACE
int main(int argc, char *argv[]) {
glog_init _(argc, argv);
auto &&device = device::select();
if (!device)
return 1;
/*
{ // auto-exposure
device->SetOptionValue(Option::EXPOSURE_MODE, 0);
device->SetOptionValue(Option::MAX_GAIN, 40); // [0.48]
device->SetOptionValue(Option::MAX_EXPOSURE_TIME, 120); // [0,240]
device->SetOptionValue(Option::DESIRED_BRIGHTNESS, 200); // [0,255]
}
{ // manual-exposure
device->SetOptionValue(Option::EXPOSURE_MODE, 1);
device->SetOptionValue(Option::GAIN, 20); // [0.48]
device->SetOptionValue(Option::BRIGHTNESS, 20); // [0,240]
device->SetOptionValue(Option::CONTRAST, 20); // [0,255]
}
device->SetOptionValue(Option::IR_CONTROL, 80);
device->SetOptionValue(Option::FRAME_RATE, 25);
device->SetOptionValue(Option::IMU_FREQUENCY, 500);
*/
device->LogOptionInfos();
// Enable this will cache the motion datas until you get them.
device->EnableMotionDatas();
device->Start(Source::ALL);
const char *outdir;
if (argc >= 2) {
outdir = argv[1];
} else {
outdir = "./dataset";
}
tools::Dataset dataset(outdir);
cv::namedWindow("frame");
std::size_t img_count = 0;
std::size_t imu_count = 0;
auto &&time_beg = times::now();
while (true) {
device->WaitForStreams();
auto &&left_datas = device->GetStreamDatas(Stream::LEFT);
auto &&right_datas = device->GetStreamDatas(Stream::RIGHT);
img_count += left_datas.size();
auto &&motion_datas = device->GetMotionDatas();
imu_count += motion_datas.size();
auto &&left_frame = left_datas.back().frame;
auto &&right_frame = right_datas.back().frame;
cv::Mat left_img(
left_frame->height(), left_frame->width(), CV_8UC1, left_frame->data());
cv::Mat right_img(
right_frame->height(), right_frame->width(), CV_8UC1,
right_frame->data());
cv::Mat img;
cv::hconcat(left_img, right_img, img);
cv::imshow("frame", img);
{ // save
for (auto &&left : left_datas) {
dataset.SaveStreamData(Stream::LEFT, left);
}
for (auto &&right : right_datas) {
dataset.SaveStreamData(Stream::RIGHT, right);
}
for (auto &&motion : motion_datas) {
dataset.SaveMotionData(motion);
}
std::cout << "\rSaved " << img_count << " imgs"
<< ", " << imu_count << " imus" << std::flush;
}
char key = static_cast<char>(cv::waitKey(1));
if (key == 27 || key == 'q' || key == 'Q') { // ESC/Q
break;
}
}
std::cout << " to " << outdir << std::endl;
auto &&time_end = times::now();
device->Stop(Source::ALL);
float elapsed_ms =
times::count<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;
}

View File

@ -15,8 +15,6 @@
cmake_minimum_required(VERSION 2.8.3) cmake_minimum_required(VERSION 2.8.3)
project(mynt_eye_ros_wrapper) project(mynt_eye_ros_wrapper)
get_filename_component(SDK_DIR "${PROJECT_SOURCE_DIR}/../../../.." ABSOLUTE)
if(NOT CMAKE_BUILD_TYPE) if(NOT CMAKE_BUILD_TYPE)
set(CMAKE_BUILD_TYPE Release) set(CMAKE_BUILD_TYPE Release)
endif() endif()
@ -77,9 +75,11 @@ catkin_package(
CATKIN_DEPENDS cv_bridge geometry_msgs image_transport nodelet roscpp sensor_msgs std_msgs tf CATKIN_DEPENDS cv_bridge geometry_msgs image_transport nodelet roscpp sensor_msgs std_msgs tf
) )
get_filename_component(SDK_DIR "${PROJECT_SOURCE_DIR}/../../../.." ABSOLUTE) #get_filename_component(SDK_DIR "${PROJECT_SOURCE_DIR}/../../../.." ABSOLUTE)
#LIST(APPEND CMAKE_PREFIX_PATH ${SDK_DIR}/_install/lib/cmake)
LIST(APPEND CMAKE_MODULE_PATH cmake)
LIST(APPEND CMAKE_PREFIX_PATH ${SDK_DIR}/_install/lib/cmake)
find_package(mynteye REQUIRED) find_package(mynteye REQUIRED)
message(STATUS "Found mynteye: ${mynteye_VERSION}") message(STATUS "Found mynteye: ${mynteye_VERSION}")
@ -87,10 +87,13 @@ if(NOT mynteye_WITH_API)
message(FATAL_ERROR "Must with API layer :(") message(FATAL_ERROR "Must with API layer :(")
endif() endif()
include(${SDK_DIR}/cmake/DetectOpenCV.cmake) include(cmake/DetectOpenCV.cmake)
if(mynteye_WITH_GLOG) if(mynteye_WITH_GLOG)
include(${SDK_DIR}/cmake/DetectGLog.cmake) find_package(glog REQUIRED)
if(glog_FOUND)
add_definitions(-DWITH_GLOG)
endif()
endif() endif()
# targets # targets

View File

@ -0,0 +1,37 @@
# Copyright 2018 Slightech Co., Ltd. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
include(${CMAKE_CURRENT_LIST_DIR}/IncludeGuard.cmake)
cmake_include_guard()
find_package(OpenCV REQUIRED)
message(STATUS "Found OpenCV: ${OpenCV_VERSION}")
if(OpenCV_VERSION VERSION_LESS 3.0)
add_definitions(-DUSE_OPENCV2)
elseif(OpenCV_VERSION VERSION_LESS 4.0)
add_definitions(-DUSE_OPENCV3)
else()
add_definitions(-DUSE_OPENCV4)
endif()
list(FIND OpenCV_LIBS "opencv_world" __index)
if(${__index} GREATER -1)
set(WITH_OPENCV_WORLD TRUE)
endif()
if(MSVC OR MSYS OR MINGW)
get_filename_component(OpenCV_LIB_SEARCH_PATH "${OpenCV_LIB_PATH}/../bin" ABSOLUTE)
else()
set(OpenCV_LIB_SEARCH_PATH "${OpenCV_LIB_PATH}")
endif()

View File

@ -0,0 +1,23 @@
# Copyright 2018 Slightech Co., Ltd. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
# include_guard: https://cmake.org/cmake/help/latest/command/include_guard.html
macro(cmake_include_guard)
get_property(INCLUDE_GUARD GLOBAL PROPERTY "_INCLUDE_GUARD_${CMAKE_CURRENT_LIST_FILE}")
if(INCLUDE_GUARD)
return()
endif()
set_property(GLOBAL PROPERTY "_INCLUDE_GUARD_${CMAKE_CURRENT_LIST_FILE}" TRUE)
endmacro()