Skip to content

Commit

Permalink
Add ability to record video based on sim time (#414)
Browse files Browse the repository at this point in the history
* add ability to record video from gui camera using sim time

Signed-off-by: Ian Chen <ichen@osrfoundation.org>

* add msg

Signed-off-by: Ian Chen <ichen@osrfoundation.org>

* use QueryBoolText

Signed-off-by: Ian Chen <ichen@osrfoundation.org>

Co-authored-by: Nate Koenig <nate@openrobotics.org>
Co-authored-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
3 people authored Dec 21, 2020
1 parent 7643e7b commit 478dea6
Show file tree
Hide file tree
Showing 4 changed files with 66 additions and 1 deletion.
5 changes: 5 additions & 0 deletions include/ignition/gazebo/rendering/RenderUtil.hh
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,11 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// Returns reference to the marker manager.
public: class MarkerManager &MarkerManager();

/// \brief Get simulation time that the current rendering state corresponds
/// to
/// \returns Simulation time.
public: std::chrono::steady_clock::duration SimTime() const;

/// \brief Set the entity being selected
/// \param[in] _node Node representing the selected entity
/// \TODO(anyone) Make const ref when merging forward
Expand Down
47 changes: 46 additions & 1 deletion src/gui/plugins/scene3d/Scene3D.cc
Original file line number Diff line number Diff line change
Expand Up @@ -198,6 +198,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \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 Target to move the user camera to
public: std::string moveToTarget;

Expand Down Expand Up @@ -489,12 +493,22 @@ void IgnRenderer::Render()
if (this->dataPtr->videoEncoder.IsEncoding())
{
this->dataPtr->camera->Copy(this->dataPtr->cameraImage);

std::chrono::steady_clock::time_point t =
std::chrono::steady_clock::now();
if (this->dataPtr->recordVideoUseSimTime)
{
t = std::chrono::steady_clock::time_point(
this->dataPtr->renderUtil.SimTime());
}
this->dataPtr->videoEncoder.AddFrame(
this->dataPtr->cameraImage.Data<unsigned char>(), width, height);
this->dataPtr->cameraImage.Data<unsigned char>(), width, height, t);
}
// Video recorder is idle. Start recording.
else
{
if (this->dataPtr->recordVideoUseSimTime)
ignmsg << "Recording video using sim time." << std::endl;
this->dataPtr->videoEncoder.Start(this->dataPtr->recordVideoFormat,
this->dataPtr->recordVideoSavePath, width, height);
}
Expand Down Expand Up @@ -1715,6 +1729,13 @@ void IgnRenderer::SetRecordVideo(bool _record, const std::string &_format,
this->dataPtr->recordVideoSavePath = _savePath;
}

/////////////////////////////////////////////////
void IgnRenderer::SetRecordVideoUseSimTime(bool _useSimTime)
{
std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
this->dataPtr->recordVideoUseSimTime = _useSimTime;
}

/////////////////////////////////////////////////
void IgnRenderer::SetMoveTo(const std::string &_target)
{
Expand Down Expand Up @@ -2331,6 +2352,23 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_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 <use_sim_time> value: "
<< useSimTimeElem->GetText() << std::endl;
}
else
{
renderWindow->SetRecordVideoUseSimTime(useSimTime);
}
}
}

if (auto elem = _pluginElem->FirstChildElement("fullscreen"))
{
auto fullscreen = false;
Expand Down Expand Up @@ -2815,6 +2853,13 @@ void RenderWindowItem::SetWorldName(const std::string &_name)
this->dataPtr->renderThread->ignRenderer.worldName = _name;
}

/////////////////////////////////////////////////
void RenderWindowItem::SetRecordVideoUseSimTime(bool _useSimTime)
{
this->dataPtr->renderThread->ignRenderer.SetRecordVideoUseSimTime(
_useSimTime);
}

/////////////////////////////////////////////////
void RenderWindowItem::OnHovered(const ignition::math::Vector2i &_hoverPos)
{
Expand Down
8 changes: 8 additions & 0 deletions src/gui/plugins/scene3d/Scene3D.hh
Original file line number Diff line number Diff line change
Expand Up @@ -206,6 +206,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
public: void SetRecordVideo(bool _record, const std::string &_format,
const std::string &_savePath);

/// \brief Set whether to record video using sim time as timestamp
/// \param[in] _true True record video using sim time
public: void SetRecordVideoUseSimTime(bool _useSimTime);

/// \brief Move the user camera to move to the speficied target
/// \param[in] _target Target to move the camera to
public: void SetMoveTo(const std::string &_target);
Expand Down Expand Up @@ -521,6 +525,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
public: void SetRecordVideo(bool _record, const std::string &_format,
const std::string &_savePath);

/// \brief Set whether to record video using sim time as timestamp
/// \param[in] _true True record video using sim time
public: void SetRecordVideoUseSimTime(bool _useSimTime);

/// \brief Move the user camera to move to the specified target
/// \param[in] _target Target to move the camera to
public: void SetMoveTo(const std::string &_target);
Expand Down
7 changes: 7 additions & 0 deletions src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1153,6 +1153,13 @@ MarkerManager &RenderUtil::MarkerManager()
return this->dataPtr->markerManager;
}

//////////////////////////////////////////////////
std::chrono::steady_clock::duration RenderUtil::SimTime() const
{
std::lock_guard<std::mutex> lock(this->dataPtr->updateMutex);
return this->dataPtr->simTime;
}

/////////////////////////////////////////////////
// NOLINTNEXTLINE
void RenderUtil::SetSelectedEntity(rendering::NodePtr _node)
Expand Down

0 comments on commit 478dea6

Please sign in to comment.