@@ -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
208218std::filesystem::path RecordMetadataOnly::getRecordFile () const {
209219 return recordFile;
0 commit comments