Skip to content

Commit 89bbc50

Browse files
authored
Merge pull request #1515 from luxonis/feature/video_encoder_tests_update
Feature/video encoder tests update
2 parents 1c9be54 + 7a9c652 commit 89bbc50

File tree

5 files changed

+407
-68
lines changed

5 files changed

+407
-68
lines changed

include/depthai/pipeline/node/host/Record.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,12 +47,14 @@ class RecordVideo : public NodeCRTP<ThreadedHostNode, RecordVideo> {
4747
RecordVideo& setRecordMetadataFile(const std::filesystem::path& recordFile);
4848
RecordVideo& setRecordVideoFile(const std::filesystem::path& recordFile);
4949
RecordVideo& setCompressionLevel(CompressionLevel compressionLevel);
50+
RecordVideo& setFps(unsigned int fps);
5051

5152
private:
5253
std::filesystem::path recordMetadataFile;
5354
std::filesystem::path recordVideoFile;
54-
unsigned int fpsInitLength = 10;
5555
CompressionLevel compressionLevel = CompressionLevel::DEFAULT;
56+
std::optional<unsigned int> fps;
57+
unsigned int fpsInitLength = 10;
5658
};
5759

5860
/**

src/pipeline/node/host/Record.cpp

Lines changed: 51 additions & 41 deletions
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,6 @@ void RecordVideo::run() {
4949
DatatypeEnum streamType = DatatypeEnum::ADatatype;
5050
unsigned int width = 0;
5151
unsigned int height = 0;
52-
unsigned int fps = 0;
5352
unsigned int i = 0;
5453
auto start = std::chrono::steady_clock::now();
5554
auto end = std::chrono::steady_clock::now();
@@ -86,53 +85,60 @@ void RecordVideo::run() {
8685
: "Byte");
8786
}
8887
if(streamType == DatatypeEnum::ImgFrame || streamType == DatatypeEnum::EncodedFrame) {
89-
if(i == 0)
90-
start = msg->getTimestampDevice();
91-
else if(i == fpsInitLength - 1) {
92-
end = msg->getTimestampDevice();
93-
fps = roundf((fpsInitLength * 1e6f) / (float)std::chrono::duration_cast<std::chrono::microseconds>(end - start).count());
94-
if(logger) logger->trace("RecordVideo node detected {} fps", fps);
95-
if(streamType == DatatypeEnum::EncodedFrame) {
96-
auto encFrame = std::dynamic_pointer_cast<EncodedFrame>(msg);
97-
videoRecorder->init(recordVideoFile.string(),
98-
width,
99-
height,
100-
fps,
101-
encFrame->getProfile() == EncodedFrame::Profile::JPEG ? VideoCodec::MJPEG : VideoCodec::H264);
102-
} else {
103-
videoRecorder->init(recordVideoFile.string(), width, height, fps, VideoCodec::RAW);
88+
if(!videoRecorder->isInitialized()) {
89+
if(i == 0) {
90+
start = msg->getTimestampDevice();
91+
}
92+
93+
if(fps.has_value() || i == (fpsInitLength - 1)) {
94+
end = msg->getTimestampDevice();
95+
unsigned int calculatedFps =
96+
roundf((fpsInitLength * 1e6f) / (float)std::chrono::duration_cast<std::chrono::microseconds>(end - start).count());
97+
if(logger) logger->trace("RecordVideo node detected {} fps", fps.value_or(calculatedFps));
98+
if(streamType == DatatypeEnum::EncodedFrame) {
99+
auto encFrame = std::dynamic_pointer_cast<EncodedFrame>(msg);
100+
videoRecorder->init(recordVideoFile.string(),
101+
width,
102+
height,
103+
fps.value_or(calculatedFps),
104+
encFrame->getProfile() == EncodedFrame::Profile::JPEG ? VideoCodec::MJPEG : VideoCodec::H264);
105+
} else {
106+
videoRecorder->init(recordVideoFile.string(), width, height, fps.value_or(calculatedFps), VideoCodec::RAW);
107+
}
108+
} else if(i < fpsInitLength) {
109+
i++;
110+
continue;
104111
}
105112
}
106-
if(i >= fpsInitLength - 1) {
107-
auto data = msg->getData();
108-
if(streamType == DatatypeEnum::ImgFrame) {
113+
114+
// Record the data
115+
auto data = msg->getData();
116+
if(streamType == DatatypeEnum::ImgFrame) {
109117
#ifdef DEPTHAI_HAVE_OPENCV_SUPPORT
110-
auto imgFrame = std::dynamic_pointer_cast<ImgFrame>(msg);
111-
auto frame = imgFrame->getCvFrame();
112-
bool isGrayscale = imgFrame->getType() == ImgFrame::Type::GRAY8 || imgFrame->getType() == ImgFrame::Type::GRAYF16
113-
|| (ImgFrame::Type::RAW16 <= imgFrame->getType() && imgFrame->getType() <= ImgFrame::Type::RAW8);
114-
if(isGrayscale) {
115-
cv::cvtColor(frame, frame, cv::COLOR_GRAY2BGR);
116-
}
117-
assert(frame.isContinuous());
118-
span cvData(frame.data, frame.total() * frame.elemSize());
119-
videoRecorder->write(cvData, frame.step);
120-
if(recordMetadata) {
121-
byteRecorder.write(imgFrame->serializeProto(true));
122-
}
118+
auto imgFrame = std::dynamic_pointer_cast<ImgFrame>(msg);
119+
auto frame = imgFrame->getCvFrame();
120+
bool isGrayscale = imgFrame->getType() == ImgFrame::Type::GRAY8 || imgFrame->getType() == ImgFrame::Type::GRAYF16
121+
|| (ImgFrame::Type::RAW16 <= imgFrame->getType() && imgFrame->getType() <= ImgFrame::Type::RAW8);
122+
if(isGrayscale) {
123+
cv::cvtColor(frame, frame, cv::COLOR_GRAY2BGR);
124+
}
125+
assert(frame.isContinuous());
126+
span cvData(frame.data, frame.total() * frame.elemSize());
127+
videoRecorder->write(cvData, frame.step);
128+
if(recordMetadata) {
129+
byteRecorder.write(imgFrame->serializeProto(true));
130+
}
123131
#else
124-
throw std::runtime_error("RecordVideo node requires OpenCV support");
132+
throw std::runtime_error("RecordVideo node requires OpenCV support");
125133
#endif
126-
} else {
127-
videoRecorder->write(data);
128-
if(recordMetadata) {
129-
auto encFrame = std::dynamic_pointer_cast<EncodedFrame>(msg);
130-
auto imgFrame = encFrame->getImgFrameMeta();
131-
byteRecorder.write(imgFrame.serializeProto(true));
132-
}
134+
} else {
135+
videoRecorder->write(data);
136+
if(recordMetadata) {
137+
auto encFrame = std::dynamic_pointer_cast<EncodedFrame>(msg);
138+
auto imgFrame = encFrame->getImgFrameMeta();
139+
byteRecorder.write(imgFrame.serializeProto(true));
133140
}
134141
}
135-
if(i < fpsInitLength) ++i;
136142
} else {
137143
throw std::runtime_error("RecordVideo can only record video streams.");
138144
}
@@ -204,6 +210,10 @@ RecordVideo& RecordVideo::setCompressionLevel(CompressionLevel compressionLevel)
204210
this->compressionLevel = compressionLevel;
205211
return *this;
206212
}
213+
RecordVideo& RecordVideo::setFps(unsigned int fps) {
214+
this->fps = fps;
215+
return *this;
216+
}
207217

208218
std::filesystem::path RecordMetadataOnly::getRecordFile() const {
209219
return recordFile;

tests/CMakeLists.txt

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -377,7 +377,7 @@ dai_set_test_labels(filesystem_test_20 rvc2_all ci)
377377

378378
# Encoded frame test
379379
dai_add_test(encoded_frame_test src/ondevice_tests/encoded_frame_test.cpp CXX_STANDARD 17)
380-
dai_set_test_labels(encoded_frame_test ondevice rvc2_all rvc4rgb ci)
380+
dai_set_test_labels(encoded_frame_test ondevice rvc2_all rvc4 rvc4rgb ci)
381381

382382
# MessageGroup tests
383383
dai_add_test(message_group_frame_test src/ondevice_tests/message_group_test.cpp CXX_STANDARD 17)
@@ -501,6 +501,7 @@ dai_set_test_labels(camera_test ondevice rvc2_all rvc4 ci)
501501
# VideoEncoder test
502502
dai_add_test(video_encoder_test src/ondevice_tests/video_encoder_test.cpp)
503503
dai_set_test_labels(video_encoder_test ondevice rvc2_all rvc4 rvc4rgb ci)
504+
target_compile_definitions(video_encoder_test PRIVATE VIDEO_PATH="${construction_vest}")
504505

505506
# XLinkIn test
506507
dai_add_test(xlink_test src/ondevice_tests/xlink_tests.cpp)

tests/src/ondevice_tests/encoded_frame_test.cpp

Lines changed: 31 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
#include <catch2/catch_all.hpp>
22
#include <catch2/catch_test_macros.hpp>
3+
#include <fstream>
34
#include <iostream>
5+
#include <opencv2/opencv.hpp>
46

57
#include "depthai/pipeline/Pipeline.hpp"
68
#include "depthai/pipeline/datatype/EncodedFrame.hpp"
@@ -27,6 +29,10 @@ TEST_CASE("OLD_OUTPUT") {
2729

2830
TEST_CASE("JPEG_ENCODING_LOSSLESS") {
2931
dai::Pipeline pipeline;
32+
if(pipeline.getDefaultDevice()->getPlatform() == dai::Platform::RVC4) {
33+
return;
34+
}
35+
3036
auto camNode = pipeline.create<dai::node::Camera>()->build();
3137
auto camOut = camNode->requestOutput({640, 480}, dai::ImgFrame::Type::NV12);
3238
auto encNode = pipeline.create<dai::node::VideoEncoder>();
@@ -44,13 +50,38 @@ TEST_CASE("JPEG_ENCODING_LOSSLESS") {
4450
encNode->setKeyframeFrequency(30);
4551

4652
auto outputQueue = encNode->out.createOutputQueue();
53+
auto camOutputQueue = camOut->createOutputQueue();
4754
pipeline.start();
4855
for(int i = 0; i < 100; ++i) {
4956
auto encfrm = outputQueue->get<dai::EncodedFrame>();
57+
auto origFrame = camOutputQueue->get<dai::ImgFrame>();
5058
REQUIRE(encfrm->getProfile() == dai::EncodedFrame::Profile::JPEG);
5159
REQUIRE(encfrm->getLossless() == true);
5260
REQUIRE(encfrm->getQuality() == 30);
61+
62+
// Encoded and original frames should be identical
63+
std::string data;
64+
std::stringstream ss;
65+
ss.write((const char*)encfrm->getData().data(), encfrm->getData().size());
66+
data = ss.str();
67+
std::filesystem::path path("encoded");
68+
std::ofstream fileStream(path, std::ios::binary);
69+
fileStream.write(data.data(), data.size());
70+
71+
ss.write((const char*)origFrame->getData().data(), origFrame->getData().size());
72+
data = ss.str();
73+
path = std::filesystem::path("original");
74+
fileStream = std::ofstream(path, std::ios::binary);
75+
fileStream.write(data.data(), data.size());
76+
77+
cv::VideoCapture originalCapture("original", cv::CAP_FFMPEG);
78+
cv::VideoCapture encodedCapture("encoded", cv::CAP_FFMPEG);
79+
cv::Mat originalFrame, encodedFrame;
80+
REQUIRE((originalCapture.read(originalFrame) && encodedCapture.read(encodedFrame)));
81+
REQUIRE(std::equal(originalFrame.begin<uchar>(), originalFrame.end<uchar>(), encodedFrame.begin<uchar>()));
5382
}
83+
std::filesystem::remove("original");
84+
std::filesystem::remove("encoded");
5485
}
5586

5687
TEST_CASE("JPEG_ENCODING_LOSSY") {

0 commit comments

Comments
 (0)