Revision: 8960
          http://playerstage.svn.sourceforge.net/playerstage/?rev=8960&view=rev
Author:   natepak
Date:     2010-11-12 02:06:48 +0000 (Fri, 12 Nov 2010)

Log Message:
-----------
Splitting out worlds so that the simulator can run multiple at once

Added Paths:
-----------
    code/gazebo/branches/dev/server/FactoryIfaceHandler.cc
    code/gazebo/branches/dev/server/FactoryIfaceHandler.hh
    code/gazebo/branches/dev/server/rendering/Camera.cc
    code/gazebo/branches/dev/server/rendering/Camera.hh
    code/gazebo/branches/dev/server/wx/ModelBuilder.cc
    code/gazebo/branches/dev/server/wx/ModelBuilder.hh

Added: code/gazebo/branches/dev/server/FactoryIfaceHandler.cc
===================================================================
--- code/gazebo/branches/dev/server/FactoryIfaceHandler.cc                      
        (rev 0)
+++ code/gazebo/branches/dev/server/FactoryIfaceHandler.cc      2010-11-12 
02:06:48 UTC (rev 8960)
@@ -0,0 +1,122 @@
+/*
+ *  Gazebo - Outdoor Multi-Robot Simulator
+ *  Copyright (C) 2003
+ *     Nate Koenig & Andrew Howard
+ *
+ *  This program is free software; you can redistribute it and/or modify
+ *  it under the terms of the GNU General Public License as published by
+ *  the Free Software Foundation; either version 2 of the License, or
+ *  (at your option) any later version.
+ *
+ *  This program is distributed in the hope that it will be useful,
+ *  but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ *  GNU General Public License for more details.
+ *
+ *  You should have received a copy of the GNU General Public License
+ *  along with this program; if not, write to the Free Software
+ *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+ *
+ */
+/*
+ * Desc: FactoryIfaceHandler Position2d controller.
+ * Author: Nathan Koenig
+ * Date: 01 Feb 2007
+ */
+
+#include "Events.hh"
+#include "Global.hh"
+#include "XMLConfig.hh"
+#include "Model.hh"
+#include "World.hh"
+#include "GazeboError.hh"
+#include "gz.h"
+#include "FactoryIfaceHandler.hh"
+
+using namespace gazebo;
+
+////////////////////////////////////////////////////////////////////////////////
+// Constructor
+FactoryIfaceHandler::FactoryIfaceHandler(World *world)
+  : world(world)
+{
+  // Prefix and suffix for xml files
+  this->xmlPrefix = "<?xml version='1.0'?> <gazebo:world 
xmlns:xi='http://www.w3.org/2001/XInclude' 
xmlns:gazebo='http://playerstage.sourceforge.net/gazebo/xmlschema/#gz' 
xmlns:model='http://playerstage.sourceforge.net/gazebo/xmlschema/#model' 
xmlns:sensor='http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor' 
xmlns:body='http://playerstage.sourceforge.net/gazebo/xmlschema/#body' 
xmlns:geom='http://playerstage.sourceforge.net/gazebo/xmlschema/#geom' 
xmlns:joint='http://playerstage.sourceforge.net/gazebo/xmlschema/#joint' 
xmlns:interface='http://playerstage.sourceforge.net/gazebo/xmlschema/#interface'
 
xmlns:rendering='http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering'
 
xmlns:renderable='http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable'
 
xmlns:controller='http://playerstage.sourceforge.net/gazebo/xmlschema/#controller'
 xmlns:physics='http://playerstage.sourceforge.net/gazebo/xmlschema/#physics' 
>";
+
+
+  this->xmlSuffix = "</gazebo:world>";
+
+  this->factoryIface = 
(libgazebo::FactoryIface*)libgazebo::IfaceFactory::NewIface("factory");
+
+  // Create the iface
+  try
+  {
+    this->factoryIface->Create(this->world->GetGzServer(), 
this->world->GetGzServer());
+    this->factoryIface->Lock(1); // lock it right away to clear up data
+    strcpy((char*)this->factoryIface->data->newModel,"");
+    this->factoryIface->Unlock();
+  }
+  catch (std::string e)
+  {
+    gzthrow(e);
+  }
+
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Destructor
+FactoryIfaceHandler::~FactoryIfaceHandler()
+{
+  if (this->factoryIface)
+  {
+    this->factoryIface->Close();
+    this->factoryIface->Destroy();
+    delete this->factoryIface;
+    this->factoryIface = NULL;
+  }
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Initialize the controller
+void FactoryIfaceHandler::Init()
+{
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Update the controller
+void FactoryIfaceHandler::Update()
+{
+  // If there is a string, then add the contents to the world
+  this->factoryIface->Lock(1);
+
+  if (strcmp((const char*)this->factoryIface->data->newModel,"")!=0)
+  {
+    std::string xmlString;
+    std::string xmlMiddle = (const char*)(this->factoryIface->data->newModel);
+    
+    // Strip leading <?xml...?> tag, if present, to allow the client to
+    // pass the contents of a valid .model file
+    std::string xmlVersion = "<?xml version=\"1.0\"?>";
+    int i = xmlMiddle.find(xmlVersion);
+    if(i >= 0)
+      xmlMiddle.replace(i, xmlVersion.length(), "");
+
+    xmlString = this->xmlPrefix + xmlMiddle + this->xmlSuffix;
+
+    // Add the new models into the World
+    this->world->InsertEntity( xmlString);
+
+    strcpy((char*)this->factoryIface->data->newModel,"");
+  }
+
+  // Attempt to delete a model by name, if the string is present
+  if (strcmp((const char*)this->factoryIface->data->deleteEntity,"")!=0)
+  {
+    const std::string e = (const char*)this->factoryIface->data->deleteEntity;
+    Events::deleteEntitySignal(e);
+
+    strcpy((char*)this->factoryIface->data->deleteEntity,"");
+  }
+  this->factoryIface->Unlock();
+
+}

Added: code/gazebo/branches/dev/server/FactoryIfaceHandler.hh
===================================================================
--- code/gazebo/branches/dev/server/FactoryIfaceHandler.hh                      
        (rev 0)
+++ code/gazebo/branches/dev/server/FactoryIfaceHandler.hh      2010-11-12 
02:06:48 UTC (rev 8960)
@@ -0,0 +1,82 @@
+/*
+ *  Gazebo - Outdoor Multi-Robot Simulator
+ *  Copyright (C) 2003  
+ *     Nate Koenig & Andrew Howard
+ *
+ *  This program is free software; you can redistribute it and/or modify
+ *  it under the terms of the GNU General Public License as published by
+ *  the Free Software Foundation; either version 2 of the License, or
+ *  (at your option) any later version.
+ *
+ *  This program is distributed in the hope that it will be useful,
+ *  but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ *  GNU General Public License for more details.
+ *
+ *  You should have received a copy of the GNU General Public License
+ *  along with this program; if not, write to the Free Software
+ *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+ *
+ */
+/*
+ * Desc: Factory controller.
+ * Author: Nathan Koenig
+ * Date: 29 July 2007
+ * SVN: $Id: Factory.hh 7551 2009-03-27 16:15:13Z natepak $
+ */
+#ifndef FACTORYIFACEHANDLER_HH
+#define FACTORYIFACEHANDLER_HH
+
+#include "Controller.hh"
+#include "Entity.hh"
+#include "gz.h"
+
+
+namespace gazebo
+{
+  class World;
+
+  /// \addtogroup gazebo_server
+  /// \{
+  /** \defgroup factory factory
+    \brief Factory used for dynamic construction of models
+  
+    The factory controller allows dynamic addition and deletion of models 
using libgazebo's \ref factory_iface interface.
+  
+  \{
+  */
+  
+  /// \brief Factory used for dynamic construction of models
+  class FactoryIfaceHandler
+  {
+  
+    /// Constructor
+    public: FactoryIfaceHandler(World *world);
+  
+    /// Destructor
+    public: virtual ~FactoryIfaceHandler();
+  
+    /// Init the controller
+    /// \return 0 on success
+    public: void Init();
+  
+    /// Update the controller
+    /// \return 0 on success
+    public: void Update();
+  
+    /// The Position interface
+    private: libgazebo::FactoryIface *factoryIface;
+  
+    private: World *world;
+  
+    private: std::string xmlPrefix;
+    private: std::string xmlSuffix;
+  };
+  
+  /** \} */
+  /// \}
+
+}
+
+#endif
+

Added: code/gazebo/branches/dev/server/rendering/Camera.cc
===================================================================
--- code/gazebo/branches/dev/server/rendering/Camera.cc                         
(rev 0)
+++ code/gazebo/branches/dev/server/rendering/Camera.cc 2010-11-12 02:06:48 UTC 
(rev 8960)
@@ -0,0 +1,1014 @@
+/*
+ *  Gazebo - Outdoor Multi-Robot Simulator
+ *  Copyright (C) 2003
+ *     Nate Koenig & Andrew Howard
+ *
+ *  This program is free software; you can redistribute it and/or modify
+ *  it under the terms of the GNU General Public License as published by
+ *  the Free Software Foundation; either version 2 of the License, or
+ *  (at your option) any later version.
+ *
+ *  This program is distributed in the hope that it will be useful,
+ *  but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the *  GNU 
General Public License for more details.
+ *
+ *  You should have received a copy of the GNU General Public License
+ *  along with this program; if not, write to the Free Software
+ *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+ *
+ */
+
+/* Desc: A camera sensor using OpenGL
+ * Author: Nate Koenig
+ * Date: 15 July 2003
+ * CVS: $Id: Camera.cc 8937 2010-10-11 16:59:55Z natepak $
+ */
+
+#include <sstream>
+#include <OgreImageCodec.h>
+#include <Ogre.h>
+#include <dirent.h>
+
+#include "Events.hh"
+#include "GazeboMessage.hh"
+#include "PhysicsEngine.hh"
+#include "Global.hh"
+#include "GazeboError.hh"
+#include "OgreVisual.hh"
+#include "OgreCreator.hh"
+#include "XMLConfig.hh"
+#include "Simulator.hh"
+#include "Model.hh"
+#include "Body.hh"
+
+#include "Scene.hh"
+#include "OgreAdaptor.hh"
+#include "Camera.hh"
+
+using namespace gazebo;
+
+unsigned int Camera::cameraCounter = 0;
+
+//////////////////////////////////////////////////////////////////////////////
+// Constructor
+Camera::Camera(const std::string &namePrefix, Scene *scene)
+{
+  this->scene = scene;
+
+  this->textureWidth = this->textureHeight = 0;
+
+  this->saveFrameBuffer = NULL;
+  this->saveCount = 0;
+  this->bayerFrameBuffer = NULL;
+
+  this->myCount = cameraCounter++;
+
+  std::ostringstream stream;
+  stream << namePrefix << "(" << this->myCount << ")";
+  this->name = stream.str();
+
+  this->renderTarget = NULL;
+  this->userMovable = true;
+
+  Param::Begin(&this->camParameters);
+  this->nearClipP = new ParamT<double>("nearClip",1,0);
+  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->imageSizeP = new ParamT< Vector2<int> >("imageSize", Vector2<int>(320, 
240),0);
+  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",32,0);
+  Param::End();
+
+  this->captureData = false;
+
+  this->camera = NULL;
+  this->viewport = NULL;
+
+  if (**this->updateRateP == 0)
+    this->renderPeriod = Time(0.0);
+  else
+    this->renderPeriod = Time(1.0/(**this->updateRateP));
+
+  this->renderingEnabled = true;
+
+  Events::ConnectShowWireframeSignal( 
boost::bind(&Camera::ToggleShowWireframe, this) );
+
+  this->pitchNode = NULL;
+  this->sceneNode = NULL;
+  this->origParentNode = NULL;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+// Destructor
+Camera::~Camera()
+{
+  if (this->saveFrameBuffer)
+    delete [] this->saveFrameBuffer;
+
+  if (this->bayerFrameBuffer)
+    delete [] this->bayerFrameBuffer;
+
+  delete this->nearClipP;
+  delete this->farClipP;
+  delete this->saveFramesP;
+  delete this->savePathnameP;
+  delete this->imageSizeP;
+  delete this->imageFormatP;
+  delete this->visMaskP;
+  delete this->hfovP;
+
+  if (this->pitchNode)
+  {
+    this->sceneNode->removeAndDestroyChild( this->name + "PitchNode");
+    this->pitchNode = NULL;
+  }
+  if (this->camera)
+  {
+    this->scene->GetManager()->destroyCamera(this->name);
+    this->camera = NULL;
+  }
+  // NATY
+  //this->scene->UnregisterCamera(this);
+}
+
+//////////////////////////////////////////////////////////////////////////////
+// Load the camera
+void Camera::Load( XMLConfigNode *node )
+{
+  if (!Simulator::Instance()->GetRenderEngineEnabled())
+    return;
+
+  this->visibilityMask = GZ_ALL_CAMERA; 
+
+  if (node)
+  {
+    this->nearClipP->Load(node);
+    this->farClipP->Load(node);
+    this->saveFramesP->Load(node);
+    this->savePathnameP->Load(node);
+    this->imageSizeP->Load(node);
+    this->imageFormatP->Load(node);
+    this->visMaskP->Load(node);
+    this->hfovP->Load(node);
+
+    if (this->visMaskP->GetValue() == "laser")
+    {
+      this->visibilityMask ^= GZ_LASER_CAMERA;
+    }
+
+    if (this->imageFormatP->GetValue() == "L8")
+      this->imageFormat = Ogre::PF_L8;
+    else if (this->imageFormatP->GetValue() == "R8G8B8")
+      this->imageFormat = Ogre::PF_R8G8B8;
+    else if (this->imageFormatP->GetValue() == "B8G8R8")
+      this->imageFormat = Ogre::PF_B8G8R8;
+    else if (this->imageFormatP->GetValue() == "FLOAT32")
+      this->imageFormat = Ogre::PF_FLOAT32_R;
+    else if (this->imageFormatP->GetValue() == "FLOAT16")
+      this->imageFormat = Ogre::PF_FLOAT16_R;
+    else if ( (this->imageFormatP->GetValue() == "BAYER_RGGB8") ||
+              (this->imageFormatP->GetValue() == "BAYER_BGGR8") ||
+              (this->imageFormatP->GetValue() == "BAYER_GBRG8") ||
+              (this->imageFormatP->GetValue() == "BAYER_GRBG8") )
+    {
+      // let ogre generate rgb8 images for all bayer format requests
+      // then post process to produce actual bayer images
+      this->imageFormat = Ogre::PF_R8G8B8;
+    }
+    else
+    {
+      std::cerr << "Error parsing image format (" << 
this->imageFormatP->GetValue() << "), using default Ogre::PF_R8G8B8\n";
+      this->imageFormat = Ogre::PF_R8G8B8;
+    }
+  }
+
+  // Create the directory to store frames
+  if (this->saveFramesP->GetValue())
+  {
+    std::string command;
+    command = "mkdir " + this->savePathnameP->GetValue() + " 2>>/dev/null";
+    if (system(command.c_str()) < 0)
+      std::cerr << "Error making directory\n";
+  }
+
+  if (this->hfovP->GetValue() < Angle(0.01) || 
+      this->hfovP->GetValue() > Angle(M_PI))
+  {
+    gzthrow("Camera horizontal field of veiw invalid.");
+  }
+  if (this->nearClipP->GetValue() <= 0)
+  {
+    gzthrow("near clipping plane (min depth) <= zero");
+  }
+
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Save camera info in xml format
+void Camera::Save(std::string &prefix, std::ostream &stream)
+{
+  stream << prefix << (*this->nearClipP) << "\n";
+  stream << prefix << (*this->farClipP) << "\n";
+  stream << prefix << (*this->saveFramesP) << "\n";
+  stream << prefix << (*this->savePathnameP) << "\n";
+  stream << prefix << (*this->imageSizeP) << "\n";
+  stream << prefix << (*this->imageFormatP) << "\n";
+  stream << prefix << (*this->visMaskP) << "\n";
+  stream << prefix << (*this->hfovP) << "\n";
+}
+ 
+//////////////////////////////////////////////////////////////////////////////
+// Initialize the camera
+void Camera::Init()
+{
+  if (!Simulator::Instance()->GetRenderEngineEnabled())
+    return;
+
+  this->CreateCamera();
+
+  // Create a scene node to control pitch motion
+  this->pitchNode = this->sceneNode->createChildSceneNode( this->name + 
"PitchNode");
+  this->pitchNode->pitch(Ogre::Degree(0));
+  this->pitchNode->attachObject(this->camera);
+  this->camera->setAutoAspectRatio(true);
+
+  this->saveCount = 0;
+
+  this->origParentNode = (Ogre::SceneNode*)this->sceneNode->getParent();
+
+  Ogre::Real left, right ,top, bottom;
+
+  //Ogre::Frustum *frustum = this->camera->getFrustum();
+  //this->camera->getFrustumExtents(left, right, top, bottom);
+  //this->camera->setFrustumExtents(-100, 100, 100, -100);
+  //printf("F Extents[%f %f %f %f]\n", left, right ,top ,bottom);
+}
+
+//////////////////////////////////////////////////////////////////////////////
+// Finalize the camera
+void Camera::Fini()
+{
+}
+
+//////////////////////////////////////////////////////////////////////////////
+// Update the drawing
+void Camera::Update()
+{
+  if (!Simulator::Instance()->GetRenderEngineEnabled())
+    return;
+
+  if (this->sceneNode)
+  {
+    Ogre::Vector3 v = this->sceneNode->_getDerivedPosition();
+
+    this->pose.pos.x = v.x;
+    this->pose.pos.y = v.y;
+    this->pose.pos.z = v.z;
+  }
+
+  if (this->pitchNode)
+  {
+    Ogre::Quaternion q = this->pitchNode->_getDerivedOrientation();
+
+    this->pose.rot.u = q.w;
+    this->pose.rot.x = q.x;
+    this->pose.rot.y = q.y;
+    this->pose.rot.z = q.z;
+  }
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set to true to enable rendering
+void Camera::SetRenderingEnabled(bool value)
+{
+  this->renderingEnabled = value;
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get whether the rendering is enabled
+bool Camera::GetRenderingEnabled() const
+{
+  return this->renderingEnabled;
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Render the camera
+void Camera::Render()
+{
+  // disable rendering if "-r" option is given
+  if (!Simulator::Instance()->GetRenderEngineEnabled())
+    return;
+
+  // disable rendering if sensor not set to active
+  if (!this->renderingEnabled)
+    return;
+
+  this->newData = true;
+  this->renderTarget->update(false);
+}
+
+void Camera::PostRender()
+{
+  if (this->newData && this->captureData)
+  {
+    // NATY
+    //boost::recursive_mutex::scoped_lock 
mr_lock(*Simulator::Instance()->GetMRMutex());
+
+    Ogre::HardwarePixelBufferSharedPtr pixelBuffer;
+    Ogre::RenderTexture *rTexture;
+    Ogre::Viewport* renderViewport;
+
+    size_t size;
+
+    // Get access to the buffer and make an image and write it to file
+    pixelBuffer = this->renderTexture->getBuffer();
+    rTexture = pixelBuffer->getRenderTarget();
+
+    Ogre::PixelFormat format = pixelBuffer->getFormat();
+    renderViewport = rTexture->getViewport(0);
+
+    size = Ogre::PixelUtil::getMemorySize((**this->imageSizeP).x,
+        (**this->imageSizeP).y, 
+        1, 
+        format);
+
+    // Allocate buffer
+    if (!this->saveFrameBuffer)
+      this->saveFrameBuffer = new unsigned char[size];
+
+    memset(this->saveFrameBuffer,128,size);
+
+    Ogre::PixelBox box((**this->imageSizeP).x, (**this->imageSizeP).y,
+        1, this->imageFormat, this->saveFrameBuffer);
+
+    pixelBuffer->blitToMemory( box );
+
+    if (this->saveFramesP->GetValue())
+    {
+      this->SaveFrame();
+    }
+  }
+
+  this->newData = false;
+}
+
+
+////////////////////////////////////////////////////////////////////////////////
+// Get the global pose of the camera
+Pose3d Camera::GetWorldPose() const
+{
+  Ogre::Vector3 camPos = this->camera->getRealPosition();
+  Ogre::Quaternion camOrient = this->camera->getRealOrientation();
+
+  Pose3d pose;
+  pose.pos.x = camPos.x;
+  pose.pos.y = camPos.y;
+  pose.pos.z = camPos.z;
+
+  return this->pose;
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get the camera position in the world
+Vector3 Camera::GetWorldPosition() const
+{
+  Ogre::Vector3 camPos = this->camera->getRealPosition();
+  return Vector3(camPos.x,camPos.y,camPos.z);
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the global pose of the camera
+void Camera::SetWorldPose(const Pose3d &pose)
+{
+  if (!Simulator::Instance()->GetRenderEngineEnabled())
+    return;
+
+  this->pose = pose;
+  this->pose.Correct();
+  this->sceneNode->setPosition( this->pose.pos.x, this->pose.pos.y, 
this->pose.pos.z);
+  this->pitchNode->setOrientation( this->pose.rot.u, this->pose.rot.x, 
this->pose.rot.y, this->pose.rot.z);
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the world position
+void Camera::SetWorldPosition(const Vector3 &pos)
+{
+  if (!Simulator::Instance()->GetRenderEngineEnabled())
+    return;
+
+  this->pose.pos = pos;
+  this->pose.Correct();
+  
+  this->sceneNode->setPosition( this->pose.pos.x, this->pose.pos.y, 
this->pose.pos.z);
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the world orientation
+void Camera::SetWorldRotation(const Quatern &quant)
+{
+  if (!Simulator::Instance()->GetRenderEngineEnabled())
+    return;
+
+  this->pose.rot = quant;
+  this->pose.Correct();
+ 
+  this->pitchNode->setOrientation( this->pose.rot.u, this->pose.rot.x, 
this->pose.rot.y, this->pose.rot.z);
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Translate the camera
+void Camera::Translate( const Vector3 &direction )
+{
+  Ogre::Vector3 vec(direction.x, direction.y, direction.z);
+
+  this->sceneNode->translate(this->sceneNode->getOrientation() * 
this->pitchNode->getOrientation() * vec);
+
+}
+
+//////////////////////////////////////////////////////////////////////////////
+// Rotate the camera around the yaw axis
+void Camera::RotateYaw( float angle )
+{
+  this->sceneNode->roll(Ogre::Radian(angle), Ogre::Node::TS_WORLD);
+}
+
+//////////////////////////////////////////////////////////////////////////////
+// Rotate the camera around the pitch axis
+void Camera::RotatePitch( float angle )
+{
+  this->pitchNode->yaw(Ogre::Radian(angle));
+}
+
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the clip distances
+void Camera::SetClipDist(float near, float far)
+{
+  this->nearClipP->SetValue(near);
+  this->farClipP->SetValue(far);
+
+  if (camera)
+  {
+    this->camera->setNearClipDistance(.001);
+    this->camera->setFarClipDistance(1000);
+  }
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the camera FOV (horizontal)  
+void Camera::SetFOV( float radians )
+{
+  this->hfovP->SetValue(radians);
+}
+
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the horizontal field of view of the camera
+Angle Camera::GetHFOV() const
+{
+  return this->hfovP->GetValue();
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the vertical field of view of the camera
+Angle Camera::GetVFOV() const
+{
+  return Angle(this->camera->getFOVy().valueRadians());
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the width of the image
+unsigned int Camera::GetImageWidth() const
+{
+  return this->imageSizeP->GetValue().x;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// \brief Get the height of the image
+unsigned int Camera::GetImageHeight() const
+{
+  return this->imageSizeP->GetValue().y;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// \brief Get the height of the image
+int Camera::GetImageDepth() const
+{
+  if (this->imageFormatP->GetValue() == "L8")
+    return 1;
+  else if (this->imageFormatP->GetValue() == "R8G8B8")
+    return 3;
+  else if (this->imageFormatP->GetValue() == "B8G8R8")
+    return 3;
+  else if ( (this->imageFormatP->GetValue() == "BAYER_RGGB8") ||
+            (this->imageFormatP->GetValue() == "BAYER_BGGR8") ||
+            (this->imageFormatP->GetValue() == "BAYER_GBRG8") ||
+            (this->imageFormatP->GetValue() == "BAYER_GRBG8") )
+    return 1;
+  else
+  {
+    std::cerr << "Error parsing image format (" << 
this->imageFormatP->GetValue() << "), using default Ogre::PF_R8G8B8\n";
+    return 3;
+  }
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// \brief Get the height of the image
+std::string Camera::GetImageFormat() const
+{
+  return this->imageFormatP->GetValue();
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the width of the texture
+unsigned int Camera::GetTextureWidth() const
+{
+  return this->renderTexture->getBuffer(0,0)->getWidth();
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// \brief Get the height of the texture
+unsigned int Camera::GetTextureHeight() const
+{
+  return this->renderTexture->getBuffer(0,0)->getHeight();
+}
+
+
+//////////////////////////////////////////////////////////////////////////////
+// Get the image size in bytes
+size_t Camera::GetImageByteSize() const
+{
+
+  return Ogre::PixelUtil::getMemorySize((**this->imageSizeP).x,
+                                        (**this->imageSizeP).y, 
+                                        1, 
+                                        this->imageFormat);
+}
+
+
+//////////////////////////////////////////////////////////////////////////////
+// Enable or disable saving
+void Camera::EnableSaveFrame(bool enable)
+{
+  this->saveFramesP->SetValue( enable );
+}
+
+//////////////////////////////////////////////////////////////////////////////
+// Set the save frame pathname
+void Camera::SetSaveFramePathname(const std::string &pathname)
+{
+  this->savePathnameP->SetValue( pathname );
+
+  // Create the directory to store frames
+  if (this->saveFramesP->GetValue())
+  {
+    std::string command;
+    command = "mkdir " + this->savePathnameP->GetValue() + " 2>>/dev/null";
+    if (system(command.c_str()) <0)
+      std::cerr << "Error making directory\n";
+  }
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Toggle saving of frames
+void Camera::ToggleSaveFrame()
+{
+  this->saveFramesP->SetValue(!this->saveFramesP->GetValue());
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get a pointer to the ogre camera
+Ogre::Camera *Camera::GetCamera() const
+{
+  return this->camera;
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get the near clip distance
+double Camera::GetNearClip()
+{
+  return this->nearClipP->GetValue();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get the far clip distance
+double Camera::GetFarClip()
+{
+  return this->farClipP->GetValue();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get the viewport width in pixels
+unsigned int Camera::GetViewportWidth() const
+{
+  if (this->renderTarget)
+    return this->renderTarget->getViewport(0)->getActualWidth();
+  else
+    return this->camera->getViewport()->getActualWidth();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get the viewport height in pixels
+unsigned int Camera::GetViewportHeight() const
+{
+  if (this->renderTarget)
+    return this->renderTarget->getViewport(0)->getActualHeight();
+  else
+    return this->camera->getViewport()->getActualHeight();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the aspect ratio
+void Camera::SetAspectRatio( float ratio )
+{
+  this->camera->setAspectRatio( ratio );
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get the viewport up vector
+Vector3 Camera::GetUp()
+{
+  Ogre::Vector3 up = this->camera->getRealUp();
+  return Vector3(up.x,up.y,up.z);
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get the viewport right vector
+Vector3 Camera::GetRight()
+{
+  Ogre::Vector3 right = this->camera->getRealRight();
+  return Vector3(right.x,right.y,right.z);
+}
+
+
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set whether the user can move the camera via the GUI
+void Camera::SetUserMovable( bool movable )
+{
+  this->userMovable = movable;
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get whether the user can move the camera via the GUI
+bool Camera::GetUserMovable() const
+{
+  return this->userMovable;
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the camera's scene node
+void Camera::SetSceneNode( Ogre::SceneNode *node )
+{
+  this->sceneNode = node;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the camera's scene node
+Ogre::SceneNode *Camera::GetSceneNode() const
+{
+  return this->pitchNode;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get a pointer to the image data
+const unsigned char *Camera::GetImageData(unsigned int i)
+{
+  if (i!=0)
+    gzerr(0) << "Camera index must be zero for cam";
+
+  int width = this->imageSizeP->GetValue().x;
+  int height = this->imageSizeP->GetValue().y;
+
+  // do last minute conversion if Bayer pattern is requested, go from R8G8B8
+  if ( (this->imageFormatP->GetValue() == "BAYER_RGGB8") ||
+       (this->imageFormatP->GetValue() == "BAYER_BGGR8") ||
+       (this->imageFormatP->GetValue() == "BAYER_GBRG8") ||
+       (this->imageFormatP->GetValue() == "BAYER_GRBG8") )
+  {
+    if (!this->bayerFrameBuffer)
+      this->bayerFrameBuffer = new unsigned char[width*height];
+    
this->ConvertRGBToBAYER(this->bayerFrameBuffer,this->saveFrameBuffer,this->imageFormatP->GetValue(),width,height);
+    return this->bayerFrameBuffer;
+  }
+  else
+    return this->saveFrameBuffer;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the camera's name
+std::string Camera::GetName() const
+{
+  return this->name;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+// Save the current frame to disk
+void Camera::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";
+    if (system(command.c_str()) < 0)
+      std::cerr << "Error making directory\n";
+  }
+
+  // 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 = this->GetImageDepth();
+  imgData->format = this->imageFormat;
+  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 wallTime = Time::GetWallTime().Double();
+    int min = (int)(wallTime / 60.0);
+    int sec = (int)(wallTime - min*60);
+    int msec = (int)(wallTime*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++;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+// Toggle whether to view the world in wireframe
+void Camera::ToggleShowWireframe()
+{
+   if (this->camera)
+  {
+    if (this->camera->getPolygonMode() == Ogre::PM_WIREFRAME)
+      this->camera->setPolygonMode(Ogre::PM_SOLID);
+    else
+      this->camera->setPolygonMode(Ogre::PM_WIREFRAME);
+  } 
+}
+
+//////////////////////////////////////////////////////////////////////////////
+// Set whether to view the world in wireframe
+void Camera::ShowWireframe(bool s)
+{
+  if (this->camera)
+  {
+    if (s)
+    {
+      this->camera->setPolygonMode(Ogre::PM_WIREFRAME);
+    }
+    else
+    {
+      this->camera->setPolygonMode(Ogre::PM_SOLID);
+    }
+  }
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get a world space ray as cast from the camer through the viewport
+void Camera::GetCameraToViewportRay(int screenx, int screeny,
+                                        Vector3 &origin, Vector3 &dir)
+{
+  Ogre::Ray ray = this->camera->getCameraToViewportRay(
+      (float)screenx / this->GetViewportWidth(),
+      (float)screeny / this->GetViewportHeight());
+
+  origin.Set(ray.getOrigin().x, ray.getOrigin().y, ray.getOrigin().z);
+  dir.Set(ray.getDirection().x, ray.getDirection().y, ray.getDirection().z);
+}
+
+
+////////////////////////////////////////////////////////////////////////////////
+/// post process, convert from rgb to bayer
+void Camera::ConvertRGBToBAYER(unsigned char* dst, unsigned char* src, 
std::string format,int width, int height)
+{
+  if (src)
+  {
+    // do last minute conversion if Bayer pattern is requested, go from R8G8B8
+    if (format == "BAYER_RGGB8")
+    {
+      for (int i=0;i<width;i++)
+      {
+        for (int j=0;j<height;j++)
+        {
+          //
+          // RG
+          // GB
+          //
+          // determine position
+          if (j%2) // even column
+            if (i%2) // even row, red
+              dst[i+j*width] = src[i*3+j*width*3+0];
+            else // odd row, green
+              dst[i+j*width] = src[i*3+j*width*3+1];
+          else // odd column
+            if (i%2) // even row, green
+              dst[i+j*width] = src[i*3+j*width*3+1];
+            else // odd row, blue
+              dst[i+j*width] = src[i*3+j*width*3+2];
+        }
+      }
+    }
+    else if (format == "BAYER_BGGR8")
+    {
+      for (int i=0;i<width;i++)
+      {
+        for (int j=0;j<height;j++)
+        {
+          //
+          // BG
+          // GR
+          //
+          // determine position
+          if (j%2) // even column
+            if (i%2) // even row, blue
+              dst[i+j*width] = src[i*3+j*width*3+2];
+            else // odd row, green
+              dst[i+j*width] = src[i*3+j*width*3+1];
+          else // odd column
+            if (i%2) // even row, green
+              dst[i+j*width] = src[i*3+j*width*3+1];
+            else // odd row, red
+              dst[i+j*width] = src[i*3+j*width*3+0];
+        }
+      }
+    }
+    else if (format == "BAYER_GBRG8")
+    {
+      for (int i=0;i<width;i++)
+      {
+        for (int j=0;j<height;j++)
+        {
+          //
+          // GB
+          // RG
+          //
+          // determine position
+          if (j%2) // even column
+            if (i%2) // even row, green
+              dst[i+j*width] = src[i*3+j*width*3+1];
+            else // odd row, blue
+              dst[i+j*width] = src[i*3+j*width*3+2];
+          else // odd column
+            if (i%2) // even row, red
+              dst[i+j*width] = src[i*3+j*width*3+0];
+            else // odd row, green
+              dst[i+j*width] = src[i*3+j*width*3+1];
+        }
+      }
+    }
+    else if (format == "BAYER_GRBG8")
+    {
+      for (int i=0;i<width;i++)
+      {
+        for (int j=0;j<height;j++)
+        {
+          //
+          // GR
+          // BG
+          //
+          // determine position
+          if (j%2) // even column
+            if (i%2) // even row, green
+              dst[i+j*width] = src[i*3+j*width*3+1];
+            else // odd row, red
+              dst[i+j*width] = src[i*3+j*width*3+0];
+          else // odd column
+            if (i%2) // even row, blue
+              dst[i+j*width] = src[i*3+j*width*3+2];
+            else // odd row, green
+              dst[i+j*width] = src[i*3+j*width*3+1];
+        }
+      }
+    }
+  }
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set whether to capture data
+void Camera::SetCaptureData( bool value )
+{
+  this->captureData = value;
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the render target
+void Camera::CreateRenderTexture( const std::string &textureName )
+{
+  // Create the render texture
+  this->renderTexture = Ogre::TextureManager::getSingleton().createManual(
+      textureName,
+      "General",
+      Ogre::TEX_TYPE_2D,
+      this->GetImageWidth(), 
+      this->GetImageHeight(),
+      0,
+      this->imageFormat,
+      Ogre::TU_RENDERTARGET);
+
+  this->renderTarget = this->renderTexture->getBuffer()->getRenderTarget();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Return this scene
+Scene *Camera::GetScene() const
+{
+  return this->scene;
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Create the ogre camera
+void Camera::CreateCamera()
+{
+  if (!Simulator::Instance()->GetRenderEngineEnabled())
+    return;
+
+  Ogre::Viewport *cviewport;
+
+  this->camera = this->scene->GetManager()->createCamera(this->name);
+
+  // Use X/Y as horizon, Z up
+  this->camera->pitch(Ogre::Degree(90));
+
+  // Don't yaw along variable axis, causes leaning
+  this->camera->setFixedYawAxis(true, Ogre::Vector3::UNIT_Z);
+
+  this->camera->setDirection(1,0,0);
+
+  this->camera->setNearClipDistance(.001);//**this->nearClipP);
+  this->camera->setFarClipDistance(1000);//**this->farClipP);
+
+  if (this->renderTarget)
+  {
+    // Setup the viewport to use the texture
+    this->viewport = this->renderTarget->addViewport(this->camera);
+    this->viewport->setClearEveryFrame(true);
+    this->viewport->setBackgroundColour( 
this->scene->GetBackgroundColor().GetOgreColor() );
+
+    double ratio = (double)this->viewport->getActualWidth() / 
+                   (double)this->viewport->getActualHeight();
+    double vfov = 2.0 * atan(tan( (**this->hfovP).GetAsRadian() / 2.0) / 
ratio);
+    this->camera->setAspectRatio(ratio);
+    this->camera->setFOVy(Ogre::Radian(vfov));
+  }
+
+  //this->scene->RegisterCamera(this);
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Get point on a plane
+Vector3 Camera::GetWorldPointOnPlane(int x, int y, Vector3 planeNorm, double d)
+{
+  Vector3 origin, dir;
+  double dist;
+
+  // Cast two rays from the camera into the world
+  this->GetCameraToViewportRay(x, y, origin, dir);
+
+  dist = origin.GetDistToPlane(dir, planeNorm, d);
+
+  // Compute two points on the plane. The first point is the current
+  // mouse position, the second is the previous mouse position
+  return origin + dir * dist; 
+}

Added: code/gazebo/branches/dev/server/rendering/Camera.hh
===================================================================
--- code/gazebo/branches/dev/server/rendering/Camera.hh                         
(rev 0)
+++ code/gazebo/branches/dev/server/rendering/Camera.hh 2010-11-12 02:06:48 UTC 
(rev 8960)
@@ -0,0 +1,320 @@
+/*
+ *  Gazebo - Outdoor Multi-Robot Simulator
+ *  Copyright (C) 2003  
+ *     Nate Koenig & Andrew Howard
+ *
+ *  This program is free software; you can redistribute it and/or modify
+ *  it under the terms of the GNU General Public License as published by
+ *  the Free Software Foundation; either version 2 of the License, or
+ *  (at your option) any later version.
+ *
+ *  This program is distributed in the hope that it will be useful,
+ *  but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ *  GNU General Public License for more details.
+ *
+ *  You should have received a copy of the GNU General Public License
+ *  along with this program; if not, write to the Free Software
+ *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+ *
+ */
+/* Desc: A persepective OGRE Camera
+ * Author: Nate Koenig
+ * Date: 15 July 2003
+ * CVS: $Id: Camera.hh 8937 2010-10-11 16:59:55Z natepak $
+ */
+
+#ifndef CAMERASENSOR_HH
+#define CAMERASENSOR_HH
+
+#include <OgrePrerequisites.h>
+#include <OgreTexture.h>
+
+#include "Param.hh"
+#include "Angle.hh"
+#include "Pose3d.hh"
+#include "Time.hh"
+
+// Forward Declarations
+namespace Ogre
+{
+  class TexturePtr;
+  class RenderTarget;
+  class Camera;
+  class Viewport;
+  class SceneNode;
+}
+
+namespace gazebo
+{
+  class XMLConfigNode;
+  class Model;
+  class Entity;
+  class MouseEvent;
+  class ViewController;
+  class Scene;
+
+  /// \addtogroup gazebo_rendering
+  /// \brief Basic camera 
+  /// \{
+  /// \defgroup gazebo_camera Camera
+  /// \brief Basic camera sensor
+  // \{
+  
+  
+  /// \brief Basic camera sensor
+  ///
+  /// This is the base class for all cameras.
+  class Camera 
+  {
+    /// \brief Constructor
+    public: Camera(const std::string &namePrefix, Scene *scene);
+  
+    /// \brief Destructor
+    public: virtual ~Camera();
+  
+    /// \brief Load the camera using parameter from an XMLConfig node
+    /// \param node The XMLConfig node
+    public: void Load( XMLConfigNode *node );
+
+    /// \brief Save camera info in xml format
+    /// \param stream Output stream
+    public: void Save(std::string &prefix, std::ostream &stream);
+  
+    /// \brief Initialize the camera
+    public: void Init();
+
+    /// \brief Render the camera
+    public: virtual void Render();
+
+    /// \brief Post render
+    public: virtual void PostRender();
+
+    /// \brief Update the sensor information
+    public: void Update();
+  
+    /// Finalize the camera
+    public: void Fini();
+
+    /// \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;
+
+    /// \brief Get the camera position in the world
+    public: Vector3 GetWorldPosition() const;
+
+
+    /// \brief Set the global pose of the camera
+    public: void SetWorldPose(const Pose3d &pose);
+
+    /// \brief Set the world position
+    public: void SetWorldPosition(const Vector3 &pos);
+
+    /// \brief Set the world orientation
+    public: void SetWorldRotation(const Quatern &quant);
+
+  
+    /// \brief Translate the camera
+    public: void Translate( const Vector3 &direction );
+  
+    /// \brief Rotate the camera around the yaw axis
+    public: void RotateYaw( float angle );
+  
+    /// \brief Rotate the camera around the pitch axis
+    public: void RotatePitch( float angle );
+
+
+
+    /// \brief Set the clip distances
+    public: void SetClipDist(float near, float far);
+
+    /// \brief Set the camera FOV (horizontal)  
+    public: void SetFOV( float radians );
+
+    /// \brief Get the camera FOV (horizontal)  
+    public: Angle GetHFOV() const;
+
+    /// \brief Get the camera FOV (vertical)  
+    public: Angle GetVFOV() const;
+  
+    /// \brief Get the width of the image
+    public: unsigned int GetImageWidth() const;
+  
+    /// \brief Get the width of the texture 
+    public: unsigned int GetTextureWidth() const;
+  
+    /// \brief Get the height of the image
+    public: unsigned int GetImageHeight() const;
+  
+    /// \brief Get the height of the image
+    public: int GetImageDepth() const;
+
+    /// \brief Get the height of the image
+    public: std::string GetImageFormat() const;
+
+    /// \brief Get the height of the texture 
+    public: unsigned int GetTextureHeight() const;
+  
+    /// \brief Get the image size in bytes
+    public: size_t GetImageByteSize() const;
+  
+    /// \brief Get the Z-buffer value at the given image coordinate.
+    ///
+    /// \param x, y Image coordinate; (0, 0) specifies the top-left corner.
+    /// \returns Image z value; note that this is abitrarily scaled and
+    /// is @e not the same as the depth value.
+    public: double GetZValue(int x, int y);
+  
+    /// \brief Get the near clip distance
+    public: double GetNearClip();
+  
+    /// \brief Get the far clip distance
+    public: double GetFarClip();
+  
+    /// \brief Enable or disable saving
+    public: void EnableSaveFrame(bool enable);
+ 
+    /// \brief Set the save frame pathname
+    public: void SetSaveFramePathname(const std::string &pathname);
+
+    /// \brief Toggle saving of frames
+    public: void ToggleSaveFrame();
+  
+    /// \brief Get a pointer to the ogre camera
+    public: Ogre::Camera *GetCamera() const;
+
+    /// \brief Get the viewport width in pixels
+    public: unsigned int GetViewportWidth() const;
+
+    /// \brief Get the viewport height in pixels
+    public: unsigned int GetViewportHeight() const;
+
+    /// \brief Get the viewport up vector
+    public: Vector3 GetUp();
+
+    /// \brief Get the viewport right vector
+    public: Vector3 GetRight();
+
+    /// \brief Get the average FPS
+    public: virtual float GetAvgFPS() { return 0;}
+
+    /// \brief Get the triangle count
+    public: virtual unsigned int GetTriangleCount() {return 0;}
+
+    /// \brief Set the aspect ratio
+    public: void SetAspectRatio( float ratio );
+
+    /// \brief Set whether the user can move the camera via the GUI
+    public: void SetUserMovable( bool movable );
+
+    /// \brief Get whether the user can move the camera via the GUI
+    public: bool GetUserMovable() const;
+
+    /// \brief Set the camera's scene node
+    public: void SetSceneNode( Ogre::SceneNode *node );
+
+    /// \brief Get the camera's scene node
+    public: Ogre::SceneNode *GetSceneNode() const;
+
+    /// \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 GetName() const;
+
+    /// \brief Set the camera's name
+    public: void SetName( const std::string &name );
+           
+    /// \brief Toggle whether to view the world in wireframe
+    public: void ToggleShowWireframe();
+
+    /// \brief Set whether to view the world in wireframe
+    public: void ShowWireframe(bool s);
+
+    /// \brief Get a world space ray as cast from the camer through the 
viewport
+    public: void GetCameraToViewportRay(int screenx, int screeny,
+                                        Vector3 &origin, Vector3 &dir);
+
+        /// \brief Set whether to capture data
+    public: void SetCaptureData( bool value );
+
+    /// \brief Set the render target
+    public: void CreateRenderTexture( const std::string &textureName );
+
+    /// \brief Get the scene this camera is in
+    public: Scene *GetScene() const;
+
+    /// \brief Get point on a plane
+    public: Vector3 GetWorldPointOnPlane(int x, int y, Vector3 planeNorm, 
double d);
+
+    /// \brief if user requests bayer image, post process rgb from ogre to 
generate bayer formats
+    private: void ConvertRGBToBAYER(unsigned char* dst, unsigned char* src, 
std::string format,int width, int height);
+
+    // Save the camera frame
+    protected: virtual void SaveFrame();
+
+    // Create the ogre camera
+    private: void CreateCamera();
+
+    private: std::string name;
+
+    protected: ParamT<Angle> *hfovP;
+    protected: ParamT<double> *nearClipP, *farClipP, *updateRateP;
+    protected: ParamT< Vector2<int> > *imageSizeP;
+    protected: unsigned int textureWidth, textureHeight;
+  
+    protected: Ogre::Camera *camera;
+    protected: Ogre::Viewport *viewport;
+    protected: Ogre::SceneNode *origParentNode;
+    protected: Ogre::SceneNode *sceneNode;
+    protected: Ogre::SceneNode *pitchNode;
+  
+    private: Pose3d pose;
+  
+    // Info for saving images
+    protected: unsigned char *saveFrameBuffer;
+    protected: unsigned char *bayerFrameBuffer;
+    protected: unsigned int saveCount;
+    protected: ParamT<bool> *saveFramesP;
+    protected: ParamT<std::string> *savePathnameP;
+    protected: ParamT<std::string> *imageFormatP;
+ 
+    protected: ParamT<std::string> *visMaskP;
+    protected: Ogre::PixelFormat imageFormat;
+    protected: unsigned int visibilityMask;
+
+    protected: Ogre::RenderTarget *renderTarget;
+
+    protected: Ogre::TexturePtr renderTexture;
+
+    private: static unsigned int cameraCounter;
+    private: unsigned int myCount;
+
+    protected: std::string uniqueName;
+
+    protected: bool captureData;
+
+    private: bool userMovable;
+    protected: std::vector<Param*> camParameters;
+
+    protected: bool renderingEnabled;
+
+    private: bool newData;
+
+    protected: Time renderPeriod;
+    protected: Time lastUpdate;
+
+    protected: Scene *scene;
+  };
+  
+  /// \}
+  /// \}
+}
+#endif
+

Added: code/gazebo/branches/dev/server/wx/ModelBuilder.cc
===================================================================
--- code/gazebo/branches/dev/server/wx/ModelBuilder.cc                          
(rev 0)
+++ code/gazebo/branches/dev/server/wx/ModelBuilder.cc  2010-11-12 02:06:48 UTC 
(rev 8960)
@@ -0,0 +1,90 @@
+#include <wx/aui/aui.h>
+
+#include "Model.hh"
+#include "Body.hh"
+#include "Image.hh"
+#include "OgreAdaptor.hh"
+#include "Global.hh"
+#include "Light.hh"
+#include "Scene.hh"
+#include "GazeboConfig.hh"
+#include "UserCamera.hh"
+#include "MeshManager.hh"
+#include "RenderControl.hh"
+#include "OrbitViewController.hh"
+#include "FPSViewController.hh"
+#include "OgreCreator.hh"
+#include "OgreVisual.hh"
+#include "Simulator.hh"
+#include "ModelBuilder.hh"
+
+using namespace gazebo;
+
+ModelBuilder::ModelBuilder( wxWindow *parent )
+  : wxDialog(parent,wxID_ANY, wxT("Model Builder"), wxDefaultPosition, 
wxSize(600, 600), wxDEFAULT_FRAME_STYLE)
+{
+  this->scene = OgreAdaptor::Instance()->CreateScene("viewer_scene");
+  this->dirLight = new Light(NULL, scene);
+  this->dirLight->Load(NULL);
+  this->dirLight->SetLightType("directional");
+  this->dirLight->SetDiffuseColor( Color(1.0, 1.0, 1.0) );
+  this->dirLight->SetSpecularColor( Color(0.1, 0.1, 0.1) );
+  this->dirLight->SetDirection( Vector3(0, 0, -1) );
+
+  this->renderControl = new RenderControl(this);
+  this->renderControl->CreateCamera(this->scene);
+  this->renderControl->Init();
+  UserCamera *cam = this->renderControl->GetCamera();
+  cam->SetClipDist(0.01, 1000);
+  cam->SetWorldPosition(Vector3(-1,0,2));
+  cam->RotatePitch(DTOR(-30));
+  cam->SetViewController( OrbitViewController::GetTypeString() );
+
+  this->MakeToolbar();
+
+  this->auiManager = new wxAuiManager(this);
+  this->auiManager->AddPane(this->renderControl, 
wxAuiPaneInfo().CenterPane().Name(wxT("Render")));
+  this->auiManager->AddPane(this->toolbar, 
wxAuiPaneInfo().ToolbarPane().RightDockable(false).LeftDockable(false).MinSize(100,30).Top().Name(wxT("Tools")).Caption(wxT("Tools")));
+  this->auiManager->Update();
+
+  this->model = new Model(NULL);
+}
+
+ModelBuilder::~ModelBuilder()
+{
+  delete this->renderControl;
+  delete this->dirLight;
+  OgreAdaptor::Instance()->RemoveScene(this->scene->GetName());
+
+  this->auiManager->UnInit();
+  delete this->auiManager;
+
+}
+
+void ModelBuilder::MakeToolbar()
+{
+#if !defined(__WXMAC__)
+  Image image;
+
+  image.Load("control_play_blue.png");
+  wxBitmap addbody_bitmap(wxString::FromAscii(image.GetFilename().c_str()), 
wxBITMAP_TYPE_PNG);
+
+  this->toolbar = new wxToolBar(this, wxID_ANY, wxDefaultPosition, 
wxDefaultSize, wxNO_BORDER|wxTB_HORIZONTAL);
+  this->toolbar->Connect( wxEVT_COMMAND_TOOL_CLICKED, wxCommandEventHandler( 
ModelBuilder::OnToolClicked), NULL , this );
+
+  this->toolbar->AddCheckTool(ADD_BODY, wxT("Add Body"), addbody_bitmap, 
wxNullBitmap, wxT("Add a body"));
+
+  this->toolbar->Realize();
+
+#endif
+}
+
+////////////////////////////////////////////////////////////////////////////////
+void ModelBuilder::OnToolClicked( wxCommandEvent &event )
+{
+  int id = event.GetId();
+  if (id == ADD_BODY)
+  {
+    this->model->CreateBody();
+  }
+}

Added: code/gazebo/branches/dev/server/wx/ModelBuilder.hh
===================================================================
--- code/gazebo/branches/dev/server/wx/ModelBuilder.hh                          
(rev 0)
+++ code/gazebo/branches/dev/server/wx/ModelBuilder.hh  2010-11-12 02:06:48 UTC 
(rev 8960)
@@ -0,0 +1,36 @@
+#ifndef MODELBUILDER_HH
+#define MODELBUILDER_HH
+
+#include <wx/wx.h>
+
+class wxAuiManager;
+
+namespace gazebo
+{
+  class RenderControl;
+  class Scene;
+  class Light;
+  class Model;
+
+  class ModelBuilder : public wxDialog
+  {
+    enum ToolbarButtons {ADD_BODY};
+
+    public: ModelBuilder( wxWindow *parent );
+    public: virtual ~ModelBuilder();
+
+    private: void MakeToolbar();
+    private: void OnToolClicked( wxCommandEvent &event );
+
+    private: wxAuiManager *auiManager;
+    private: wxToolBar *toolbar;
+
+    private: RenderControl *renderControl;
+    private: Scene *scene;
+    private: Light *dirLight;
+    private: Model *model;
+
+  };
+}
+
+#endif


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

------------------------------------------------------------------------------
Centralized Desktop Delivery: Dell and VMware Reference Architecture
Simplifying enterprise desktop deployment and management using
Dell EqualLogic storage and VMware View: A highly scalable, end-to-end
client virtualization framework. Read more!
http://p.sf.net/sfu/dell-eql-dev2dev
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to