Skip to content

Commit

Permalink
set bit rate and pub recorder video stats
Browse files Browse the repository at this point in the history
Signed-off-by: Ian Chen <[email protected]>
  • Loading branch information
iche033 committed Oct 21, 2020
1 parent 7348bf4 commit 6533d0d
Show file tree
Hide file tree
Showing 2 changed files with 82 additions and 2 deletions.
76 changes: 74 additions & 2 deletions src/gui/plugins/scene3d/Scene3D.cc
Original file line number Diff line number Diff line change
Expand Up @@ -209,6 +209,15 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// By default (false), video encoding is done using real time.
public: bool recordVideoUseSimTime = false;

/// \brief Video recorder bitrate (bps)
public: unsigned int recordVideoBitrate = 2070000;

/// \brief Start tiem of video recording
public: std::chrono::steady_clock::time_point recordStartTime;

/// \brief Camera pose publisher
public: transport::Node::Publisher recorderStatsPub;

/// \brief Target to move the user camera to
public: std::string moveToTarget;

Expand Down Expand Up @@ -414,6 +423,13 @@ IgnRenderer::IgnRenderer()
: dataPtr(new IgnRendererPrivate)
{
this->dataPtr->moveToHelper.initCameraPose = this->cameraPose;

// recorder stats topic
std::string recorderStatsTopic = "/gui/record_video/stats";
this->dataPtr->recorderStatsPub =
this->dataPtr->node.Advertise<msgs::Time>(recorderStatsTopic);
ignmsg << "Video recorder stats topic advertised on ["
<< recorderStatsTopic << "]" << std::endl;
}


Expand Down Expand Up @@ -507,16 +523,42 @@ void IgnRenderer::Render()
t = std::chrono::steady_clock::time_point(
this->dataPtr->renderUtil.SimTime());
}
this->dataPtr->videoEncoder.AddFrame(
bool frameAdded = this->dataPtr->videoEncoder.AddFrame(
this->dataPtr->cameraImage.Data<unsigned char>(), width, height, t);

if (frameAdded)
{
// publish recorder stats
if (this->dataPtr->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->dataPtr->recordStartTime = t;
}

std::chrono::steady_clock::duration dt;
dt = t - this->dataPtr->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-dataPtr->recorderStatsPub.Publish(msg);
}
}
// Video recorder is idle. Start recording.
else
{
if (this->dataPtr->recordVideoUseSimTime)
ignmsg << "Recording video using sim time." << std::endl;
ignmsg << "Recording video using bitrate: "
<< this->dataPtr->recordVideoBitrate << std::endl;
this->dataPtr->videoEncoder.Start(this->dataPtr->recordVideoFormat,
this->dataPtr->recordVideoSavePath, width, height);
this->dataPtr->recordVideoSavePath, width, height, 25,
this->dataPtr->recordVideoBitrate);
this->dataPtr->recordStartTime = std::chrono::steady_clock::time_point(
std::chrono::duration(std::chrono::seconds(0)));
}
}
else if (this->dataPtr->videoEncoder.IsEncoding())
Expand Down Expand Up @@ -1699,6 +1741,13 @@ void IgnRenderer::SetRecordVideoUseSimTime(bool _useSimTime)
this->dataPtr->recordVideoUseSimTime = _useSimTime;
}

/////////////////////////////////////////////////
void IgnRenderer::SetRecordVideoBitrate(unsigned int _bitrate)
{
std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
this->dataPtr->recordVideoBitrate = _bitrate;
}

/////////////////////////////////////////////////
void IgnRenderer::SetMoveTo(const std::string &_target)
{
Expand Down Expand Up @@ -2349,6 +2398,22 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem)
<< std::endl;
}
}
if (auto bitrateElem = elem->FirstChildElement("bitrate"))
{
unsigned int bitrate = 0u;
std::stringstream bitrateStr;
bitrateStr << std::string(bitrateElem->GetText());
bitrateStr >> bitrate;
if (bitrate > 0u)
{
renderWindow->SetRecordVideoBitrate(bitrate);
}
else
{
ignerr << "Video recorder bitrate must be larger than 0"
<< std::endl;
}
}
}

if (auto elem = _pluginElem->FirstChildElement("fullscreen"))
Expand Down Expand Up @@ -2837,6 +2902,13 @@ void RenderWindowItem::SetRecordVideoUseSimTime(bool _useSimTime)
_useSimTime);
}

/////////////////////////////////////////////////
void RenderWindowItem::SetRecordVideoBitrate(unsigned int _bitrate)
{
this->dataPtr->renderThread->ignRenderer.SetRecordVideoBitrate(
_bitrate);
}

/////////////////////////////////////////////////
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 @@ -210,6 +210,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \param[in] _true True record video using sim time
public: void SetRecordVideoUseSimTime(bool _useSimTime);

/// \brief Set video recorder bitrate in bps
/// \param[in] _bitrate Bit rate to set to
public: void SetRecordVideoBitrate(unsigned int _bitrate);

/// \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 @@ -523,6 +527,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \param[in] _true True record video using sim time
public: void SetRecordVideoUseSimTime(bool _useSimTime);

/// \brief Set video recorder bitrate in bps
/// \param[in] _bitrate Bit rate to set to
public: void SetRecordVideoBitrate(unsigned int _bitrate);

/// \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

0 comments on commit 6533d0d

Please sign in to comment.