Revision: 7051
          http://playerstage.svn.sourceforge.net/playerstage/?rev=7051&view=rev
Author:   natepak
Date:     2008-09-29 03:01:33 +0000 (Mon, 29 Sep 2008)

Log Message:
-----------
Give the stereo iface the names of the two camera ifaces

Modified Paths:
--------------
    code/gazebo/trunk/libgazebo/gazebo.h
    code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.cc
    code/gazebo/trunk/server/rendering/OgreCamera.cc
    code/gazebo/trunk/server/rendering/OgreCamera.hh
    code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc
    code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc

Modified: code/gazebo/trunk/libgazebo/gazebo.h
===================================================================
--- code/gazebo/trunk/libgazebo/gazebo.h        2008-09-28 21:14:00 UTC (rev 
7050)
+++ code/gazebo/trunk/libgazebo/gazebo.h        2008-09-29 03:01:33 UTC (rev 
7051)
@@ -1398,6 +1398,8 @@
   /// Right depth map (float)
   public: float right_depth[GAZEBO_STEREO_CAMERA_MAX_DISPARITY_SIZE];
 
+  public: char left_camera_iface_name[256];
+  public: char right_camera_iface_name[256];
 }; 
 
 

Modified: code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.cc
===================================================================
--- code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.cc 
2008-09-28 21:14:00 UTC (rev 7050)
+++ code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.cc 
2008-09-29 03:01:33 UTC (rev 7051)
@@ -142,10 +142,18 @@
     this->stereoIface->Lock(1);
     if (this->stereoIface->data->head.openCount > 0)
       this->PutStereoData();
+
+    strcpy( this->stereoIface->data->left_camera_iface_name, 
+            (**this->leftCameraNameP).c_str() );
+
+    strcpy( this->stereoIface->data->right_camera_iface_name, 
+            (**this->rightCameraNameP).c_str() );
+
     this->stereoIface->Unlock();
 
     this->stereoIface->Post();
   }
+
 }
 
 
////////////////////////////////////////////////////////////////////////////////

Modified: code/gazebo/trunk/server/rendering/OgreCamera.cc
===================================================================
--- code/gazebo/trunk/server/rendering/OgreCamera.cc    2008-09-28 21:14:00 UTC 
(rev 7050)
+++ code/gazebo/trunk/server/rendering/OgreCamera.cc    2008-09-29 03:01:33 UTC 
(rev 7051)
@@ -66,8 +66,7 @@
   this->farClipP = new ParamT<double>("farClip",100,0);
   this->saveFramesP = new ParamT<bool>("saveFrames",false,0);
   this->savePathnameP = new ParamT<std::string>("saveFramePath","",0);
-  this->imageWidthP = new ParamT<unsigned int>("imageSize",640,0);
-  this->imageHeightP = new ParamT<unsigned int>("imageSize",480,0);
+  this->imageSizeP = new ParamT< Vector2<int> >("imageSize", 
Vector2<int>(640,480),0);
   this->visMaskP = new ParamT<std::string>("mask","none",0);
   this->hfovP = new ParamT<Angle>("hfov", Angle(DTOR(60)),0);
   Param::End();
@@ -88,8 +87,7 @@
   delete this->farClipP;
   delete this->saveFramesP;
   delete this->savePathnameP;
-  delete this->imageWidthP;
-  delete this->imageHeightP;
+  delete this->imageSizeP;
   delete this->visMaskP;
   delete this->hfovP;
 }
@@ -107,8 +105,7 @@
     this->farClipP->Load(node);
     this->saveFramesP->Load(node);
     this->savePathnameP->Load(node);
-    this->imageWidthP->Load(node);
-    this->imageHeightP->Load(node);
+    this->imageSizeP->Load(node);
     this->visMaskP->Load(node);
     this->hfovP->Load(node);
 
@@ -146,8 +143,7 @@
   stream << prefix << (*this->farClipP) << "\n";
   stream << prefix << (*this->saveFramesP) << "\n";
   stream << prefix << (*this->savePathnameP) << "\n";
-  stream << prefix << (*this->imageWidthP) << "\n";
-  stream << prefix << (*this->imageHeightP) << "\n";
+  stream << prefix << (*this->imageSizeP) << "\n";
   stream << prefix << (*this->visMaskP) << "\n";
   stream << prefix << (*this->hfovP) << "\n";
 }
