diff --git a/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.cpp b/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.cpp index 0a2475bec..5b6b925f8 100644 --- a/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.cpp +++ b/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.cpp @@ -118,13 +118,7 @@ void AutowareScreenCapturePanel::on_timer() size, CV_8UC3, const_cast(q_image.bits()), static_cast(q_image.bytesPerLine())); - const auto q_size = screen->grabWindow(main_window_->winId()) - .toImage() - .convertToFormat(QImage::Format_RGB888) - .rgbSwapped() - .size(); - - current_movie_size_ = cv::Size(q_size.width(), q_size.height()); + size_ = size; if (is_buffering_) { buffer_.push_back(image.clone()); @@ -267,7 +261,6 @@ bool AutowareScreenCapturePanel::save_movie(const std::string & file_name) save(movie_, file_name); - // writer_.release(); capture_to_mp4_button_ptr_->setText("waiting for capture"); capture_to_mp4_button_ptr_->setStyleSheet("background-color: #00FF00;"); @@ -298,11 +291,11 @@ void AutowareScreenCapturePanel::save( writer.open( "capture/" + file_name + ros_time_label_->text().toStdString() + ".mp4", fourcc, rate_->value(), - current_movie_size_); + size_); for (const auto & frame : images) { cv::Mat resized_frame; - cv::resize(frame, resized_frame, current_movie_size_); + cv::resize(frame, resized_frame, size_); writer.write(resized_frame); } diff --git a/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.hpp b/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.hpp index ac0395f6b..4d8b78d52 100644 --- a/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.hpp +++ b/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.hpp @@ -105,13 +105,12 @@ public Q_SLOTS: QSpinBox * rate_; QMainWindow * main_window_{nullptr}; - cv::Size current_movie_size_; + cv::Size size_; std::deque movie_; std::deque buffer_; - // std::deque> frame_buffer_; // Size of the frame buffer (number of frames to keep in memory) // At 10 Hz capture rate, 100 frames correspond to approximately 10 seconds of video const size_t buffer_size_ = 100;