From 7650dda7343bad48a040dfa234eec5320904e025 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Fri, 13 Aug 2021 16:01:36 -0700 Subject: [PATCH] Move video recording logic to existing plugin and add legacy mode Signed-off-by: Louise Poubel --- examples/worlds/minimal_scene.sdf | 33 +- src/gui/gui.config | 36 +- src/gui/plugins/CMakeLists.txt | 1 - src/gui/plugins/video_recorder/CMakeLists.txt | 8 +- .../plugins/video_recorder/VideoRecorder.cc | 403 ++++++++++++++++-- .../plugins/video_recorder/VideoRecorder.hh | 13 +- .../video_recorder_logic/CMakeLists.txt | 8 - .../VideoRecorderLogic.cc | 400 ----------------- .../VideoRecorderLogic.hh | 62 --- .../VideoRecorderLogic.qml | 28 -- .../VideoRecorderLogic.qrc | 5 - 11 files changed, 419 insertions(+), 578 deletions(-) delete mode 100644 src/gui/plugins/video_recorder_logic/CMakeLists.txt delete mode 100644 src/gui/plugins/video_recorder_logic/VideoRecorderLogic.cc delete mode 100644 src/gui/plugins/video_recorder_logic/VideoRecorderLogic.hh delete mode 100644 src/gui/plugins/video_recorder_logic/VideoRecorderLogic.qml delete mode 100644 src/gui/plugins/video_recorder_logic/VideoRecorderLogic.qrc diff --git a/examples/worlds/minimal_scene.sdf b/examples/worlds/minimal_scene.sdf index 8dc69f2bbf..03d8e91615 100644 --- a/examples/worlds/minimal_scene.sdf +++ b/examples/worlds/minimal_scene.sdf @@ -11,6 +11,7 @@ Features: * Markers * Tape measure * Grid config +* Video recording Missing for parity with GzScene3D: @@ -118,8 +119,6 @@ Missing for parity with GzScene3D: true true true - /world/buoyancy/control - /world/buoyancy/stats @@ -144,7 +143,6 @@ Missing for parity with GzScene3D: true true true - /world/buoyancy/stats @@ -203,19 +201,40 @@ Missing for parity with GzScene3D: + + + + false + 300 + 50 + 50 + 50 + floating + false + #777777 + + + + true + true + 4000000 + + + + false + + - false - docked + docked_collapsed - false - docked + docked_collapsed diff --git a/src/gui/gui.config b/src/gui/gui.config index 2fa5bca5bd..137c55e648 100644 --- a/src/gui/gui.config +++ b/src/gui/gui.config @@ -27,7 +27,7 @@ - + 3D View false @@ -41,40 +41,6 @@ 6 0 6 0 0.5 3.14 - - - - - - - false - 5 - 5 - floating - false - - - - - - - - - - false - 5 - 5 - floating - false - - - - true - true - 4000000 - - - diff --git a/src/gui/plugins/CMakeLists.txt b/src/gui/plugins/CMakeLists.txt index 686052ca6a..c8d7ab74f4 100644 --- a/src/gui/plugins/CMakeLists.txt +++ b/src/gui/plugins/CMakeLists.txt @@ -133,7 +133,6 @@ add_subdirectory(scene_manager) add_subdirectory(shapes) add_subdirectory(transform_control) add_subdirectory(video_recorder) -add_subdirectory(video_recorder_logic) add_subdirectory(view_angle) add_subdirectory(visualize_contacts) add_subdirectory(visualize_lidar) diff --git a/src/gui/plugins/video_recorder/CMakeLists.txt b/src/gui/plugins/video_recorder/CMakeLists.txt index 93964b3490..bf721fc2f6 100644 --- a/src/gui/plugins/video_recorder/CMakeLists.txt +++ b/src/gui/plugins/video_recorder/CMakeLists.txt @@ -1,4 +1,8 @@ gz_add_gui_plugin(VideoRecorder - SOURCES VideoRecorder.cc - QT_HEADERS VideoRecorder.hh + SOURCES + VideoRecorder.cc + QT_HEADERS + VideoRecorder.hh + PUBLIC_LINK_LIBS + ignition-rendering${IGN_RENDERING_VER}::ignition-rendering${IGN_RENDERING_VER} ) diff --git a/src/gui/plugins/video_recorder/VideoRecorder.cc b/src/gui/plugins/video_recorder/VideoRecorder.cc index 84406d718f..6c692783a0 100644 --- a/src/gui/plugins/video_recorder/VideoRecorder.cc +++ b/src/gui/plugins/video_recorder/VideoRecorder.cc @@ -25,81 +25,430 @@ #include #include +#include +#include #include +#include +#include #include +#include +#include +#include #include #include +/// \brief condition variable for lockstepping video recording +/// todo(anyone) avoid using a global condition variable when we support +/// multiple viewports in the future. +std::condition_variable g_renderCv; + namespace ignition::gazebo { class VideoRecorderPrivate { + /// \brief Capture a video frame in the render thread. + public: void OnRender(); + + /// \brief Initialize rendering and transport. + public: void Initialize(); + /// \brief Ignition communication node. public: transport::Node node; - /// \brief Video record service name - public: std::string service; + /// \brief Pointer to the camera being recorded + public: rendering::CameraPtr camera{nullptr}; + + /// \brief Pointer to the 3D scene + public: rendering::ScenePtr scene{nullptr}; + + /// \brief Video encoder + public: common::VideoEncoder videoEncoder; + + /// \brief Image from user camera + public: rendering::Image cameraImage; + + /// \brief True to record a video from the user camera + public: bool recordVideo = false; + + /// \brief Video encoding format + public: std::string format; + + /// \brief Use sim time as timestamp during video recording + /// By default (false), video encoding is done using real time. + public: bool useSimTime = false; + + /// \brief Lockstep gui with ECM when recording + public: bool lockstep = false; + + /// \brief Video recorder bitrate (bps) + public: unsigned int bitrate = 2070000; + + /// \brief Previous camera update time during video recording + /// only used in lockstep mode and recording in sim time. + public: std::chrono::steady_clock::time_point updateTime; + + /// \brief Start tiem of video recording + public: std::chrono::steady_clock::time_point startTime; + + /// \brief Camera pose publisher + public: transport::Node::Publisher recorderStatsPub; + + /// \brief Record stats topic name + public: std::string recorderStatsTopic = "/gui/record_video/stats"; + + /// \brief Record video service + /// Only used when in legacy mode, where this plugin requests a + /// transport service provided by `GzScene3D`. + /// The new behaviour is that this plugin performs the entire operation. + public: std::string service = "/gui/record_video"; + + /// \brief True to indicate video recording in progress + public: bool recording = false; + + /// \brief mutex to protect the recording variable + public: std::mutex recordMutex; + + /// \brief mutex to protect the render condition variable + /// Used when recording in lockstep mode. + public: std::mutex renderMutex; + + /// \brief Total time elapsed in simulation. This will not increase while + /// paused. + public: std::chrono::steady_clock::duration simTime{0}; /// \brief Filename of the recorded video public: std::string filename; + + /// \brief Enable legacy features for plugin to work with GzScene3D. + /// Disable them to work with the new MinimalScene plugin. + public: bool legacy{true}; }; } using namespace ignition; using namespace gazebo; +///////////////////////////////////////////////// +void VideoRecorderPrivate::Initialize() +{ + // Don't setup rendering or transport in legacy mode, GzScene3D takes care of + // that + if (this->legacy) + return; + + // Already initialized + if (this->scene) + return; + + this->scene = rendering::sceneFromFirstRenderEngine(); + if (!this->scene) + return; + + for (unsigned int i = 0; i < this->scene->NodeCount(); ++i) + { + auto cam = std::dynamic_pointer_cast( + this->scene->NodeByIndex(i)); + if (cam) + { + if (std::get(cam->UserData("user-camera"))) + { + this->camera = cam; + igndbg << "Video Recorder plugin is recoding camera [" + << this->camera->Name() << "]" << std::endl; + break; + } + } + } + + if (!this->camera) + { + ignerr << "Camera is not available" << std::endl; + return; + } + + // recorder stats topic + this->recorderStatsPub = + this->node.Advertise(this->recorderStatsTopic); + ignmsg << "Video recorder stats topic advertised on [" + << this->recorderStatsTopic << "]" << std::endl; +} + +///////////////////////////////////////////////// +void VideoRecorderPrivate::OnRender() +{ + // Don't render in legacy mode, GzScene3D takes care of that + if (this->legacy) + return; + + this->Initialize(); + + // check if recording is in lockstep mode and if it is using sim time + // if so, there is no need to update camera if sim time has not advanced + bool update = false; + if (this->lockstep && + this->useSimTime && + this->videoEncoder.IsEncoding()) + { + std::chrono::steady_clock::time_point t = + std::chrono::steady_clock::time_point( + this->simTime); + if (t - this->updateTime != std::chrono::seconds(0)) + { + this->updateTime = t; + update = true; + } + } + + // Force a camera update + if (update) + { + IGN_PROFILE("VideoRecorder Update camera"); + this->camera->Update(); + } + + // record video is requested + { + IGN_PROFILE("VideoRecorder Record Video"); + if (this->recordVideo) + { + unsigned int width = this->camera->ImageWidth(); + unsigned int height = this->camera->ImageHeight(); + + if (this->cameraImage.Width() != width || + this->cameraImage.Height() != height) + { + this->cameraImage = this->camera->CreateImage(); + } + + // Video recorder is on. Add more frames to it + if (this->videoEncoder.IsEncoding()) + { + this->camera->Copy(this->cameraImage); + + std::chrono::steady_clock::time_point t = + std::chrono::steady_clock::now(); + if (this->useSimTime) + { + t = std::chrono::steady_clock::time_point( + this->simTime); + } + bool frameAdded = this->videoEncoder.AddFrame( + this->cameraImage.Data(), width, height, t); + + if (frameAdded) + { + // publish recorder stats + if (this->startTime == + std::chrono::steady_clock::time_point( + std::chrono::duration(std::chrono::seconds(0)))) + { + // start time, i.e. time when first frame is added + this->startTime = t; + } + + std::chrono::steady_clock::duration dt; + dt = t - this->startTime; + int64_t sec, nsec; + std::tie(sec, nsec) = ignition::math::durationToSecNsec(dt); + msgs::Time msg; + msg.set_sec(sec); + msg.set_nsec(nsec); + this->recorderStatsPub.Publish(msg); + } + } + // Video recorder is idle. Start recording. + else + { + if (this->useSimTime) + ignmsg << "Recording video using sim time." << std::endl; + if (this->lockstep) + { + ignmsg << "Recording video in lockstep mode" << std::endl; + if (!this->useSimTime) + { + ignwarn << "It is recommended to set to true " + << "when recording video in lockstep mode." << std::endl; + } + } + ignmsg << "Recording video using bitrate: " + << this->bitrate << std::endl; + this->videoEncoder.Start(this->format, + this->filename, width, height, 25, + this->bitrate); + this->startTime = std::chrono::steady_clock::time_point( + std::chrono::duration(std::chrono::seconds(0))); + } + } + else if (this->videoEncoder.IsEncoding()) + { + this->videoEncoder.Stop(); + } + } + // only has an effect in video recording lockstep mode + // this notifes ECM to continue updating the scene + g_renderCv.notify_one(); +} + ///////////////////////////////////////////////// VideoRecorder::VideoRecorder() - : gui::Plugin(), dataPtr(std::make_unique()) + : GuiSystem(), dataPtr(std::make_unique()) { } ///////////////////////////////////////////////// VideoRecorder::~VideoRecorder() = default; +////////////////////////////////////////////////// +void VideoRecorder::Update(const UpdateInfo &_info, + EntityComponentManager & /*_ecm*/) +{ + // Don't lockstep in legacy mode, GzScene3D takes care of that + if (this->dataPtr->legacy) + return; + + this->dataPtr->simTime = _info.simTime; + + // check if video recording is enabled and if we need to lock step + // ECM updates with GUI rendering during video recording + std::unique_lock lock(this->dataPtr->recordMutex); + if (this->dataPtr->recording && this->dataPtr->lockstep) + { + std::unique_lock lock2(this->dataPtr->renderMutex); + g_renderCv.wait(lock2); + } +} + ///////////////////////////////////////////////// -void VideoRecorder::LoadConfig(const tinyxml2::XMLElement *) +void VideoRecorder::LoadConfig(const tinyxml2::XMLElement * _pluginElem) { if (this->title.empty()) this->title = "Video recorder"; - // For video record requests - this->dataPtr->service = "/gui/record_video"; + // Custom parameters + if (_pluginElem) + { + if (auto elem = _pluginElem->FirstChildElement("record_video")) + { + if (auto useSimTimeElem = elem->FirstChildElement("use_sim_time")) + { + bool useSimTime = false; + if (useSimTimeElem->QueryBoolText(&useSimTime) != tinyxml2::XML_SUCCESS) + { + ignerr << "Faild to parse value: " + << useSimTimeElem->GetText() << std::endl; + } + else + { + this->dataPtr->useSimTime = useSimTime; + } + } + if (auto lockstepElem = elem->FirstChildElement("lockstep")) + { + bool lockstep = false; + if (lockstepElem->QueryBoolText(&lockstep) != tinyxml2::XML_SUCCESS) + { + ignerr << "Failed to parse value: " + << lockstepElem->GetText() << std::endl; + } + else + { + this->dataPtr->lockstep = lockstep; + } + } + if (auto bitrateElem = elem->FirstChildElement("bitrate")) + { + unsigned int bitrate = 0u; + std::stringstream bitrateStr; + bitrateStr << std::string(bitrateElem->GetText()); + bitrateStr >> bitrate; + if (bitrate > 0u) + { + this->dataPtr->bitrate = bitrate; + } + else + { + ignerr << "Video recorder bitrate must be larger than 0" + << std::endl; + } + } + } + + if (auto elem = _pluginElem->FirstChildElement("legacy")) + { + elem->QueryBoolText(&this->dataPtr->legacy); + } + } + + if (this->dataPtr->legacy) + { + igndbg << "Legacy mode is enabled; this plugin must be used with " + << "GzScene3D." << std::endl; + } + else + { + igndbg << "Legacy mode is disabled; this plugin must be used with " + << "MinimalScene." << std::endl; + } + + ignition::gui::App()->findChild< + ignition::gui::MainWindow *>()->installEventFilter(this); } ///////////////////////////////////////////////// -void VideoRecorder::OnStart(const QString &_format) +bool VideoRecorder::eventFilter(QObject *_obj, QEvent *_event) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + if (_event->type() == ignition::gui::events::Render::kType) { - if (!_result) - ignerr << "Error sending video record start request" << std::endl; - }; + this->dataPtr->OnRender(); + } + // Standard event processing + return QObject::eventFilter(_obj, _event); +} - std::string format = _format.toStdString(); - this->dataPtr->filename = "ign_recording." + format; +///////////////////////////////////////////////// +void VideoRecorder::OnStart(const QString &_format) +{ + std::unique_lock lock(this->dataPtr->recordMutex); + this->dataPtr->format = _format.toStdString(); + this->dataPtr->filename = "ign_recording." + this->dataPtr->format; + this->dataPtr->recordVideo = true; + this->dataPtr->recording = true; - ignition::msgs::VideoRecord req; - req.set_start(true); - req.set_format(format); - req.set_save_filename(this->dataPtr->filename); - this->dataPtr->node.Request(this->dataPtr->service, req, cb); + if (this->dataPtr->legacy) + { + std::function cb = + [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + { + if (!_result) + ignerr << "Error sending video record start request" << std::endl; + }; + ignition::msgs::VideoRecord req; + req.set_start(this->dataPtr->recordVideo); + req.set_format(this->dataPtr->format); + req.set_save_filename(this->dataPtr->filename); + this->dataPtr->node.Request(this->dataPtr->service, req, cb); + } } ///////////////////////////////////////////////// void VideoRecorder::OnStop() { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + this->dataPtr->recordVideo = false; + this->dataPtr->recording = false; + + if (this->dataPtr->legacy) { - if (!_result) - ignerr << "Error sending video record stop request" << std::endl; - }; + std::function cb = + [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + { + if (!_result) + ignerr << "Error sending video record stop request" << std::endl; + }; - ignition::msgs::VideoRecord req; - req.set_stop(true); - this->dataPtr->node.Request(this->dataPtr->service, req, cb); + ignition::msgs::VideoRecord req; + req.set_stop(true); + this->dataPtr->node.Request(this->dataPtr->service, req, cb); + } } ///////////////////////////////////////////////// diff --git a/src/gui/plugins/video_recorder/VideoRecorder.hh b/src/gui/plugins/video_recorder/VideoRecorder.hh index b9f98e8ddf..bed6fe3a02 100644 --- a/src/gui/plugins/video_recorder/VideoRecorder.hh +++ b/src/gui/plugins/video_recorder/VideoRecorder.hh @@ -20,7 +20,7 @@ #include -#include +#include namespace ignition { @@ -28,8 +28,8 @@ namespace gazebo { class VideoRecorderPrivate; - /// \brief Provides buttons for starting and stopping video recording - class VideoRecorder : public ignition::gui::Plugin + /// \brief Provides video recording cababilities to the 3D scene. + class VideoRecorder : public ignition::gazebo::GuiSystem { Q_OBJECT @@ -42,6 +42,13 @@ namespace gazebo // Documentation inherited public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override; + // Documentation inherited + public: void Update(const UpdateInfo &_info, EntityComponentManager &_ecm) + override; + + // Documentation inherited + public: bool eventFilter(QObject *_obj, QEvent *_event); + /// \brief Callback when video record start request is received /// \param[in] _format Video encoding format public slots: void OnStart(const QString &_format); diff --git a/src/gui/plugins/video_recorder_logic/CMakeLists.txt b/src/gui/plugins/video_recorder_logic/CMakeLists.txt deleted file mode 100644 index c76934945c..0000000000 --- a/src/gui/plugins/video_recorder_logic/CMakeLists.txt +++ /dev/null @@ -1,8 +0,0 @@ -gz_add_gui_plugin(VideoRecorderLogic - SOURCES - VideoRecorderLogic.cc - QT_HEADERS - VideoRecorderLogic.hh - PUBLIC_LINK_LIBS - ignition-rendering${IGN_RENDERING_VER}::ignition-rendering${IGN_RENDERING_VER} -) diff --git a/src/gui/plugins/video_recorder_logic/VideoRecorderLogic.cc b/src/gui/plugins/video_recorder_logic/VideoRecorderLogic.cc deleted file mode 100644 index b012b335aa..0000000000 --- a/src/gui/plugins/video_recorder_logic/VideoRecorderLogic.cc +++ /dev/null @@ -1,400 +0,0 @@ -/* - * Copyright (C) 2021 Open Source Robotics Foundation - * - * 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 - -#include -#include -#include - -#include -#include -#include - -#include - -#include -#include -#include - -#include - -#include "VideoRecorderLogic.hh" - -/// \brief condition variable for lockstepping video recording -/// todo(anyone) avoid using a global condition variable when we support -/// multiple viewports in the future. -std::condition_variable g_renderCv; - -namespace ignition::gazebo::plugins -{ - class VideoRecorderLogicPrivate - { - /// \brief Update the Video Recorder Plugin on the latest state of the ECM. - public: void OnRender(); - - // Initialize Video Recorder Logic plugin - public: void Initialize(); - - /// \brief Callback for a record video request - /// \param[in] _msg Request message to enable/disable video recording. - /// \param[in] _res Response data - /// \return True if the request is received - public: bool OnRecordVideo( - const msgs::VideoRecord &_msg, msgs::Boolean &_res); - - /// \brief Ignition communication node. - public: transport::Node node; - - /// \brief Pointer to the camera being moved - public: rendering::CameraPtr camera{nullptr}; - - /// \brief Pointer to the camera being moved - public: rendering::ScenePtr scene{nullptr}; - - /// \brief Video encoder - public: common::VideoEncoder videoEncoder; - - /// \brief Image from user camera - public: rendering::Image cameraImage; - - /// \brief True to record a video from the user camera - public: bool recordVideo = false; - - /// \brief Video encoding format - public: std::string recordVideoFormat; - - /// \brief Path to save the recorded video - public: std::string recordVideoSavePath; - - /// \brief Use sim time as timestamp during video recording - /// By default (false), video encoding is done using real time. - public: bool recordVideoUseSimTime = false; - - /// \brief Lockstep gui with ECM when recording - public: bool recordVideoLockstep = false; - - /// \brief Video recorder bitrate (bps) - public: unsigned int recordVideoBitrate = 2070000; - - /// \brief Previous camera update time during video recording - /// only used in lockstep mode and recording in sim time. - public: std::chrono::steady_clock::time_point recordVideoUpdateTime; - - /// \brief Start tiem of video recording - public: std::chrono::steady_clock::time_point recordStartTime; - - /// \brief Camera pose publisher - public: transport::Node::Publisher recorderStatsPub; - - /// \brief Record stats topic name - public: std::string recorderStatsTopic = "/gui/record_video/stats"; - - /// \brief Record video service - public: std::string recordVideoService = "/gui/record_video"; - - /// \brief True to indicate video recording in progress - public: bool recording = false; - - /// \brief mutex to protect the recording variable - public: std::mutex recordMutex; - - /// \brief mutex to protect the render condition variable - /// Used when recording in lockstep mode. - public: std::mutex renderMutex; - - /// \brief Total time elapsed in simulation. This will not increase while - /// paused. - public: std::chrono::steady_clock::duration simTime{0}; - }; -} - -using namespace ignition; -using namespace gazebo; -using namespace plugins; - -void VideoRecorderLogicPrivate::Initialize() -{ - if (!this->scene) - { - this->scene = rendering::sceneFromFirstRenderEngine(); - if (!this->scene) - return; - - for (unsigned int i = 0; i < scene->NodeCount(); ++i) - { - auto cam = std::dynamic_pointer_cast( - scene->NodeByIndex(i)); - if (cam) - { - if (std::get(cam->UserData("user-camera"))) - { - this->camera = cam; - igndbg << "Video Recorder plugin is recoding camera [" - << this->camera->Name() << "]" << std::endl; - break; - } - } - } - - if (!this->camera) - { - ignerr << "InteractiveViewControl camera is not available" << std::endl; - return; - } - - // video recorder - this->node.Advertise(this->recordVideoService, - &VideoRecorderLogicPrivate::OnRecordVideo, this); - ignmsg << "Record video service on [" - << this->recordVideoService << "]" << std::endl; - - // recorder stats topic - this->recorderStatsPub = - this->node.Advertise(this->recorderStatsTopic); - ignmsg << "Video recorder stats topic advertised on [" - << this->recorderStatsTopic << "]" << std::endl; - } -} - -///////////////////////////////////////////////// -bool VideoRecorderLogicPrivate::OnRecordVideo(const msgs::VideoRecord &_msg, - msgs::Boolean &_res) -{ - bool record = _msg.start() && !_msg.stop(); - - this->recordVideo = record; - this->recordVideoFormat = _msg.format(); - this->recordVideoSavePath = _msg.save_filename(); - - _res.set_data(true); - - std::unique_lock lock(this->recordMutex); - this->recording = record; - return true; -} - -///////////////////////////////////////////////// -void VideoRecorderLogicPrivate::OnRender() -{ - this->Initialize(); - - // check if recording is in lockstep mode and if it is using sim time - // if so, there is no need to update camera if sim time has not advanced - bool update = true; - if (this->recordVideoLockstep && - this->recordVideoUseSimTime && - this->videoEncoder.IsEncoding()) - { - std::chrono::steady_clock::time_point t = - std::chrono::steady_clock::time_point( - this->simTime); - if (t - this->recordVideoUpdateTime == std::chrono::seconds(0)) - update = false; - else - this->recordVideoUpdateTime = t; - } - - // update and render to texture - if (update) - { - IGN_PROFILE("IgnRenderer::Render Update camera"); - this->camera->Update(); - } - - // record video is requested - { - IGN_PROFILE("IgnRenderer::Render Record Video"); - if (this->recordVideo) - { - unsigned int width = this->camera->ImageWidth(); - unsigned int height = this->camera->ImageHeight(); - - if (this->cameraImage.Width() != width || - this->cameraImage.Height() != height) - { - this->cameraImage = this->camera->CreateImage(); - } - - // Video recorder is on. Add more frames to it - if (this->videoEncoder.IsEncoding()) - { - this->camera->Copy(this->cameraImage); - - std::chrono::steady_clock::time_point t = - std::chrono::steady_clock::now(); - if (this->recordVideoUseSimTime) - { - t = std::chrono::steady_clock::time_point( - this->simTime); - } - bool frameAdded = this->videoEncoder.AddFrame( - this->cameraImage.Data(), width, height, t); - - if (frameAdded) - { - // publish recorder stats - if (this->recordStartTime == - std::chrono::steady_clock::time_point( - std::chrono::duration(std::chrono::seconds(0)))) - { - // start time, i.e. time when first frame is added - this->recordStartTime = t; - } - - std::chrono::steady_clock::duration dt; - dt = t - this->recordStartTime; - int64_t sec, nsec; - std::tie(sec, nsec) = ignition::math::durationToSecNsec(dt); - msgs::Time msg; - msg.set_sec(sec); - msg.set_nsec(nsec); - this->recorderStatsPub.Publish(msg); - } - } - // Video recorder is idle. Start recording. - else - { - if (this->recordVideoUseSimTime) - ignmsg << "Recording video using sim time." << std::endl; - if (this->recordVideoLockstep) - { - ignmsg << "Recording video in lockstep mode" << std::endl; - if (!this->recordVideoUseSimTime) - { - ignwarn << "It is recommended to set to true " - << "when recording video in lockstep mode." << std::endl; - } - } - ignmsg << "Recording video using bitrate: " - << this->recordVideoBitrate << std::endl; - this->videoEncoder.Start(this->recordVideoFormat, - this->recordVideoSavePath, width, height, 25, - this->recordVideoBitrate); - this->recordStartTime = std::chrono::steady_clock::time_point( - std::chrono::duration(std::chrono::seconds(0))); - } - } - else if (this->videoEncoder.IsEncoding()) - { - this->videoEncoder.Stop(); - } - } - // only has an effect in video recording lockstep mode - // this notifes ECM to continue updating the scene - g_renderCv.notify_one(); -} - -///////////////////////////////////////////////// -VideoRecorderLogic::VideoRecorderLogic() - : GuiSystem(), dataPtr(std::make_unique()) -{ -} - -///////////////////////////////////////////////// -VideoRecorderLogic::~VideoRecorderLogic() = default; - -////////////////////////////////////////////////// -void VideoRecorderLogic::Update(const UpdateInfo &_info, - EntityComponentManager & /*_ecm*/) -{ - this->dataPtr->simTime = _info.simTime; - - // check if video recording is enabled and if we need to lock step - // ECM updates with GUI rendering during video recording - std::unique_lock lock(this->dataPtr->recordMutex); - if (this->dataPtr->recording && this->dataPtr->recordVideoLockstep) - { - std::unique_lock lock2(this->dataPtr->renderMutex); - g_renderCv.wait(lock2); - } -} - -///////////////////////////////////////////////// -void VideoRecorderLogic::LoadConfig(const tinyxml2::XMLElement * _pluginElem) -{ - if (this->title.empty()) - this->title = "Video recorder"; - - // Custom parameters - if (_pluginElem) - { - if (auto elem = _pluginElem->FirstChildElement("record_video")) - { - if (auto useSimTimeElem = elem->FirstChildElement("use_sim_time")) - { - bool useSimTime = false; - if (useSimTimeElem->QueryBoolText(&useSimTime) != tinyxml2::XML_SUCCESS) - { - ignerr << "Faild to parse value: " - << useSimTimeElem->GetText() << std::endl; - } - else - { - this->dataPtr->recordVideoUseSimTime = useSimTime; - } - } - if (auto lockstepElem = elem->FirstChildElement("lockstep")) - { - bool lockstep = false; - if (lockstepElem->QueryBoolText(&lockstep) != tinyxml2::XML_SUCCESS) - { - ignerr << "Failed to parse value: " - << lockstepElem->GetText() << std::endl; - } - else - { - this->dataPtr->recordVideoLockstep = lockstep; - } - } - if (auto bitrateElem = elem->FirstChildElement("bitrate")) - { - unsigned int bitrate = 0u; - std::stringstream bitrateStr; - bitrateStr << std::string(bitrateElem->GetText()); - bitrateStr >> bitrate; - if (bitrate > 0u) - { - this->dataPtr->recordVideoBitrate = bitrate; - } - else - { - ignerr << "Video recorder bitrate must be larger than 0" - << std::endl; - } - } - } - } - - ignition::gui::App()->findChild< - ignition::gui::MainWindow *>()->installEventFilter(this); -} - -///////////////////////////////////////////////// -bool VideoRecorderLogic::eventFilter(QObject *_obj, QEvent *_event) -{ - if (_event->type() == ignition::gui::events::Render::kType) - { - this->dataPtr->OnRender(); - } - // Standard event processing - return QObject::eventFilter(_obj, _event); -} - -// Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::plugins::VideoRecorderLogic, - ignition::gui::Plugin) diff --git a/src/gui/plugins/video_recorder_logic/VideoRecorderLogic.hh b/src/gui/plugins/video_recorder_logic/VideoRecorderLogic.hh deleted file mode 100644 index 8b501c4a2b..0000000000 --- a/src/gui/plugins/video_recorder_logic/VideoRecorderLogic.hh +++ /dev/null @@ -1,62 +0,0 @@ -/* - * Copyright (C) 2021 Open Source Robotics Foundation - * - * 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 IGNITION_GAZEBO_GUI_VIDEORECORDERLOGIC_HH_ -#define IGNITION_GAZEBO_GUI_VIDEORECORDERLOGIC_HH_ - -#include - -#include - -namespace ignition -{ -namespace gazebo -{ -namespace plugins -{ - class VideoRecorderLogicPrivate; - - /// \brief Provides buttons for starting and stopping video recording - class VideoRecorderLogic : public ignition::gazebo::GuiSystem - { - Q_OBJECT - - /// \brief Constructor - public: VideoRecorderLogic(); - - /// \brief Destructor - public: ~VideoRecorderLogic() override; - - // Documentation inherited - public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override; - - // Documentation inherited - public: bool eventFilter(QObject *_obj, QEvent *_event); - - // Documentation inherited - public: void Update(const UpdateInfo &_info, EntityComponentManager &_ecm) - override; - - /// \internal - /// \brief Pointer to private data. - private: std::unique_ptr dataPtr; - }; -} -} -} - -#endif diff --git a/src/gui/plugins/video_recorder_logic/VideoRecorderLogic.qml b/src/gui/plugins/video_recorder_logic/VideoRecorderLogic.qml deleted file mode 100644 index 873da30014..0000000000 --- a/src/gui/plugins/video_recorder_logic/VideoRecorderLogic.qml +++ /dev/null @@ -1,28 +0,0 @@ -/* - * Copyright (C) 2021 Open Source Robotics Foundation - * - * 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. - * -*/ - -import QtQuick 2.0 -import QtQuick.Controls 2.0 -import QtQuick.Layouts 1.3 - -// TODO: remove invisible rectangle, see -// https://github.com/ignitionrobotics/ign-gui/issues/220 -Rectangle { - visible: false - Layout.minimumWidth: 100 - Layout.minimumHeight: 100 -} diff --git a/src/gui/plugins/video_recorder_logic/VideoRecorderLogic.qrc b/src/gui/plugins/video_recorder_logic/VideoRecorderLogic.qrc deleted file mode 100644 index 32b50ae391..0000000000 --- a/src/gui/plugins/video_recorder_logic/VideoRecorderLogic.qrc +++ /dev/null @@ -1,5 +0,0 @@ - - - VideoRecorderLogic.qml - -