@@ -275,14 +271,14 @@
 /// Get the width of the image
 unsigned int OgreCamera::GetImageWidth() const
 {
-  return this->imageWidthP->GetValue();
+  return this->imageSizeP->GetValue().x;
 }
 
 //////////////////////////////////////////////////////////////////////////////
 /// \brief Get the height of the image
 unsigned int OgreCamera::GetImageHeight() const
 {
-  return this->imageHeightP->GetValue();
+  return this->imageSizeP->GetValue().y;
 }
 
 //////////////////////////////////////////////////////////////////////////////
@@ -304,7 +300,7 @@
 // Get the image size in bytes
 size_t OgreCamera::GetImageByteSize() const
 {
-  return this->imageHeightP->GetValue() * this->imageWidthP->GetValue() * 3;
+  return this->imageSizeP->GetValue().y * this->imageSizeP->GetValue().x * 3;
 }
 
 

Modified: code/gazebo/trunk/server/rendering/OgreCamera.hh
===================================================================
--- code/gazebo/trunk/server/rendering/OgreCamera.hh    2008-09-28 21:14:00 UTC 
(rev 7050)
+++ code/gazebo/trunk/server/rendering/OgreCamera.hh    2008-09-29 03:01:33 UTC 
(rev 7051)
@@ -174,7 +174,7 @@
 
     protected: ParamT<Angle> *hfovP;
     protected: ParamT<double> *nearClipP, *farClipP;
-    protected: ParamT<unsigned int> *imageWidthP, *imageHeightP;
+    protected: ParamT< Vector2<int> > *imageSizeP;
     protected: unsigned int textureWidth, textureHeight;
   
     private: Ogre::Camera *camera;

Modified: code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc
===================================================================
--- code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc 2008-09-28 
21:14:00 UTC (rev 7050)
+++ code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc 2008-09-29 
03:01:33 UTC (rev 7051)
@@ -67,7 +67,8 @@
   this->LoadCam( node );
 
   // Do some sanity checks
-  if (this->imageWidthP->GetValue() == 0 || this->imageHeightP->GetValue() == 
0)
+  if (this->imageSizeP->GetValue().x == 0 || 
+      this->imageSizeP->GetValue().y == 0)
   {
     gzthrow("image has zero size");
   }
@@ -82,8 +83,8 @@
                           this->ogreTextureName,
                           
Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
                           Ogre::TEX_TYPE_2D,
-                          this->imageWidthP->GetValue(), 
-                          this->imageHeightP->GetValue(), 0,
+                          this->imageSizeP->GetValue().x, 
+                          this->imageSizeP->GetValue().y, 0,
                           Ogre::PF_R8G8B8,
                           Ogre::TU_RENDERTARGET);
 
@@ -147,7 +148,7 @@
   // Get access to the buffer and make an image and write it to file
   mBuffer = this->renderTexture->getBuffer(0, 0);
 
-  size = this->imageWidthP->GetValue() * this->imageHeightP->GetValue() * 3;
+  size = this->imageSizeP->GetValue().x * this->imageSizeP->GetValue().y * 3;
 
   // Allocate buffer
   if (!this->saveFrameBuffer)
@@ -155,18 +156,18 @@
 
   mBuffer->lock(Ogre::HardwarePixelBuffer::HBL_READ_ONLY);
 
-  int top = (int)((mBuffer->getHeight() - this->imageHeightP->GetValue()) / 
2.0);
-  int left = (int)((mBuffer->getWidth() - this->imageWidthP->GetValue()) / 
2.0);
-  int right = left + this->imageWidthP->GetValue();
-  int bottom = top + this->imageHeightP->GetValue();
+  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->imageWidthP->GetValue(),
-      this->imageHeightP->GetValue(),
+      this->imageSizeP->GetValue().x,
+      this->imageSizeP->GetValue().y,
       1,
       Ogre::PF_B8G8R8,
       this->saveFrameBuffer)
@@ -215,8 +216,8 @@
   // Create image data structure
   imgData  = new Ogre::ImageCodec::ImageData();
 
-  imgData->width = this->imageWidthP->GetValue();
-  imgData->height = this->imageHeightP->GetValue();
+  imgData->width = this->imageSizeP->GetValue().x;
+  imgData->height = this->imageSizeP->GetValue().y;
   imgData->depth = 1;
   imgData->format = Ogre::PF_B8G8R8;
   size = this->GetImageByteSize();

