Revision: 8275
http://playerstage.svn.sourceforge.net/playerstage/?rev=8275&view=rev
Author: natepak
Date: 2009-10-01 23:54:20 +0000 (Thu, 01 Oct 2009)
Log Message:
-----------
Update the camera throttling
Modified Paths:
--------------
code/gazebo/trunk/CMakeLists.txt
code/gazebo/trunk/server/Simulator.cc
code/gazebo/trunk/server/rendering/OgreAdaptor.cc
code/gazebo/trunk/server/rendering/OgreCamera.cc
code/gazebo/trunk/server/rendering/OgreCamera.hh
code/gazebo/trunk/server/rendering/OgreCreator.cc
code/gazebo/trunk/server/rendering/UserCamera.cc
code/gazebo/trunk/server/sensors/Sensor.hh
code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc
code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.hh
code/gazebo/trunk/worlds/pioneer2dx_camera.world
code/gazebo/trunk/worlds/simpleshapes.world
Modified: code/gazebo/trunk/CMakeLists.txt
===================================================================
--- code/gazebo/trunk/CMakeLists.txt 2009-09-30 23:33:22 UTC (rev 8274)
+++ code/gazebo/trunk/CMakeLists.txt 2009-10-01 23:54:20 UTC (rev 8275)
@@ -11,7 +11,6 @@
SET (GAZEBO_VERSION 0.9.0)
MESSAGE (STATUS "${PROJECT_NAME} version ${GAZEBO_VERSION}")
-SET (ENABLE_SHADOWS OFF CACHE BOOL "If ON, must apply ogre_patch.diff to Ogre
sources")
SET (BUILD_GAZEBO ON CACHE INTERNAL "Build Gazebo" FORCE)
SET (gazeboserver_sources_desc "List of server sources"
Modified: code/gazebo/trunk/server/Simulator.cc
===================================================================
--- code/gazebo/trunk/server/Simulator.cc 2009-09-30 23:33:22 UTC (rev
8274)
+++ code/gazebo/trunk/server/Simulator.cc 2009-10-01 23:54:20 UTC (rev
8275)
@@ -47,8 +47,6 @@
#include "Simulator.hh"
-#define MAX_FRAME_RATE 60
-
using namespace gazebo;
////////////////////////////////////////////////////////////////////////////////
@@ -76,6 +74,9 @@
selectedBody(NULL)
{
this->mutex = new boost::recursive_mutex();
+
+ printf("Simulator Init\n");
+ this->startTime = this->GetWallTime();
}
////////////////////////////////////////////////////////////////////////////////
@@ -241,8 +242,6 @@
/// Initialize the simulation
void Simulator::Init()
{
- this->startTime = this->GetWallTime();
-
//Initialize the world
try
{
@@ -330,7 +329,7 @@
{
double currTime = 0;
double lastTime = 0;
- double freq = 30.0;
+ double freq = 80.0;
#ifdef TIMING
double tmpT1 = this->GetWallTime();
@@ -345,7 +344,7 @@
while (!this->userQuit)
{
currTime = this->GetWallTime();
- if ( currTime - lastTime > 1/freq)
+ if ( currTime - lastTime > 1.0/freq)
{
lastTime = this->GetWallTime();
@@ -353,9 +352,7 @@
OgreAdaptor::Instance()->UpdateCameras();
if (this->gui)
- {
this->gui->Update();
- }
World::Instance()->ProcessEntitiesToLoad();
World::Instance()->GraphicsUpdate();
Modified: code/gazebo/trunk/server/rendering/OgreAdaptor.cc
===================================================================
--- code/gazebo/trunk/server/rendering/OgreAdaptor.cc 2009-09-30 23:33:22 UTC
(rev 8274)
+++ code/gazebo/trunk/server/rendering/OgreAdaptor.cc 2009-10-01 23:54:20 UTC
(rev 8275)
@@ -74,7 +74,6 @@
this->shadowTextureSizeP = new ParamT<int>("shadowTextureSize", 512,0);
this->shadowTechniqueP = new ParamT<std::string>("shadowTechnique",
"stencilModulative", 0);
this->drawGridP = new ParamT<bool>("grid", true, 0);
- this->updateRateP = new ParamT<double>("maxUpdateRate",0,0);
this->skyMaterialP = new ParamT<std::string>("material","",1);
Param::End();
}
@@ -95,7 +94,6 @@
delete this->shadowIndexSizeP;
delete this->shadowTechniqueP;
delete this->drawGridP;
- delete this->updateRateP;
delete this->skyMaterialP;
}
@@ -210,7 +208,6 @@
this->shadowIndexSizeP->Load(node);
this->shadowTechniqueP->Load(node);
this->drawGridP->Load(node);
- this->updateRateP->Load(node);
//Preload basic shapes that can be used anywhere
OgreCreator::LoadBasicShapes();
@@ -292,7 +289,6 @@
stream << prefix << "<rendering:ogre>\n";
stream << prefix << " " << *(this->ambientP) << "\n";
stream << prefix << " " << *(this->drawGridP) << "\n";
- stream << prefix << " " << *(this->updateRateP) << "\n";
stream << prefix << " <sky>\n";
stream << prefix << " " << *(this->skyMaterialP) << "\n";
stream << prefix << " </sky>\n";
@@ -525,13 +521,6 @@
////////////////////////////////////////////////////////////////////////////////
-/// Get the desired update rate
-double OgreAdaptor::GetUpdateRate()
-{
- return **(this->updateRateP);
-}
-
-////////////////////////////////////////////////////////////////////////////////
/// Register a user camera
void OgreAdaptor::RegisterCamera( OgreCamera *cam )
{
Modified: code/gazebo/trunk/server/rendering/OgreCamera.cc
===================================================================
--- code/gazebo/trunk/server/rendering/OgreCamera.cc 2009-09-30 23:33:22 UTC
(rev 8274)
+++ code/gazebo/trunk/server/rendering/OgreCamera.cc 2009-10-01 23:54:20 UTC
(rev 8275)
@@ -29,6 +29,7 @@
#include <Ogre.h>
#include <dirent.h>
+#include "PhysicsEngine.hh"
#include "Global.hh"
#include "World.hh"
#include "GazeboError.hh"
@@ -74,6 +75,7 @@
this->visMaskP = new ParamT<std::string>("mask","none",0);
this->hfovP = new ParamT<Angle>("hfov", Angle(DTOR(60)),0);
this->imageFormatP = new ParamT<std::string>("imageFormat", "R8G8B8", 0);
+ this->updateRateP = new ParamT<double>("updateRate",30,0);
Param::End();
this->captureData = false;
@@ -82,6 +84,9 @@
CameraManager::Instance()->AddCamera(this);
this->camera = NULL;
+
+ this->renderPeriod = 1.0/(**this->updateRateP);
+ this->renderingEnabled = true;
}
@@ -106,7 +111,6 @@
// Load the camera
void OgreCamera::LoadCam( XMLConfigNode *node )
{
-
if (!Simulator::Instance()->GetRenderEngineEnabled())
gzthrow("Cameras can not be used when running Gazebo without rendering
engine");
@@ -160,6 +164,7 @@
gzthrow("near clipping plane (min depth) <= zero");
}
+ this->lastUpdate = Simulator::Instance()->GetSimTime();
}
//////////////////////////////////////////////////////////////////////////////
@@ -236,48 +241,72 @@
}
////////////////////////////////////////////////////////////////////////////////
+/// Set to true to enable rendering
+void OgreCamera::SetRenderingEnabled(bool value)
+{
+ this->renderingEnabled = value;
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get whether the rendering is enabled
+bool OgreCamera::GetRenderingEnabled() const
+{
+ return this->renderingEnabled;
+}
+
+////////////////////////////////////////////////////////////////////////////////
// Render the camera
void OgreCamera::Render()
{
- this->renderTarget->update();
+ if (!this->renderingEnabled)
+ return;
- if (this->captureData)
+ double physics_dt = World::Instance()->GetPhysicsEngine()->GetStepTime();
+ if
(round((Simulator::Instance()->GetSimTime()-this->lastUpdate-this->renderPeriod)/physics_dt)
>= 0)
{
- boost::recursive_mutex::scoped_lock
mr_lock(*Simulator::Instance()->GetMRMutex());
- Ogre::HardwarePixelBufferSharedPtr pixelBuffer;
- Ogre::RenderTexture *rTexture;
- Ogre::Viewport* renderViewport;
+ this->renderTarget->update();
- size_t size;
+ if (this->captureData)
+ {
+ boost::recursive_mutex::scoped_lock
mr_lock(*Simulator::Instance()->GetMRMutex());
- // Get access to the buffer and make an image and write it to file
- pixelBuffer = this->renderTexture->getBuffer();
- rTexture = pixelBuffer->getRenderTarget();
+ Ogre::HardwarePixelBufferSharedPtr pixelBuffer;
+ Ogre::RenderTexture *rTexture;
+ Ogre::Viewport* renderViewport;
- Ogre::PixelFormat format = pixelBuffer->getFormat();
- renderViewport = rTexture->getViewport(0);
+ size_t size;
- size = Ogre::PixelUtil::getMemorySize((**this->imageSizeP).x,
- (**this->imageSizeP).y,
- 1,
- format);
+ // Get access to the buffer and make an image and write it to file
+ pixelBuffer = this->renderTexture->getBuffer();
+ rTexture = pixelBuffer->getRenderTarget();
- // Allocate buffer
- if (!this->saveFrameBuffer)
- this->saveFrameBuffer = new unsigned char[size];
+ Ogre::PixelFormat format = pixelBuffer->getFormat();
+ renderViewport = rTexture->getViewport(0);
- memset(this->saveFrameBuffer,128,size);
+ size = Ogre::PixelUtil::getMemorySize((**this->imageSizeP).x,
+ (**this->imageSizeP).y,
+ 1,
+ format);
- Ogre::PixelBox box((**this->imageSizeP).x, (**this->imageSizeP).y,
- 1, this->imageFormat, this->saveFrameBuffer);
+ // Allocate buffer
+ if (!this->saveFrameBuffer)
+ this->saveFrameBuffer = new unsigned char[size];
- pixelBuffer->blitToMemory( box );
+ memset(this->saveFrameBuffer,128,size);
- if (this->saveFramesP->GetValue())
- {
- this->SaveFrame();
+ Ogre::PixelBox box((**this->imageSizeP).x, (**this->imageSizeP).y,
+ 1, this->imageFormat, this->saveFrameBuffer);
+
+ pixelBuffer->blitToMemory( box );
+
+ if (this->saveFramesP->GetValue())
+ {
+ this->SaveFrame();
+ }
}
+
+ this->lastUpdate = Simulator::Instance()->GetSimTime();
}
}
Modified: code/gazebo/trunk/server/rendering/OgreCamera.hh
===================================================================
--- code/gazebo/trunk/server/rendering/OgreCamera.hh 2009-09-30 23:33:22 UTC
(rev 8274)
+++ code/gazebo/trunk/server/rendering/OgreCamera.hh 2009-10-01 23:54:20 UTC
(rev 8275)
@@ -86,6 +86,12 @@
/// Finalize the camera
public: void FiniCam();
+
+ /// \brief Set to true to enable rendering
+ public: void SetRenderingEnabled(bool value);
+
+ /// \brief Get whether the rendering is enabled
+ public: bool GetRenderingEnabled() const;
/// \brief Get the global pose of the camera
public: Pose3d GetWorldPose() const;
@@ -209,7 +215,7 @@
private: std::string name;
protected: ParamT<Angle> *hfovP;
- protected: ParamT<double> *nearClipP, *farClipP;
+ protected: ParamT<double> *nearClipP, *farClipP, *updateRateP;
protected: ParamT< Vector2<int> > *imageSizeP;
protected: unsigned int textureWidth, textureHeight;
@@ -246,6 +252,11 @@
private: bool userMovable;
protected: std::vector<Param*> camParameters;
+
+ protected: bool renderingEnabled;
+
+ protected: double renderPeriod;
+ protected: double lastUpdate;
};
/// \}
Modified: code/gazebo/trunk/server/rendering/OgreCreator.cc
===================================================================
--- code/gazebo/trunk/server/rendering/OgreCreator.cc 2009-09-30 23:33:22 UTC
(rev 8274)
+++ code/gazebo/trunk/server/rendering/OgreCreator.cc 2009-10-01 23:54:20 UTC
(rev 8275)
@@ -654,15 +654,10 @@
<< ":" << (unsigned long)winId
<< ":" << (unsigned long)vi;
*/
-
ogreHandle << winId;
-#ifdef ENABLE_SHADOWS
params["parentWindowHandle"] = ogreHandle.str();
-#else
- params["externalWindowHandle"] = ogreHandle.str();
-#endif
//params["vsync"] = "true";
params["FSAA"] = "2";
Modified: code/gazebo/trunk/server/rendering/UserCamera.cc
===================================================================
--- code/gazebo/trunk/server/rendering/UserCamera.cc 2009-09-30 23:33:22 UTC
(rev 8274)
+++ code/gazebo/trunk/server/rendering/UserCamera.cc 2009-10-01 23:54:20 UTC
(rev 8275)
@@ -27,6 +27,7 @@
#include <Ogre.h>
#include <sstream>
+#include "Simulator.hh"
#include "Global.hh"
#include "GLWindow.hh"
#include "OgreCamera.hh"
@@ -68,6 +69,7 @@
this->SetClipDist(0.1, 50);
this->SetFOV( DTOR(60) );
+
}
////////////////////////////////////////////////////////////////////////////////
@@ -86,12 +88,21 @@
this->viewport->setVisibilityMask(this->visibilityMask);
this->renderTarget = this->window;
+
+ printf("User Camera Init\n");
+ this->lastUpdate = Simulator::Instance()->GetRealTime();
}
////////////////////////////////////////////////////////////////////////////////
/// Update
void UserCamera::Update()
{
+ if (Simulator::Instance()->GetRealTime() - this->lastUpdate <
+ this->renderPeriod)
+ return;
+
+ this->lastUpdate = Simulator::Instance()->GetRealTime();
+
OgreCamera::UpdateCam();
this->window->update();
@@ -112,6 +123,7 @@
this->saveCount++;
}
+
}
Modified: code/gazebo/trunk/server/sensors/Sensor.hh
===================================================================
--- code/gazebo/trunk/server/sensors/Sensor.hh 2009-09-30 23:33:22 UTC (rev
8274)
+++ code/gazebo/trunk/server/sensors/Sensor.hh 2009-10-01 23:54:20 UTC (rev
8275)
@@ -79,7 +79,7 @@
public: void GetInterfaceNames(std::vector<std::string>& list) const;
/// \brief Set whether the sensor is active or not
- public: void SetActive(bool value);
+ public: virtual void SetActive(bool value);
public: bool IsActive();
/// \brief Load the child sensor
Modified: code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc
===================================================================
--- code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc 2009-09-30
23:33:22 UTC (rev 8274)
+++ code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc 2009-10-01
23:54:20 UTC (rev 8275)
@@ -140,6 +140,14 @@
}
//////////////////////////////////////////////////////////////////////////////
+/// Set whether the sensor is active or not
+void MonoCameraSensor::SetActive(bool value)
+{
+ Sensor::SetActive(value);
+ this->SetRenderingEnabled(value);
+}
+
+//////////////////////////////////////////////////////////////////////////////
// Update the drawing
void MonoCameraSensor::UpdateChild()
{
Modified: code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.hh
===================================================================
--- code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.hh 2009-09-30
23:33:22 UTC (rev 8274)
+++ code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.hh 2009-10-01
23:54:20 UTC (rev 8275)
@@ -69,6 +69,9 @@
/// Finalize the camera
protected: virtual void FiniChild();
+ /// \brief Set whether the sensor is active or not
+ public: virtual void SetActive(bool value);
+
/// \brief Return the material the camera renders to
public: virtual std::string GetMaterialName() const;
Modified: code/gazebo/trunk/worlds/pioneer2dx_camera.world
===================================================================
--- code/gazebo/trunk/worlds/pioneer2dx_camera.world 2009-09-30 23:33:22 UTC
(rev 8274)
+++ code/gazebo/trunk/worlds/pioneer2dx_camera.world 2009-10-01 23:54:20 UTC
(rev 8275)
@@ -23,7 +23,7 @@
<gravity>0 0 -9.8</gravity>
<cfm>10e-5</cfm>
<erp>0.3</erp>
- <updateRate>2</updateRate>
+ <updateRate>0</updateRate>
</physics:ode>
<rendering:gui>
Modified: code/gazebo/trunk/worlds/simpleshapes.world
===================================================================
--- code/gazebo/trunk/worlds/simpleshapes.world 2009-09-30 23:33:22 UTC (rev
8274)
+++ code/gazebo/trunk/worlds/simpleshapes.world 2009-10-01 23:54:20 UTC (rev
8275)
@@ -23,7 +23,7 @@
<!-- updateRate: <0 == throttle simTime to match realTime.
0 == No throttling
>0 == Frequency at which to throttle the sim -->
- <updateRate>-1</updateRate>
+ <updateRate>0</updateRate>
</physics:ode>
<rendering:gui>
This was sent by the SourceForge.net collaborative development platform, the
world's largest Open Source development site.
------------------------------------------------------------------------------
Come build with us! The BlackBerry® Developer Conference in SF, CA
is the only developer event you need to attend this year. Jumpstart your
developing skills, take BlackBerry mobile applications to market and stay
ahead of the curve. Join us from November 9-12, 2009. Register now!
http://p.sf.net/sfu/devconf
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit