Revision: 6897
          http://playerstage.svn.sourceforge.net/playerstage/?rev=6897&view=rev
Author:   natepak
Date:     2008-07-21 18:27:33 +0000 (Mon, 21 Jul 2008)

Log Message:
-----------
Renamed result to response in the simulation interface

Modified Paths:
--------------
    code/gazebo/trunk/libgazebo/gazebo.h
    code/gazebo/trunk/player/SimulationInterface.cc
    code/gazebo/trunk/server/World.cc

Modified: code/gazebo/trunk/libgazebo/gazebo.h
===================================================================
--- code/gazebo/trunk/libgazebo/gazebo.h        2008-07-21 18:16:50 UTC (rev 
6896)
+++ code/gazebo/trunk/libgazebo/gazebo.h        2008-07-21 18:27:33 UTC (rev 
6897)
@@ -406,9 +406,9 @@
   public: SimulationRequestData requests[GAZEBO_SIMULATION_MAX_REQUESTS];
   public: unsigned int requestCount;
 
-  /// Array of request results from the simulator
-  public: SimulationRequestData results[GAZEBO_SIMULATION_MAX_REQUESTS];
-  public: unsigned int resultCount;
+  /// Array of request responses from the simulator
+  public: SimulationRequestData responses[GAZEBO_SIMULATION_MAX_REQUESTS];
+  public: unsigned int responseCount;
 };
 
 /// \brief Common simulation interface

Modified: code/gazebo/trunk/player/SimulationInterface.cc
===================================================================
--- code/gazebo/trunk/player/SimulationInterface.cc     2008-07-21 18:16:50 UTC 
(rev 6896)
+++ code/gazebo/trunk/player/SimulationInterface.cc     2008-07-21 18:27:33 UTC 
(rev 6897)
@@ -223,14 +223,14 @@
 // called from GazeboDriver::Update
 void SimulationInterface::Update()
 {
-  gazebo::SimulationRequestData *result = NULL;
+  gazebo::SimulationRequestData *response = NULL;
   this->iface->Lock(1);
 
-  for (unsigned int i=0; i < this->iface->data->resultCount; i++)
+  for (unsigned int i=0; i < this->iface->data->responseCount; i++)
   {
-    result = &(this->iface->data->results[i]);
+    response = &(this->iface->data->responses[i]);
 
-    switch (result->type)
+    switch (response->type)
     {
       case gazebo::SimulationRequestData::PAUSE:
       case gazebo::SimulationRequestData::RESET:
@@ -243,16 +243,16 @@
         {
           player_simulation_pose3d_req_t req;
 
-          strcpy(req.name, result->modelName);
+          strcpy(req.name, response->modelName);
           req.name_count = strlen(req.name);
 
-          req.pose.px = result->modelPose.pos.x;
-          req.pose.py = result->modelPose.pos.y;
-          req.pose.pz = result->modelPose.pos.z;
+          req.pose.px = response->modelPose.pos.x;
+          req.pose.py = response->modelPose.pos.y;
+          req.pose.pz = response->modelPose.pos.z;
 
-          req.pose.proll = result->modelPose.roll;
-          req.pose.ppitch = result->modelPose.pitch;
-          req.pose.pyaw = result->modelPose.yaw;
+          req.pose.proll = response->modelPose.roll;
+          req.pose.ppitch = response->modelPose.pitch;
+          req.pose.pyaw = response->modelPose.yaw;
 
           this->driver->Publish(this->device_addr, *(this->responseQueue),
               PLAYER_MSGTYPE_RESP_ACK, PLAYER_SIMULATION_REQ_GET_POSE3D,
@@ -264,12 +264,12 @@
         {
           player_simulation_pose2d_req_t req;
 
-          strcpy(req.name, result->modelName);
+          strcpy(req.name, response->modelName);
           req.name_count = strlen(req.name);
 
-          req.pose.px = result->modelPose.pos.x;
-          req.pose.py = result->modelPose.pos.y;
-          req.pose.pa = result->modelPose.yaw;
+          req.pose.px = response->modelPose.pos.x;
+          req.pose.py = response->modelPose.pos.y;
+          req.pose.pa = response->modelPose.yaw;
 
           this->driver->Publish(this->device_addr, *(this->responseQueue),
               PLAYER_MSGTYPE_RESP_ACK, PLAYER_SIMULATION_REQ_GET_POSE2D,
@@ -280,6 +280,8 @@
     }
   }
 
+  this->iface->data->responseCount = 0;
+
   this->iface->Unlock();
 
   return;

Modified: code/gazebo/trunk/server/World.cc
===================================================================
--- code/gazebo/trunk/server/World.cc   2008-07-21 18:16:50 UTC (rev 6896)
+++ code/gazebo/trunk/server/World.cc   2008-07-21 18:27:33 UTC (rev 6897)
@@ -490,7 +490,7 @@
 // Update the simulation interface
 void World::UpdateSimulationIface()
 {
-  SimulationRequestData *results = NULL;
+  SimulationRequestData *response = NULL;
 
   //TODO: Move this method to simulator? Hard because of the models
   this->simIface->Lock(1);
@@ -501,8 +501,8 @@
     return;
   }
 
-  results = this->simIface->data->results;
-  this->simIface->data->resultCount = 0;
+  response = this->simIface->data->responses;
+  this->simIface->data->responseCount = 0;
 
   this->simIface->data->simTime = Simulator::Instance()->GetSimTime();
   this->simIface->data->pauseTime = Simulator::Instance()->GetPauseTime();
@@ -571,19 +571,19 @@
             Pose3d pose = model->GetPose();
             Vector3 rot = pose.rot.GetAsEuler();
 
-            results->type = req->type;
+            response->type = req->type;
 
-            strcpy( results->modelName, req->modelName);
-            results->modelPose.pos.x = pose.pos.x;
-            results->modelPose.pos.y = pose.pos.y;
-            results->modelPose.pos.z = pose.pos.z;
+            strcpy( response->modelName, req->modelName);
+            response->modelPose.pos.x = pose.pos.x;
+            response->modelPose.pos.y = pose.pos.y;
+            response->modelPose.pos.z = pose.pos.z;
 
-            results->modelPose.roll = rot.x;
-            results->modelPose.pitch = rot.y;
-            results->modelPose.yaw = rot.z;
+            response->modelPose.roll = rot.x;
+            response->modelPose.pitch = rot.y;
+            response->modelPose.yaw = rot.z;
 
-            results++;
-            this->simIface->data->resultCount++;
+            response++;
+            this->simIface->data->responseCount++;
           }
           else
           {


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

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

Reply via email to