Revision: 8836
          http://playerstage.svn.sourceforge.net/playerstage/?rev=8836&view=rev
Author:   natepak
Date:     2010-07-28 15:38:26 +0000 (Wed, 28 Jul 2010)

Log Message:
-----------
Added more improvements to wx

Modified Paths:
--------------
    code/gazebo/branches/wx/libgazebo/Server.cc
    code/gazebo/branches/wx/server/Param.hh
    code/gazebo/branches/wx/server/Simulator.cc
    code/gazebo/branches/wx/server/Simulator.hh
    code/gazebo/branches/wx/server/World.cc
    code/gazebo/branches/wx/server/World.hh
    code/gazebo/branches/wx/server/physics/PhysicsEngine.cc
    code/gazebo/branches/wx/server/physics/PhysicsEngine.hh
    code/gazebo/branches/wx/server/physics/bullet/BulletPhysics.cc
    code/gazebo/branches/wx/server/physics/bullet/BulletPhysics.hh
    code/gazebo/branches/wx/server/physics/ode/ODEPhysics.cc
    code/gazebo/branches/wx/server/physics/ode/ODEPhysics.hh
    code/gazebo/branches/wx/server/rendering/OgreAdaptor.cc
    code/gazebo/branches/wx/server/wx/SimulationFrame.cc
    code/gazebo/branches/wx/server/wx/SimulationFrame.hh

Modified: code/gazebo/branches/wx/libgazebo/Server.cc
===================================================================
--- code/gazebo/branches/wx/libgazebo/Server.cc 2010-07-27 14:49:44 UTC (rev 
8835)
+++ code/gazebo/branches/wx/libgazebo/Server.cc 2010-07-28 15:38:26 UTC (rev 
8836)
@@ -61,6 +61,24 @@
 // Destroy a server
 Server::~Server()
 {
+  if (rmdir(this->filename.c_str()))
+  {
+    std::cerr << "Error deleting directory\n";
+    /*if (errno == EEXIST)
+    {
+      errStream << "directory [" <<  this->filename
+      <<  "] already exists (previous crash?)"
+      << "remove the directory and re-run gazebo";
+      throw(errStream.str());
+    }
+    else
+    {
+      errStream << "failed to create [" << this->filename << "] : ["
+      <<  strerror(errno) << "]";
+      throw(errStream.str());
+    }
+    */
+  }
 }
 
 
////////////////////////////////////////////////////////////////////////////////

Modified: code/gazebo/branches/wx/server/Param.hh
===================================================================
--- code/gazebo/branches/wx/server/Param.hh     2010-07-27 14:49:44 UTC (rev 
8835)
+++ code/gazebo/branches/wx/server/Param.hh     2010-07-28 15:38:26 UTC (rev 
8836)
@@ -118,7 +118,7 @@
     public: T GetValue() const;
 
     /// \brief Set the value of the parameter
-    public: void SetValue(const T &value);
+    public: void SetValue(const T &value, bool callback=false);
 
     public: inline T operator*() const {return value;}
 
@@ -238,9 +238,12 @@
   
//////////////////////////////////////////////////////////////////////////////
   /// Set the value of the parameter
   template<typename T>
-  void ParamT<T>::SetValue(const T &v)
+  void ParamT<T>::SetValue(const T &v, bool callback)
   {
     this->value = v;
+
+    if (callback)
+      this->changeSignal(this->value);
   }
 
 }

Modified: code/gazebo/branches/wx/server/Simulator.cc
===================================================================
--- code/gazebo/branches/wx/server/Simulator.cc 2010-07-27 14:49:44 UTC (rev 
8835)
+++ code/gazebo/branches/wx/server/Simulator.cc 2010-07-28 15:38:26 UTC (rev 
8836)
@@ -97,8 +97,7 @@
 
////////////////////////////////////////////////////////////////////////////////
 // Constructor
 Simulator::Simulator()
-: xmlFile(NULL),
-  gui(NULL),
+: gui(NULL),
   renderEngine(NULL),
   gazeboConfig(NULL),
   loaded(false),
@@ -111,6 +110,7 @@
   renderUpdates(0),
   stepInc(false),
   userQuit(false),
+  physicsQuit(false),
   guiEnabled(true),
   renderEngineEnabled(true),
   physicsEnabled(true),
