feat(*): add record samples..
This commit is contained in:
parent
80b6bc599b
commit
0f546e55fb
|
@ -279,3 +279,11 @@ make_executable(save_all_infos
|
|||
DLL_SEARCH_PATHS ${PRO_DIR}/_install/bin ${OpenCV_LIB_SEARCH_PATH}
|
||||
)
|
||||
|
||||
## record
|
||||
|
||||
make_executable(record
|
||||
SRCS record.cc dataset.cc
|
||||
LINK_LIBS mynteye ${OpenCV_LIBS}
|
||||
DLL_SEARCH_PATHS ${PRO_DIR}/_install/bin ${OpenCV_LIB_SEARCH_PATH}
|
||||
)
|
||||
|
||||
|
|
203
samples/dataset.cc
Normal file
203
samples/dataset.cc
Normal file
|
@ -0,0 +1,203 @@
|
|||
// 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 "dataset.h"
|
||||
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
#include <opencv2/imgproc/imgproc.hpp>
|
||||
|
||||
#include <iomanip>
|
||||
#include <limits>
|
||||
#include <stdexcept>
|
||||
#include <utility>
|
||||
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/util/files.h"
|
||||
|
||||
#define FULL_PRECISION \
|
||||
std::fixed << std::setprecision(std::numeric_limits<double>::max_digits10)
|
||||
|
||||
#define IMAGE_FILENAME_WIDTH 6
|
||||
|
||||
MYNTEYE_BEGIN_NAMESPACE
|
||||
|
||||
namespace tools {
|
||||
|
||||
Dataset::Dataset(std::string outdir) : outdir_(std::move(outdir)) {
|
||||
VLOG(2) << __func__;
|
||||
if (!files::mkdir(outdir_)) {
|
||||
LOG(FATAL) << "Create directory failed: " << outdir_;
|
||||
}
|
||||
}
|
||||
|
||||
Dataset::~Dataset() {
|
||||
VLOG(2) << __func__;
|
||||
for (auto &&it = stream_writers_.begin(); it != stream_writers_.end(); it++) {
|
||||
if (it->second) {
|
||||
it->second->ofs.flush();
|
||||
it->second->ofs.close();
|
||||
}
|
||||
}
|
||||
if (motion_writer_) {
|
||||
motion_writer_->ofs.flush();
|
||||
motion_writer_->ofs.close();
|
||||
}
|
||||
}
|
||||
|
||||
void Dataset::SaveStreamData(
|
||||
const Stream &stream, const device::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) {
|
||||
std::stringstream ss;
|
||||
ss << writer->outdir << MYNTEYE_OS_SEP << std::dec
|
||||
<< std::setw(IMAGE_FILENAME_WIDTH) << std::setfill('0') << seq << ".png";
|
||||
if (data.frame->format() == Format::GREY) {
|
||||
cv::Mat img(
|
||||
data.frame->height(), data.frame->width(), CV_8UC1,
|
||||
data.frame->data());
|
||||
cv::imwrite(ss.str(), img);
|
||||
} else if (data.frame->format() == Format::YUYV) {
|
||||
cv::Mat img(
|
||||
data.frame->height(), data.frame->width(), CV_8UC2,
|
||||
data.frame->data());
|
||||
cv::cvtColor(img, img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::imwrite(ss.str(), img);
|
||||
} else if (data.frame->format() == Format::BGR888) {
|
||||
cv::Mat img(
|
||||
data.frame->height(), data.frame->width(), CV_8UC3,
|
||||
data.frame->data());
|
||||
cv::imwrite(ss.str(), img);
|
||||
} else {
|
||||
cv::Mat img(
|
||||
data.frame->height(), data.frame->width(), CV_8UC1,
|
||||
data.frame->data());
|
||||
cv::imwrite(ss.str(), img);
|
||||
}
|
||||
}
|
||||
++stream_counts_[stream];
|
||||
}
|
||||
|
||||
void Dataset::SaveMotionData(const device::MotionData &data) {
|
||||
auto &&writer = GetMotionWriter();
|
||||
// auto seq = data.imu->serial_number;
|
||||
auto seq = motion_count_;
|
||||
writer->ofs << seq << ", " << static_cast<int>(data.imu->flag) << ", "
|
||||
<< 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_;
|
||||
/*
|
||||
if(motion_count_ != seq) {
|
||||
LOG(INFO) << "motion_count_ != seq !" << " motion_count_: " << motion_count_
|
||||
<< " seq: " << seq;
|
||||
motion_count_ = seq;
|
||||
}
|
||||
*/
|
||||
}
|
||||
|
||||
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 = data.imu->serial_number;
|
||||
auto seq = motion_count_;
|
||||
if (data.imu->flag == 1 || data.imu->flag == 2) {
|
||||
writer->ofs << seq << ", " << static_cast<int>(data.imu->flag) << ", "
|
||||
<< 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_;
|
||||
}
|
||||
/*
|
||||
if(motion_count_ != seq) {
|
||||
LOG(INFO) << "motion_count_ != seq !" << " motion_count_: " << motion_count_
|
||||
<< " seq: " << seq;
|
||||
motion_count_ = seq;
|
||||
}
|
||||
*/
|
||||
}
|
||||
|
||||
Dataset::writer_t Dataset::GetStreamWriter(const Stream &stream) {
|
||||
try {
|
||||
return stream_writers_.at(stream);
|
||||
} catch (const std::out_of_range &e) {
|
||||
writer_t writer = std::make_shared<Writer>();
|
||||
switch (stream) {
|
||||
case Stream::LEFT: {
|
||||
writer->outdir = outdir_ + MYNTEYE_OS_SEP "left";
|
||||
} break;
|
||||
case Stream::RIGHT: {
|
||||
writer->outdir = outdir_ + MYNTEYE_OS_SEP "right";
|
||||
} break;
|
||||
default:
|
||||
LOG(FATAL) << "Unsupported stream: " << stream;
|
||||
}
|
||||
writer->outfile = writer->outdir + MYNTEYE_OS_SEP "stream.txt";
|
||||
|
||||
files::mkdir(writer->outdir);
|
||||
writer->ofs.open(writer->outfile, std::ofstream::out);
|
||||
writer->ofs << "seq, frame_id, timestamp, exposure_time" << std::endl;
|
||||
writer->ofs << FULL_PRECISION;
|
||||
|
||||
stream_writers_[stream] = writer;
|
||||
stream_counts_[stream] = 0;
|
||||
return writer;
|
||||
}
|
||||
}
|
||||
|
||||
Dataset::writer_t Dataset::GetMotionWriter() {
|
||||
if (motion_writer_ == nullptr) {
|
||||
writer_t writer = std::make_shared<Writer>();
|
||||
writer->outdir = outdir_;
|
||||
writer->outfile = writer->outdir + MYNTEYE_OS_SEP "motion.txt";
|
||||
|
||||
files::mkdir(writer->outdir);
|
||||
writer->ofs.open(writer->outfile, std::ofstream::out);
|
||||
writer->ofs << "seq, flag, timestamp, accel_x, accel_y, accel_z, "
|
||||
"gyro_x, gyro_y, gyro_z, temperature"
|
||||
<< std::endl;
|
||||
writer->ofs << FULL_PRECISION;
|
||||
|
||||
motion_writer_ = writer;
|
||||
motion_count_ = 0;
|
||||
accel_count_ = 0;
|
||||
gyro_count_ = 0;
|
||||
}
|
||||
return motion_writer_;
|
||||
}
|
||||
|
||||
} // namespace tools
|
||||
|
||||
MYNTEYE_END_NAMESPACE
|
69
samples/dataset.h
Normal file
69
samples/dataset.h
Normal file
|
@ -0,0 +1,69 @@
|
|||
// 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.
|
||||
#ifndef MYNTEYE_TOOLS_DATASET_H_ // NOLINT
|
||||
#define MYNTEYE_TOOLS_DATASET_H_
|
||||
#pragma once
|
||||
|
||||
#include <fstream>
|
||||
#include <map>
|
||||
#include <memory>
|
||||
#include <string>
|
||||
|
||||
#include "mynteye/mynteye.h"
|
||||
#include "mynteye/api/api.h"
|
||||
#include "mynteye/device/callbacks.h"
|
||||
|
||||
MYNTEYE_BEGIN_NAMESPACE
|
||||
|
||||
namespace tools {
|
||||
|
||||
class Dataset {
|
||||
public:
|
||||
struct Writer {
|
||||
std::ofstream ofs;
|
||||
std::string outdir;
|
||||
std::string outfile;
|
||||
};
|
||||
|
||||
using writer_t = std::shared_ptr<Writer>;
|
||||
|
||||
explicit Dataset(std::string outdir);
|
||||
~Dataset();
|
||||
|
||||
void SaveStreamData(const Stream &stream, const device::StreamData &data);
|
||||
void SaveMotionData(const device::MotionData &data);
|
||||
|
||||
void SaveStreamData(const Stream &stream, const api::StreamData &data);
|
||||
void SaveMotionData(const api::MotionData &data);
|
||||
|
||||
private:
|
||||
writer_t GetStreamWriter(const Stream &stream);
|
||||
writer_t GetMotionWriter();
|
||||
|
||||
std::string outdir_;
|
||||
|
||||
std::map<Stream, writer_t> stream_writers_;
|
||||
writer_t motion_writer_;
|
||||
|
||||
std::map<Stream, std::size_t> stream_counts_;
|
||||
std::size_t motion_count_;
|
||||
std::size_t accel_count_;
|
||||
std::size_t gyro_count_;
|
||||
};
|
||||
|
||||
} // namespace tools
|
||||
|
||||
MYNTEYE_END_NAMESPACE
|
||||
|
||||
#endif // MYNTEYE_TOOLS_DATASET_H_ NOLINT
|
137
samples/record.cc
Normal file
137
samples/record.cc
Normal file
|
@ -0,0 +1,137 @@
|
|||
// 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.h"
|
||||
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
int main(int argc, char *argv[]) {
|
||||
glog_init _(argc, argv);
|
||||
|
||||
auto &&device = device::select();
|
||||
if (!device) return 1;
|
||||
|
||||
bool ok;
|
||||
auto &&request = device::select_request(device, &ok);
|
||||
if (!ok) return 1;
|
||||
device->ConfigStreamRequest(request);
|
||||
|
||||
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 img;
|
||||
|
||||
if (left_frame->format() == Format::GREY) {
|
||||
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::hconcat(left_img, right_img, img);
|
||||
} else if (left_frame->format() == Format::YUYV) {
|
||||
cv::Mat left_img(
|
||||
left_frame->height(), left_frame->width(), CV_8UC2,
|
||||
left_frame->data());
|
||||
cv::Mat right_img(
|
||||
right_frame->height(), right_frame->width(), CV_8UC2,
|
||||
right_frame->data());
|
||||
cv::cvtColor(left_img, left_img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::cvtColor(right_img, right_img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else if (left_frame->format() == Format::BGR888) {
|
||||
cv::Mat left_img(
|
||||
left_frame->height(), left_frame->width(), CV_8UC3,
|
||||
left_frame->data());
|
||||
cv::Mat right_img(
|
||||
right_frame->height(), right_frame->width(), CV_8UC3,
|
||||
right_frame->data());
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else {
|
||||
return -1;
|
||||
}
|
||||
cv::imshow("frame", img);
|
||||
if (img_count > 10 && imu_count > 50) { // 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;
|
||||
}
|
Loading…
Reference in New Issue
Block a user