Revision: 7999
http://playerstage.svn.sourceforge.net/playerstage/?rev=7999&view=rev
Author: rtv
Date: 2009-07-11 22:58:34 +0000 (Sat, 11 Jul 2009)
Log Message:
-----------
working on time sync
Modified Paths:
--------------
code/gazebo/trunk/webgazebo/Properties.cc
code/gazebo/trunk/webgazebo/WebGazebo.cc
code/gazebo/trunk/webgazebo/WebGazebo.hh
code/gazebo/trunk/worlds/federation.world
Modified: code/gazebo/trunk/webgazebo/Properties.cc
===================================================================
--- code/gazebo/trunk/webgazebo/Properties.cc 2009-07-11 22:57:40 UTC (rev
7998)
+++ code/gazebo/trunk/webgazebo/Properties.cc 2009-07-11 22:58:34 UTC (rev
7999)
@@ -362,34 +362,34 @@
}
-bool
-WebGazebo::CheckTolerances(gazebo::Pose p, gazebo::Pose q)
-{
- // Check position
- double sq_dd = ((p.pos.x - q.pos.x)*(p.pos.x - q.pos.x) +
- (p.pos.y - q.pos.y)*(p.pos.y - q.pos.y) +
- (p.pos.z - q.pos.z)*(p.pos.z - q.pos.z));
- if((sq_dist_tol > 0) && (sq_dd > sq_dist_tol))
- return false;
+// bool
+// WebGazebo::CheckTolerances(gazebo::Pose p, gazebo::Pose q)
+// {
+// // Check position
+// double sq_dd = ((p.pos.x - q.pos.x)*(p.pos.x - q.pos.x) +
+// (p.pos.y - q.pos.y)*(p.pos.y - q.pos.y) +
+// (p.pos.z - q.pos.z)*(p.pos.z - q.pos.z));
+// if((sq_dist_tol > 0) && (sq_dd > sq_dist_tol))
+// return false;
- // Check orientation
- gazebo::Quatern p_quat, q_quat;
- gazebo::Vector3 pv(p.roll, p.pitch, p.yaw);
- gazebo::Vector3 qv(q.roll, q.pitch, q.yaw);
- p_quat.SetFromEuler(pv);
- q_quat.SetFromEuler(qv);
- gazebo::Quatern da = p_quat - q_quat;
- //da.Normalize();
+// // Check orientation
+// gazebo::Quatern p_quat, q_quat;
+// gazebo::Vector3 pv(p.roll, p.pitch, p.yaw);
+// gazebo::Vector3 qv(q.roll, q.pitch, q.yaw);
+// p_quat.SetFromEuler(pv);
+// q_quat.SetFromEuler(qv);
+// gazebo::Quatern da = p_quat - q_quat;
+// //da.Normalize();
- double sq_da = ((da.u*da.u) +
- (da.x*da.x) +
- (da.y*da.y) +
- (da.z*da.z));
- if((sq_ang_tol > 0) && (sq_da > sq_ang_tol))
- return false;
+// double sq_da = ((da.u*da.u) +
+// (da.x*da.x) +
+// (da.y*da.y) +
+// (da.z*da.z));
+// if((sq_ang_tol > 0) && (sq_da > sq_ang_tol))
+// return false;
- return true;
-}
+// return true;
+// }
/*
bool
Modified: code/gazebo/trunk/webgazebo/WebGazebo.cc
===================================================================
--- code/gazebo/trunk/webgazebo/WebGazebo.cc 2009-07-11 22:57:40 UTC (rev
7998)
+++ code/gazebo/trunk/webgazebo/WebGazebo.cc 2009-07-11 22:58:34 UTC (rev
7999)
@@ -35,30 +35,33 @@
#include <time.h>
#include <string.h>
-#include "Quatern.hh"
-
WebGazebo::WebGazebo(const std::string& fedfile,
const std::string& host,
- unsigned short port,
- double dtol,
- double atol) :
+ unsigned short port,
+ double distance_tolerance,
+ double angle_tolerance ) :
websim::WebSim(host, port),
- sq_dist_tol(dtol*dtol),
- sq_ang_tol(atol*atol)
+ distance_tolerance(distance_tolerance),
+ angle_tolerance(angle_tolerance),
+ goMutex(),
+ goCond(),
+ client(NULL),
+ simIface(NULL),
+ factoryIface(NULL)
{
// Hook up to Gazebo
printf("[webgazebo] Opening Gazebo simulation interface...");
fflush(stdout);
+
this->client = new gazebo::Client();
this->simIface = new gazebo::SimulationIface();
this->factoryIface = new gazebo::FactoryIface();
- this->laserIface = new gazebo::LaserIface();
+
this->client->ConnectWait(0, GZ_CLIENT_ID_USER_FIRST);
+
// Open the Simulation Interface; let exceptions leak out
this->simIface->Open(this->client, "default");
- puts( "(opened sim interface)" );
this->factoryIface->Open(this->client, "default");
- puts( "(opened factory interface)" );
puts("Done.");
puts("[webgazebo] Ready");
@@ -66,7 +69,7 @@
WebGazebo::~WebGazebo()
{
- //delete this->laserIface;
+ // delete all open interfaces
std::map<std::string, gazebo::Iface*>::iterator itr;
for(itr = interfaces.begin(); itr != interfaces.end(); itr++)
{
@@ -75,6 +78,7 @@
}
delete this->simIface;
+ delete this->factoryIface;
delete this->client;
}
@@ -91,7 +95,6 @@
return t;
}
-
bool
WebGazebo::GetModel(const std::string& name,
const std::string& type,
@@ -215,9 +218,9 @@
}
bool
-WebGazebo::Go(double t)
+WebGazebo::ClockRunFor( double seconds )
{
- unsigned int us = (unsigned int)rint(t*1e6);
+ unsigned int us = (unsigned int)rint(seconds*1e6);
this->simIface->Go(us, boost::bind(&WebGazebo::GoCallback, this));
// Wait for the callback to fire
boost::mutex::scoped_lock lock(this->goMutex);
Modified: code/gazebo/trunk/webgazebo/WebGazebo.hh
===================================================================
--- code/gazebo/trunk/webgazebo/WebGazebo.hh 2009-07-11 22:57:40 UTC (rev
7998)
+++ code/gazebo/trunk/webgazebo/WebGazebo.hh 2009-07-11 22:58:34 UTC (rev
7999)
@@ -20,7 +20,7 @@
*/
/* Desc: HTTP portal to libgazebo
- * Author: Brian Gerkey
+ * Author: Brian Gerkey, Richard Vaughan, Nate Koenig, Abbas Sadat
* Date: 9 March 2009
* SVN: $Id: gazebo.h 7398 2009-03-09 07:21:49Z natepak $
*/
@@ -38,14 +38,14 @@
bool Go(double t);
- // start WebSim Interface
============================================================
+ // start WebSim Interface ===================================================
virtual std::string IdentificationString()
{ return "WebGazebo"; }
virtual std::string VersionString()
{ return "0.1"; }
-
+
virtual bool CreateModel(const std::string& name,
const std::string& type,
std::string& error);
@@ -83,23 +83,24 @@
websim::Pose& center,
std::string& response);
- /** Get the current simulation time */
virtual websim::Time GetTime();
virtual bool ClockStart() { simIface->Unpause(); return true;}
virtual bool ClockStop() { simIface->Pause(); return true;}
- // end WebSim Interface =====================================================
+ virtual bool ClockRunFor( double seconds );
+ // end WebSim Interface ====================================================
+
private: // all private members are specific to WebGazebo
- bool WaitForResponse();
+ //bool WaitForResponse();
- double sq_dist_tol;
- double sq_ang_tol;
+ double distance_tolerance;
+ double angle_tolerance;
boost::mutex goMutex;
boost::condition goCond;
@@ -107,18 +108,19 @@
gazebo::Client *client;
gazebo::SimulationIface *simIface;
gazebo::FactoryIface *factoryIface;
- gazebo::LaserIface *laserIface;
std::map<std::string,gazebo::Iface*> interfaces;
// Available models
std::map<std::string,int> models;
- bool CheckTolerances(gazebo::Pose p, gazebo::Pose q);
+ //bool CheckTolerances(gazebo::Pose p, gazebo::Pose q);
+
bool GetModel(const std::string& name,
const std::string& type,
std::string& xmldata,
std::string& response);
+
void GoCallback();
};
Modified: code/gazebo/trunk/worlds/federation.world
===================================================================
--- code/gazebo/trunk/worlds/federation.world 2009-07-11 22:57:40 UTC (rev
7998)
+++ code/gazebo/trunk/worlds/federation.world 2009-07-11 22:58:34 UTC (rev
7999)
@@ -48,12 +48,6 @@
<shadowTechnique>stencilAdditive</shadowTechnique>
</rendering:ogre>
- <model:empty name="factory_model">
- <controller:factory name="factory_controller">
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
<!-- Ground Plane -->
<model:physical name="plane1_model">
<xyz>0 0 0</xyz>
This was sent by the SourceForge.net collaborative development platform, the
world's largest Open Source development site.
------------------------------------------------------------------------------
Enter the BlackBerry Developer Challenge
This is your chance to win up to $100,000 in prizes! For a limited time,
vendors submitting new applications to BlackBerry App World(TM) will have
the opportunity to enter the BlackBerry Developer Challenge. See full prize
details at: http://p.sf.net/sfu/Challenge
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit