Revision: 4444
http://playerstage.svn.sourceforge.net/playerstage/?rev=4444&view=rev
Author: natepak
Date: 2008-03-26 15:53:54 -0700 (Wed, 26 Mar 2008)
Log Message:
-----------
Updates to stereo vision
Modified Paths:
--------------
code/gazebo/trunk/SConstruct
code/gazebo/trunk/server/GazeboMessage.cc
code/gazebo/trunk/server/GazeboMessage.hh
code/gazebo/trunk/server/main.cc
code/gazebo/trunk/server/rendering/OgreCreator.cc
code/gazebo/trunk/server/rendering/OgreVisual.cc
code/gazebo/trunk/server/sensors/camera/CameraSensor.hh
code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc
code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.hh
code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc
code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.hh
code/gazebo/trunk/worlds/stereocamera.world
code/gazebo/trunk/worlds/test.world
Modified: code/gazebo/trunk/SConstruct
===================================================================
--- code/gazebo/trunk/SConstruct 2008-03-26 08:59:00 UTC (rev 4443)
+++ code/gazebo/trunk/SConstruct 2008-03-26 22:53:54 UTC (rev 4444)
@@ -85,7 +85,8 @@
if env['mode'] == 'debug':
env['CCFLAGS'] += Split('-ggdb -g3')
elif env['mode'] == 'profile':
- env['CCFLAGS'] += Split('-p -pg')
+ env['CCFLAGS'] += Split('-pg')
+ env['LINKFLAGS'] += Split('-pg')
elif env['mode'] == 'optimized':
env['CCFLAGS'] += Split('-O3')
Modified: code/gazebo/trunk/server/GazeboMessage.cc
===================================================================
--- code/gazebo/trunk/server/GazeboMessage.cc 2008-03-26 08:59:00 UTC (rev
4443)
+++ code/gazebo/trunk/server/GazeboMessage.cc 2008-03-26 22:53:54 UTC (rev
4444)
@@ -39,6 +39,8 @@
GazeboMessage::GazeboMessage()
{
this->msgStream = &std::cout;
+ this->errStream = &std::cerr;
+
this->level = 0;
}
@@ -128,6 +130,16 @@
}
////////////////////////////////////////////////////////////////////////////////
+/// Get the error stream
+std::ostream &GazeboMessage::Err( int msglevel )
+{
+ if (msglevel <= this->level)
+ return *this->errStream;
+ else
+ return this->nullStream;
+}
+
+////////////////////////////////////////////////////////////////////////////////
// Log a message
std::ofstream &GazeboMessage::Log()
{
Modified: code/gazebo/trunk/server/GazeboMessage.hh
===================================================================
--- code/gazebo/trunk/server/GazeboMessage.hh 2008-03-26 08:59:00 UTC (rev
4443)
+++ code/gazebo/trunk/server/GazeboMessage.hh 2008-03-26 22:53:54 UTC (rev
4444)
@@ -42,6 +42,8 @@
/// 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 ")
/// Log a message
#define gzlog() (gazebo::GazeboMessage::Instance()->Log() << "[" << __FILE__
<< ":" << __LINE__ << "] ")
@@ -85,6 +87,10 @@
/// \brief Use this to output a message to the terminal
/// \param level Level of the message
public: std::ostream &Msg( int level = 0 );
+
+ /// \brief Use this to output an error to the terminal
+ /// \param level Level of the message
+ public: std::ostream &Err( int level = 0 );
/// \brief Use this to output a message to a log file
public: std::ofstream &Log();
@@ -97,6 +103,7 @@
private: std::ostringstream nullStream;
private: std::ostream *msgStream;
+ private: std::ostream *errStream;
private: std::ofstream logStream;
/// Pointer to myself
Modified: code/gazebo/trunk/server/main.cc
===================================================================
--- code/gazebo/trunk/server/main.cc 2008-03-26 08:59:00 UTC (rev 4443)
+++ code/gazebo/trunk/server/main.cc 2008-03-26 22:53:54 UTC (rev 4444)
@@ -331,6 +331,8 @@
return -1;
}
+ printf("Finalize\n");
+
// Finalization and clean up
try
{
@@ -343,5 +345,6 @@
return -1;
}
+ printf("Quit\n");
return 0;
}
Modified: code/gazebo/trunk/server/rendering/OgreCreator.cc
===================================================================
--- code/gazebo/trunk/server/rendering/OgreCreator.cc 2008-03-26 08:59:00 UTC
(rev 4443)
+++ code/gazebo/trunk/server/rendering/OgreCreator.cc 2008-03-26 22:53:54 UTC
(rev 4444)
@@ -166,8 +166,8 @@
// Helper function to create a camera
Ogre::Camera *OgreCreator::CreateCamera(const std::string &name, double
nearClip, double farClip, double hfov, Ogre::RenderTarget *renderTarget)
{
+ Ogre::Camera *camera;
Ogre::Viewport *cviewport;
- Ogre::Camera *camera;
camera = OgreAdaptor::Instance()->sceneMgr->createCamera(name);
Modified: code/gazebo/trunk/server/rendering/OgreVisual.cc
===================================================================
--- code/gazebo/trunk/server/rendering/OgreVisual.cc 2008-03-26 08:59:00 UTC
(rev 4443)
+++ code/gazebo/trunk/server/rendering/OgreVisual.cc 2008-03-26 22:53:54 UTC
(rev 4444)
@@ -73,7 +73,7 @@
Pose3d pose;
Vector3 size;
Ogre::Vector3 meshSize;
- Ogre::MovableObject *obj;
+ Ogre::MovableObject *obj = NULL;
this->xmlNode=node;
std::string meshName = node->GetString("mesh","",1);
@@ -91,17 +91,20 @@
}
catch (Ogre::Exception e)
{
+ std::cerr << "Ogre Error:" << e.getFullDescription() << "\n";
gzthrow("Unable to create a mesh from " + meshName);
}
// Attach the entity to the node
- this->AttachObject(obj);
+ if (obj)
+ this->AttachObject(obj);
// Set the pose of the scene node
this->SetPose(pose);
// Get the size of the mesh
- meshSize = obj->getBoundingBox().getSize();
+ if (obj)
+ meshSize = obj->getBoundingBox().getSize();
// Get the desired size of the mesh
if (node->GetChild("size") != NULL)
Modified: code/gazebo/trunk/server/sensors/camera/CameraSensor.hh
===================================================================
--- code/gazebo/trunk/server/sensors/camera/CameraSensor.hh 2008-03-26
08:59:00 UTC (rev 4443)
+++ code/gazebo/trunk/server/sensors/camera/CameraSensor.hh 2008-03-26
22:53:54 UTC (rev 4444)
@@ -109,12 +109,11 @@
/// \brief Get the height of the texture
public: unsigned int GetTextureHeight() const;
- /// \brief Get a pointer to the image data
- public: virtual const unsigned char *GetImageData() = 0;
-
/// \brief Get the image size in bytes
public: size_t GetImageByteSize() const;
+ public: virtual const unsigned char *GetImageData(unsigned int i=0) = 0;
+
/// \brief Get the Z-buffer value at the given image coordinate.
///
/// \param x, y Image coordinate; (0, 0) specifies the top-left corner.
Modified: code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc
===================================================================
--- code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc 2008-03-26
08:59:00 UTC (rev 4443)
+++ code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc 2008-03-26
22:53:54 UTC (rev 4444)
@@ -93,6 +93,8 @@
Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
+
mat->getTechnique(0)->getPass(0)->createTextureUnitState(this->ogreTextureName);
+
Ogre::HardwarePixelBufferSharedPtr mBuffer;
// Get access to the buffer and make an image and write it to file
@@ -128,8 +130,11 @@
//////////////////////////////////////////////////////////////////////////////
/// Get a pointer to the image data
-const unsigned char *MonoCameraSensor::GetImageData()
+const unsigned char *MonoCameraSensor::GetImageData(unsigned int i)
{
+ if (i!=0)
+ gzerr(0) << "Camera index must be zero for mono cam";
+
Ogre::HardwarePixelBufferSharedPtr mBuffer;
size_t size;
Modified: code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.hh
===================================================================
--- code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.hh 2008-03-26
08:59:00 UTC (rev 4443)
+++ code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.hh 2008-03-26
22:53:54 UTC (rev 4444)
@@ -82,7 +82,7 @@
public: virtual std::string GetMaterialName() const;
/// \brief Get a pointer to the image data
- public: virtual const unsigned char *GetImageData();
+ public: virtual const unsigned char *GetImageData(unsigned int i=0);
// Save the camera frame
private: void SaveFrame();
Modified: code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc
===================================================================
--- code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc
2008-03-26 08:59:00 UTC (rev 4443)
+++ code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc
2008-03-26 22:53:54 UTC (rev 4444)
@@ -26,6 +26,7 @@
#include <sstream>
#include <OgreImageCodec.h>
+#include <GL/gl.h>
#include <Ogre.h>
#include "Global.hh"
@@ -64,19 +65,22 @@
void StereoCameraSensor::LoadChild( XMLConfigNode *node )
{
CameraSensor::LoadChild(node);
+
+ this->baseline = node->GetDouble("baseline",0,1);
}
//////////////////////////////////////////////////////////////////////////////
// Initialize the camera
void StereoCameraSensor::InitChild()
{
- this->leftOgreTextureName = this->GetName() + "_LEFTRttTex";
- this->rightOgreTextureName = this->GetName() + "_RIGHTRttTex";
+ this->leftOgreTextureName = this->GetName() + "_RttTex_Stereo_Left";
+ this->rightOgreTextureName = this->GetName() + "_RttTex_Stereo_Right";
- this->ogreMaterialName = this->GetName() + "_RttMat";
+ this->leftOgreMaterialName = this->GetName() + "_RttMat_Stereo_Left";
+ this->rightOgreMaterialName = this->GetName() + "_RttMat_Stereo_Right";
// Create the render texture
- this->leftRenderTexture = Ogre::TextureManager::getSingleton().createManual(
+ this->renderTexture[0] = Ogre::TextureManager::getSingleton().createManual(
this->leftOgreTextureName,
Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
Ogre::TEX_TYPE_2D,
@@ -84,9 +88,9 @@
Ogre::PF_R8G8B8,
Ogre::TU_RENDERTARGET);
- this->leftRenderTarget =
this->leftRenderTexture->getBuffer()->getRenderTarget();
+ this->leftRenderTarget =
this->renderTexture[0]->getBuffer()->getRenderTarget();
- this->rightRenderTexture = Ogre::TextureManager::getSingleton().createManual(
+ this->renderTexture[1] = Ogre::TextureManager::getSingleton().createManual(
this->rightOgreTextureName,
Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
Ogre::TEX_TYPE_2D,
@@ -94,7 +98,7 @@
Ogre::PF_R8G8B8,
Ogre::TU_RENDERTARGET);
- this->rightRenderTarget =
this->rightRenderTexture->getBuffer()->getRenderTarget();
+ this->rightRenderTarget =
this->renderTexture[1]->getBuffer()->getRenderTarget();
// Create the camera
this->camera = OgreCreator::CreateCamera(this->GetName(),
@@ -111,20 +115,27 @@
cviewport->setOverlaysEnabled(false);
}
- Ogre::MaterialPtr mat = Ogre::MaterialManager::getSingleton().create(
- this->ogreMaterialName,
+ Ogre::MaterialPtr leftmat = Ogre::MaterialManager::getSingleton().create(
+ this->leftOgreMaterialName,
Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
+ Ogre::MaterialPtr rightmat = Ogre::MaterialManager::getSingleton().create(
+ this->rightOgreMaterialName,
+
Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
+
+
leftmat->getTechnique(0)->getPass(0)->createTextureUnitState(this->leftOgreTextureName);
+
rightmat->getTechnique(0)->getPass(0)->createTextureUnitState(this->rightOgreTextureName);
+
Ogre::HardwarePixelBufferSharedPtr mBuffer;
// Get access to the buffer and make an image and write it to file
- mBuffer = this->leftRenderTexture->getBuffer(0, 0);
+ mBuffer = this->renderTexture[0]->getBuffer(0, 0);
this->textureWidth = mBuffer->getWidth();
this->textureHeight = mBuffer->getHeight();
- this->leftCameraListener.Init(this, true);
- this->rightCameraListener.Init(this, false);
+ this->leftCameraListener.Init(this, this->leftRenderTarget, true);
+ this->rightCameraListener.Init(this, this->rightRenderTarget, false);
this->leftRenderTarget->addListener(&this->leftCameraListener);
this->rightRenderTarget->addListener(&this->rightCameraListener);
@@ -149,18 +160,24 @@
// Return the material the camera renders to
std::string StereoCameraSensor::GetMaterialName() const
{
- return this->ogreMaterialName;
+ return this->leftOgreMaterialName;
}
//////////////////////////////////////////////////////////////////////////////
/// Get a pointer to the image data
-const unsigned char *StereoCameraSensor::GetImageData()
+const unsigned char *StereoCameraSensor::GetImageData(unsigned int i)
{
Ogre::HardwarePixelBufferSharedPtr mBuffer;
size_t size;
+ if (i > 1)
+ {
+ gzerr(0) << "Camera index must be 0=Left or 1=Right for stereo camera\n";
+ i = 1;
+ }
+
// Get access to the buffer and make an image and write it to file
- mBuffer = this->leftRenderTexture->getBuffer(0, 0);
+ mBuffer = this->renderTexture[i]->getBuffer(0, 0);
size = this->imageWidth * this->imageHeight * 3;
@@ -202,94 +219,166 @@
Ogre::Codec * pCodec;
size_t size, pos;
- this->GetImageData();
+ for (int i=0; i<2; i++)
+ {
+ this->GetImageData(i);
- // Get access to the buffer and make an image and write it to file
- mBuffer = this->leftRenderTexture->getBuffer(0, 0);
+ // Get access to the buffer and make an image and write it to file
+ mBuffer = this->renderTexture[i]->getBuffer(0, 0);
- // Create image data structure
- imgData = new Ogre::ImageCodec::ImageData();
+ // Create image data structure
+ imgData = new Ogre::ImageCodec::ImageData();
- imgData->width = this->imageWidth;
- imgData->height = this->imageHeight;
- imgData->depth = 1;
- imgData->format = Ogre::PF_B8G8R8;
- size = this->GetImageByteSize();
+ imgData->width = this->imageWidth;
+ imgData->height = this->imageHeight;
+ imgData->depth = 1;
+ imgData->format = Ogre::PF_B8G8R8;
+ size = this->GetImageByteSize();
- // Wrap buffer in a chunk
- Ogre::MemoryDataStreamPtr stream(new Ogre::MemoryDataStream(
this->saveFrameBuffer, size, false));
+ // Wrap buffer in a chunk
+ Ogre::MemoryDataStreamPtr stream(new Ogre::MemoryDataStream(
this->saveFrameBuffer, size, false));
- char tmp[1024];
- if (!this->savePathname.empty())
- {
- sprintf(tmp, "%s/%s-%04d.jpg", this->savePathname.c_str(),
+ char tmp[1024];
+ if (!this->savePathname.empty())
+ {
+ if (i==0)
+ sprintf(tmp, "%s/%s-%04d-left.png", this->savePathname.c_str(),
this->GetName().c_str(), this->saveCount);
+ else
+ sprintf(tmp, "%s/%s-%04d-right.png", this->savePathname.c_str(),
+ this->GetName().c_str(), this->saveCount);
+ }
+ else
+ {
+ if (i==0)
+ sprintf(tmp, "%s-%04d-left.png", this->GetName().c_str(),
this->saveCount);
+ else
+ sprintf(tmp, "%s-%04d-right.png", this->GetName().c_str(),
this->saveCount);
+ }
+
+ // Get codec
+ Ogre::String filename = tmp;
+ pos = filename.find_last_of(".");
+ Ogre::String extension;
+
+ while (pos != filename.length() - 1)
+ extension += filename[++pos];
+
+ // Get the codec
+ pCodec = Ogre::Codec::getCodec(extension);
+
+ // Write out
+ Ogre::Codec::CodecDataPtr codecDataPtr(imgData);
+ pCodec->codeToFile(stream, filename, codecDataPtr);
}
- else
- {
- sprintf(tmp, "%s-%04d.jpg", this->GetName().c_str(), this->saveCount);
+
+ this->saveCount++;
+}
+
+//void StereCameraSensor::UpdateAllDependentRenderTargets()
+//{
+/* Ogre::RenderTargetList::iterator iter;
+
+ for( iter = mRenderTargetList.begin(); iter != mRenderTargetList.end();
++iter )
+ {
(*iter)->update();
}
+ */
+//}
- // Get codec
- Ogre::String filename = tmp;
- pos = filename.find_last_of(".");
- Ogre::String extension;
+////////////////////////////////////////////////////////////////////////////////
+/// Get the baselien of the camera
+double StereoCameraSensor::GetBaseline() const
+{
+ return this->baseline;
+}
- while (pos != filename.length() - 1)
- extension += filename[++pos];
+////////////////////////////////////////////////////////////////////////////////
+// Read the depth data
+void StereoCameraSensor::ReadDepthImage()
+{
+ float *depthImage = new float[this->imageWidth * this->imageHeight];
- // Get the codec
- pCodec = Ogre::Codec::getCodec(extension);
+ glPixelStorei(GL_PACK_ALIGNMENT, 1);
+ glReadBuffer(GL_BACK);
+ glReadPixels(0, 0, this->imageWidth, this->imageHeight, GL_DEPTH_COMPONENT,
GL_FLOAT, depthImage);
- // Write out
- Ogre::Codec::CodecDataPtr codecDataPtr(imgData);
- pCodec->codeToFile(stream, filename, codecDataPtr);
+ char tmp[1024];
+ FILE *fp;
- this->saveCount++;
+ // Save depth image
+ sprintf(tmp, "left_depth_%04d.pnm", this->saveCount++);
+ fp = fopen( tmp, "wb" );
+ if (!fp)
+ {
+ printf( "unable to open file %s\n for writing\n", tmp );
+ return;
+ }
+
+ fprintf( fp, "P5\n# Gazebo\n%d %d\n255\n", this->imageWidth,
this->imageHeight);
+ unsigned char *dst = new unsigned char[this->imageWidth];
+ float a = (this->nearClip * this->farClip) / (this->farClip -
this->nearClip);
+ float b = -this->nearClip / (this->farClip - this->nearClip);
+
+ for (int i = this->imageHeight-1; i >= 0; i--)
+ {
+ float *src = depthImage + i * this->imageWidth;
+ for (int j = 0; j < this->imageWidth; j++)
+ {
+ dst[j] = src[j];
+ printf("%4.2f ",src[j]);
+ /*if (src[j] < 1e-6)
+ dst[j] = 0;
+ else
+ dst[j] = (int) (255 * (a / src[j] + b));
+ */
+ }
+ printf("\n");
+ fwrite( dst, 1, this->imageWidth, fp);
+ }
+ fclose( fp);
+
}
void StereoCameraSensor::StereoCameraListener::Init(
- StereoCameraSensor *cam, bool isLeft)
+ StereoCameraSensor *cam, Ogre::RenderTarget *target, bool isLeft)
{
this->sensor = cam;
this->camera = this->sensor->GetOgreCamera();
+ this->renderTarget = target;
this->isLeftCamera = isLeft;
}
void StereoCameraSensor::StereoCameraListener::preViewportUpdate(const
Ogre::RenderTargetViewportEvent &evt)
{
- if (this->isLeftCamera)
- printf("Left Pre\n");
- else
- printf("Rightt Pre\n");
+ if(evt.source != this->renderTarget->getViewport(0))
+ {
+ printf("Invalid viewport");
+ return;
+ }
-/* if(evt.source != mViewport)
- return;
- Real offset = mStereoMgr->getEyesSpacing()/2;
- if(mIsLeftEye)
+ double offset = this->sensor->GetBaseline()/2;
+
+ if(this->isLeftCamera)
{
offset = -offset;
}
- mCamera->setFrustumOffset(-offset,0);
- mPos = mCamera->getPosition();
- Vector3 pos = mPos;
- pos += offset * mCamera->getRight();
- mCamera->setPosition(pos);
- mStereoMgr->updateAllDependentRenderTargets();
- mStereoMgr->chooseDebugPlaneMaterial(mIsLeftEye);
- */
+ this->camera->setFrustumOffset(-offset,0);
+
+ this->pos = this->camera->getPosition();
+ Ogre::Vector3 pos = this->pos;
+
+ pos += offset * this->camera->getRight();
+ this->camera->setPosition(pos);
+
+ //this->sensor->UpdateAllDependentRenderTargets();
+ //this->sensor->chooseDebugPlaneMaterial(mIsLeftEye);
}
void StereoCameraSensor::StereoCameraListener::postViewportUpdate(const
Ogre::RenderTargetViewportEvent &evt)
{
- if (this->isLeftCamera)
- printf("Left Post\n");
- else
- printf("Rightt Post\n");
+ this->sensor->ReadDepthImage();
-/* mCamera->setFrustumOffset(0,0);
- mCamera->setPosition(mPos);
- */
-
+ this->camera->setFrustumOffset(0,0);
+ this->camera->setPosition(this->pos);
}
Modified: code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.hh
===================================================================
--- code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.hh
2008-03-26 08:59:00 UTC (rev 4443)
+++ code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.hh
2008-03-26 22:53:54 UTC (rev 4444)
@@ -81,32 +81,43 @@
public: virtual std::string GetMaterialName() const;
/// \brief Get a pointer to the image data
- public: virtual const unsigned char *GetImageData();
+ public: virtual const unsigned char *GetImageData(unsigned int i=0);
+ /// \brief Get the baselien of the camera
+ public: double GetBaseline() const;
+
// Save the camera frame
protected: virtual void SaveFrame();
- private: Ogre::TexturePtr leftRenderTexture;
+ private: void ReadDepthImage();
+
+ //private: void UpdateAllDependentRenderTargets();
+
+ private: Ogre::TexturePtr renderTexture[2];
private: Ogre::RenderTarget *leftRenderTarget;
- private: Ogre::TexturePtr rightRenderTexture;
private: Ogre::RenderTarget *rightRenderTarget;
private: std::string leftOgreTextureName;
private: std::string rightOgreTextureName;
- private: std::string ogreMaterialName;
+ private: std::string leftOgreMaterialName;
+ private: std::string rightOgreMaterialName;
+ private: double baseline;
+
private:
class StereoCameraListener : public Ogre::RenderTargetListener
{
public: StereoCameraListener() : Ogre::RenderTargetListener() {}
- public: void Init(StereoCameraSensor *sensor, bool isLeft);
+
+ public: void Init(StereoCameraSensor *sensor, Ogre::RenderTarget
*target, bool isLeft);
public: void preViewportUpdate(const
Ogre::RenderTargetViewportEvent &evt);
public: void postViewportUpdate(const
Ogre::RenderTargetViewportEvent &evt);
private: Ogre::Vector3 pos;
private: StereoCameraSensor *sensor;
private: Ogre::Camera *camera;
+ private: Ogre::RenderTarget *renderTarget;
private: bool isLeftCamera;
};
Modified: code/gazebo/trunk/worlds/stereocamera.world
===================================================================
--- code/gazebo/trunk/worlds/stereocamera.world 2008-03-26 08:59:00 UTC (rev
4443)
+++ code/gazebo/trunk/worlds/stereocamera.world 2008-03-26 22:53:54 UTC (rev
4444)
@@ -36,7 +36,7 @@
</rendering:ogre>
<model:physical name="sphere1_model">
- <xyz>1 0 1.5</xyz>
+ <xyz>4 -1 1.5</xyz>
<rpy>0.0 0.0 0.0</rpy>
<static>false</static>
@@ -55,7 +55,7 @@
</model:physical>
<model:physical name="box1_model">
- <xyz>1 1.5 0.5</xyz>
+ <xyz>4 1 0.5</xyz>
<canonicalBody>box1_body</canonicalBody>
<static>false</static>
@@ -90,8 +90,8 @@
</model:physical>
<model:physical name="cam1_model">
- <xyz>-6 0 3.5</xyz>
- <rpy>0 28 0</rpy>
+ <xyz>0 0 1</xyz>
+ <rpy>0 0 0</rpy>
<static>true</static>
<body:empty name="cam1_body">
@@ -102,6 +102,7 @@
<farClip>100</farClip>
<saveFrames>false</saveFrames>
<saveFramePath>frames</saveFramePath>
+ <baseline>0.2</baseline>
</sensor:stereocamera>
</body:empty>
</model:physical>
Modified: code/gazebo/trunk/worlds/test.world
===================================================================
--- code/gazebo/trunk/worlds/test.world 2008-03-26 08:59:00 UTC (rev 4443)
+++ code/gazebo/trunk/worlds/test.world 2008-03-26 22:53:54 UTC (rev 4444)
@@ -105,41 +105,6 @@
</include>
-->
- <model:physical name="pioneer2dx_model1">
- <xyz>0 0 0.145</xyz>
- <rpy>0.0 0.0 0.0</rpy>
-
- <controller:differential_position2d name="controller1">
- <leftJoint>left_wheel_hinge</leftJoint>
- <rightJoint>right_wheel_hinge</rightJoint>
- <wheelSeparation>0.34</wheelSeparation>
- <wheelDiameter>0.15</wheelDiameter>
- <torque>5</torque>
- <interface:position name="position_iface_0"/>
- </controller:differential_position2d>
-
- <model:physical name="laser">
- <xyz>0.15 0 0.18</xyz>
-
- <attach>
- <parentBody>chassis_body</parentBody>
- <myBody>laser_body</myBody>
- </attach>
-
- <include embedded="true">
- <xi:include href="models/sicklms200.model" />
- </include>
- </model:physical>
-
- <!--
- The include should be last within a model. All previous statements
- will override those in the included file
- -->
- <include embedded="true">
- <xi:include href="models/pioneer2dx.model" />
- </include>
- </model:physical>
-
<!-- White Directional light -->
<model:renderable name="directional_white">
<light>
This was sent by the SourceForge.net collaborative development platform, the
world's largest Open Source development site.
-------------------------------------------------------------------------
Check out the new SourceForge.net Marketplace.
It's the best place to buy or sell services for
just about anything Open Source.
http://ad.doubleclick.net/clk;164216239;13503038;w?http://sf.net/marketplace
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit