Revision: 8683
          http://playerstage.svn.sourceforge.net/playerstage/?rev=8683&view=rev
Author:   natepak
Date:     2010-05-17 16:02:40 +0000 (Mon, 17 May 2010)

Log Message:
-----------
Added start of orbit view controller

Modified Paths:
--------------
    code/gazebo/trunk/benchmarks/CMakeLists.txt
    code/gazebo/trunk/server/Entity.cc
    code/gazebo/trunk/server/Entity.hh
    code/gazebo/trunk/server/Model.hh
    code/gazebo/trunk/server/World.cc
    code/gazebo/trunk/server/gui/GLFrame.cc
    code/gazebo/trunk/server/gui/GLWindow.cc
    code/gazebo/trunk/server/gui/GLWindow.hh
    code/gazebo/trunk/server/gui/MouseEvent.hh
    code/gazebo/trunk/server/physics/Body.hh
    code/gazebo/trunk/server/physics/Geom.cc
    code/gazebo/trunk/server/physics/Geom.hh
    code/gazebo/trunk/server/rendering/CMakeLists.txt
    code/gazebo/trunk/server/rendering/FPSViewController.cc
    code/gazebo/trunk/server/rendering/FPSViewController.hh
    code/gazebo/trunk/server/rendering/OgreCamera.cc
    code/gazebo/trunk/server/rendering/OgreCamera.hh
    code/gazebo/trunk/worlds/pendulum.world
    code/gazebo/trunk/worlds/simpleshapes.world

Added Paths:
-----------
    code/gazebo/trunk/benchmarks/pendulum_benchmark.cc
    code/gazebo/trunk/server/rendering/OrbitViewController.cc
    code/gazebo/trunk/server/rendering/OrbitViewController.hh

Modified: code/gazebo/trunk/benchmarks/CMakeLists.txt
===================================================================
--- code/gazebo/trunk/benchmarks/CMakeLists.txt 2010-05-14 23:02:16 UTC (rev 
8682)
+++ code/gazebo/trunk/benchmarks/CMakeLists.txt 2010-05-17 16:02:40 UTC (rev 
8683)
@@ -27,6 +27,7 @@
              joint_chain_benchmark.cc
              camera_benchmark.cc
              spinningbox_benchmark.cc
+             pendulum_benchmark.cc
              )
 
 set_source_files_properties(${sources} PROPERTIES COMPILE_FLAGS "-ggdb -g2 
-Wall")
@@ -37,6 +38,7 @@
 add_executable(joint_chain_benchmark joint_chain_benchmark.cc)
 add_executable(camera_benchmark camera_benchmark.cc)
 add_executable(spinningbox_benchmark spinningbox_benchmark.cc)
+add_executable(pendulum_benchmark pendulum_benchmark.cc)
 
 target_link_libraries(laser_benchmark       gazebo ${LINK_LIBS} )
 target_link_libraries(box_grid_benchmark    gazebo ${LINK_LIBS} )
@@ -44,21 +46,22 @@
 target_link_libraries(joint_chain_benchmark gazebo ${LINK_LIBS} )
 target_link_libraries(camera_benchmark      gazebo ${LINK_LIBS} )
 target_link_libraries(spinningbox_benchmark gazebo ${LINK_LIBS} )
+target_link_libraries(pendulum_benchmark    gazebo ${LINK_LIBS} )
 
 set_target_properties(laser_benchmark       PROPERTIES SKIP_BUILD_RPATH TRUE)
 set_target_properties(box_grid_benchmark    PROPERTIES SKIP_BUILD_RPATH TRUE)
 set_target_properties(box_pile_benchmark    PROPERTIES SKIP_BUILD_RPATH TRUE)
 set_target_properties(joint_chain_benchmark PROPERTIES SKIP_BUILD_RPATH TRUE)
 set_target_properties(camera_benchmark      PROPERTIES SKIP_BUILD_RPATH TRUE)
-set_target_properties(spinningbox_benchmark      PROPERTIES SKIP_BUILD_RPATH 
TRUE)
+set_target_properties(spinningbox_benchmark   PROPERTIES SKIP_BUILD_RPATH TRUE)
+set_target_properties(pendulum_benchmark      PROPERTIES SKIP_BUILD_RPATH TRUE)
 
 set_target_properties(laser_benchmark       PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
 set_target_properties(box_grid_benchmark    PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
 set_target_properties(box_pile_benchmark    PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
 set_target_properties(joint_chain_benchmark PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
 set_target_properties(camera_benchmark      PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
-set_target_properties(spinningbox_benchmark      PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
+set_target_properties(spinningbox_benchmark PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
+set_target_properties(pendulum_benchmark    PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
 
-install (TARGETS laser_benchmark box_grid_benchmark box_pile_benchmark 
joint_chain_benchmark camera_benchmark spinningbox_benchmark DESTINATION 
${CMAKE_INSTALL_PREFIX}/bin)
-
-     
+install (TARGETS laser_benchmark box_grid_benchmark box_pile_benchmark 
joint_chain_benchmark camera_benchmark spinningbox_benchmark pendulum_benchmark 
DESTINATION ${CMAKE_INSTALL_PREFIX}/bin)

Added: code/gazebo/trunk/benchmarks/pendulum_benchmark.cc
===================================================================
--- code/gazebo/trunk/benchmarks/pendulum_benchmark.cc                          
(rev 0)
+++ code/gazebo/trunk/benchmarks/pendulum_benchmark.cc  2010-05-17 16:02:40 UTC 
(rev 8683)
@@ -0,0 +1,93 @@
+#include <iostream>
+#include <stdio.h>
+#include <stdlib.h>
+#include <vector>
+#include <libgazebo/gz.h>
+
+gazebo::Client *client = NULL;
+gazebo::SimulationIface *simIface = NULL;
+
+std::string test_name="Pendulum Benchmark";
+std::string xlabel = "Pendulum Count";
+std::string ylabel = "Simtime / Realtime";
+std::string data_filename = "/tmp/" + test_name + ".data";
+
+void make_plot()
+{
+  std::ostringstream cmd;
+
+  cmd << "echo \"";
+  cmd << "set xlabel '" << xlabel << "'\n";
+  cmd << "set ylabel '" << ylabel << "'\n";
+  cmd << "set title '" << test_name << "'\n";
+  cmd << "set terminal png\n";
+  cmd << "set output '" << test_name << ".png'\n";
+  cmd << "plot '" << data_filename << "' with lines\n";
+  cmd << "\" | gnuplot";
+
+  if (system(cmd.str().c_str() ) < 0)
+    std::cerr << "Error\n";
+}
+
+int main(int argc, char **argv)
+{
+  client = new gazebo::Client();
+  simIface = new gazebo::SimulationIface();
+
+  try
+  {
+    client->ConnectWait(0, GZ_CLIENT_ID_USER_FIRST);
+  }
+  catch(std::string e)
+  {
+    std::cerr << "Gazebo Error: Unable to connect: " << e << "\n";
+    return -1;
+  }
+
+  /// Open the sim iface
+  try
+  {
+    simIface->Open(client, "default");
+  }
+  catch (std::string e)
+  {
+    std::cerr << "Gazebo error: Unable to connect to sim iface:" << e << "\n";
+    return -1;
+  }
+
+  //FILE *out = fopen(data_filename.c_str(), "w");
+
+  /*if (!out)
+    std::cerr << "Unable to open log file";
+    */
+
+  //double simTime = 0;
+  //double realTime = 0;
+
+  gazebo::Vec3 linearVel, angularVel, linearAccel, angularAccel;
+  gazebo::Pose modelPose;
+
+  bool done = false;
+  while (!done)
+  {
+    //simIface->SetAngularVel("box_model", gazebo::Vec3(0,0,vel));
+    
+    simIface->GetState("base_model::swing_body", modelPose, linearVel, 
angularVel, 
+                       linearAccel, angularAccel);
+    printf("Pos[%4.2f %4.2f %4.2f] RPY[%4.2f %4.2f %4.2f] ", modelPose.pos.x, 
modelPose.pos.y, modelPose.pos.z, modelPose.roll, modelPose.pitch, 
modelPose.yaw);
+    printf("LV[%4.2f %4.2f %4.2f] ",linearVel.x, linearVel.y, linearVel.z );
+    printf("AV[%4.2f %4.2f %4.2f] ",angularVel.x, angularVel.y, angularVel.z);
+    printf("LA[%4.2f %4.2f %4.2f] ",linearAccel.x, linearAccel.y, 
linearAccel.z);
+    printf("AA[%4.2f %4.2f %4.2f]\n",angularAccel.x, angularAccel.y, 
angularAccel.z );
+  }
+
+  //double percent = simTime / realTime;
+  //fprintf(out,"%f\n",percent);
+
+  //fclose(out);
+
+  //make_plot();
+
+  simIface->Close();
+  client->Disconnect();
+}

Modified: code/gazebo/trunk/server/Entity.cc
===================================================================
--- code/gazebo/trunk/server/Entity.cc  2010-05-14 23:02:16 UTC (rev 8682)
+++ code/gazebo/trunk/server/Entity.cc  2010-05-17 16:02:40 UTC (rev 8683)
@@ -328,6 +328,34 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+/// Get the linear velocity of the model
+Vector3 Entity::GetLinearVel() const
+{
+  return Vector3();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get the angular velocity of the model
+Vector3 Entity::GetAngularVel() const
+{
+  return Vector3();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get the linear acceleration of the model
+Vector3 Entity::GetLinearAccel() const
+{
+  return Vector3();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get the angular acceleration of the model
+Vector3 Entity::GetAngularAccel() const
+{
+  return Vector3();
+}
+
+////////////////////////////////////////////////////////////////////////////////
 /// Get the pose relative to the model this entity belongs to
 Pose3d Entity::GetModelRelativePose() const
 {

Modified: code/gazebo/trunk/server/Entity.hh
===================================================================
--- code/gazebo/trunk/server/Entity.hh  2010-05-14 23:02:16 UTC (rev 8682)
+++ code/gazebo/trunk/server/Entity.hh  2010-05-17 16:02:40 UTC (rev 8683)
@@ -129,10 +129,23 @@
     /// \brief Set the rotation of the entity relative to its parent
     public: void SetRelativeRotation(const Quatern &rot);
 
+    /// \brief Get the linear velocity of the model
+    public: virtual Vector3 GetLinearVel() const;
+
+    /// \brief Get the angular velocity of the model
+    public: virtual Vector3 GetAngularVel() const;
+
+    /// \brief Get the linear acceleration of the model
+    public: virtual Vector3 GetLinearAccel() const;
+
+    /// \brief Get the angular acceleration of the model
+    public: virtual Vector3 GetAngularAccel() const;
+
     /// \brief This function is called when the entity's (or one of its 
parents)
     ///        pose of the parent has changed
     protected: virtual void OnPoseChange() {}
 
+
     /// \brief Returns true if the entities are the same. Checks only the name
     public: bool operator==(const Entity &ent) const;
 

Modified: code/gazebo/trunk/server/Model.hh
===================================================================
--- code/gazebo/trunk/server/Model.hh   2010-05-14 23:02:16 UTC (rev 8682)
+++ code/gazebo/trunk/server/Model.hh   2010-05-17 16:02:40 UTC (rev 8683)
@@ -129,16 +129,16 @@
     public: void SetAngularAccel( const Vector3 &vel );
 
     /// \brief Get the linear velocity of the model
-    public: Vector3 GetLinearVel() const;
+    public: virtual Vector3 GetLinearVel() const;
 
     /// \brief Get the angular velocity of the model
-    public: Vector3 GetAngularVel() const;
+    public: virtual Vector3 GetAngularVel() const;
 
     /// \brief Get the linear acceleration of the model
-    public: Vector3 GetLinearAccel() const;
+    public: virtual Vector3 GetLinearAccel() const;
 
     /// \brief Get the angular acceleration of the model
-    public: Vector3 GetAngularAccel() const;
+    public: virtual Vector3 GetAngularAccel() const;
  
     /// \brief Get the size of the bounding box
     public: void GetBoundingBox(Vector3 &min, Vector3 &max) const;

Modified: code/gazebo/trunk/server/World.cc
===================================================================
--- code/gazebo/trunk/server/World.cc   2010-05-14 23:02:16 UTC (rev 8682)
+++ code/gazebo/trunk/server/World.cc   2010-05-17 16:02:40 UTC (rev 8683)
@@ -1235,25 +1235,23 @@
       case SimulationRequestData::GET_STATE:
         {
           Entity *ent = this->GetEntityByName((char*)req->name);
-          if (ent && ent->GetType() == Entity::MODEL)
+          if (ent)// && ent->GetType() == Entity::MODEL)
           {
-            Model *model = (Model*)ent;
-
             Pose3d pose;
             Vector3 linearVel;
             Vector3 angularVel;
             Vector3 linearAccel;
             Vector3 angularAccel;
 
-            pose = model->GetAbsPose();
+            pose = ent->GetAbsPose();
 
             // Get the model's linear and angular velocity
-            linearVel = model->GetLinearVel();
-            angularVel = model->GetAngularVel();
+            linearVel = ent->GetLinearVel();
+            angularVel = ent->GetAngularVel();
 
             // Get the model's linear and angular acceleration
-            linearAccel = model->GetLinearAccel();
-            angularAccel = model->GetAngularAccel();
+            linearAccel = ent->GetLinearAccel();
+            angularAccel = ent->GetAngularAccel();
 
             response->modelPose.pos.x = pose.pos.x;
             response->modelPose.pos.y = pose.pos.y;

Modified: code/gazebo/trunk/server/gui/GLFrame.cc
===================================================================
--- code/gazebo/trunk/server/gui/GLFrame.cc     2010-05-14 23:02:16 UTC (rev 
8682)
+++ code/gazebo/trunk/server/gui/GLFrame.cc     2010-05-17 16:02:40 UTC (rev 
8683)
@@ -297,7 +297,7 @@
 /// Set the pose of the camera attached to this frame
 void GLFrame::SetCameraPose( const Pose3d &pose )
 {
-  this->glWindow->GetCamera()->SetWorldPose( pose );  
+  //this->glWindow->GetCamera()->SetWorldPose( pose );  
 }
 
 
////////////////////////////////////////////////////////////////////////////////

Modified: code/gazebo/trunk/server/gui/GLWindow.cc
===================================================================
--- code/gazebo/trunk/server/gui/GLWindow.cc    2010-05-14 23:02:16 UTC (rev 
8682)
+++ code/gazebo/trunk/server/gui/GLWindow.cc    2010-05-17 16:02:40 UTC (rev 
8683)
@@ -71,12 +71,7 @@
   this->end();
 
   this->userCamera = NULL;
-  this->moveAmount = 0.1;
 
-  this->directionVec.x = 0;
-  this->directionVec.y = 0;
-  this->directionVec.z = 0;
-
   this->keys.clear();
 
   if (activeWin == NULL)
@@ -129,9 +124,10 @@
   }
 
   this->userCamera->Init();
-  this->userCamera->RotatePitch( DTOR(30) );
-  this->userCamera->Translate( Vector3(-5, 0, 1) );
 
+  //this->userCamera->RotatePitch( DTOR(30) );
+  //this->userCamera->Translate( Vector3(-5, 0, 1) );
+
   this->activeCamera = this->userCamera;
 }
 
@@ -357,9 +353,7 @@
   std::map<int,int>::iterator iter;
   this->keys[keyNum] = 1;
 
-  // loop through the keys to find the modifiers -- swh
-  float moveAmount = this->moveAmount;
-
+  // loop through the keys to find the modifiers
   for (iter = this->keys.begin(); iter!= this->keys.end(); iter++)
   {
     if (iter->second == 1)
@@ -369,7 +363,6 @@
         case FL_Control_L:
         case FL_Control_R:
           Events::manipModeSignal(true);
-          moveAmount = this->moveAmount * 10;
           break;
         case FL_CTRL+'q':
           Simulator::Instance()->SetUserQuit();
@@ -377,43 +370,13 @@
 
         case '=':
         case '+':
-          this->moveAmount *= 2;
+          this->mouseEvent.moveScale *= 2;
           break;
 
         case '-':
         case '_':
-          this->moveAmount *= 0.5;
+          this->mouseEvent.moveScale *= 0.5;
           break;
-
-        case XK_Up:
-        case XK_w:
-          this->directionVec.x += this->moveAmount;
-          break;
-
-        case XK_Down:
-        case XK_s:
-          this->directionVec.x -= this->moveAmount;
-          break;
-
-        case XK_Left:
-        case XK_a:
-          this->directionVec.y += this->moveAmount;
-          break;
-
-        case XK_Right:
-        case XK_d:
-          this->directionVec.y -= this->moveAmount;
-          break;
-
-        case XK_Page_Down:
-        case XK_e:
-          this->directionVec.z += this->moveAmount;
-          break;
-
-        case XK_Page_Up:
-        case XK_q:
-          this->directionVec.z -= this->moveAmount;
-          break;
         default:
           break;
       }

Modified: code/gazebo/trunk/server/gui/GLWindow.hh
===================================================================
--- code/gazebo/trunk/server/gui/GLWindow.hh    2010-05-14 23:02:16 UTC (rev 
8682)
+++ code/gazebo/trunk/server/gui/GLWindow.hh    2010-05-17 16:02:40 UTC (rev 
8683)
@@ -159,10 +159,6 @@
     /// pointer to the display
     private: Display *display;
 
-    private: float moveAmount;
-
-    private: Vector3 directionVec;
-
     private: MouseEvent mouseEvent;
 
     private: std::map<int,int> keys;

Modified: code/gazebo/trunk/server/gui/MouseEvent.hh
===================================================================
--- code/gazebo/trunk/server/gui/MouseEvent.hh  2010-05-14 23:02:16 UTC (rev 
8682)
+++ code/gazebo/trunk/server/gui/MouseEvent.hh  2010-05-17 16:02:40 UTC (rev 
8683)
@@ -11,7 +11,7 @@
 
     public: MouseEvent()
             : pos(0,0), prevPos(0,0), pressPos(0,0), scroll(0,0),
-              dragging(false), left(UP), right(UP), middle(UP)
+              moveScale(0.01),dragging(false), left(UP), right(UP), middle(UP)
             {}
 
     public: Vector2<int> pos; 
@@ -19,6 +19,8 @@
     public: Vector2<int> pressPos; 
     public: Vector2<int> scroll; 
 
+    public: float moveScale;
+
     public: bool dragging;
 
     public: ButtonState left;

Modified: code/gazebo/trunk/server/physics/Body.hh
===================================================================
--- code/gazebo/trunk/server/physics/Body.hh    2010-05-14 23:02:16 UTC (rev 
8682)
+++ code/gazebo/trunk/server/physics/Body.hh    2010-05-17 16:02:40 UTC (rev 
8683)
@@ -126,26 +126,20 @@
     /// \brief Set the linear velocity of the body
     public: virtual void SetLinearVel(const Vector3 &vel) = 0;
 
-    /// \brief Get the linear velocity of the body
-    public: virtual Vector3 GetLinearVel() const = 0;
-
     /// \brief Set the angular velocity of the body
     public: virtual void SetAngularVel(const Vector3 &vel) = 0;
 
-    /// \brief Get the angular velocity of the body
-    public: virtual Vector3 GetAngularVel() const = 0;
-
     /// \brief Set the linear acceleration of the body
     public: void SetLinearAccel(const Vector3 &accel);
 
     /// \brief Get the linear acceleration of the body
-    public: Vector3 GetLinearAccel() const;
+    public: virtual Vector3 GetLinearAccel() const;
 
     /// \brief Set the angular acceleration of the body
     public: void SetAngularAccel(const Vector3 &accel);
 
     /// \brief Get the angular acceleration of the body
-    public: Vector3 GetAngularAccel() const;
+    public: virtual Vector3 GetAngularAccel() const;
 
     /// \brief Set the force applied to the body
     public: virtual void SetForce(const Vector3 &force) = 0;

Modified: code/gazebo/trunk/server/physics/Geom.cc
===================================================================
--- code/gazebo/trunk/server/physics/Geom.cc    2010-05-14 23:02:16 UTC (rev 
8682)
+++ code/gazebo/trunk/server/physics/Geom.cc    2010-05-17 16:02:40 UTC (rev 
8683)
@@ -530,3 +530,44 @@
       this->bbVisual->SetBoundingBoxMaterial("Gazebo/RedTransparent");
   }
 }
+
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get the linear velocity of the model
+Vector3 Geom::GetLinearVel() const
+{
+  if (this->body)
+    return this->body->GetLinearVel();
+  else
+    return Vector3();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get the angular velocity of the model
+Vector3 Geom::GetAngularVel() const
+{
+  if (this->body)
+    return this->body->GetAngularVel();
+  else
+    return Vector3();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get the linear acceleration of the model
+Vector3 Geom::GetLinearAccel() const
+{
+  if (this->body)
+    return this->body->GetLinearAccel();
+  else
+    return Vector3();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get the angular acceleration of the model
+Vector3 Geom::GetAngularAccel() const
+{
+  if (this->body)
+    return this->body->GetAngularAccel();
+  else
+    return Vector3();
+}

Modified: code/gazebo/trunk/server/physics/Geom.hh
===================================================================
--- code/gazebo/trunk/server/physics/Geom.hh    2010-05-14 23:02:16 UTC (rev 
8682)
+++ code/gazebo/trunk/server/physics/Geom.hh    2010-05-17 16:02:40 UTC (rev 
8683)
@@ -168,6 +168,18 @@
     /// \brief Get a specific contact
     public: Contact GetContact(unsigned int i) const;
 
+    /// \brief Get the linear velocity of the model
+    public: virtual Vector3 GetLinearVel() const;
+
+    /// \brief Get the angular velocity of the model
+    public: virtual Vector3 GetAngularVel() const;
+
+    /// \brief Get the linear acceleration of the model
+    public: virtual Vector3 GetLinearAccel() const;
+
+    /// \brief Get the angular acceleration of the model
+    public: virtual Vector3 GetAngularAccel() const;
+ 
     public: template< typename C>
             void ContactCallback( void (C::*func)(const Contact&), C *c )
             {

Modified: code/gazebo/trunk/server/rendering/CMakeLists.txt
===================================================================
--- code/gazebo/trunk/server/rendering/CMakeLists.txt   2010-05-14 23:02:16 UTC 
(rev 8682)
+++ code/gazebo/trunk/server/rendering/CMakeLists.txt   2010-05-17 16:02:40 UTC 
(rev 8683)
@@ -25,6 +25,7 @@
              SelectionObj.cc
              ViewController.cc
              FPSViewController.cc
+             OrbitViewController.cc
 )
 
 set (headers OgreMovableText.hh
@@ -47,6 +48,7 @@
              SelectionObj.hh
              ViewController.hh
              FPSViewController.hh
+             OrbitViewController.hh
 )
 
 add_library(gazebo_rendering SHARED ${sources})

Modified: code/gazebo/trunk/server/rendering/FPSViewController.cc
===================================================================
--- code/gazebo/trunk/server/rendering/FPSViewController.cc     2010-05-14 
23:02:16 UTC (rev 8682)
+++ code/gazebo/trunk/server/rendering/FPSViewController.cc     2010-05-17 
16:02:40 UTC (rev 8683)
@@ -12,9 +12,6 @@
 FPSViewController::FPSViewController(OgreCamera *camera)
   : ViewController(camera)
 {
-  this->directionVec.x = 0;
-  this->directionVec.y = 0;
-  this->directionVec.z = 0;
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -38,7 +35,7 @@
 
   Vector2<int> drag = event.pos - event.prevPos;
 
-  this->directionVec.Set(0,0,0);
+  Vector3 directionVec(0,0,0);
 
   if (event.left == MouseEvent::DOWN)
   {
@@ -48,23 +45,22 @@
   else if (event.right == MouseEvent::DOWN)
   {
     // interactively pan view
-    this->directionVec.x = 0;
-    this->directionVec.y =  drag.x * 0.01;//this->moveAmount;
-    this->directionVec.z =  drag.y * 0.01;//this->moveAmount;
+    directionVec.x = 0;
+    directionVec.y =  drag.x * event.moveScale;
+    directionVec.z =  drag.y * event.moveScale;
   }
   else if (event.middle == MouseEvent::DOWN)
   {
-    this->directionVec.x =  drag.y * 0.01;//this->moveAmount;
-    this->directionVec.y =  0;
-    this->directionVec.z =  0;
+    directionVec.x =  drag.y * event.moveScale;
+    directionVec.y =  0;
+    directionVec.z =  0;
   }
   else if (event.middle == MouseEvent::SCROLL)
   {
-    this->directionVec.x -=  50.0 * event.scroll.y * 0.01;//this->moveAmount;
-    this->directionVec.y =  0;
-    this->directionVec.z =  0;
+    directionVec.x -=  50.0 * event.scroll.y * event.moveScale;
+    directionVec.y =  0;
+    directionVec.z =  0;
   }
 
   this->camera->Translate(directionVec);
-  this->directionVec.Set(0,0,0);
 }

Modified: code/gazebo/trunk/server/rendering/FPSViewController.hh
===================================================================
--- code/gazebo/trunk/server/rendering/FPSViewController.hh     2010-05-14 
23:02:16 UTC (rev 8682)
+++ code/gazebo/trunk/server/rendering/FPSViewController.hh     2010-05-17 
16:02:40 UTC (rev 8683)
@@ -2,8 +2,6 @@
 #define FPSVIEWCONTROLLER_HH
 
 #include "ViewController.hh"
-#include "Vector3.hh"
-#include "Time.hh"
 
 namespace gazebo
 {
@@ -21,8 +19,6 @@
     /// \brief Handle a mouse event
     public: virtual void HandleMouseEvent(const MouseEvent &event);
 
-    protected: Time lastUpdateTime;
-    protected: Vector3 directionVec;
   };
 }
 #endif

Modified: code/gazebo/trunk/server/rendering/OgreCamera.cc
===================================================================
--- code/gazebo/trunk/server/rendering/OgreCamera.cc    2010-05-14 23:02:16 UTC 
(rev 8682)
+++ code/gazebo/trunk/server/rendering/OgreCamera.cc    2010-05-17 16:02:40 UTC 
(rev 8683)
@@ -30,6 +30,7 @@
 #include <dirent.h>
 
 #include "FPSViewController.hh"
+#include "OrbitViewController.hh"
 #include "PhysicsEngine.hh"
 #include "Global.hh"
 #include "World.hh"
@@ -387,6 +388,17 @@
   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 OgreCamera::SetPosition(const Vector3 &pos)
+{
+  if (!Simulator::Instance()->GetRenderEngineEnabled())
+    return;
+
+  this->pose.pos = pos;
+  this->sceneNode->setPosition( this->pose.pos.x, this->pose.pos.y, 
this->pose.pos.z);
+}
  
 
////////////////////////////////////////////////////////////////////////////////
 /// Set the clip distances
@@ -1005,6 +1017,16 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+/// Set the direction of the camera
+void OgreCamera::SetDirection(Vector3 vec)
+{
+  /*this->pitchNode->setDirection(Ogre::Vector3(vec.x, vec.y, vec.z), 
Ogre::Node::TS_WORLD, Ogre::Vector3::NEGATIVE_UNIT_X);
+  this->camera->setDirection(Ogre::Vector3(vec.x, vec.y, vec.z));
+  Ogre::Quaternion q = this->camera->getOrientation();
+  */
+}
+
+////////////////////////////////////////////////////////////////////////////////
 /// Hande a mouse event
 void OgreCamera::HandleMouseEvent(const MouseEvent &evt)
 {

Modified: code/gazebo/trunk/server/rendering/OgreCamera.hh
===================================================================
--- code/gazebo/trunk/server/rendering/OgreCamera.hh    2010-05-14 23:02:16 UTC 
(rev 8682)
+++ code/gazebo/trunk/server/rendering/OgreCamera.hh    2010-05-17 16:02:40 UTC 
(rev 8683)
@@ -103,6 +103,9 @@
 
     /// \brief Set the global pose of the camera
     public: void SetWorldPose(const Pose3d &pose);
+
+    /// \brief Set the world position
+    public: void SetPosition(const Vector3 &pos);
   
     /// \brief Translate the camera
     public: void Translate( const Vector3 &direction );
@@ -235,6 +238,9 @@
     /// \brief Get the direction the camera is facing
     public: Vector3 GetDirection() const;
 
+    /// Set the direction of the camera
+    public: void SetDirection(Vector3 vec);
+
     /// \brief Hande a mouse event
     public: void HandleMouseEvent(const MouseEvent &evt);
 
@@ -255,7 +261,7 @@
     protected: Ogre::Camera *camera;
     protected: Ogre::SceneNode *origParentNode;
     protected: Ogre::SceneNode *sceneNode;
-    protected: Ogre::SceneNode *pitchNode;
+    public: Ogre::SceneNode *pitchNode;
   
     private: Pose3d pose;
   

Added: code/gazebo/trunk/server/rendering/OrbitViewController.cc
===================================================================
--- code/gazebo/trunk/server/rendering/OrbitViewController.cc                   
        (rev 0)
+++ code/gazebo/trunk/server/rendering/OrbitViewController.cc   2010-05-17 
16:02:40 UTC (rev 8683)
@@ -0,0 +1,108 @@
+#include <Ogre.h>
+#include "Simulator.hh"
+#include "Global.hh"
+#include "OgreCamera.hh"
+#include "Vector2.hh"
+#include "MouseEvent.hh"
+#include "OrbitViewController.hh"
+
+using namespace gazebo;
+
+static const float PITCH_LIMIT_LOW = 0.001;
+static const float PITCH_LIMIT_HIGH = M_PI - 0.001;
+
+////////////////////////////////////////////////////////////////////////////////
+/// Constructor
+OrbitViewController::OrbitViewController(OgreCamera *camera)
+  : ViewController(camera), yaw(M_PI), pitch(M_PI*.5), distance(5.0f)
+{
+  this->focalPoint.Set(0,0,0);
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Destructor
+OrbitViewController::~OrbitViewController()
+{
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Activate the controller
+//void OrbitViewController::Activate()
+//{
+//}
+
+////////////////////////////////////////////////////////////////////////////////
+// Update
+void OrbitViewController::Update()
+{
+  Vector3 pos;
+  pos.x = this->distance * cos( this->yaw ) * sin( this->pitch ) + 
this->focalPoint.x;
+  pos.z = this->distance * cos( this->pitch ) + this->focalPoint.z;
+  pos.y = this->distance * sin( this->yaw ) * sin( this->pitch ) + 
this->focalPoint.y;
+
+  this->camera->SetPosition(pos);
+  Pose3d pose = this->camera->GetWorldPose();
+
+  Vector3 vec = pose.rot * (this->focalPoint - pos);
+
+  this->camera->SetDirection(vec);
+  //this->camera->GetOgreCamera()->setDirection(Ogre::Vector3(vec.x, vec.y, 
vec.z));
+
+  //camera_->setFixedYawAxis(true, reference_node_->getOrientation() * 
Ogre::Vector3::UNIT_Y);
+  //camera_->setDirection(reference_node_->getOrientation() * (focal_point_ - 
pos));
+
+  //focal_shape_->setPosition(focal_point_);
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Handle a mouse event
+void OrbitViewController::HandleMouseEvent(const MouseEvent &event)
+{
+  if (!this->camera->GetUserMovable())
+    return;
+
+  Vector2<int> drag = event.pos - event.prevPos;
+
+  Vector3 directionVec(0,0,0);
+
+  if (event.left == MouseEvent::DOWN)
+  {
+    this->yaw += drag.x * event.moveScale * 0.1;
+    this->pitch += drag.y * event.moveScale *0.1;
+
+    this->yaw = fmod(this->yaw, M_PI*2);
+    if (this->yaw < 0.0f)
+      this->yaw = M_PI * 2 + this->yaw;
+
+    if (this->pitch < PITCH_LIMIT_LOW)
+      this->pitch = PITCH_LIMIT_LOW;
+    else if (this->pitch > PITCH_LIMIT_HIGH)
+      this->pitch = PITCH_LIMIT_HIGH;
+
+    //this->camera->RotateYaw(DTOR(drag.x * 0.1));
+    //this->camera->RotatePitch(DTOR(-drag.y * 0.1));
+  }
+  /*else if (event.right == MouseEvent::DOWN)
+  {
+    // interactively pan view
+    directionVec.x = 0;
+    directionVec.y =  drag.x * event.moveScale;
+    directionVec.z =  drag.y * event.moveScale;
+  }
+  else if (event.middle == MouseEvent::DOWN)
+  {
+    directionVec.x =  drag.y * event.moveScale;
+    directionVec.y =  0;
+    directionVec.z =  0;
+  }
+  else if (event.middle == MouseEvent::SCROLL)
+  {
+    directionVec.x -=  50.0 * event.scroll.y * event.moveScale;
+    directionVec.y =  0;
+    directionVec.z =  0;
+  }
+
+  this->camera->Translate(directionVec);
+  this->directionVec.Set(0,0,0);
+  */
+}

Added: code/gazebo/trunk/server/rendering/OrbitViewController.hh
===================================================================
--- code/gazebo/trunk/server/rendering/OrbitViewController.hh                   
        (rev 0)
+++ code/gazebo/trunk/server/rendering/OrbitViewController.hh   2010-05-17 
16:02:40 UTC (rev 8683)
@@ -0,0 +1,29 @@
+#ifndef ORBITVIEWCONTROLLER_HH
+#define ORBITVIEWCONTROLLER_HH
+
+#include "ViewController.hh"
+#include "Vector3.hh"
+
+namespace gazebo
+{
+  class OrbitViewController : public ViewController
+  {
+    /// \brief Constructor
+    public: OrbitViewController(OgreCamera *camera);
+
+    /// \brief Destructor
+    public: virtual ~OrbitViewController();
+
+    /// \brief Update
+    public: virtual void Update();
+
+    /// \brief Handle a mouse event
+    public: virtual void HandleMouseEvent(const MouseEvent &event);
+
+    private: float yaw, pitch;
+    private: float distance;
+    private: Vector3 focalPoint;
+  };
+}
+
+#endif

Modified: code/gazebo/trunk/worlds/pendulum.world
===================================================================
--- code/gazebo/trunk/worlds/pendulum.world     2010-05-14 23:02:16 UTC (rev 
8682)
+++ code/gazebo/trunk/worlds/pendulum.world     2010-05-17 16:02:40 UTC (rev 
8683)
@@ -17,16 +17,26 @@
   <physics:ode>
     <stepTime>0.001</stepTime>
     <gravity>0 0 -9.8</gravity>
-    <cfm>10e-2</cfm>
+    <cfm>10e-10</cfm>
     <erp>0.2</erp>
+    <quickStep>true</quickStep>
+    <quickStepIters>50</quickStepIters>
+    <quickStepW>1.3</quickStepW>
+    <contactMaxCorrectingVel>100.0</contactMaxCorrectingVel>
+    <contactSurfaceLayer>0.001</contactSurfaceLayer>
+
+    <!-- updateRate: <0 == throttle simTime to match realTime.
+                      0 == No throttling
+                     >0 == Frequency at which to throttle the sim --> 
     <updateRate>0</updateRate>
+
   </physics:ode>
 
   <rendering:gui>
     <type>fltk</type>
     <size>1024 768</size>
     <pos>0 0</pos>
-    <frames>
+    <!--<frames>
       <row height="100%">
         <camera width="100%">
           <xyz>-3.15 4 2.55</xyz>
@@ -34,6 +44,7 @@
         </camera>
       </row>
     </frames>
+    -->
   </rendering:gui>
 
   <rendering:ogre>
@@ -41,7 +52,7 @@
     <sky>
       <material>Gazebo/Grey</material>
     </sky>
-    <shadowTechnique>stencilAdditive</shadowTechnique>
+    <shadowTechnique>stencilModulative</shadowTechnique>
     <grid>false</grid>
   </rendering:ogre>
 
@@ -70,6 +81,7 @@
     <!-- Bottom & Upright of the pendulum -->
     <body:box name="base_body">
       <dampingFactor>1.0</dampingFactor>
+      <static>true</static>
       <geom:box name="base_geom">
         <size>1.0 1.0 0.2</size>
         <mass>10.1</mass>
@@ -104,7 +116,6 @@
     </body:box>
 
     <body:box name="swing_body">
-      <!--<xyz>-0.46 0.7 2.235</xyz>-->
       <xyz>-0.46 0.7 2.15</xyz>
       <rpy>90 0 0</rpy>
       <dampingFactor>0.00006</dampingFactor>
@@ -134,7 +145,7 @@
       <body1>base_body</body1>
       <body2>swing_body</body2>
       <anchor>swing_body</anchor>
-      <anchorOffset>0 -0.7 0</anchorOffset>
+      <anchorOffset>0 0 0.7</anchorOffset>
       <axis>1 0 0</axis>
       <erp>0.8</erp>
       <cfm>10e-5</cfm>
@@ -156,7 +167,7 @@
     </light>
   </model:renderable>
 
-  <model:renderable name="point_white2">
+  <!--  <model:renderable name="point_white2">
     <xyz>-1 2 10</xyz>
     <static>true</static>
 
@@ -170,5 +181,6 @@
       <castShadows>false</castShadows>
     </light>
   </model:renderable>
+  -->
  
 </gazebo:world>

Modified: code/gazebo/trunk/worlds/simpleshapes.world
===================================================================
--- code/gazebo/trunk/worlds/simpleshapes.world 2010-05-14 23:02:16 UTC (rev 
8682)
+++ code/gazebo/trunk/worlds/simpleshapes.world 2010-05-17 16:02:40 UTC (rev 
8683)
@@ -48,7 +48,7 @@
 
   <model:physical name="sphere1_model">
     <xyz>0 0 0.2</xyz>
-    <rpy>45 0.0 0.0</rpy>
+    <rpy>0 0.0 0.0</rpy>
     <static>true</static>
 
     <body:sphere name="sphere1_body">


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

------------------------------------------------------------------------------

_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to