@@ -133,12 +133,6 @@
     this->gazeboConfig = NULL;
   }
 
-  if (this->xmlFile)
-  {
-    delete this->xmlFile;
-    this->xmlFile = NULL;
-  }
-
   if (this->render_mutex)
   {
     delete this->render_mutex;
@@ -166,13 +160,6 @@
   if (!this->loaded)
     return;
 
-  if (this->gui)
-  {
-    delete this->gui;
-    this->gui = NULL;
-  }
-
-
   gazebo::World::Instance()->Close();
 
   if (this->renderEngineEnabled)
@@ -193,14 +180,14 @@
   }
 
   // Load the world file
-  this->xmlFile=new gazebo::XMLConfig();
+  XMLConfig *xmlFile=new gazebo::XMLConfig();
 
   try
   {
     if (worldFileName.size())
-      this->xmlFile->Load(worldFileName);
+      xmlFile->Load(worldFileName);
     else
-      this->xmlFile->LoadString(defaultWorld);
+      xmlFile->LoadString(defaultWorld);
   }
   catch (GazeboError e)
   {
@@ -226,7 +213,6 @@
   if (this->renderEngineEnabled)
     OgreAdaptor::Instance()->Load(rootNode);
 
-
   // Create and initialize the Gui
   if (this->renderEngineEnabled && this->guiEnabled)
   {
@@ -250,15 +236,10 @@
       }
 
         // Create the GUI
-      if (childNode || !rootNode)
+      if (!this->gui && (childNode || !rootNode))
       {
         this->gui = new SimulationApp();
         this->gui->Load();
-
-        /*this->gui = new Gui(x, y, width, height, "Gazebo");
-        this->gui->Load(childNode);
-        this->gui->CreateCameras();
-        */
       }
     }
     catch (GazeboError e)
@@ -310,8 +291,6 @@
   }
 
   this->loaded=true;
-
-  //OgreAdaptor::Instance()->PrintSceneGraph();
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -405,6 +384,31 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+// Stop the physics engine
+void Simulator::StopPhysics()
+{
+  this->physicsQuit = true;
+  if (this->physicsThread)
+  {
+    this->physicsThread->join();
+    delete this->physicsThread;
+    this->physicsThread = NULL;
+  }
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Start the physics engine
+void Simulator::StartPhysics()
+{
+  if (this->physicsThread)
+    this->StopPhysics();
+
+  this->physicsQuit = false;
+  this->physicsThread = new boost::thread( 
+      boost::bind(&Simulator::PhysicsLoop, this));
+}
+
+////////////////////////////////////////////////////////////////////////////////
 /// Main simulation loop, when this loop ends the simulation finish
 void Simulator::Run()
 {
@@ -416,8 +420,7 @@
   struct timespec timeSpec;
   double freq = 80.0;
 
-  this->physicsThread = new boost::thread( 
-                         boost::bind(&Simulator::PhysicsLoop, this));
+  this->StartPhysics();
 
   if (this->gui)
     this->gui->Run();
@@ -451,7 +454,7 @@
     }
   }
 
-  this->physicsThread->join();
+  this->StopPhysics();
 }
 
 void Simulator::GraphicsUpdate()
@@ -709,7 +712,7 @@
   struct timespec req, rem;
 
 
-  while (!this->userQuit)
+  while (!this->physicsQuit)
   {
     //DiagnosticTimer timer("PhysicsLoop Timer ");
 

Modified: code/gazebo/branches/wx/server/Simulator.hh
===================================================================
--- code/gazebo/branches/wx/server/Simulator.hh 2010-07-27 14:49:44 UTC (rev 
8835)
+++ code/gazebo/branches/wx/server/Simulator.hh 2010-07-28 15:38:26 UTC (rev 
8836)
@@ -131,6 +131,12 @@
     /// \brief Simulator finished by the user
     public: void SetUserQuit();
 
+    /// \brief Stop the physics engine
+    public: void StopPhysics();
+
+    /// \brief Start the physics engine
+    public: void StartPhysics();
+
     /// \brief Return true if the step has incremented
     public: bool GetStepInc() const;
 
@@ -237,6 +243,7 @@
 
     //The user has somewhat signaled the end of the program
     private: bool userQuit;
+    private: bool physicsQuit;
 
     /// True if the GUI is enabled
     private: bool guiEnabled;

Modified: code/gazebo/branches/wx/server/World.cc
===================================================================
--- code/gazebo/branches/wx/server/World.cc     2010-07-27 14:49:44 UTC (rev 
8835)
+++ code/gazebo/branches/wx/server/World.cc     2010-07-28 15:38:26 UTC (rev 
8836)
@@ -110,12 +110,6 @@
     this->physicsEngine = NULL;
   }
 
-  if (this->server)
-  {
-    delete this->server;
-    this->server =NULL;
-  }
-
   try
   {
     if (this->simIface)
@@ -129,6 +123,12 @@
     gzthrow(e);
   }
 
+  if (this->server)
+  {
+    delete this->server;
+    this->server =NULL;
+  }
+
   if (this->factory)
   {
     delete this->factory;
@@ -163,22 +163,28 @@
       boost::bind(&World::PauseSlot, this, _1) );
   
   // Create the server object (needs to be done before models initialize)
-  this->server = new libgazebo::Server();
+  if (this->server == NULL)
+  {
+    this->server = new libgazebo::Server();
 
-  try
-  {
-    this->server->Init(serverId, true );
+    try
+    {
+      this->server->Init(serverId, true );
+    }
+    catch ( std::string err)
+    {
+      gzthrow (err);
+    }
   }
-  catch ( std::string err)
-  {
-    gzthrow (err);
-  }
 
   // Create the simulator interface
   try
   {
-    this->simIface = new libgazebo::SimulationIface();
-    this->simIface->Create(this->server, "default" );
+    if (!this->simIface)
+    {
+      this->simIface = new libgazebo::SimulationIface();
+      this->simIface->Create(this->server, "default" );
+    }
   }
   catch (std::string err)
   {
@@ -186,10 +192,11 @@
   }
 
   // Create the default factory
-  this->factory = new Factory();
+  if (!this->factory)
+    this->factory = new Factory();
 
   // Create the graphics iface handler
-  if (Simulator::Instance()->GetRenderEngineEnabled())
+  if (!this->graphics && Simulator::Instance()->GetRenderEngineEnabled())
   {
     this->graphics = new GraphicsIfaceHandler();
     this->graphics->Load("default");
@@ -208,6 +215,12 @@
 
   if (Simulator::Instance()->GetPhysicsEnabled() && physicsNode)
   {
+    if (this->physicsEngine)
+    {
+      delete this->physicsEngine;
+      this->physicsEngine = NULL;
+    }
+
     this->physicsEngine = PhysicsFactory::NewPhysicsEngine( 
physicsNode->GetName());
     if (this->physicsEngine == NULL)
       gzthrow("Unable to create physics engine\n");
@@ -438,6 +451,16 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+/// Remove all entities from the world
+void World::Clear()
+{
+  std::vector<Model*>::iterator iter;
+  for (iter = this->models.begin(); iter != this->models.end(); iter++)
+    this->DeleteEntity((*iter)->GetCompleteScopedName());
+  this->ProcessEntitiesToDelete();
+}
+
+////////////////////////////////////////////////////////////////////////////////
 /// Get the number of parameters
 unsigned int World::GetParamCount() const
 {
@@ -1849,3 +1872,10 @@
     (*iter)->Print("");
   }
 }
+
+////////////////////////////////////////////////////////////////////////////////
+// Get the server id
+int World::GetServerId() const
+{
+  return this->server->serverId;
+}

Modified: code/gazebo/branches/wx/server/World.hh
===================================================================
--- code/gazebo/branches/wx/server/World.hh     2010-07-27 14:49:44 UTC (rev 
8835)
+++ code/gazebo/branches/wx/server/World.hh     2010-07-28 15:38:26 UTC (rev 
8836)
@@ -110,6 +110,9 @@
   /// Finilize the world
   public: void Fini();
 
+  /// \brief Remove all entities from the world
+  public: void Clear();
+
   /// \brief Get the number of parameters
   public: unsigned int GetParamCount() const;
 
@@ -245,6 +248,9 @@
   /// \brief Print entity tree
   public: void PrintEntityTree();
 
+  /// \brief Get the server id
+  public: int GetServerId() const;
+
   /// \brief Save the state of the world
   private: void SaveState();
 

Modified: code/gazebo/branches/wx/server/physics/PhysicsEngine.cc
===================================================================
--- code/gazebo/branches/wx/server/physics/PhysicsEngine.cc     2010-07-27 
14:49:44 UTC (rev 8835)
+++ code/gazebo/branches/wx/server/physics/PhysicsEngine.cc     2010-07-28 
15:38:26 UTC (rev 8836)
@@ -43,6 +43,8 @@
 {
   Param::Begin(&this->parameters);
   this->gravityP = new ParamT<Vector3>("gravity",Vector3(0.0, -9.80665, 0.0), 
0);
+  this->gravityP->Callback(&PhysicsEngine::SetGravity, this);
+
   this->updateRateP = new ParamT<double>("updateRate", 0.0, 0);
   this->stepTimeP = new ParamT<Time>("stepTime",0.025,0);
   Param::End();
@@ -116,13 +118,6 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
-/// Set the gavity vector
-void PhysicsEngine::SetGravity(Vector3 gravity) const
-{
-  this->gravityP->SetValue(gravity);
-}
-
-////////////////////////////////////////////////////////////////////////////////
 /// Get the time between each update cycle
 double PhysicsEngine::GetUpdateRate() const
 {

Modified: code/gazebo/branches/wx/server/physics/PhysicsEngine.hh
===================================================================
--- code/gazebo/branches/wx/server/physics/PhysicsEngine.hh     2010-07-27 
14:49:44 UTC (rev 8835)
+++ code/gazebo/branches/wx/server/physics/PhysicsEngine.hh     2010-07-28 
15:38:26 UTC (rev 8836)
@@ -131,7 +131,7 @@
     public: Vector3 GetGravity() const;
 
     /// \brief Set the gavity vector
-    public: void SetGravity(Vector3 gravity) const;
+    public: virtual void SetGravity(const gazebo::Vector3 &gravity) = 0;
 
     /// \brief Get the time between each update cycle
     /// \return seconds between updates 

Modified: code/gazebo/branches/wx/server/physics/bullet/BulletPhysics.cc
===================================================================
--- code/gazebo/branches/wx/server/physics/bullet/BulletPhysics.cc      
2010-07-27 14:49:44 UTC (rev 8835)
+++ code/gazebo/branches/wx/server/physics/bullet/BulletPhysics.cc      
2010-07-28 15:38:26 UTC (rev 8836)
@@ -302,3 +302,11 @@
                                    pose.rot.z, pose.rot.u) );
   return trans;
 }
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the gavity vector
+void BulletPhysics::SetGravity(const gazebo::Vector3 &gravity)
+{
+  this->gravityP->SetValue(gravity);
+  this->dynamicsWorld->setGravity(btVector3(gravity.x, gravity.y, gravity.z));
+}

Modified: code/gazebo/branches/wx/server/physics/bullet/BulletPhysics.hh
===================================================================
--- code/gazebo/branches/wx/server/physics/bullet/BulletPhysics.hh      
2010-07-27 14:49:44 UTC (rev 8835)
+++ code/gazebo/branches/wx/server/physics/bullet/BulletPhysics.hh      
2010-07-28 15:38:26 UTC (rev 8836)
@@ -146,6 +146,9 @@
   public: btDynamicsWorld *GetDynamicsWorld() const
           {return this->dynamicsWorld;}
 
+  /// \brief Set the gavity vector
+  public: virtual void SetGravity(const gazebo::Vector3 &gravity);
+
   //private: btAxisSweep3 *broadPhase;
   private: btBroadphaseInterface *broadPhase;
   private: btDefaultCollisionConfiguration *collisionConfig;

Modified: code/gazebo/branches/wx/server/physics/ode/ODEPhysics.cc
===================================================================
--- code/gazebo/branches/wx/server/physics/ode/ODEPhysics.cc    2010-07-27 
14:49:44 UTC (rev 8835)
+++ code/gazebo/branches/wx/server/physics/ode/ODEPhysics.cc    2010-07-28 
15:38:26 UTC (rev 8836)
@@ -639,6 +639,14 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+/// Set the gavity vector
+void ODEPhysics::SetGravity(const gazebo::Vector3 &gravity)
+{
+  this->gravityP->SetValue(gravity);
+  dWorldSetGravity(this->worldId, gravity.x, gravity.y, gravity.z);
+}
+
+////////////////////////////////////////////////////////////////////////////////
 // Handle a collision
 void ODEPhysics::CollisionCallback( void *data, dGeomID o1, dGeomID o2)
 {

Modified: code/gazebo/branches/wx/server/physics/ode/ODEPhysics.hh
===================================================================
--- code/gazebo/branches/wx/server/physics/ode/ODEPhysics.hh    2010-07-27 
14:49:44 UTC (rev 8835)
+++ code/gazebo/branches/wx/server/physics/ode/ODEPhysics.hh    2010-07-28 
15:38:26 UTC (rev 8836)
@@ -143,6 +143,9 @@
   /// \brief Set the step type
   public: virtual void SetStepType(const std::string type);
 
+  /// \brief Set the gavity vector
+  public: virtual void SetGravity(const gazebo::Vector3 &gravity);
+
   /// \brief access functions to set ODE parameters
   public: void SetWorldCFM(double cfm);
   /// \brief access functions to set ODE parameters

Modified: code/gazebo/branches/wx/server/rendering/OgreAdaptor.cc
===================================================================
--- code/gazebo/branches/wx/server/rendering/OgreAdaptor.cc     2010-07-27 
14:49:44 UTC (rev 8835)
+++ code/gazebo/branches/wx/server/rendering/OgreAdaptor.cc     2010-07-28 
15:38:26 UTC (rev 8836)
@@ -112,6 +112,9 @@
 /// Load the parameters for Ogre
 void OgreAdaptor::Load(XMLConfigNode *rootNode)
 {
+  if (this->root)
+    return;
+
   // Make the root
   try
   {

Modified: code/gazebo/branches/wx/server/wx/SimulationFrame.cc
===================================================================
--- code/gazebo/branches/wx/server/wx/SimulationFrame.cc        2010-07-27 
14:49:44 UTC (rev 8835)
+++ code/gazebo/branches/wx/server/wx/SimulationFrame.cc        2010-07-28 
15:38:26 UTC (rev 8836)
@@ -1,6 +1,9 @@
 #include <wx/aui/aui.h>
 #include <stack>
 
+#include "GazeboError.hh"
+#include "GazeboMessage.hh"
+#include "XMLConfig.hh"
 #include "propgrid/propgrid.h"
 #include "OgreCamera.hh"
 #include "CameraManager.hh"
@@ -18,6 +21,7 @@
 
 using namespace gazebo;
 
+
 class EntityTreeItemData : public wxTreeItemData
 {
   public: std::string name;
@@ -33,10 +37,18 @@
   wxMenuBar *menuBar = new wxMenuBar;
   wxMenu *fileMenu = new wxMenu;
 
-  wxMenuItem *item = fileMenu->Append(wxID_EXIT, wxT("&Quit\tCtrl-Q") );
-  Connect(item->GetId(), wxEVT_COMMAND_MENU_SELECTED, 
wxCommandEventHandler(SimulationFrame::OnQuit), NULL, this);
+  wxMenuItem *openItem = fileMenu->Append(ID_OPEN, wxT("&Open\tCtrl-O") );
+  Connect(openItem->GetId(), wxEVT_COMMAND_MENU_SELECTED, 
wxCommandEventHandler(SimulationFrame::OnOpen), NULL, this);
 
+  wxMenuItem *saveItem = fileMenu->Append(ID_SAVE, wxT("&Save\tCtrl-S") );
+  Connect(saveItem->GetId(), wxEVT_COMMAND_MENU_SELECTED, 
wxCommandEventHandler(SimulationFrame::OnSave), NULL, this);
 
+  wxMenuItem *resetItem = fileMenu->Append(ID_RESET, wxT("&Reset\tCtrl-R") );
+  Connect(resetItem->GetId(), wxEVT_COMMAND_MENU_SELECTED, 
wxCommandEventHandler(SimulationFrame::OnReset), NULL, this);
+
+  wxMenuItem *quitItem = fileMenu->Append(wxID_EXIT, wxT("&Quit\tCtrl-Q") );
+  Connect(quitItem->GetId(), wxEVT_COMMAND_MENU_SELECTED, 
wxCommandEventHandler(SimulationFrame::OnQuit), NULL, this);
+
   menuBar->Append( fileMenu, _("&File") );
   SetMenuBar( menuBar );
 
@@ -193,6 +205,74 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+void SimulationFrame::OnOpen(wxCommandEvent & WXUNUSED(event))
+{
+  wxFileDialog* openDialog = new wxFileDialog(
+      this, _("Choose a file to open"), wxEmptyString, wxEmptyString, 
+      _("world files (*.world; *.xml)|*.world;*.xml"), wxFD_OPEN, 
wxDefaultPosition);
+
+  // Creates a "open file" dialog with 4 file types
+  if (openDialog->ShowModal() == wxID_OK) 
+  {
+    std::string doc( openDialog->GetPath().mb_str() );
+
+    // Load the world file
+    XMLConfig *xmlFile = new gazebo::XMLConfig();
+
+    try
+    {
+      xmlFile->Load(doc);
+    }
+    catch (GazeboError e)
+    {
+      gzthrow("The XML config file can not be loaded, please make sure is a 
correct file\n" << e); 
+    }
+
+    XMLConfigNode *rootNode(xmlFile->GetRootNode());
+    //Create the world
+    try
+    {
+      Simulator::Instance()->StopPhysics();
+      //World::Instance()->Clear();
+      Simulator::Instance()->Load( doc, World::Instance()->GetServerId() );
+      Simulator::Instance()->StartPhysics();
+    }
+    catch (GazeboError e)
+    {
+      gzthrow("Failed to load the World\n"  << e);
+    }
+  }
+
+  // Clean up after ourselves
+  openDialog->Destroy();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+void SimulationFrame::OnSave(wxCommandEvent & WXUNUSED(event))
+{
+  wxFileDialog* saveDialog = new wxFileDialog(
+      this, _("Choose a file to save"), wxEmptyString, wxEmptyString, 
+      _("world files (*.world; *.xml)|*.world;*.xml"), wxFD_SAVE, 
wxDefaultPosition);
+
+  // Creates a "open file" dialog with 4 file types
+  if (saveDialog->ShowModal() == wxID_OK) 
+  {
+    std::string doc( saveDialog->GetPath().mb_str() );
+
+    Simulator::Instance()->Save( doc );
+  }
+
+}
+
+////////////////////////////////////////////////////////////////////////////////
+void SimulationFrame::OnReset(wxCommandEvent & WXUNUSED(event))
+{
+  // stop simulation when this is happening
+  boost::recursive_mutex::scoped_lock 
lock(*Simulator::Instance()->GetMRMutex());
+  World::Instance()->Reset();
+}
+
+////////////////////////////////////////////////////////////////////////////////
 void SimulationFrame::OnToolClicked( wxCommandEvent &event )
 {
   int id = event.GetId();

Modified: code/gazebo/branches/wx/server/wx/SimulationFrame.hh
===================================================================
--- code/gazebo/branches/wx/server/wx/SimulationFrame.hh        2010-07-27 
14:49:44 UTC (rev 8835)
+++ code/gazebo/branches/wx/server/wx/SimulationFrame.hh        2010-07-28 
15:38:26 UTC (rev 8836)
@@ -15,8 +15,10 @@
   class SimulationFrame : public wxFrame
   {
     enum ToolbarButtons {PLAY, PAUSE, STEP, BOX, SPHERE, CYLINDER, 
DIRECTIONAL, POINT, SPOT, CURSOR};
+    enum MenuIds {ID_OPEN, ID_SAVE, ID_RESET};
 
     public: SimulationFrame(wxWindow *parent);
+
     public: virtual ~SimulationFrame();
 
     /// \brief Create the cameras
@@ -29,6 +31,9 @@
     private: void OnPause(bool pause);
 
     private: void OnQuit(wxCommandEvent &event);
+    private: void OnOpen(wxCommandEvent &event);
+    private: void OnSave(wxCommandEvent &event);
+    private: void OnReset(wxCommandEvent &event);
 
     private: void OnToolClicked( wxCommandEvent &event );
 


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

------------------------------------------------------------------------------
The Palm PDK Hot Apps Program offers developers who use the
Plug-In Development Kit to bring their C/C++ apps to Palm for a share
of $1 Million in cash or HP Products. Visit us here for more details:
http://p.sf.net/sfu/dev2dev-palm
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to