Skip to content

Commit

Permalink
[Gazebo 9] Added Profiler to gazebo::rendering and gzclient (#2836)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <ahcorde@gmail.com>
Signed-off-by: Louise Poubel <louise@openrobotics.org>

Co-authored-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
ahcorde and chapulina authored Oct 3, 2020
1 parent fededa7 commit ce6570f
Show file tree
Hide file tree
Showing 35 changed files with 123 additions and 12 deletions.
1 change: 0 additions & 1 deletion gazebo/common/Profiler.hh
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@
#include <string>

#include "gazebo/common/SingletonT.hh"
#include "gazebo/common/Remotery/lib/Remotery.h"
#include "gazebo/util/system.hh"

/// \brief Explicit instantiation for typed SingletonT.
Expand Down
22 changes: 17 additions & 5 deletions gazebo/gui/GLWidget.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@

#include "gazebo/common/Assert.hh"
#include "gazebo/common/Exception.hh"
#include "gazebo/common/Profiler.hh"
#include "gazebo/rendering/Conversions.hh"
#include "gazebo/rendering/FPSViewController.hh"
#include "gazebo/rendering/Heightmap.hh"
Expand Down Expand Up @@ -279,16 +280,27 @@ void GLWidget::paintEvent(QPaintEvent *_e)
rendering::UserCameraPtr cam = gui::get_active_camera();
if (cam && cam->Initialized())
{
event::Events::preRender();

{
GZ_PROFILE("gui::GLWidget::paintEvent pre-render");
event::Events::preRender();
}
// Tell all the cameras to render
event::Events::render();
{
GZ_PROFILE("gui::GLWidget::paintEvent render");
event::Events::render();
}

event::Events::postRender();
{
GZ_PROFILE("gui::GLWidget::paintEvent post-render");
event::Events::postRender();
}
}
else
{
event::Events::preRender();
{
GZ_PROFILE("gui::GLWidget::paintEvent pre-render");
event::Events::preRender();
}
}

_e->accept();
Expand Down
3 changes: 3 additions & 0 deletions gazebo/gui/GuiIface.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include "gazebo/common/ModelDatabase.hh"
#include "gazebo/common/Console.hh"
#include "gazebo/common/Plugin.hh"
#include "gazebo/common/Profiler.hh"
#include "gazebo/common/CommonTypes.hh"
#include "gazebo/gui/SplashScreen.hh"
#include "gazebo/gui/MainWindow.hh"
Expand Down Expand Up @@ -382,6 +383,8 @@ unsigned int gui::get_entity_id(const std::string &_name)
/////////////////////////////////////////////////
bool gui::run(int _argc, char **_argv)
{
GZ_PROFILE_THREAD_NAME("gzclient");

// Initialize the informational logger. This will log warnings, and errors.
gzLogInit("client-", "gzclient.log");

Expand Down
3 changes: 3 additions & 0 deletions gazebo/gui/main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,9 @@
//////////////////////////////////////////////////
int main(int _argc, char **_argv)
{
#ifndef _WIN32
::setenv("RMT_PORT", "1501", true);
#endif
Q_INIT_RESOURCE(resources);
int result = 0;
try
Expand Down
4 changes: 4 additions & 0 deletions gazebo/rendering/ApplyWrenchVisual.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <ignition/math/Matrix4.hh>

#include "gazebo/common/MeshManager.hh"
#include "gazebo/common/Profiler.hh"

#include "gazebo/rendering/Material.hh"
#include "gazebo/rendering/MovableText.hh"
Expand Down Expand Up @@ -307,6 +308,7 @@ void ApplyWrenchVisual::SetTorque(const ignition::math::Vector3d &_torqueVector,
///////////////////////////////////////////////////
void ApplyWrenchVisual::UpdateForceVisual()
{
GZ_PROFILE("ApplyWrenchVisual::UpdateForceVisual");
ApplyWrenchVisualPrivate *dPtr =
reinterpret_cast<ApplyWrenchVisualPrivate *>(this->dataPtr);

Expand Down Expand Up @@ -342,6 +344,7 @@ void ApplyWrenchVisual::UpdateForceVisual()
///////////////////////////////////////////////////
void ApplyWrenchVisual::UpdateTorqueVisual()
{
GZ_PROFILE("ApplyWrenchVisual::UpdateTorqueVisual");
ApplyWrenchVisualPrivate *dPtr =
reinterpret_cast<ApplyWrenchVisualPrivate *>(this->dataPtr);

Expand Down Expand Up @@ -380,6 +383,7 @@ void ApplyWrenchVisual::UpdateTorqueVisual()
/////////////////////////////////////////////////
void ApplyWrenchVisual::Resize()
{
GZ_PROFILE("ApplyWrenchVisual::Resize");
ApplyWrenchVisualPrivate *dPtr =
reinterpret_cast<ApplyWrenchVisualPrivate *>(this->dataPtr);

Expand Down
3 changes: 3 additions & 0 deletions gazebo/rendering/Camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
#include "gazebo/common/Events.hh"
#include "gazebo/common/Console.hh"
#include "gazebo/common/Exception.hh"
#include "gazebo/common/Profiler.hh"
#include "gazebo/common/VideoEncoder.hh"

#include "gazebo/rendering/ogre_gazebo.h"
Expand Down Expand Up @@ -408,6 +409,7 @@ void Camera::SetScene(ScenePtr _scene)
//////////////////////////////////////////////////
void Camera::Update()
{
GZ_PROFILE("rendering::Camera::Update");
std::lock_guard<std::mutex> lock(this->dataPtr->receiveMutex);

// Process all the command messages.
Expand Down Expand Up @@ -539,6 +541,7 @@ void Camera::Update()
//////////////////////////////////////////////////
void Camera::Render(const bool _force)
{
GZ_PROFILE("rendering::Camera::Render");
if (this->initialized && (_force ||
common::Time::GetWallTime() - this->lastRenderWallTime >=
this->dataPtr->renderPeriod))
Expand Down
4 changes: 4 additions & 0 deletions gazebo/rendering/CameraVisual.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include <boost/bind.hpp>

#include "gazebo/common/Profiler.hh"
#include "gazebo/rendering/ogre_gazebo.h"
#include "gazebo/rendering/RenderEngine.hh"
#include "gazebo/rendering/DynamicLines.hh"
Expand Down Expand Up @@ -127,11 +128,14 @@ void CameraVisual::Load(const msgs::CameraSensor &_msg)
/////////////////////////////////////////////////
void CameraVisual::Update()
{
GZ_PROFILE("rendering::CameraVisual::Update");
CameraVisualPrivate *dPtr =
reinterpret_cast<CameraVisualPrivate *>(this->dataPtr);

if (!dPtr->camera)
{
return;
}

dPtr->camera->Render();
}
Expand Down
4 changes: 4 additions & 0 deletions gazebo/rendering/ContactVisual.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
*/
#include <boost/bind.hpp>

#include "gazebo/common/Profiler.hh"
#include "gazebo/common/MeshManager.hh"
#include "gazebo/transport/Node.hh"
#include "gazebo/transport/Subscriber.hh"
Expand Down Expand Up @@ -69,13 +70,16 @@ ContactVisual::~ContactVisual()
/////////////////////////////////////////////////
void ContactVisual::Update()
{
GZ_PROFILE("rendering::ContactVisual::Update");
ContactVisualPrivate *dPtr =
reinterpret_cast<ContactVisualPrivate *>(this->dataPtr);

boost::mutex::scoped_lock lock(dPtr->mutex);

if (!dPtr->contactsMsg || !dPtr->receivedMsg)
{
return;
}

// The following values are used to calculate normal scaling factor based
// on force value.
Expand Down
2 changes: 2 additions & 0 deletions gazebo/rendering/DynamicLines.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@

#include "gazebo/common/Console.hh"
#include "gazebo/common/Exception.hh"
#include "gazebo/common/Profiler.hh"
#include "gazebo/rendering/DynamicLines.hh"

using namespace gazebo;
Expand Down Expand Up @@ -158,6 +159,7 @@ void DynamicLines::Clear()
/////////////////////////////////////////////////
void DynamicLines::Update()
{
GZ_PROFILE("rendering::DynamicLines::Update");
if (this->dirty && this->points.size() > 1)
this->FillHardwareBuffers();
}
Expand Down
2 changes: 2 additions & 0 deletions gazebo/rendering/FPSViewController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
* limitations under the License.
*
*/
#include "gazebo/common/Profiler.hh"
#include "gazebo/common/MouseEvent.hh"

#include "gazebo/rendering/UserCamera.hh"
Expand Down Expand Up @@ -52,6 +53,7 @@ void FPSViewController::Init()
//////////////////////////////////////////////////
void FPSViewController::Update()
{
GZ_PROFILE("rendering::FPSViewController::Update");
if (this->xVelocity != ignition::math::Vector3d::Zero ||
this->yVelocity != ignition::math::Vector3d::Zero)
{
Expand Down
2 changes: 2 additions & 0 deletions gazebo/rendering/GpuLaser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include "gazebo/common/Events.hh"
#include "gazebo/common/Console.hh"
#include "gazebo/common/Exception.hh"
#include "gazebo/common/Profiler.hh"
#include "gazebo/common/Mesh.hh"
#include "gazebo/common/MeshManager.hh"
#include "gazebo/common/Timer.hh"
Expand Down Expand Up @@ -412,6 +413,7 @@ void GpuLaser::notifyRenderSingleObject(Ogre::Renderable *_rend,
//////////////////////////////////////////////////
void GpuLaser::RenderImpl()
{
GZ_PROFILE("rendering::GpuLaser::RenderImpl");
common::Timer firstPassTimer, secondPassTimer;

firstPassTimer.Start();
Expand Down
4 changes: 4 additions & 0 deletions gazebo/rendering/LaserVisual.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include <boost/bind.hpp>

#include "gazebo/common/Profiler.hh"
#include "gazebo/common/MeshManager.hh"
#include "gazebo/transport/transport.hh"

Expand Down Expand Up @@ -89,6 +90,7 @@ void LaserVisual::OnScan(ConstLaserScanStampedPtr &_msg)
/////////////////////////////////////////////////
void LaserVisual::Update()
{
GZ_PROFILE("rendering::LaserVisual::Update");
LaserVisualPrivate *dPtr =
reinterpret_cast<LaserVisualPrivate *>(this->dataPtr);

Expand All @@ -103,7 +105,9 @@ void LaserVisual::Update()
}

if (!dPtr->laserMsg || !dPtr->receivedMsg)
{
return;
}

dPtr->receivedMsg = false;

Expand Down
4 changes: 4 additions & 0 deletions gazebo/rendering/LensFlare.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <mutex>

#include "gazebo/common/Assert.hh"
#include "gazebo/common/Profiler.hh"

#include "gazebo/transport/Node.hh"

Expand Down Expand Up @@ -443,6 +444,7 @@ void LensFlare::SetScale(const double _scale)
//////////////////////////////////////////////////
void LensFlare::Update()
{
GZ_PROFILE("rendering::LensFlare::Update");
std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
// remove lens flare if we got a delete msg
if (this->dataPtr->removeLensFlare)
Expand All @@ -468,7 +470,9 @@ void LensFlare::Update()
}
}
if (!directionalLight)
{
return;
}

this->dataPtr->lightName = directionalLight->Name();

Expand Down
2 changes: 2 additions & 0 deletions gazebo/rendering/Light.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include "gazebo/common/Events.hh"
#include "gazebo/common/Exception.hh"
#include "gazebo/common/Console.hh"
#include "gazebo/common/Profiler.hh"

#include "gazebo/rendering/Scene.hh"
#include "gazebo/rendering/DynamicLines.hh"
Expand Down Expand Up @@ -114,6 +115,7 @@ void Light::Load()
//////////////////////////////////////////////////
void Light::Update()
{
GZ_PROFILE("rendering::Light::Update");
// shadow support is also affected by light type so set type first.
this->SetLightType(this->dataPtr->sdf->Get<std::string>("type"));
this->SetCastShadows(this->dataPtr->sdf->Get<bool>("cast_shadows"));
Expand Down
2 changes: 2 additions & 0 deletions gazebo/rendering/MarkerVisual.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
*
*/
#include "gazebo/common/Console.hh"
#include "gazebo/common/Profiler.hh"
#include "gazebo/rendering/RenderEvents.hh"
#include "gazebo/rendering/DynamicLines.hh"
#include "gazebo/rendering/Scene.hh"
Expand Down Expand Up @@ -188,6 +189,7 @@ common::Time MarkerVisual::Lifetime() const
/////////////////////////////////////////////////
void MarkerVisual::DynamicRenderable(const ignition::msgs::Marker &_msg)
{
GZ_PROFILE("rendering::MarkerVisual::DynamicRenderable");
if (!this->dPtr->dynamicRenderable)
{
switch (_msg.type())
Expand Down
2 changes: 2 additions & 0 deletions gazebo/rendering/Material.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
*
*/
#include "gazebo/common/Color.hh"
#include "gazebo/common/Profiler.hh"
#include "gazebo/rendering/ogre_gazebo.h"
#include "gazebo/common/Console.hh"
#include "gazebo/rendering/RenderEngine.hh"
Expand Down Expand Up @@ -140,6 +141,7 @@ void Material::CreateMaterials()
//////////////////////////////////////////////////
void Material::Update(const gazebo::common::Material *_mat)
{
GZ_PROFILE("rendering::Material::Update");
Ogre::MaterialPtr matPtr;

if (Ogre::MaterialManager::getSingleton().resourceExists(_mat->GetName()))
Expand Down
2 changes: 2 additions & 0 deletions gazebo/rendering/MovableText.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@

#include "gazebo/common/common.hh"
#include "gazebo/common/Assert.hh"
#include "gazebo/common/Profiler.hh"
#include "gazebo/rendering/MovableText.hh"

#define POS_TEX_BINDING 0
Expand Down Expand Up @@ -176,6 +177,7 @@ void MovableText::Load(const std::string &_name,
//////////////////////////////////////////////////
void MovableText::Update()
{
GZ_PROFILE("rendering::MovableText::Update");
if (this->dataPtr->dirty)
{
this->SetupGeometry();
Expand Down
4 changes: 4 additions & 0 deletions gazebo/rendering/OculusCamera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include "gazebo/common/Console.hh"
#include "gazebo/common/Exception.hh"
#include "gazebo/common/Events.hh"
#include "gazebo/common/Profiler.hh"

#include "gazebo/rendering/skyx/include/SkyX.h"
#include "gazebo/rendering/selection_buffer/SelectionBuffer.hh"
Expand Down Expand Up @@ -235,8 +236,11 @@ void OculusCamera::RenderImpl()
//////////////////////////////////////////////////
void OculusCamera::Update()
{
GZ_PROFILE("rendering::OculusCamera::Update");
if (!this->Ready())
{
return;
}

Camera::Update();

Expand Down
4 changes: 4 additions & 0 deletions gazebo/rendering/RTShaderSystem.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
#include "gazebo/common/Console.hh"
#include "gazebo/common/Exception.hh"
#include "gazebo/common/SystemPaths.hh"
#include "gazebo/common/Profiler.hh"
#include "gazebo/rendering/ogre_gazebo.h"
#include "gazebo/rendering/CustomPSSMShadowCameraSetup.hh"
#include "gazebo/rendering/RenderEngine.hh"
Expand Down Expand Up @@ -634,8 +635,11 @@ Ogre::PSSMShadowCameraSetup *RTShaderSystem::GetPSSMShadowCameraSetup() const
/////////////////////////////////////////////////
void RTShaderSystem::Update()
{
GZ_PROFILE("rendering::RTShaderSystem::Update");
if (!this->dataPtr->initialized || !this->dataPtr->updateShaders)
{
return;
}

for (const auto &scene : this->dataPtr->scenes)
{
Expand Down
Loading

0 comments on commit ce6570f

Please sign in to comment.