Revision: 8750
http://playerstage.svn.sourceforge.net/playerstage/?rev=8750&view=rev
Author: natepak
Date: 2010-06-03 00:34:23 +0000 (Thu, 03 Jun 2010)
Log Message:
-----------
Updates
Modified Paths:
--------------
code/gazebo/branches/simpar/benchmarks/box_drop_benchmark.cc
code/gazebo/branches/simpar/benchmarks/pioneer_circle_benchmark.cc
code/gazebo/branches/simpar/benchmarks/pioneer_spiral_benchmark.cc
code/gazebo/branches/simpar/benchmarks/table_benchmark.cc
code/gazebo/branches/simpar/libgazebo/SimIface.cc
code/gazebo/branches/simpar/libgazebo/gz.h
code/gazebo/branches/simpar/plugins/CMakeLists.txt
code/gazebo/branches/simpar/server/GazeboMessage.hh
code/gazebo/branches/simpar/server/Logger.cc
code/gazebo/branches/simpar/server/Logger.hh
code/gazebo/branches/simpar/server/World.cc
code/gazebo/branches/simpar/server/physics/Joint.cc
code/gazebo/branches/simpar/server/physics/SurfaceParams.cc
code/gazebo/branches/simpar/worlds/models/pioneer2dx.model
code/gazebo/branches/simpar/worlds/pioneer2dx.world
code/gazebo/branches/simpar/worlds/simpleshapes.world
Added Paths:
-----------
code/gazebo/branches/simpar/plugins/pioneer_line.cc
Removed Paths:
-------------
code/gazebo/branches/simpar/plugins/pioneer_spiral.cc
code/gazebo/branches/simpar/plugins/pioneer_spiral.hh
Modified: code/gazebo/branches/simpar/benchmarks/box_drop_benchmark.cc
===================================================================
--- code/gazebo/branches/simpar/benchmarks/box_drop_benchmark.cc
2010-06-02 15:00:16 UTC (rev 8749)
+++ code/gazebo/branches/simpar/benchmarks/box_drop_benchmark.cc
2010-06-03 00:34:23 UTC (rev 8750)
@@ -66,7 +66,7 @@
void RunSim()
{
- simIface->StartLogEntity("box");
+ simIface->StartLogEntity("box", "/tmp/box.log");
simIface->Unpause();
/*libgazebo::Vec3 linearVel, angularVel, linearAccel, angularAccel;
libgazebo::Pose modelPose;
Modified: code/gazebo/branches/simpar/benchmarks/pioneer_circle_benchmark.cc
===================================================================
--- code/gazebo/branches/simpar/benchmarks/pioneer_circle_benchmark.cc
2010-06-02 15:00:16 UTC (rev 8749)
+++ code/gazebo/branches/simpar/benchmarks/pioneer_circle_benchmark.cc
2010-06-03 00:34:23 UTC (rev 8750)
@@ -173,7 +173,7 @@
void RunSim(double stepTime)
{
- simIface->StartLogEntity("pioneer");
+ simIface->StartLogEntity("pioneer", "/tmp/pioneer.log");
simIface->Unpause();
double angle = 10;
Modified: code/gazebo/branches/simpar/benchmarks/pioneer_spiral_benchmark.cc
===================================================================
--- code/gazebo/branches/simpar/benchmarks/pioneer_spiral_benchmark.cc
2010-06-02 15:00:16 UTC (rev 8749)
+++ code/gazebo/branches/simpar/benchmarks/pioneer_spiral_benchmark.cc
2010-06-03 00:34:23 UTC (rev 8750)
@@ -170,7 +170,7 @@
void RunSim()
{
- simIface->StartLogEntity("pioneer");
+ simIface->StartLogEntity("pioneer", "/tmp/pioneer.log");
simIface->Unpause();
libgazebo::Pose pose;
Modified: code/gazebo/branches/simpar/benchmarks/table_benchmark.cc
===================================================================
--- code/gazebo/branches/simpar/benchmarks/table_benchmark.cc 2010-06-02
15:00:16 UTC (rev 8749)
+++ code/gazebo/branches/simpar/benchmarks/table_benchmark.cc 2010-06-03
00:34:23 UTC (rev 8750)
@@ -190,8 +190,8 @@
usleep(100000);
spawn_box(0, 0, prev_z);
usleep(1000000);
- simIface->StartLogEntity("box");
- simIface->StartLogEntity("table");
+ simIface->StartLogEntity("box","/tmp/box.log");
+ simIface->StartLogEntity("table","/tmp/table.log");
simIface->Unpause();
libgazebo::Vec3 linearVel, angularVel, linearAccel, angularAccel;
Modified: code/gazebo/branches/simpar/libgazebo/SimIface.cc
===================================================================
--- code/gazebo/branches/simpar/libgazebo/SimIface.cc 2010-06-02 15:00:16 UTC
(rev 8749)
+++ code/gazebo/branches/simpar/libgazebo/SimIface.cc 2010-06-03 00:34:23 UTC
(rev 8750)
@@ -898,7 +898,8 @@
////////////////////////////////////////////////////////////////////////////////
/// Start logging entity information
-void SimulationIface::StartLogEntity(const std::string &entityName)
+void SimulationIface::StartLogEntity(const std::string &entityName,
+ const std::string &filename)
{
this->Lock(1);
@@ -912,6 +913,10 @@
strncpy(request->name, entityName.c_str(), 512);
request->name[511] = '\0';
+ memset(request->strValue, 0, 512);
+ strncpy(request->strValue, filename.c_str(), 512);
+ request->strValue[511] = '\0';
+
this->Unlock();
}
Modified: code/gazebo/branches/simpar/libgazebo/gz.h
===================================================================
--- code/gazebo/branches/simpar/libgazebo/gz.h 2010-06-02 15:00:16 UTC (rev
8749)
+++ code/gazebo/branches/simpar/libgazebo/gz.h 2010-06-03 00:34:23 UTC (rev
8750)
@@ -670,7 +670,8 @@
public: void GoAckPost();
/// \brief Start logging entity information
- public: void StartLogEntity(const std::string &entityName);
+ public: void StartLogEntity(const std::string &entityName,
+ const std::string &filename);
/// \brief Stop logging entity information
public: void StopLogEntity(const std::string &entityName);
Modified: code/gazebo/branches/simpar/plugins/CMakeLists.txt
===================================================================
--- code/gazebo/branches/simpar/plugins/CMakeLists.txt 2010-06-02 15:00:16 UTC
(rev 8749)
+++ code/gazebo/branches/simpar/plugins/CMakeLists.txt 2010-06-03 00:34:23 UTC
(rev 8750)
@@ -15,7 +15,7 @@
link_directories(${GAZEBO_LIBRARY_DIRS})
endif (PKG_CONFIG_FOUND)
-set (plugins pioneer_spiral
+set (plugins pioneer_line
pioneer_circle)
Copied: code/gazebo/branches/simpar/plugins/pioneer_line.cc (from rev 8748,
code/gazebo/branches/simpar/plugins/pioneer_spiral.cc)
===================================================================
--- code/gazebo/branches/simpar/plugins/pioneer_line.cc
(rev 0)
+++ code/gazebo/branches/simpar/plugins/pioneer_line.cc 2010-06-03 00:34:23 UTC
(rev 8750)
@@ -0,0 +1,168 @@
+#include <stdlib.h>
+#include <boost/bind.hpp>
+#include <gazebo/gazeboserver.hh>
+
+namespace gazebo
+{
+
+ class PioneerLine : public Handler
+ {
+ public: PioneerLine() : Handler()
+ {
+ for (double i=0.001; i > 1e-5; i*=0.5)
+ this->stepTimes.push_back(i);
+
+ for (unsigned int i=10; i<=100; i+=10)
+ this->stepIters.push_back(i);
+
+ this->stepTypes.push_back("world");
+ this->stepTypes.push_back("quick");
+ //this->stepTypes.push_back("robust");
+
+ this->stepTypesIter = this->stepTypes.begin();
+ this->stepTimesIter = this->stepTimes.begin();
+ this->stepItersIter = this->stepIters.begin();
+
+ this->path = std::string("/home/nate/work/simpar/data/pioneer_line/");
+ system( (std::string("mkdir -p ") + this->path).c_str() );
+
+ this->count = 0;
+
+ this->indexFile = fopen(std::string(this->path + "index.txt").c_str(),
"w");
+ fprintf(this->indexFile, "# index step_type step_time
step_iterations\n");
+ }
+
+ public: ~PioneerLine()
+ {
+ fclose(this->indexFile);
+
+ World::Instance()->DisconnectWorldUpdateStartSignal(
+ boost::bind(&PioneerLine::UpdateCB, this));
+
+ for (unsigned int i=0; i < this->robot->GetChildCount(); i++)
+ {
+ Body *body = dynamic_cast<Body*>(this->robot->GetChild(i));
+ if (body)
+ {
+ body->SetForce(Vector3(0,0,0));
+ body->SetTorque(Vector3(0,0,0));
+ body->SetLinearVel(Vector3(0,0,0));
+ body->SetAngularVel(Vector3(0,0,0));
+ }
+ }
+ this->robot->Reset();
+ }
+
+ public: void Load()
+ {
+ std::string model_name = "pioneer";
+ this->robot = (Model*)World::Instance()->GetEntityByName(model_name);
+
+
+ if (this->robot)
+ {
+
+ this->robot->GetVisualNode()->SetRibbonTrail(true);
+ this->leftWheel = (Body*)this->robot->GetChild("left_wheel");
+ this->rightWheel = (Body*)this->robot->GetChild("right_wheel");
+
+ World::Instance()->ConnectWorldUpdateStartSignal(
+ boost::bind(&PioneerLine::UpdateCB, this));
+
+ this->prevTime = Simulator::Instance()->GetRealTime();
+
+ this->physics = World::Instance()->GetPhysicsEngine();
+
+ Logger::Instance()->AddLog("pioneer","/tmp/pioneer.log");
+
+ this->physics->SetStepTime( *this->stepTimesIter );
+ this->physics->SetStepType( *this->stepTypesIter );
+ this->physics->SetSORPGSIters( *this->stepItersIter );
+ std::cout << "Type[" << *this->stepTypesIter << "] "
+ << "Time[" << *this->stepTimesIter << "] "
+ << "Iters[" << *this->stepItersIter << "]\n";
+ }
+ else
+ std::cerr << "Unable to find model[" << model_name << "]\n";
+ }
+
+ public: void UpdateCB()
+ {
+ if (Simulator::Instance()->IsPaused())
+ return;
+
+ Time realTime = Simulator::Instance()->GetRealTime();
+
+ //double speedSum = this->robot->GetWorldLinearVel().GetLength();
+
+ if (realTime - prevTime < Time(0,100000000))
+ {
+ this->leftWheel->SetTorque(Vector3(0.0,0.0,.1));
+ this->rightWheel->SetTorque(Vector3(0.0,0.0,.1));
+ }
+ else if (realTime - prevTime >= Time(20,0))
+ {
+ Logger::Instance()->RemoveLog("pioneer");
+
+ std::string mv_cmd = std::string("mv /tmp/pioneer.log ") + this->path
+
+ "pioneer_line_" + boost::lexical_cast<std::string>(this->count) +
+ ".data";
+
+ fprintf(this->indexFile,"%d %s %f %d\n",this->count,
(*this->stepTypesIter).c_str(), *this->stepTimesIter, *this->stepItersIter);
+
+ system(mv_cmd.c_str());
+
+ this->stepItersIter++;
+ if (this->stepItersIter == this->stepIters.end())
+ {
+ this->stepItersIter = this->stepIters.begin();
+ this->stepTimesIter++;
+ if (this->stepTimesIter == this->stepTimes.end())
+ {
+ this->stepTimesIter = this->stepTimes.begin();
+ this->stepTypesIter++;
+ if (this->stepTypesIter == this->stepTypes.end())
+ {
+ Simulator::Instance()->RemoveHandler(this->name);
+ return;
+ }
+ }
+ }
+
+ this->physics->SetStepType( *this->stepTypesIter );
+ this->physics->SetStepTime( *this->stepTimesIter );
+ this->physics->SetSORPGSIters( *this->stepItersIter );
+
+ this->count++;
+ std::cout << "Type[" << *this->stepTypesIter << "] "
+ << "Time[" << *this->stepTimesIter << "] "
+ << "Iters[" << *this->stepItersIter << "] "
+ << "Count[" << this->count << "]\n";
+
+ this->robot->Reset();
+ this->prevTime = Simulator::Instance()->GetRealTime();
+ Logger::Instance()->AddLog("pioneer","/tmp/pioneer.log");
+ }
+ }
+
+ private: std::vector<unsigned int> stepIters;
+ private: std::vector<unsigned int>::iterator stepItersIter;
+
+ private: std::vector<double> stepTimes;
+ private: std::vector<double>::iterator stepTimesIter;
+
+ private: std::vector<std::string> stepTypes;
+ private: std::vector<std::string>::iterator stepTypesIter;
+ private: std::string path;
+ private: unsigned int count;
+
+ private: Model *robot;
+ private: Body *rightWheel, *leftWheel;
+ private: FILE *indexFile;
+ private: Time prevTime;
+ private: PhysicsEngine *physics;
+
+ };
+
+ GZ_REGISTER_HANDLER("PioneerLine", PioneerLine)
+}
Deleted: code/gazebo/branches/simpar/plugins/pioneer_spiral.cc
===================================================================
--- code/gazebo/branches/simpar/plugins/pioneer_spiral.cc 2010-06-02
15:00:16 UTC (rev 8749)
+++ code/gazebo/branches/simpar/plugins/pioneer_spiral.cc 2010-06-03
00:34:23 UTC (rev 8750)
@@ -1,141 +0,0 @@
-#include <stdlib.h>
-#include <boost/bind.hpp>
-#include "pioneer_spiral.hh"
-
-using namespace gazebo;
-
-GZ_REGISTER_HANDLER("PioneerSpiral", PioneerSpiral)
-
-PioneerSpiral::PioneerSpiral() : Handler()
-{
- for (double i=0.001; i > 1e-5; i*=0.5)
- this->stepTimes.push_back(i);
-
- for (unsigned int i=10; i<=100; i+=10)
- this->stepIters.push_back(i);
-
- this->stepTypes.push_back("world");
- this->stepTypes.push_back("quick");
- //this->stepTypes.push_back("robust");
-
- this->stepTypesIter = this->stepTypes.begin();
- this->stepTimesIter = this->stepTimes.begin();
- this->stepItersIter = this->stepIters.begin();
-
- this->path = std::string("/home/nate/work/simpar/data/pioneer_spiral/");
- system( (std::string("mkdir -p ") + this->path).c_str() );
-
- this->count = 0;
-
- this->indexFile = fopen(std::string(this->path + "index.txt").c_str(), "w");
- fprintf(this->indexFile, "# index step_type step_time step_iterations\n");
-}
-
-PioneerSpiral::~PioneerSpiral()
-{
- fclose(this->indexFile);
-
- World::Instance()->DisconnectWorldUpdateStartSignal(
- boost::bind(&PioneerSpiral::UpdateCB, this));
-
- for (unsigned int i=0; i < this->robot->GetChildCount(); i++)
- {
- Body *body = dynamic_cast<Body*>(this->robot->GetChild(i));
- if (body)
- {
- body->SetForce(Vector3(0,0,0));
- body->SetTorque(Vector3(0,0,0));
- body->SetLinearVel(Vector3(0,0,0));
- body->SetAngularVel(Vector3(0,0,0));
- }
- }
-}
-
-void PioneerSpiral::Load()
-{
- std::string model_name = "pioneer";
- this->robot = (Model*)World::Instance()->GetEntityByName(model_name);
-
-
- if (this->robot)
- {
-
- this->robot->GetVisualNode()->SetRibbonTrail(true);
- this->leftWheel = (Body*)this->robot->GetChild("left_wheel");
- this->rightWheel = (Body*)this->robot->GetChild("right_wheel");
-
- World::Instance()->ConnectWorldUpdateStartSignal(
- boost::bind(&PioneerSpiral::UpdateCB, this));
-
- this->prevTime = Simulator::Instance()->GetRealTime();
-
- this->physics = World::Instance()->GetPhysicsEngine();
-
- Logger::Instance()->AddLog("pioneer");
-
- this->physics->SetStepTime( *this->stepTimesIter );
- this->physics->SetStepType( *this->stepTypesIter );
- this->physics->SetSORPGSIters( *this->stepItersIter );
- std::cout << "Type[" << *this->stepTypesIter << "] "
- << "Time[" << *this->stepTimesIter << "] "
- << "Iters[" << *this->stepItersIter << "]\n";
- }
- else
- std::cerr << "Unable to find model[" << model_name << "]\n";
-}
-
-void PioneerSpiral::UpdateCB()
-{
- Time realTime = Simulator::Instance()->GetRealTime();
-
- double speedSum = this->robot->GetWorldLinearVel().GetLength();
-
- if (realTime - prevTime < Time(0,100000000))
- {
- this->leftWheel->SetTorque(Vector3(0.0,0.0,.1));
- this->rightWheel->SetTorque(Vector3(0.0,0.0,.1));
- }
- else if (speedSum < 1e-3)
- {
- Logger::Instance()->RemoveLog("pioneer");
-
- std::string mv_cmd = std::string("mv /tmp/pioneer.log ") + this->path +
- "pioneer_spiral_" + boost::lexical_cast<std::string>(this->count) +
- ".data";
-
- fprintf(this->indexFile,"%d %s %f %d\n",this->count,
(*this->stepTypesIter).c_str(), *this->stepTimesIter, *this->stepItersIter);
-
- system(mv_cmd.c_str());
-
- this->stepItersIter++;
- if (this->stepItersIter == this->stepIters.end())
- {
- this->stepItersIter = this->stepIters.begin();
- this->stepTimesIter++;
- if (this->stepTimesIter == this->stepTimes.end())
- {
- this->stepTimesIter = this->stepTimes.begin();
- this->stepTypesIter++;
- if (this->stepTypesIter == this->stepTypes.end())
- {
- Simulator::Instance()->RemoveHandler(this->name);
- return;
- }
- }
- }
-
- this->physics->SetStepType( *this->stepTypesIter );
- this->physics->SetStepTime( *this->stepTimesIter );
- this->physics->SetSORPGSIters( *this->stepItersIter );
-
- this->count++;
- std::cout << "Type[" << *this->stepTypesIter << "] "
- << "Time[" << *this->stepTimesIter << "] "
- << "Iters[" << *this->stepItersIter << "] "
- << "Count[" << this->count << "]\n";
-
- this->robot->Reset();
- this->prevTime = Simulator::Instance()->GetRealTime();
- Logger::Instance()->AddLog("pioneer");
- }
-}
Deleted: code/gazebo/branches/simpar/plugins/pioneer_spiral.hh
===================================================================
--- code/gazebo/branches/simpar/plugins/pioneer_spiral.hh 2010-06-02
15:00:16 UTC (rev 8749)
+++ code/gazebo/branches/simpar/plugins/pioneer_spiral.hh 2010-06-03
00:34:23 UTC (rev 8750)
@@ -1,43 +0,0 @@
-#ifndef pioneer_spiral_hh
-#define pioneer_spiral_hh
-
-#include <gazebo/gazeboserver.hh>
-
-namespace gazebo
-{
- class Model;
-
- class PioneerSpiral : public Handler
- {
- public: PioneerSpiral();
- public: virtual ~PioneerSpiral();
-
- public: void Load();
-
- public: void UpdateCB();
-
- public: void LeftContactCB(const Contact &contact);
- public: void RightContactCB(const Contact &contact);
-
- private: Model *robot;
- private: Body *leftWheel;
- private: Body *rightWheel;
- private: PhysicsEngine *physics;
- private: Time prevTime;
-
- private: std::vector<std::string> stepTypes;
- private: std::vector<std::string>::iterator stepTypesIter;
-
- private: std::vector<double> stepTimes;
- private: std::vector<double>::iterator stepTimesIter;
-
- private: std::vector<unsigned int> stepIters;
- private: std::vector<unsigned int>::iterator stepItersIter;
-
- private: unsigned int count;
- private: std::string path;
- private: FILE *indexFile;
- };
-}
-
-#endif
Modified: code/gazebo/branches/simpar/server/GazeboMessage.hh
===================================================================
--- code/gazebo/branches/simpar/server/GazeboMessage.hh 2010-06-02 15:00:16 UTC
(rev 8749)
+++ code/gazebo/branches/simpar/server/GazeboMessage.hh 2010-06-03 00:34:23 UTC
(rev 8750)
@@ -45,7 +45,7 @@
/// Output a message
#define gzmsg(level) (gazebo::GazeboMessage::Instance()->Msg(level) << "["
<< __FILE__ << ":" << __LINE__ << "]\n ")
- #define gzerr(level) (gazebo::GazeboMessage::Instance()->Err(level) <<
"Error: [" << __FILE__ << ":" << __LINE__ << "]\n ")
+ #define gzerr(level) (gazebo::GazeboMessage::Instance()->Err(level) <<
"\033[1;31m" << "Error: [" << __FILE__ << ":" << __LINE__ << "]" << "\033[0m"
<<"\n")
/// Log a message
#define gzlog() (gazebo::GazeboMessage::Instance()->Log() << "[" << __FILE__
<< ":" << __LINE__ << "] ")
Modified: code/gazebo/branches/simpar/server/Logger.cc
===================================================================
--- code/gazebo/branches/simpar/server/Logger.cc 2010-06-02 15:00:16 UTC
(rev 8749)
+++ code/gazebo/branches/simpar/server/Logger.cc 2010-06-03 00:34:23 UTC
(rev 8750)
@@ -3,6 +3,7 @@
#include "World.hh"
#include "Entity.hh"
#include "Simulator.hh"
+#include "GazeboMessage.hh"
#include "Logger.hh"
using namespace gazebo;
@@ -26,11 +27,13 @@
////////////////////////////////////////////////////////////////////////////////
// Add a log
-void Logger::AddLog(const std::string &entity)
+void Logger::AddLog(const std::string &entity, const std::string &filename)
{
- Logger::LogObj *newLog = new Logger::LogObj(entity + ".log");
- newLog->entityName = entity;
- this->logObjects.push_back(newLog);
+ Logger::LogObj *newLog = new Logger::LogObj(entity, filename);
+ if (newLog->valid)
+ this->logObjects.push_back(newLog);
+ else
+ delete newLog;
}
////////////////////////////////////////////////////////////////////////////////
@@ -41,7 +44,7 @@
for (iter = this->logObjects.begin(); iter != this->logObjects.end(); iter++)
{
- if ( (*iter)->entityName == entity)
+ if ( (*iter)->GetEntityName() == entity)
{
delete *iter;
this->logObjects.erase(iter);
@@ -64,14 +67,28 @@
////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////
/// Constructor
-Logger::LogObj::LogObj(const std::string &filename)
+Logger::LogObj::LogObj(const std::string &entityName, const std::string
&filename) : valid(false)
{
- std::string fullname = std::string("/tmp/") + filename;
- this->logFile.open(fullname.c_str(), std::fstream::out);
+ this->logFile.open(filename.c_str(), std::fstream::out);
this->startRealTime = Simulator::Instance()->GetRealTime();
- this->startSimTime = Simulator::Instance()->GetRealTime();
+ this->startSimTime = Simulator::Instance()->GetSimTime();
+ this->entity = World::Instance()->GetEntityByName(entityName);
+ if (!this->logFile.is_open())
+ {
+ gzerr(0) << "Unable to open file for logging:" << filename << "\n";
+ return;
+ }
+
+ if (!this->entity)
+ {
+ gzerr(0) << "Unable to find entity with name:" << entityName << "\n";
+ return;
+ }
+
this->logFile << "# Global_Sim_Time Global_Real_Time Accum_Sim_Time
Accum_Real_Time X Y Z Roll Pitch Yaw\n";
+
+ this->valid = true;
}
////////////////////////////////////////////////////////////////////////////////
@@ -85,8 +102,7 @@
// Update the log object
void Logger::LogObj::Update()
{
- Entity *entity = World::Instance()->GetEntityByName(this->entityName);
- if (entity)
+ if (this->entity)
{
Pose3d pose3d = entity->GetWorldPose();
Time simTime = Simulator::Instance()->GetSimTime();
@@ -106,3 +122,13 @@
<< " " << roll << " " << pitch << " " << yaw << "\n";
}
}
+
+////////////////////////////////////////////////////////////////////////////////
+// Get the entity name
+std::string Logger::LogObj::GetEntityName() const
+{
+ if (this->entity)
+ return this->entity->GetName();
+ else
+ return std::string("");
+}
Modified: code/gazebo/branches/simpar/server/Logger.hh
===================================================================
--- code/gazebo/branches/simpar/server/Logger.hh 2010-06-02 15:00:16 UTC
(rev 8749)
+++ code/gazebo/branches/simpar/server/Logger.hh 2010-06-03 00:34:23 UTC
(rev 8750)
@@ -43,7 +43,7 @@
public: virtual ~Logger();
/// \brief Add a log file
- public: void AddLog(const std::string &model);
+ public: void AddLog(const std::string &model, const std::string &filename);
/// \brief Remove a log
public: void RemoveLog(const std::string &entity);
@@ -53,11 +53,14 @@
private: class LogObj
{
- public: LogObj(const std::string &filename);
+ public: LogObj(const std::string &entityName,
+ const std::string &filename);
public: virtual ~LogObj();
public: void Update();
+ public: std::string GetEntityName() const;
- public: std::string entityName;
+ public: bool valid;
+ private: Entity *entity;
private: std::fstream logFile;
private: Time startSimTime;
private: Time startRealTime;
Modified: code/gazebo/branches/simpar/server/World.cc
===================================================================
--- code/gazebo/branches/simpar/server/World.cc 2010-06-02 15:00:16 UTC (rev
8749)
+++ code/gazebo/branches/simpar/server/World.cc 2010-06-03 00:34:23 UTC (rev
8750)
@@ -1554,7 +1554,7 @@
case libgazebo::SimulationRequestData::START_LOG:
{
- Logger::Instance()->AddLog(req->name);
+ Logger::Instance()->AddLog(req->name, req->strValue);
break;
}
Modified: code/gazebo/branches/simpar/server/physics/Joint.cc
===================================================================
--- code/gazebo/branches/simpar/server/physics/Joint.cc 2010-06-02 15:00:16 UTC
(rev 8749)
+++ code/gazebo/branches/simpar/server/physics/Joint.cc 2010-06-03 00:34:23 UTC
(rev 8750)
@@ -262,6 +262,9 @@
/// Reset the joint
void Joint::Reset()
{
+ this->SetForce(0,0);
+ this->SetMaxForce(0,0);
+ this->SetVelocity(0,0);
}
//////////////////////////////////////////////////////////////////////////////
Modified: code/gazebo/branches/simpar/server/physics/SurfaceParams.cc
===================================================================
--- code/gazebo/branches/simpar/server/physics/SurfaceParams.cc 2010-06-02
15:00:16 UTC (rev 8749)
+++ code/gazebo/branches/simpar/server/physics/SurfaceParams.cc 2010-06-03
00:34:23 UTC (rev 8750)
@@ -53,6 +53,9 @@
this->slip2 = 0.01;
this->enableFriction = true;
+
+ this->useGlobalERP = false;
+ this->useGlobalCFM = false;
}
//////////////////////////////////////////////////////////////////////////////
Modified: code/gazebo/branches/simpar/worlds/models/pioneer2dx.model
===================================================================
--- code/gazebo/branches/simpar/worlds/models/pioneer2dx.model 2010-06-02
15:00:16 UTC (rev 8749)
+++ code/gazebo/branches/simpar/worlds/models/pioneer2dx.model 2010-06-03
00:34:23 UTC (rev 8750)
@@ -64,8 +64,6 @@
<xyz>0.1 -0.17 -0.0725</xyz>
<rpy>0 90 90</rpy>
- <dampingFactor>0.0001</dampingFactor>
-
<geom:cylinder name="left_wheel_geom">
<size>0.075 0.05</size>
<mass>0.5</mass>
@@ -99,7 +97,6 @@
<body:cylinder name="right_wheel">
<xyz>0.1 0.17 -0.0725</xyz>
<rpy>0 90 90</rpy>
- <dampingFactor>0.0001</dampingFactor>
<geom:cylinder name="right_wheel_geom">
<size>0.075 0.05</size>
@@ -133,7 +130,6 @@
<body:sphere name="castor_body">
<xyz>-0.200 0 -0.108</xyz>
<rpy>0 0 0</rpy>
- <dampingFactor>0.0001</dampingFactor>
<geom:sphere name="castor_geom">
<size>0.04</size>
Modified: code/gazebo/branches/simpar/worlds/pioneer2dx.world
===================================================================
--- code/gazebo/branches/simpar/worlds/pioneer2dx.world 2010-06-02 15:00:16 UTC
(rev 8749)
+++ code/gazebo/branches/simpar/worlds/pioneer2dx.world 2010-06-03 00:34:23 UTC
(rev 8750)
@@ -96,7 +96,7 @@
-->
<model:physical name="pioneer">
- <xyz>0 0 0.147</xyz>
+ <xyz>0 0 0.148</xyz>
<rpy>0.0 0.0 0.0</rpy>
<!--
Modified: code/gazebo/branches/simpar/worlds/simpleshapes.world
===================================================================
--- code/gazebo/branches/simpar/worlds/simpleshapes.world 2010-06-02
15:00:16 UTC (rev 8749)
+++ code/gazebo/branches/simpar/worlds/simpleshapes.world 2010-06-03
00:34:23 UTC (rev 8750)
@@ -43,6 +43,7 @@
<material>Gazebo/CloudySky</material>
</sky>
<grid>false</grid>
+ <shadows>false</shadows>
</rendering:ogre>
<model:physical name="sphere1_model">
@@ -59,9 +60,9 @@
<visual>
<size>0.4 0.4 0.4</size>
- <mesh>unit_sphere</mesh>
+ <mesh>lightsensor.3ds</mesh>
<shader>pixel</shader>
- <material>Gazebo/Rocky</material>
+ <!--<material>Gazebo/Rocky</material>-->
</visual>
</geom:sphere>
</body:sphere>
This was sent by the SourceForge.net collaborative development platform, the
world's largest Open Source development site.
------------------------------------------------------------------------------
ThinkGeek and WIRED's GeekDad team up for the Ultimate
GeekDad Father's Day Giveaway. ONE MASSIVE PRIZE to the
lucky parental unit. See the prize list and enter to win:
http://p.sf.net/sfu/thinkgeek-promo
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit