Revision: 6500
          http://playerstage.svn.sourceforge.net/playerstage/?rev=6500&view=rev
Author:   natepak
Date:     2008-06-09 21:38:58 -0700 (Mon, 09 Jun 2008)

Log Message:
-----------
Fixed stereo camera

Modified Paths:
--------------
    code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc
    code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.hh

Modified: code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc
===================================================================
--- code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc       
2008-06-10 01:13:51 UTC (rev 6499)
+++ code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc       
2008-06-10 04:38:58 UTC (rev 6500)
@@ -42,7 +42,7 @@
 #include "CameraManager.hh"
 #include "StereoCameraSensor.hh"
 
-#define PF_FLOAT Ogre::PF_FLOAT16_R
+#define PF_FLOAT Ogre::PF_FLOAT32_R
 
 using namespace gazebo;
 
@@ -195,6 +195,7 @@
   }
   catch (...)
   {
+    gridNode = NULL;
   }
 
   CameraSensor::UpdateChild(params);
@@ -330,7 +331,7 @@
     {
       hardwareBuffer->blitToMemory (Ogre::Box(left,top,right,bottom),
           Ogre::PixelBox( this->imageWidth, this->imageHeight,
-            1, Ogre::PF_FLOAT32_R, this->depthBuffer[i-2])
+            1, PF_FLOAT, this->depthBuffer[i-2])
           );
     }
 
@@ -361,9 +362,9 @@
   {
     for (unsigned int j =0; j<this->imageWidth; j++)
     {
-      float f = this->depthBuffer[0][i*this->imageWidth+j];
-      
-      unsigned char value =  static_cast<unsigned char>((double)f * 255);
+      double f = this->depthBuffer[0][i*this->imageWidth+j];
+     
+      unsigned char value = static_cast<unsigned char>(f * 255);
       fwrite( &value, 1, 1, fp );
       fwrite( &value, 1, 1, fp );
       fwrite( &value, 1, 1, fp );
@@ -505,7 +506,7 @@
   Ogre::PixelFormat pf;
 
   if (depth)
-    pf = Ogre::PF_FLOAT16_R;
+    pf = PF_FLOAT;
   else
     pf = Ogre::PF_R8G8B8;
 

Modified: code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.hh
===================================================================
--- code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.hh       
2008-06-10 01:13:51 UTC (rev 6499)
+++ code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.hh       
2008-06-10 04:38:58 UTC (rev 6500)
@@ -44,102 +44,102 @@
 
 namespace gazebo
 {
-/// \addtogroup gazebo_sensor
-/// \brief Stereo camera sensor
-/// \{
-/// \defgroup gazebo_stereo_camera Stereo Camera
-/// \brief Stereo camera sensor
-// \{
+  /// \addtogroup gazebo_sensor
+  /// \brief Stereo camera sensor
+  /// \{
+  /// \defgroup gazebo_stereo_camera Stereo Camera
+  /// \brief Stereo camera sensor
+  // \{
+  
+  
+  /// \brief Stereo camera sensor
+  ///
+  /// This sensor is used for simulating a stereo camera.
+  class StereoCameraSensor : public CameraSensor
+  {
+  
+    enum Sides {LEFT, RIGHT, D_LEFT, D_RIGHT};
+  
+    /// \brief Constructor
+    public: StereoCameraSensor(Body *body);
+  
+    /// \brief Destructor
+    public: virtual ~StereoCameraSensor();
+  
+    /// \brief Load the camera using parameter from an XMLConfig node
+    /// \param node The XMLConfig node
+    protected: virtual void LoadChild( XMLConfigNode *node );
+  
+    /// \brief Initialize the camera
+    protected: virtual void InitChild();
+  
+    /// \brief Update the sensor information
+    protected: virtual void UpdateChild(UpdateParams &params);
+  
+    /// Finalize the camera
+    protected: virtual void FiniChild();
+  
+    /// \brief Return the material the camera renders to
+    public: virtual std::string GetMaterialName() const;
+  
+    /// \brief Get a pointer to the image data
+    /// \param i 0=left, 1=right
+    public: virtual const unsigned char *GetImageData(unsigned int i=0);
+  
+    /// \brief Get a point to the disparity data
+    /// \param i 0=left, 1=right
+    public: const float *GetDisparityData(unsigned int i=0);
+  
+    /// \brief Get the baselien of the camera
+    public: double GetBaseline() const;
+  
+    // Save the camera frame
+    protected: virtual void SaveFrame();
+  
+    /// \brief Fill all the image buffers
+    private: void FillBuffers();
+  
+    private: Ogre::TexturePtr CreateRTT( const std::string &name, bool depth);
+  
+    //private: void UpdateAllDependentRenderTargets();
+  
+    private: Ogre::TexturePtr renderTexture[4];
+    private: Ogre::RenderTarget *renderTarget[4];
+    private: Ogre::MaterialPtr depthMaterial;
+  
+    private: std::string textureName[4];
+    private: std::string materialName[4];
+  
+    private: unsigned int depthBufferSize;
+    private: unsigned int rgbBufferSize;
+    private: float *depthBuffer[2];
+    private: unsigned char *rgbBuffer[2];
+    private: double baseline;
+  
+    private: Ogre::Camera *depthCamera;
+  
+    /*private: 
+             class StereoCameraListener : public Ogre::RenderTargetListener
+             {
+               public: StereoCameraListener() : Ogre::RenderTargetListener() {}
+  
+               public: void Init(StereoCameraSensor *sensor, 
Ogre::RenderTarget *target, bool isLeft);
+               public: void preViewportUpdate(const 
Ogre::RenderTargetViewportEvent &evt);
+               public: void postViewportUpdate(const 
Ogre::RenderTargetViewportEvent &evt);
+  
+               private: Ogre::Vector3 pos;
+               private: StereoCameraSensor *sensor;
+               private: Ogre::Camera *camera;
+               private: Ogre::RenderTarget *renderTarget;
+               private: bool isLeftCamera;
+             };
+  
+  
+    private: StereoCameraListener leftCameraListener;
+    private: StereoCameraListener rightCameraListener;
+    */
+  };
 
-
-/// \brief Stereo camera sensor
-///
-/// This sensor is used for simulating a stereo camera.
-class StereoCameraSensor : public CameraSensor
-{
-
-  enum Sides {LEFT, RIGHT, D_LEFT, D_RIGHT};
-
-  /// \brief Constructor
-  public: StereoCameraSensor(Body *body);
-
-  /// \brief Destructor
-  public: virtual ~StereoCameraSensor();
-
-  /// \brief Load the camera using parameter from an XMLConfig node
-  /// \param node The XMLConfig node
-  protected: virtual void LoadChild( XMLConfigNode *node );
-
-  /// \brief Initialize the camera
-  protected: virtual void InitChild();
-
-  /// \brief Update the sensor information
-  protected: virtual void UpdateChild(UpdateParams &params);
-
-  /// Finalize the camera
-  protected: virtual void FiniChild();
-
-  /// \brief Return the material the camera renders to
-  public: virtual std::string GetMaterialName() const;
-
-  /// \brief Get a pointer to the image data
-  /// \param i 0=left, 1=right
-  public: virtual const unsigned char *GetImageData(unsigned int i=0);
-
-  /// \brief Get a point to the disparity data
-  /// \param i 0=left, 1=right
-  public: const float *GetDisparityData(unsigned int i=0);
-
-  /// \brief Get the baselien of the camera
-  public: double GetBaseline() const;
-
-  // Save the camera frame
-  protected: virtual void SaveFrame();
-
-  /// \brief Fill all the image buffers
-  private: void FillBuffers();
-
-  private: Ogre::TexturePtr CreateRTT( const std::string &name, bool depth);
-
-  //private: void UpdateAllDependentRenderTargets();
-
-  private: Ogre::TexturePtr renderTexture[4];
-  private: Ogre::RenderTarget *renderTarget[4];
-  private: Ogre::MaterialPtr depthMaterial;
-
-  private: std::string textureName[4];
-  private: std::string materialName[4];
-
-  private: unsigned int depthBufferSize;
-  private: unsigned int rgbBufferSize;
-  private: float *depthBuffer[2];
-  private: unsigned char *rgbBuffer[2];
-  private: double baseline;
-
-  private: Ogre::Camera *depthCamera;
-
-  /*private: 
-           class StereoCameraListener : public Ogre::RenderTargetListener
-           {
-             public: StereoCameraListener() : Ogre::RenderTargetListener() {}
-
-             public: void Init(StereoCameraSensor *sensor, Ogre::RenderTarget 
*target, bool isLeft);
-             public: void preViewportUpdate(const 
Ogre::RenderTargetViewportEvent &evt);
-             public: void postViewportUpdate(const 
Ogre::RenderTargetViewportEvent &evt);
-
-             private: Ogre::Vector3 pos;
-             private: StereoCameraSensor *sensor;
-             private: Ogre::Camera *camera;
-             private: Ogre::RenderTarget *renderTarget;
-             private: bool isLeftCamera;
-           };
-
-
-  private: StereoCameraListener leftCameraListener;
-  private: StereoCameraListener rightCameraListener;
-  */
-};
-
 /// \}
 /// \}
 }


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

-------------------------------------------------------------------------
Check out the new SourceForge.net Marketplace.
It's the best place to buy or sell services for
just about anything Open Source.
http://sourceforge.net/services/buy/index.php
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to