Revision: 7393
http://playerstage.svn.sourceforge.net/playerstage/?rev=7393&view=rev
Author: natepak
Date: 2009-03-09 02:15:32 +0000 (Mon, 09 Mar 2009)
Log Message:
-----------
Geoms check for valid spaceid when setting collide bits
Modified Paths:
--------------
code/branches/federation/gazebo/examples/libgazebo/simiface/simiface.cc
code/branches/federation/gazebo/libgazebo/SConscript
code/branches/federation/gazebo/libgazebo/SimIface.cc
code/branches/federation/gazebo/libgazebo/gazebo.h
code/branches/federation/gazebo/player/SimulationInterface.cc
code/branches/federation/gazebo/server/World.cc
code/branches/federation/gazebo/server/physics/Geom.cc
code/branches/federation/gazebo/worlds/federation.world
code/branches/federation/gazebo/worlds/pioneer2dx.world
Modified:
code/branches/federation/gazebo/examples/libgazebo/simiface/simiface.cc
===================================================================
--- code/branches/federation/gazebo/examples/libgazebo/simiface/simiface.cc
2009-03-09 00:06:43 UTC (rev 7392)
+++ code/branches/federation/gazebo/examples/libgazebo/simiface/simiface.cc
2009-03-09 02:15:32 UTC (rev 7393)
@@ -35,7 +35,7 @@
//simIface->data->reset = 1;
// Example of how to move a model (box1_model)
- char name[512] = "pioneer2dx_model1";
+ /*char name[512] = "pioneer2dx_model1";
for (int i=0; i< 10; i++)
{
@@ -52,9 +52,13 @@
simIface->SetState(name, pose, linearVel, angularVel,
linearAccel, angularAccel );
usleep(90000000);
- }
+ }*/
+ printf("Go\n");
+ simIface->Go(100);
+ printf("Go Done\n");
+
// Example of resetting the simulator
// simIface->Reset();
//usleep(1000000);
Modified: code/branches/federation/gazebo/libgazebo/SConscript
===================================================================
--- code/branches/federation/gazebo/libgazebo/SConscript 2009-03-09
00:06:43 UTC (rev 7392)
+++ code/branches/federation/gazebo/libgazebo/SConscript 2009-03-09
02:15:32 UTC (rev 7393)
@@ -25,6 +25,7 @@
myEnv = Environment (
CC = 'g++',
CCFLAGS = Split ('-pthread -pipe -W -Wall -O2'),
+ LIBS=Split('boost_signals boost_thread'),
CXXCOMSTR = 'Compiling $TARGET',
CCCOMSTR = 'Compiling $TARGET',
Modified: code/branches/federation/gazebo/libgazebo/SimIface.cc
===================================================================
--- code/branches/federation/gazebo/libgazebo/SimIface.cc 2009-03-09
00:06:43 UTC (rev 7392)
+++ code/branches/federation/gazebo/libgazebo/SimIface.cc 2009-03-09
02:15:32 UTC (rev 7393)
@@ -1,3 +1,5 @@
+#include <boost/thread/thread.hpp>
+#include <boost/bind.hpp>
#include <string.h>
#include "gazebo.h"
@@ -3,5 +5,30 @@
using namespace gazebo;
+void SimulationIface::BlockThread(unsigned int ms)
+{
+ printf("Run thread\n");
+ boost::this_thread::sleep(boost::posix_time::milliseconds(ms));
+ printf("Run thread done\n");
+}
+
////////////////////////////////////////////////////////////////////////////////
+/// Tell gazebo to execute for a specified amount of time
+void SimulationIface::Go(unsigned int ms)
+{
+ this->Lock(1);
+ SimulationRequestData *request =
&(this->data->requests[this->data->requestCount++]);
+ request->type = SimulationRequestData::GO;
+ request->runTime = ms;
+ this->Unlock();
+
+ printf("Create Thread\n");
+ /*boost::thread *thread = new boost::thread(
+ boost::bind(&SimulationIface::BlockThread, this, boost::_1)(100) );
+ */
+
+ printf("Thread created\n");
+}
+
+////////////////////////////////////////////////////////////////////////////////
/// Pause the simulation
void SimulationIface::Pause()
Modified: code/branches/federation/gazebo/libgazebo/gazebo.h
===================================================================
--- code/branches/federation/gazebo/libgazebo/gazebo.h 2009-03-09 00:06:43 UTC
(rev 7392)
+++ code/branches/federation/gazebo/libgazebo/gazebo.h 2009-03-09 02:15:32 UTC
(rev 7393)
@@ -395,7 +395,8 @@
GET_POSE2D,
SET_POSE3D,
SET_POSE2D,
- SET_STATE
+ SET_STATE,
+ GO
};
public: Type type;
@@ -405,6 +406,7 @@
public: Vec3 modelAngularVel;
public: Vec3 modelLinearAccel;
public: Vec3 modelAngularAccel;
+ public: double runTime;
};
/// \brief Simulation interface data
@@ -461,6 +463,10 @@
this->data =
(SimulationData*)((char*)this->mMap+sizeof(SimulationIface));
}
+ /// \brief Tell gazebo to execute for a specified amount of time
+ /// \param ms Number of milliseconds to run
+ public: void Go(unsigned int ms);
+
/// \brief Pause the simulation
public: void Pause();
@@ -487,6 +493,8 @@
const Vec3 &linearVel, const Vec3 &angularVel,
const Vec3 &linearAccel, const Vec3 &angularAccel );
+ private: void BlockThread(unsigned int ms);
+
/// Pointer to the simulation data
public: SimulationData *data;
};
Modified: code/branches/federation/gazebo/player/SimulationInterface.cc
===================================================================
--- code/branches/federation/gazebo/player/SimulationInterface.cc
2009-03-09 00:06:43 UTC (rev 7392)
+++ code/branches/federation/gazebo/player/SimulationInterface.cc
2009-03-09 02:15:32 UTC (rev 7393)
@@ -246,6 +246,7 @@
switch (response->type)
{
case gazebo::SimulationRequestData::SET_STATE:
+ case gazebo::SimulationRequestData::GO:
case gazebo::SimulationRequestData::PAUSE:
case gazebo::SimulationRequestData::RESET:
case gazebo::SimulationRequestData::SAVE:
Modified: code/branches/federation/gazebo/server/World.cc
===================================================================
--- code/branches/federation/gazebo/server/World.cc 2009-03-09 00:06:43 UTC
(rev 7392)
+++ code/branches/federation/gazebo/server/World.cc 2009-03-09 02:15:32 UTC
(rev 7393)
@@ -682,8 +682,14 @@
break;
}
- case SimulationRequestData::SET_POSE2D:
+ case SimulationRequestData::GO:
{
+ printf("World got a go\n");
+ break;
+ }
+
+ case SimulationRequestData::SET_POSE2D:
+ {
Model *model = this->GetModelByName((char*)req->modelName);
if (model)
{
Modified: code/branches/federation/gazebo/server/physics/Geom.cc
===================================================================
--- code/branches/federation/gazebo/server/physics/Geom.cc 2009-03-09
00:06:43 UTC (rev 7392)
+++ code/branches/federation/gazebo/server/physics/Geom.cc 2009-03-09
02:15:32 UTC (rev 7393)
@@ -385,16 +385,20 @@
/// Set the category bits, used during collision detection
void Geom::SetCategoryBits(unsigned int bits)
{
- dGeomSetCategoryBits(this->geomId, bits);
- dGeomSetCategoryBits((dGeomID)this->spaceId, bits);
+ if (this->geomId)
+ dGeomSetCategoryBits(this->geomId, bits);
+ if (this->spaceId)
+ dGeomSetCategoryBits((dGeomID)this->spaceId, bits);
}
////////////////////////////////////////////////////////////////////////////////
/// Set the collide bits, used during collision detection
void Geom::SetCollideBits(unsigned int bits)
{
- dGeomSetCollideBits(this->geomId, bits);
- dGeomSetCollideBits((dGeomID)this->spaceId, bits);
+ if (this->geomId)
+ dGeomSetCollideBits(this->geomId, bits);
+ if (this->spaceId)
+ dGeomSetCollideBits((dGeomID)this->spaceId, bits);
}
////////////////////////////////////////////////////////////////////////////////
Modified: code/branches/federation/gazebo/worlds/federation.world
===================================================================
--- code/branches/federation/gazebo/worlds/federation.world 2009-03-09
00:06:43 UTC (rev 7392)
+++ code/branches/federation/gazebo/worlds/federation.world 2009-03-09
02:15:32 UTC (rev 7393)
@@ -65,7 +65,7 @@
</body:plane>
</model:physical>
- <model:physical name="sphere1_model">
+ <!--<model:physical name="sphere1_model">
<xyz>2.15 -1.68 .3</xyz>
<rpy>0.0 0.0 0.0</rpy>
<static>true</static>
@@ -82,17 +82,9 @@
</geom:sphere>
</body:sphere>
</model:physical>
-
-
- <!--
- Include the complete model described in the .model file
- This assumes the root node is a <model:...>
-->
- <!-- <include embedded="false">
- <xi:include href="pioneer2dx.model" />
- </include>
- -->
+ <!--
<model:physical name="pioneer2dx_model1">
<xyz>2 2 .145</xyz>
<rpy>0.0 0.0 90.0</rpy>
@@ -126,6 +118,7 @@
<xi:include href="models/pioneer2dx.model" />
</include>
</model:physical>
+ -->
<!-- White Point light -->
<model:renderable name="point_white">
Modified: code/branches/federation/gazebo/worlds/pioneer2dx.world
===================================================================
--- code/branches/federation/gazebo/worlds/pioneer2dx.world 2009-03-09
00:06:43 UTC (rev 7392)
+++ code/branches/federation/gazebo/worlds/pioneer2dx.world 2009-03-09
02:15:32 UTC (rev 7393)
@@ -98,7 +98,7 @@
<rpy>0.0 0.0 90.0</rpy>
<enableGravity>false</enableGravity>
<enableFriction>false</enableFriction>
- <collide>ghost</collide>
+ <!--<collide>ghost</collide>-->
<controller:differential_position2d name="controller1">
<leftJoint>left_wheel_hinge</leftJoint>
@@ -112,7 +112,7 @@
<model:physical name="laser">
<xyz>0.15 0 0.18</xyz>
<enableGravity>false</enableGravity>
- <collide>ghost</collide>
+ <!-- <collide>ghost</collide>-->
<attach>
<parentBody>chassis_body</parentBody>
This was sent by the SourceForge.net collaborative development platform, the
world's largest Open Source development site.
------------------------------------------------------------------------------
Open Source Business Conference (OSBC), March 24-25, 2009, San Francisco, CA
-OSBC tackles the biggest issue in open source: Open Sourcing the Enterprise
-Strategies to boost innovation and cut costs with open source participation
-Receive a $600 discount off the registration fee with the source code: SFAD
http://p.sf.net/sfu/XcvMzF8H
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit