Revision: 7486
          http://playerstage.svn.sourceforge.net/playerstage/?rev=7486&view=rev
Author:   natepak
Date:     2009-03-15 05:49:00 +0000 (Sun, 15 Mar 2009)

Log Message:
-----------
Made MonoCamera thread safe

Modified Paths:
--------------
    code/branches/federation/gazebo/server/Simulator.cc
    
code/branches/federation/gazebo/server/controllers/camera/generic/Generic_Camera.cc
    code/branches/federation/gazebo/server/rendering/OgreAdaptor.cc
    code/branches/federation/gazebo/server/rendering/OgreAdaptor.hh
    code/branches/federation/gazebo/server/rendering/OgreCamera.cc
    code/branches/federation/gazebo/server/rendering/OgreCamera.hh
    code/branches/federation/gazebo/server/rendering/UserCamera.cc
    code/branches/federation/gazebo/server/sensors/camera/MonoCameraSensor.cc
    code/branches/federation/gazebo/server/sensors/camera/MonoCameraSensor.hh

Modified: code/branches/federation/gazebo/server/Simulator.cc
===================================================================
--- code/branches/federation/gazebo/server/Simulator.cc 2009-03-14 20:19:28 UTC 
(rev 7485)
+++ code/branches/federation/gazebo/server/Simulator.cc 2009-03-15 05:49:00 UTC 
(rev 7486)
@@ -294,6 +294,7 @@
     while (!this->userQuit)
     {
       this->gui->Update();
+      usleep(1000);
     }
   }
 
@@ -544,6 +545,8 @@
         boost::recursive_mutex::scoped_lock lock(*this->mutex);
         world->Update();
       }
+
+      usleep(100);
     }
 
     // Process all incoming messages from simiface

Modified: 
code/branches/federation/gazebo/server/controllers/camera/generic/Generic_Camera.cc
===================================================================
--- 
code/branches/federation/gazebo/server/controllers/camera/generic/Generic_Camera.cc
 2009-03-14 20:19:28 UTC (rev 7485)
+++ 
code/branches/federation/gazebo/server/controllers/camera/generic/Generic_Camera.cc
 2009-03-15 05:49:00 UTC (rev 7486)
@@ -142,5 +142,6 @@
   // New data is available
   this->cameraIface->Post();
 
+
 }
 

Modified: code/branches/federation/gazebo/server/rendering/OgreAdaptor.cc
===================================================================
--- code/branches/federation/gazebo/server/rendering/OgreAdaptor.cc     
2009-03-14 20:19:28 UTC (rev 7485)
+++ code/branches/federation/gazebo/server/rendering/OgreAdaptor.cc     
2009-03-15 05:49:00 UTC (rev 7486)
@@ -458,7 +458,7 @@
 // Update the user cameras
 void OgreAdaptor::UpdateCameras()
 {
-  std::vector<UserCamera*>::iterator iter;
+  std::vector<OgreCamera*>::iterator iter;
 
   OgreCreator::Instance()->Update();
 
@@ -467,24 +467,13 @@
   // Draw all the windows
   for (iter = this->cameras.begin(); iter != this->cameras.end(); iter++)
   {
-    (*iter)->GetWindow()->update();
+    (*iter)->Render();
   }
 
   this->root->_fireFrameEnded();
 }
 
 
////////////////////////////////////////////////////////////////////////////////
-// Update a window
-void OgreAdaptor::UpdateWindow(Ogre::RenderWindow *window, OgreCamera *camera)
-{
-  this->root->_fireFrameStarted();
-
-  window->update();
-
-  this->root->_fireFrameEnded();
-}
-
-////////////////////////////////////////////////////////////////////////////////
 /// Get an entity at a pixel location using a camera. Used for mouse picking. 
 Entity *OgreAdaptor::GetEntityAt(OgreCamera *camera, Vector2<int> mousePos) 
 {
@@ -539,7 +528,7 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 /// Register a user camera
-void OgreAdaptor::RegisterCamera( UserCamera *cam )
+void OgreAdaptor::RegisterCamera( OgreCamera *cam )
 {
   this->cameras.push_back( cam );
 }

Modified: code/branches/federation/gazebo/server/rendering/OgreAdaptor.hh
===================================================================
--- code/branches/federation/gazebo/server/rendering/OgreAdaptor.hh     
2009-03-14 20:19:28 UTC (rev 7485)
+++ code/branches/federation/gazebo/server/rendering/OgreAdaptor.hh     
2009-03-15 05:49:00 UTC (rev 7486)
@@ -94,18 +94,16 @@
   
     /// \brief Get the desired update rate
     public: double GetUpdateRate();
- 
+
+    /// \brief Update all the cameras 
     public: void UpdateCameras();
 
-    /// \brief Update a window
-    public: void UpdateWindow(Ogre::RenderWindow *window, OgreCamera *camera);
-
     /// \brief Get an entity at a pixel location using a camera. Used for
     ///        mouse picking. 
     public: Entity *GetEntityAt(OgreCamera *camera, Vector2<int> mousePos);
 
     /// \brief Register a user camera
-    public: void RegisterCamera( UserCamera *cam );
+    public: void RegisterCamera( OgreCamera *cam );
 
     private: void LoadPlugins();
     private: void SetupResources();
@@ -163,7 +161,7 @@
     private: ParamT<std::string> *skyMaterialP;
     private: std::vector<Param*> parameters;
 
-    private: std::vector<UserCamera*> cameras;
+    private: std::vector<OgreCamera*> cameras;
   };
   
  

Modified: code/branches/federation/gazebo/server/rendering/OgreCamera.cc
===================================================================
--- code/branches/federation/gazebo/server/rendering/OgreCamera.cc      
2009-03-14 20:19:28 UTC (rev 7485)
+++ code/branches/federation/gazebo/server/rendering/OgreCamera.cc      
2009-03-15 05:49:00 UTC (rev 7486)
@@ -27,6 +27,7 @@
 #include <sstream>
 #include <OgreImageCodec.h>
 #include <Ogre.h>
+#include <dirent.h>
 
 #include "Global.hh"
 #include "World.hh"
@@ -34,6 +35,7 @@
 #include "OgreVisual.hh"
 #include "OgreCreator.hh"
 #include "XMLConfig.hh"
+#include "Simulator.hh"
 
 #include "OgreAdaptor.hh"
 #include "CameraManager.hh"
@@ -47,6 +49,8 @@
 // Constructor
 OgreCamera::OgreCamera(const std::string &namePrefix)
 {
+  this->name = "DefaultCameraName";
+
   this->textureWidth = this->textureHeight = 0;
 
   this->saveFrameBuffer = NULL;
@@ -71,6 +75,8 @@
   this->hfovP = new ParamT<Angle>("hfov", Angle(DTOR(60)),0);
   Param::End();
 
+  this->captureData = false;
+
   // This should be last in the constructor
   CameraManager::Instance()->AddCamera(this);
 }
@@ -162,6 +168,7 @@
 
   this->saveCount = 0;
 
+  OgreAdaptor::Instance()->RegisterCamera(this);
 }
 
 //////////////////////////////////////////////////////////////////////////////
@@ -199,6 +206,57 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+// Render the camera
+void OgreCamera::Render()
+{
+  this->renderTarget->update();
+
+  if (this->captureData)
+  {
+    Ogre::HardwarePixelBufferSharedPtr mBuffer;
+    size_t size;
+
+    // Get access to the buffer and make an image and write it to file
+    mBuffer = this->renderTexture->getBuffer(0, 0);
+
+    size = this->imageSizeP->GetValue().x * this->imageSizeP->GetValue().y * 3;
+
+    // Allocate buffer
+    if (!this->saveFrameBuffer)
+      this->saveFrameBuffer = new unsigned char[size];
+
+    mBuffer->lock(Ogre::HardwarePixelBuffer::HBL_READ_ONLY);
+
+    int top = (int)((mBuffer->getHeight() - this->imageSizeP->GetValue().y) / 
2.0);
+    int left = (int)((mBuffer->getWidth() - this->imageSizeP->GetValue().x) / 
2.0);
+    int right = left + this->imageSizeP->GetValue().x;
+    int bottom = top + this->imageSizeP->GetValue().y;
+
+    // Get the center of the texture in RGB 24 bit format
+    mBuffer->blitToMemory(
+        Ogre::Box(left, top, right, bottom),
+
+        Ogre::PixelBox(
+          this->imageSizeP->GetValue().x,
+          this->imageSizeP->GetValue().y,
+          1,
+          Ogre::PF_B8G8R8,
+          this->saveFrameBuffer)
+        );
+
+    mBuffer->unlock();
+
+
+    if (this->saveFramesP->GetValue())
+    {
+      this->SaveFrame();
+    }
+  }
+
+}
+
+
+////////////////////////////////////////////////////////////////////////////////
 // Get the global pose of the camera
 Pose3d OgreCamera::GetWorldPose() const
 {
@@ -411,4 +469,96 @@
   this->sceneNode = node;
 }
 
+//////////////////////////////////////////////////////////////////////////////
+/// Get a pointer to the image data
+const unsigned char *OgreCamera::GetImageData(unsigned int i)
+{
+  if (i!=0)
+    gzerr(0) << "Camera index must be zero for mono cam";
 
+  return this->saveFrameBuffer;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the camera's name
+std::string OgreCamera::GetCamName()
+{
+  return this->name;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Set the camera's name
+void OgreCamera::SetCamName( const std::string &_name )
+{
+  this->name = _name;
+}
+
+
+//////////////////////////////////////////////////////////////////////////////
+// Save the current frame to disk
+void OgreCamera::SaveFrame()
+{
+  Ogre::HardwarePixelBufferSharedPtr mBuffer;
+  std::ostringstream sstream;
+  Ogre::ImageCodec::ImageData *imgData;
+  Ogre::Codec * pCodec;
+  size_t size, pos;
+
+  this->GetImageData();
+
+  // Create a directory if not present
+  DIR *dir = opendir( this->savePathnameP->GetValue().c_str() );
+  if (!dir)
+  {
+    std::string command;
+    command = "mkdir " + this->savePathnameP->GetValue() + " 2>>/dev/null";
+    system(command.c_str());
+  }
+
+  // Get access to the buffer and make an image and write it to file
+  mBuffer = this->renderTexture->getBuffer(0, 0);
+
+  // Create image data structure
+  imgData  = new Ogre::ImageCodec::ImageData();
+
+  imgData->width = this->imageSizeP->GetValue().x;
+  imgData->height = this->imageSizeP->GetValue().y;
+  imgData->depth = 1;
+  imgData->format = Ogre::PF_B8G8R8;
+  size = this->GetImageByteSize();
+
+  // Wrap buffer in a chunk
+  Ogre::MemoryDataStreamPtr stream(new Ogre::MemoryDataStream( 
this->saveFrameBuffer, size, false));
+
+  char tmp[1024];
+  if (!this->savePathnameP->GetValue().empty())
+  {
+    double simTime = Simulator::Instance()->GetSimTime();
+    int min = (int)(simTime / 60.0);
+    int sec = (int)(simTime - min*60);
+    int msec = (int)(simTime*1000 - min*60000 - sec*1000);
+
+    sprintf(tmp, "%s/%s-%04d-%03dm_%02ds_%03dms.jpg", 
this->savePathnameP->GetValue().c_str(), this->GetCamName().c_str(), 
this->saveCount, min, sec, msec);
+  }
+  else
+  {
+    sprintf(tmp, "%s-%04d.jpg", this->GetCamName().c_str(), this->saveCount);
+  }
+
+  // Get codec
+  Ogre::String filename = tmp;
+  pos = filename.find_last_of(".");
+  Ogre::String extension;
+
+  while (pos != filename.length() - 1)
+    extension += filename[++pos];
+
+  // Get the codec
+  pCodec = Ogre::Codec::getCodec(extension);
+
+  // Write out
+  Ogre::Codec::CodecDataPtr codecDataPtr(imgData);
+  pCodec->codeToFile(stream, filename, codecDataPtr);
+
+  this->saveCount++;
+}

Modified: code/branches/federation/gazebo/server/rendering/OgreCamera.hh
===================================================================
--- code/branches/federation/gazebo/server/rendering/OgreCamera.hh      
2009-03-14 20:19:28 UTC (rev 7485)
+++ code/branches/federation/gazebo/server/rendering/OgreCamera.hh      
2009-03-15 05:49:00 UTC (rev 7486)
@@ -77,7 +77,10 @@
   
     /// \brief Initialize the camera
     public: void InitCam();
-  
+
+    /// \brief Render the camera
+    public: void Render();
+
     /// \brief Update the sensor information
     public: void UpdateCam();
   
@@ -175,6 +178,21 @@
     /// \brief Set the camera's scene node
     public: void SetCameraSceneNode( Ogre::SceneNode *node );
 
+    /// \brief Get a pointer to the image data
+    public: virtual const unsigned char *GetImageData(unsigned int i=0);
+
+    /// \brief Get the camera's name
+    public: std::string GetCamName();
+
+    /// \brief Set the camera's name
+    public: void SetCamName( const std::string &name );
+
+    // Save the camera frame
+    private: virtual void SaveFrame();
+
+
+    private: std::string name;
+
     protected: ParamT<Angle> *hfovP;
     protected: ParamT<double> *nearClipP, *farClipP;
     protected: ParamT< Vector2<int> > *imageSizeP;
@@ -207,6 +225,8 @@
 
     private: std::string cameraName;
 
+    protected: bool captureData;
+
     private: bool userMovable;
     protected: std::vector<Param*> camParameters;
   };

Modified: code/branches/federation/gazebo/server/rendering/UserCamera.cc
===================================================================
--- code/branches/federation/gazebo/server/rendering/UserCamera.cc      
2009-03-14 20:19:28 UTC (rev 7485)
+++ code/branches/federation/gazebo/server/rendering/UserCamera.cc      
2009-03-15 05:49:00 UTC (rev 7486)
@@ -84,7 +84,7 @@
 
   this->viewport->setVisibilityMask(this->visibilityMask);
 
-  OgreAdaptor::Instance()->RegisterCamera(this);
+  this->renderTarget = this->window;
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -93,9 +93,6 @@
 {
   OgreCamera::UpdateCam();
 
-  // NATE
-  //OgreAdaptor::Instance()->UpdateWindow(this->window, this);
-
   if (this->saveFramesP->GetValue())
   {
     char tmp[1024];

Modified: 
code/branches/federation/gazebo/server/sensors/camera/MonoCameraSensor.cc
===================================================================
--- code/branches/federation/gazebo/server/sensors/camera/MonoCameraSensor.cc   
2009-03-14 20:19:28 UTC (rev 7485)
+++ code/branches/federation/gazebo/server/sensors/camera/MonoCameraSensor.cc   
2009-03-15 05:49:00 UTC (rev 7486)
@@ -26,8 +26,7 @@
 
 #include <sstream>
 #include <OgreImageCodec.h>
-#include <Ogre.h>
-#include <dirent.h>
+//#include <Ogre.h>
 
 #include "Controller.hh"
 #include "Global.hh"
@@ -53,6 +52,7 @@
     : Sensor(body), OgreCamera("Mono")
 {
   this->typeName = "monocamera";
+  this->captureData = true;
 }
 
 
@@ -106,6 +106,7 @@
 void MonoCameraSensor::InitChild()
 {
   this->InitCam();
+  this->SetCamName(this->GetName());
 
   Ogre::MaterialPtr mat = Ogre::MaterialManager::getSingleton().create(
                             this->ogreMaterialName,
@@ -142,7 +143,9 @@
 
   this->UpdateCam();
 
-  this->renderTarget->update();
+  // NATE
+ /* this->renderTarget->update();
+  
 
   Ogre::HardwarePixelBufferSharedPtr mBuffer;
   size_t size;
@@ -182,6 +185,8 @@
   {
     this->SaveFrame();
   }
+  */
+ 
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -192,81 +197,3 @@
 }
 
 
-//////////////////////////////////////////////////////////////////////////////
-/// Get a pointer to the image data
-const unsigned char *MonoCameraSensor::GetImageData(unsigned int i)
-{
-  if (i!=0)
-    gzerr(0) << "Camera index must be zero for mono cam";
-
-  return this->saveFrameBuffer;
-}
-
-//////////////////////////////////////////////////////////////////////////////
-// Save the current frame to disk
-void MonoCameraSensor::SaveFrame()
-{
-  Ogre::HardwarePixelBufferSharedPtr mBuffer;
-  std::ostringstream sstream;
-  Ogre::ImageCodec::ImageData *imgData;
-  Ogre::Codec * pCodec;
-  size_t size, pos;
-
-  this->GetImageData();
-
-  // Create a directory if not present
-  DIR *dir = opendir( this->savePathnameP->GetValue().c_str() );
-  if (!dir)
-  {
-    std::string command;
-    command = "mkdir " + this->savePathnameP->GetValue() + " 2>>/dev/null";
-    system(command.c_str());
-  }
-
-  // Get access to the buffer and make an image and write it to file
-  mBuffer = this->renderTexture->getBuffer(0, 0);
-
-  // Create image data structure
-  imgData  = new Ogre::ImageCodec::ImageData();
-
-  imgData->width = this->imageSizeP->GetValue().x;
-  imgData->height = this->imageSizeP->GetValue().y;
-  imgData->depth = 1;
-  imgData->format = Ogre::PF_B8G8R8;
-  size = this->GetImageByteSize();
-
-  // Wrap buffer in a chunk
-  Ogre::MemoryDataStreamPtr stream(new Ogre::MemoryDataStream( 
this->saveFrameBuffer, size, false));
-
-  char tmp[1024];
-  if (!this->savePathnameP->GetValue().empty())
-  {
-    double simTime = Simulator::Instance()->GetSimTime();
-    int min = (int)(simTime / 60.0);
-    int sec = (int)(simTime - min*60);
-    int msec = (int)(simTime*1000 - min*60000 - sec*1000);
-
-    sprintf(tmp, "%s/%s-%04d-%03dm_%02ds_%03dms.jpg", 
this->savePathnameP->GetValue().c_str(), this->GetName().c_str(), 
this->saveCount, min, sec, msec);
-  }
-  else
-  {
-    sprintf(tmp, "%s-%04d.jpg", this->GetName().c_str(), this->saveCount);
-  }
-
-  // Get codec
-  Ogre::String filename = tmp;
-  pos = filename.find_last_of(".");
-  Ogre::String extension;
-
-  while (pos != filename.length() - 1)
-    extension += filename[++pos];
-
-  // Get the codec
-  pCodec = Ogre::Codec::getCodec(extension);
-
-  // Write out
-  Ogre::Codec::CodecDataPtr codecDataPtr(imgData);
-  pCodec->codeToFile(stream, filename, codecDataPtr);
-
-  this->saveCount++;
-}

Modified: 
code/branches/federation/gazebo/server/sensors/camera/MonoCameraSensor.hh
===================================================================
--- code/branches/federation/gazebo/server/sensors/camera/MonoCameraSensor.hh   
2009-03-14 20:19:28 UTC (rev 7485)
+++ code/branches/federation/gazebo/server/sensors/camera/MonoCameraSensor.hh   
2009-03-15 05:49:00 UTC (rev 7486)
@@ -72,14 +72,8 @@
   /// \brief Return the material the camera renders to
   public: virtual std::string GetMaterialName() const;
 
-  /// \brief Get a pointer to the image data
-  public: virtual const unsigned char *GetImageData(unsigned int i=0);
-
   public: virtual std::string GetName() const { return Sensor::GetName(); }
 
-  // Save the camera frame
-  private: void SaveFrame();
-
 };
 
 /// \}


This was sent by the SourceForge.net collaborative development platform, the 
world's largest Open Source development site.

------------------------------------------------------------------------------
Apps built with the Adobe(R) Flex(R) framework and Flex Builder(TM) are
powering Web 2.0 with engaging, cross-platform capabilities. Quickly and
easily build your RIAs with Flex Builder, the Eclipse(TM)based development
software that enables intelligent coding and step-through debugging.
Download the free 60 day trial. http://p.sf.net/sfu/www-adobe-com
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to