Modified: code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc
===================================================================
--- code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc       
2008-09-28 21:14:00 UTC (rev 7050)
+++ code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc       
2008-09-29 03:01:33 UTC (rev 7051)
@@ -178,8 +178,8 @@
   //this->renderTargets[0]->addListener(&this->leftCameraListener);
   //this->renderTargets[1]->addListener(&this->rightCameraListener);
  
-  this->rgbBufferSize = 
this->imageWidthP->GetValue()*this->imageHeightP->GetValue() * 3;
-  this->depthBufferSize = 
this->imageWidthP->GetValue()*this->imageHeightP->GetValue();
+  this->rgbBufferSize = this->imageSizeP->GetValue().x * 
this->imageSizeP->GetValue().y * 3;
+  this->depthBufferSize = 
this->imageSizeP->GetValue().x*this->imageSizeP->GetValue().y;
 
   // Allocate buffers
   this->depthBuffer[0] = new float[this->depthBufferSize];
@@ -338,22 +338,22 @@
 
     hardwareBuffer->lock(Ogre::HardwarePixelBuffer::HBL_NORMAL);
 
-    top = (int)((hardwareBuffer->getHeight() - this->imageHeightP->GetValue()) 
/ 2.0);
-    left = (int)((hardwareBuffer->getWidth() - this->imageWidthP->GetValue()) 
/ 2.0);
-    right = left + this->imageWidthP->GetValue();
-    bottom = top + this->imageHeightP->GetValue();
+    top = (int)((hardwareBuffer->getHeight() - this->imageSizeP->GetValue().y) 
/ 2.0);
+    left = (int)((hardwareBuffer->getWidth() - this->imageSizeP->GetValue().x) 
/ 2.0);
+    right = left + this->imageSizeP->GetValue().x;
+    bottom = top + this->imageSizeP->GetValue().y;
 
     if (i < 2)
     {
       hardwareBuffer->blitToMemory ( Ogre::Box(left,top,right,bottom),
-          Ogre::PixelBox( this->imageWidthP->GetValue(), 
this->imageHeightP->GetValue(),
+          Ogre::PixelBox( this->imageSizeP->GetValue().x, 
this->imageSizeP->GetValue().y,
             1, PF_RGB, this->rgbBuffer[i])
           );
     }
     else
     {
       hardwareBuffer->blitToMemory (Ogre::Box(left,top,right,bottom),
-          Ogre::PixelBox( this->imageWidthP->GetValue(), 
this->imageHeightP->GetValue(),
+          Ogre::PixelBox( this->imageSizeP->GetValue().x, 
this->imageSizeP->GetValue().y,
             1, PF_FLOAT, this->depthBuffer[i-2])
           );
     }
@@ -379,13 +379,13 @@
     return;
   }
 
-  fprintf( fp, "P6\n# Gazebo\n%d %d\n255\n", this->imageWidthP->GetValue(), 
this->imageHeightP->GetValue());
+  fprintf( fp, "P6\n# Gazebo\n%d %d\n255\n", this->imageSizeP->GetValue().x, 
this->imageSizeP->GetValue().y);
 
-  for (unsigned int i = 0; i<this->imageHeightP->GetValue(); i++)
+  for (unsigned int i = 0; i<this->imageSizeP->GetValue().x; i++)
   {
-    for (unsigned int j =0; j<this->imageWidthP->GetValue(); j++)
+    for (unsigned int j =0; j<this->imageSizeP->GetValue().y; j++)
     {
-      double f = this->depthBuffer[0][i*this->imageWidthP->GetValue()+j];
+      double f = this->depthBuffer[0][i*this->imageSizeP->GetValue().x+j];
      
       unsigned char value = static_cast<unsigned char>(f * 255);
       fwrite( &value, 1, 1, fp );
@@ -538,7 +538,7 @@
       name, 
       Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
       Ogre::TEX_TYPE_2D,
-      this->imageWidthP->GetValue(), this->imageHeightP->GetValue(), 0,
+      this->imageSizeP->GetValue().x, this->imageSizeP->GetValue().y, 0,
       pf,
       Ogre::TU_RENDERTARGET);
 }


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

-------------------------------------------------------------------------
This SF.Net email is sponsored by the Moblin Your Move Developer's challenge
Build the coolest Linux based applications with Moblin SDK & win great prizes
Grand prize is a trip for two to an Open Source event anywhere in the world
http://moblin-contest.org/redirect.php?banner_id=100&url=/
_______________________________________________
Playerstage-commit mailing list
Playerstage-commit@lists.sourceforge.net
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to