Revision: 8324
          http://playerstage.svn.sourceforge.net/playerstage/?rev=8324&view=rev
Author:   natepak
Date:     2009-10-21 23:45:08 +0000 (Wed, 21 Oct 2009)

Log Message:
-----------
Improved the multiray shape

Modified Paths:
--------------
    code/gazebo/branches/bullet2/server/controllers/CMakeLists.txt
    code/gazebo/branches/bullet2/server/physics/Body.cc
    code/gazebo/branches/bullet2/server/physics/MultiRayShape.cc
    code/gazebo/branches/bullet2/server/physics/MultiRayShape.hh
    code/gazebo/branches/bullet2/server/physics/RayShape.cc
    code/gazebo/branches/bullet2/server/physics/RayShape.hh
    code/gazebo/branches/bullet2/server/physics/bullet/BulletGeom.cc
    code/gazebo/branches/bullet2/server/physics/ode/ODEGeom.cc
    code/gazebo/branches/bullet2/server/physics/ode/ODEMultiRayShape.cc
    code/gazebo/branches/bullet2/server/rendering/OgreAdaptor.cc
    code/gazebo/branches/bullet2/server/rendering/OgreVisual.cc
    code/gazebo/branches/bullet2/server/sensors/CMakeLists.txt
    code/gazebo/branches/bullet2/server/sensors/imu/ImuSensor.cc
    code/gazebo/branches/bullet2/server/sensors/imu/ImuSensor.hh
    code/gazebo/branches/bullet2/server/sensors/ir/IRSensor.cc
    code/gazebo/branches/bullet2/server/sensors/ir/IRSensor.hh
    code/gazebo/branches/bullet2/server/sensors/ray/RaySensor.cc
    code/gazebo/branches/bullet2/server/sensors/ray/RaySensor.hh
    code/gazebo/branches/bullet2/worlds/pioneer2dx.world

Modified: code/gazebo/branches/bullet2/server/controllers/CMakeLists.txt
===================================================================
--- code/gazebo/branches/bullet2/server/controllers/CMakeLists.txt      
2009-10-21 16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/controllers/CMakeLists.txt      
2009-10-21 23:45:08 UTC (rev 8324)
@@ -6,7 +6,7 @@
 #ADD_SUBDIRECTORY(gripper)
 #ADD_SUBDIRECTORY(imu)
 #ADD_SUBDIRECTORY(irarray)
-#ADD_SUBDIRECTORY(laser)
+ADD_SUBDIRECTORY(laser)
 #ADD_SUBDIRECTORY(opaque)
 #ADD_SUBDIRECTORY(position2d)
 #ADD_SUBDIRECTORY(ptz)

Modified: code/gazebo/branches/bullet2/server/physics/Body.cc
===================================================================
--- code/gazebo/branches/bullet2/server/physics/Body.cc 2009-10-21 16:29:07 UTC 
(rev 8323)
+++ code/gazebo/branches/bullet2/server/physics/Body.cc 2009-10-21 23:45:08 UTC 
(rev 8324)
@@ -30,14 +30,6 @@
 #include "XMLConfig.hh"
 #include "Model.hh"
 #include "GazeboMessage.hh"
-
-//#include "HeightmapGeom.hh"
-//#include "MapGeom.hh"
-//#include "SphereGeom.hh"
-//#include "TrimeshGeom.hh"
-//#include "BoxGeom.hh"
-//#include "CylinderGeom.hh"
-//#include "PlaneGeom.hh"
 #include "Geom.hh"
 
 #include "OgreVisual.hh"
@@ -187,8 +179,6 @@
   this->dampingFactorP->Load(node);
   this->turnGravityOffP->Load(node);
 
-  std::cout << "Loading Body[" << this->GetName() << "]\n";
-
   this->SetRelativePose(Pose3d(**this->xyzP, **this->rpyP));
 
   // save transform from this Parent Model Frame to this Body Frame
@@ -348,23 +338,14 @@
 // Initialize the body
 void Body::Init()
 {
-  std::cout << "Body[" << this->GetName() << "] Init\n";
-
   // If no geoms are attached, then don't let gravity affect the body.
   if (this->geoms.size()==0 || this->turnGravityOffP->GetValue())
-  {
     this->SetGravityMode(false);
-  }
 
-  // Set the intial pose. Must do this to handle static models
-  //this->SetPose(this->GetPose());
-
   std::vector< Sensor* >::iterator siter;
 
   for (siter = this->sensors.begin(); siter != this->sensors.end(); siter++)
-  {
     (*siter)->Init();
-  }
 
   // global-inertial damping is implemented in ode svn trunk
   if(this->GetId() && this->dampingFactorP->GetValue() > 0)

Modified: code/gazebo/branches/bullet2/server/physics/MultiRayShape.cc
===================================================================
--- code/gazebo/branches/bullet2/server/physics/MultiRayShape.cc        
2009-10-21 16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/physics/MultiRayShape.cc        
2009-10-21 23:45:08 UTC (rev 8324)
@@ -1,3 +1,4 @@
+#include "XMLConfig.hh"
 #include "MultiRayShape.hh"
 
 using namespace gazebo;
@@ -20,8 +21,24 @@
   this->rayFan->setMaterial("Gazebo/BlueLaser");
   this->rayFanOutline->setMaterial("Gazebo/BlueEmissive");
 
-  this->displayType = "fan";
+  Param::Begin(&this->parameters);
+  this->rayCountP = new ParamT<int>("rayCount",0,1);
+  this->rangeCountP = new ParamT<int>("rangeCount",0,1);
+  this->minAngleP = new ParamT<Angle>("minAngle",DTOR(-90),1);
+  this->maxAngleP = new ParamT<Angle>("maxAngle",DTOR(-90),1);
+  this->minRangeP = new ParamT<double>("minRange",0,1);
+  this->maxRangeP = new ParamT<double>("maxRange",0,1);
+  this->resRangeP = new ParamT<double>("resRange",0.1,1);
+  this->originP = new ParamT<Vector3>("origin", Vector3(0,0,0), 0);
+  this->displayTypeP = new ParamT<std::string>("displayRays", "off", 0);
 
+  // for block rays, vertical setting
+  this->verticalRayCountP = new ParamT<int>("verticalRayCount", 1, 0);
+  this->verticalRangeCountP = new ParamT<int>("verticalRangeCount", 1, 0);
+  this->verticalMinAngleP = new ParamT<Angle>("verticalMinAngle", DTOR(0), 0);
+  this->verticalMaxAngleP = new ParamT<Angle>("verticalMaxAngle", DTOR(0), 0);
+  Param::End();
+
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -41,34 +58,70 @@
     delete *iter;
   }
   this->rays.clear();
+
+  delete this->rayCountP;
+  delete this->rangeCountP;
+  delete this->minAngleP;
+  delete this->maxAngleP;
+  delete this->minRangeP;
+  delete this->maxRangeP;
+  delete this->resRangeP;
+  delete this->originP;
+  delete this->displayTypeP;
+
+  delete this->verticalRayCountP;
+  delete this->verticalRangeCountP;
+  delete this->verticalMinAngleP;
+  delete this->verticalMaxAngleP;
+
 }
 
 
////////////////////////////////////////////////////////////////////////////////
-void MultiRayShape::Load(unsigned int vertRayCount, unsigned int rayCount,
+// Load a multi-ray shape from xml file
+void MultiRayShape::Load(XMLConfigNode *node)
+{
+  this->rayCountP->Load(node);
+  this->rangeCountP->Load(node);
+  this->minAngleP->Load(node);
+  this->maxAngleP->Load(node);
+  this->minRangeP->Load(node);
+  this->maxRangeP->Load(node);
+  this->resRangeP->Load(node);
+  this->originP->Load(node);
+  this->displayTypeP->Load(node);
+  this->verticalRayCountP->Load(node);
+  this->verticalRangeCountP->Load(node);
+  this->verticalMinAngleP->Load(node);
+  this->verticalMaxAngleP->Load(node);
+//}
+
+////////////////////////////////////////////////////////////////////////////////
+/*void MultiRayShape::Load(unsigned int vertRayCount, unsigned int rayCount,
             Vector3 origin, double minRange, double maxRange,
             Angle minVertAngle, Angle maxVertAngle,
             Angle minAngle, Angle maxAngle )
 {
+*/
   Vector3 start, end, axis;
 
   Angle yawAngle, pitchAngle; 
-  Angle pDiff = maxVertAngle - minVertAngle;
-  Angle yDiff = maxAngle - minAngle;
+  Angle pDiff = **this->verticalMaxAngleP - **this->verticalMinAngleP;
+  Angle yDiff = **this->maxAngleP - **this->minAngleP;
 
-  this->maxRange = maxRange;
+  //this->maxRange = maxRange;
 
   // Create and array of ray geoms
-  for (unsigned int j = 0; j < vertRayCount; j++)
+  for (int j = 0; j < **this->verticalRayCountP; j++)
   {
-    for (unsigned int i = 0; i < rayCount; i++)
+    for (int i = 0; i < **this->rayCountP; i++)
     {
-      yawAngle = (rayCount == 1)? 0 : 
-        i * yDiff.GetAsRadian() / (rayCount - 1) + 
-        minAngle.GetAsRadian();
+      yawAngle = (**this->rayCountP == 1)? 0 : 
+        i * yDiff.GetAsRadian() / (**this->rayCountP - 1) + 
+        (**this->minAngleP).GetAsRadian();
 
-      pitchAngle = (vertRayCount == 1)? 0 :  
-        j * pDiff.GetAsRadian() / (vertRayCount - 1) + 
-        minVertAngle.GetAsRadian();
+      pitchAngle = (**this->verticalRayCountP == 1)? 0 :  
+        j * pDiff.GetAsRadian() / (**this->verticalRayCountP - 1) + 
+        (**this->verticalMinAngleP).GetAsRadian();
 
       axis.Set(cos(pitchAngle.GetAsRadian()) * 
           cos(yawAngle.GetAsRadian()), 
@@ -76,8 +129,8 @@
           sin(pitchAngle.GetAsRadian())*
           cos(yawAngle.GetAsRadian()));
 
-      start = (axis * minRange) + origin;
-      end = (axis * maxRange) + origin;
+      start = (axis * **this->minRangeP) + **this->originP;
+      end = (axis * **this->maxRangeP) + **this->originP;
 
       this->AddRay(start,end);
     }
@@ -85,7 +138,7 @@
 
   if (this->rayFan && this->rayFanOutline)
   {
-    if (this->displayType == "fan")
+    if (**this->displayTypeP == "fan")
     {
       this->rayFan->AddPoint(this->rayFan->GetPoint(0));
       this->rayFanOutline->AddPoint(this->rayFanOutline->GetPoint(0));
@@ -93,10 +146,23 @@
   }
 }
 
-////////////////////////////////////////////////////////////////////////////////
-void MultiRayShape::SetDisplayType(const std::string &type)
+//////////////////////////////////////////////////////////////////////////////
+/// Save the sensor info in XML format
+void MultiRayShape::Save(std::string &prefix, std::ostream &stream)
 {
-  this->displayType = type;
+  stream << prefix << "  " << *(this->minAngleP) << "\n";
+  stream << prefix << "  " << *(this->maxAngleP) << "\n";
+  stream << prefix << "  " << *(this->minRangeP) << "\n";
+  stream << prefix << "  " << *(this->maxRangeP) << "\n";
+  stream << prefix << "  " << *(this->resRangeP) << "\n";
+  stream << prefix << "  " << *(this->originP) << "\n";
+  stream << prefix << "  " << *(this->rayCountP) << "\n";
+  stream << prefix << "  " << *(this->rangeCountP) << "\n";
+  stream << prefix << "  " << *(this->displayTypeP) << "\n";
+  stream << prefix << "  " << *(this->verticalRayCountP) << "\n";
+  stream << prefix << "  " << *(this->verticalRangeCountP) << "\n";
+  stream << prefix << "  " << *(this->verticalMinAngleP) << "\n";
+  stream << prefix << "  " << *(this->verticalMaxAngleP) << "\n";
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -158,7 +224,7 @@
   for (iter = this->rays.begin(); 
       iter != this->rays.end(); iter++, i++)
   {
-    (*iter)->SetLength( this->maxRange );
+    (*iter)->SetLength( **this->maxRangeP );
     (*iter)->SetRetro( 0.0 );
     (*iter)->SetFiducial( -1 );
 
@@ -170,7 +236,7 @@
 
   if (this->rayFan && this->rayFanOutline)
   {
-    if (this->displayType == "fan")
+    if (**this->displayTypeP == "fan")
     { 
       i = 1;
       for (iter = this->rays.begin(); 
@@ -194,7 +260,7 @@
   // Add to the renderable
   if (this->rayFan && this->rayFanOutline)
   {
-    if (this->displayType == "fan")
+    if (**this->displayTypeP == "fan")
     {
       if (this->rayFan->GetNumPoints() == 0)
       {
@@ -207,3 +273,81 @@
     }
   }
 }
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the minimum angle
+Angle MultiRayShape::GetMinAngle() const
+{
+  return **this->minAngleP;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the maximum angle
+Angle MultiRayShape::GetMaxAngle() const
+{
+  return **this->maxAngleP;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the minimum range
+double MultiRayShape::GetMinRange() const
+{
+  return **this->minRangeP;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+///  Get the maximum range
+double MultiRayShape::GetMaxRange() const
+{
+  return **this->maxRangeP;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+///  Get the range resolution
+double MultiRayShape::GetResRange() const
+{
+  return **this->resRangeP;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the ray count
+int MultiRayShape::GetRayCount() const
+{
+  return **this->rayCountP;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the range count
+int MultiRayShape::GetRangeCount() const
+{
+  return **this->rangeCountP;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the vertical scan line count
+int MultiRayShape::GetVerticalRayCount() const
+{
+  return **this->verticalRayCountP;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the vertical scan line count
+int MultiRayShape::GetVerticalRangeCount() const
+{
+  return **this->verticalRangeCountP;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the vertical min angle
+Angle MultiRayShape::GetVerticalMinAngle() const
+{
+  return **this->verticalMinAngleP;
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Get the vertical max angle
+Angle MultiRayShape::GetVerticalMaxAngle() const
+{
+  return **this->verticalMaxAngleP;
+}
+

Modified: code/gazebo/branches/bullet2/server/physics/MultiRayShape.hh
===================================================================
--- code/gazebo/branches/bullet2/server/physics/MultiRayShape.hh        
2009-10-21 16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/physics/MultiRayShape.hh        
2009-10-21 23:45:08 UTC (rev 8324)
@@ -14,6 +14,8 @@
 
 namespace gazebo
 {
+  class XMLConfigNode;
+
   /// \brief Laser geom contains a set of ray-geoms, structured to simulate
   ///        a laser range scanner
   class MultiRayShape : public Shape
@@ -24,15 +26,17 @@
     /// \brief Destructor
     public: virtual ~MultiRayShape();
 
-    public: void Load(XMLConfigNode *node) {}
+    /// \brief Load a multi-ray shape from xml file
+    public: void Load(XMLConfigNode *node);
 
     /// \brief Save child parameters
-    public: virtual void Save(std::string &prefix, std::ostream &stream) {}
+    public: virtual void Save(std::string &prefix, std::ostream &stream);
 
-    public: void Load(unsigned int vertRayCount, unsigned int rayCount,
+    /*public: void Load(unsigned int vertRayCount, unsigned int rayCount,
                       Vector3 origin, double minRange, double maxRange,
                       Angle minVertAngle, Angle maxVertAngle,
                       Angle minAngle, Angle maxAngle );
+                      */
             
 
     public: void SetDisplayType(const std::string &type);
@@ -46,7 +50,40 @@
   
     /// \brief Get detected fiducial value for a ray.
     public: int GetFiducial(int index);
-  
+
+    /// \brief Get the minimum angle
+    public: Angle GetMinAngle() const;
+            
+    /// \brief Get the maximum angle
+    public: Angle GetMaxAngle() const;
+
+    /// \brief Get the minimum range
+    public: double GetMinRange() const;
+
+    /// \brief Get the maximum range
+    public: double GetMaxRange() const;
+
+    /// \brief Get the range resolution
+    public: double GetResRange() const;
+
+    /// \brief Get the ray count
+    public: int GetRayCount() const;
+
+    /// \brief Get the range count
+    public: int GetRangeCount() const;
+
+    /// \brief Get the vertical scan line count
+    public: int GetVerticalRayCount() const;
+
+    /// \brief Get the vertical scan line count
+    public: int GetVerticalRangeCount() const;
+
+    /// \brief Get the vertical min angle
+    public: Angle GetVerticalMinAngle() const;
+
+    /// \brief Get the vertical max angle
+    public: Angle GetVerticalMaxAngle() const;
+
     /// \brief Update the geom
     public: void Update();
   
@@ -62,8 +99,22 @@
     /// Ray data
     protected: std::vector< RayShape* > rays;
 
-    protected: std::string displayType;
     protected: double maxRange;
+
+    protected: ParamT<Angle> *minAngleP, *maxAngleP;
+    protected: ParamT<double> *minRangeP, *maxRangeP, *resRangeP;
+    protected: ParamT<Vector3> *originP;
+    protected: ParamT<int> *rayCountP;
+    protected: ParamT<int> *rangeCountP;
+
+     /// Display rays when rendering images
+    protected: ParamT<std::string> *displayTypeP;
+  
+    // For ray blocks such as Velodyne
+    protected: ParamT<int> *verticalRayCountP;
+    protected: ParamT<int> *verticalRangeCountP;
+    protected: ParamT<Angle> *verticalMinAngleP;
+    protected: ParamT<Angle> *verticalMaxAngleP;
   };
 
 }

Modified: code/gazebo/branches/bullet2/server/physics/RayShape.cc
===================================================================
--- code/gazebo/branches/bullet2/server/physics/RayShape.cc     2009-10-21 
16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/physics/RayShape.cc     2009-10-21 
23:45:08 UTC (rev 8324)
@@ -35,8 +35,7 @@
   this->type = Shape::RAY;
   this->SetName("Ray");
 
-  if (displayRays && 
-      Simulator::Instance()->GetRenderEngineEnabled() )
+  if (displayRays && Simulator::Instance()->GetRenderEngineEnabled() )
   {
     this->line = OgreCreator::Instance()->CreateDynamicLine(
         OgreDynamicRenderable::OT_LINE_LIST);
@@ -68,9 +67,21 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+/// Set to true in order to view individual rays
+void RayShape::SetDisplayType( bool displayRays )
+{
+  if (Simulator::Instance()->GetRenderEngineEnabled() )
+  {
+    if (!displayRays)
+      this->parent->GetVisualNode()->DetachObjects();
+    else
+      this->parent->GetVisualNode()->AttachObject(this->line);
+  }
+}
+ 
+////////////////////////////////////////////////////////////////////////////////
 /// Set the ray based on starting and ending points relative to the body
-void RayShape::SetPoints(const Vector3 &posStart, 
-            const Vector3 &posEnd)
+void RayShape::SetPoints(const Vector3 &posStart, const Vector3 &posEnd)
 {
   Vector3 dir;
 

Modified: code/gazebo/branches/bullet2/server/physics/RayShape.hh
===================================================================
--- code/gazebo/branches/bullet2/server/physics/RayShape.hh     2009-10-21 
16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/physics/RayShape.hh     2009-10-21 
23:45:08 UTC (rev 8324)
@@ -60,6 +60,9 @@
   
     /// \brief Destructor
     public: virtual ~RayShape();
+
+    /// \brief Set to true in order to view individual rays
+    public: void SetDisplayType( bool displayRays );
   
     /// \brief Set the ray based on starting and ending points relative to 
     ///        the body
@@ -122,6 +125,7 @@
     /// Start and end positions of the ray in global cs
     protected: Vector3 globalStartPos;
     protected: Vector3 globalEndPos;
+
   };
   
   /// \}

Modified: code/gazebo/branches/bullet2/server/physics/bullet/BulletGeom.cc
===================================================================
--- code/gazebo/branches/bullet2/server/physics/bullet/BulletGeom.cc    
2009-10-21 16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/physics/bullet/BulletGeom.cc    
2009-10-21 23:45:08 UTC (rev 8324)
@@ -47,6 +47,7 @@
 BulletGeom::BulletGeom( Body *_body )
     : Geom(_body)
 {
+  this->SetName("Bullet Geom");
   this->bulletPhysics = dynamic_cast<BulletPhysics*>(this->physicsEngine);
   this->collisionShape = NULL;
 }

Modified: code/gazebo/branches/bullet2/server/physics/ode/ODEGeom.cc
===================================================================
--- code/gazebo/branches/bullet2/server/physics/ode/ODEGeom.cc  2009-10-21 
16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/physics/ode/ODEGeom.cc  2009-10-21 
23:45:08 UTC (rev 8324)
@@ -47,7 +47,8 @@
 ODEGeom::ODEGeom( Body *_body )
     : Geom(_body)
 {
-  this->SetSpaceId( ((ODEBody*)this->body)->GetSpaceId());
+  this->SetName("ODE Geom");
+  this->SetSpaceId( ((ODEBody*)this->body)->GetSpaceId() );
 
   this->geomId = NULL;
 }
@@ -91,11 +92,25 @@
 
 void ODEGeom::OnPoseChange()
 {
-  if (this->geomId && this->placeable)
+  Pose3d localPose;
+  dQuaternion q;
+
+  if (this->IsStatic() && this->geomId && this->placeable)
   {
-    Pose3d localPose;
-    dQuaternion q;
+    // Transform into global pose since a static geom does not have a body 
+    localPose = this->GetAbsPose();
 
+    q[0] = localPose.rot.u;
+    q[1] = localPose.rot.x;
+    q[2] = localPose.rot.y;
+    q[3] = localPose.rot.z;
+
+    dGeomSetPosition(this->geomId, localPose.pos.x, localPose.pos.y, 
+        localPose.pos.z);
+    dGeomSetQuaternion(this->geomId, q);
+  }
+  else if (this->geomId && this->placeable)
+  {
     // Transform into CoM relative Pose
     //localPose = newPose - this->body->GetCoMPose();
     localPose = this->GetRelativePose();

Modified: code/gazebo/branches/bullet2/server/physics/ode/ODEMultiRayShape.cc
===================================================================
--- code/gazebo/branches/bullet2/server/physics/ode/ODEMultiRayShape.cc 
2009-10-21 16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/physics/ode/ODEMultiRayShape.cc 
2009-10-21 23:45:08 UTC (rev 8324)
@@ -25,8 +25,6 @@
   ODEBody *pBody = (ODEBody*)(this->parent->GetBody());
   pBody->SetSpaceId( this->raySpaceId );
   ((ODEGeom*)parent)->SetSpaceId(this->raySpaceId);
-
-  this->displayType = "fan";
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -129,7 +127,7 @@
         RayShape *shape = (RayShape*)(rayGeom->GetShape());
         if (contact.depth < shape->GetLength())
         {
-          shape->SetLength( 20);//contact.depth );
+          shape->SetLength(contact.depth );
           shape->SetRetro( hitGeom->GetLaserRetro() );
           shape->SetFiducial( hitGeom->GetLaserFiducialId() );
         }
@@ -143,8 +141,9 @@
 void ODEMultiRayShape::AddRay(const Vector3 &start, const Vector3 &end )
 {
   MultiRayShape::AddRay(start,end);
-  ODERayShape *ray;
-  ray = new ODERayShape(this->parent, this->displayType == "lines");
+
+  ODERayShape *ray = new ODERayShape( new ODEGeom(parent->GetBody()), 
**this->displayTypeP == "lines");
+
   ray->SetPoints(start,end);
   this->rays.push_back(ray);
 }

Modified: code/gazebo/branches/bullet2/server/rendering/OgreAdaptor.cc
===================================================================
--- code/gazebo/branches/bullet2/server/rendering/OgreAdaptor.cc        
2009-10-21 16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/rendering/OgreAdaptor.cc        
2009-10-21 23:45:08 UTC (rev 8324)
@@ -231,18 +231,22 @@
   else 
     gzthrow(std::string("Unsupported shadow technique: ") + 
**(this->shadowTechniqueP) + "\n");
 
-  this->sceneMgr->setShadowTextureSelfShadow(true);
-  this->sceneMgr->setShadowTexturePixelFormat(Ogre::PF_FLOAT16_R);
-  this->sceneMgr->setShadowTextureSize(**(this->shadowTextureSizeP));
-  this->sceneMgr->setShadowIndexBufferSize(**(this->shadowIndexSizeP) );
-  
+  // Not sure if this does something useful.
+  /*if (**(this->shadowTechniqueP) != std::string("none"))
+  {
+    this->sceneMgr->setShadowTextureSelfShadow(true);
+    this->sceneMgr->setShadowTexturePixelFormat(Ogre::PF_FLOAT16_R);
+    this->sceneMgr->setShadowTextureSize(**(this->shadowTextureSizeP));
+    this->sceneMgr->setShadowIndexBufferSize(**(this->shadowIndexSizeP) );
 
+    this->sceneMgr->setShadowTextureSettings(512,2);
+    this->sceneMgr->setShadowColour(Ogre::ColourValue(0.2, 0.2, 0.2));
+    this->sceneMgr->setShadowFarDistance(30);
+  }*/
+
   // Ambient lighting
   this->sceneMgr->setAmbientLight(ambient);
 
-  this->sceneMgr->setShadowTextureSettings(512,2);
-  this->sceneMgr->setShadowColour(Ogre::ColourValue(0.2, 0.2, 0.2));
-  this->sceneMgr->setShadowFarDistance(30);
 
   // Add a sky dome to our scene
   if (node->GetChild("sky"))

Modified: code/gazebo/branches/bullet2/server/rendering/OgreVisual.cc
===================================================================
--- code/gazebo/branches/bullet2/server/rendering/OgreVisual.cc 2009-10-21 
16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/rendering/OgreVisual.cc 2009-10-21 
23:45:08 UTC (rev 8324)
@@ -259,6 +259,7 @@
 /// Detach all objects
 void OgreVisual::DetachObjects()
 {
+  printf("Detaching objects\n");
   boost::recursive_mutex::scoped_lock lock(*this->mutex);
 
   // Stop here if the rendering engine has been disabled

Modified: code/gazebo/branches/bullet2/server/sensors/CMakeLists.txt
===================================================================
--- code/gazebo/branches/bullet2/server/sensors/CMakeLists.txt  2009-10-21 
16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/sensors/CMakeLists.txt  2009-10-21 
23:45:08 UTC (rev 8324)
@@ -1,10 +1,10 @@
 include (${gazebo_cmake_dir}/GazeboUtils.cmake)
 
-#ADD_SUBDIRECTORY(camera)
-#ADD_SUBDIRECTORY(contact)
-#ADD_SUBDIRECTORY(imu)
+ADD_SUBDIRECTORY(camera)
+ADD_SUBDIRECTORY(contact)
+ADD_SUBDIRECTORY(imu)
+ADD_SUBDIRECTORY(ray)
 #ADD_SUBDIRECTORY(ir)
-ADD_SUBDIRECTORY(ray)
 
 SET (sources Sensor.cc
              SensorFactory.cc

Modified: code/gazebo/branches/bullet2/server/sensors/imu/ImuSensor.cc
===================================================================
--- code/gazebo/branches/bullet2/server/sensors/imu/ImuSensor.cc        
2009-10-21 16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/sensors/imu/ImuSensor.cc        
2009-10-21 23:45:08 UTC (rev 8324)
@@ -140,5 +140,3 @@
 
   }
 }
-
-}

Modified: code/gazebo/branches/bullet2/server/sensors/imu/ImuSensor.hh
===================================================================
--- code/gazebo/branches/bullet2/server/sensors/imu/ImuSensor.hh        
2009-10-21 16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/sensors/imu/ImuSensor.hh        
2009-10-21 23:45:08 UTC (rev 8324)
@@ -30,41 +30,37 @@
 namespace gazebo
 {
 
-class XMLConfigNode;
-class ImuSensor: public Sensor
-{
-  /// \brief Constructor
-  /// \param body The IMU sensor must be attached to a body.
-  public: ImuSensor(Body *body);
-
-  /// \brief Destructor
-  public: virtual ~ImuSensor();
-
-  /// \param node The XMLConfig node
-  protected: virtual void LoadChild(XMLConfigNode *node);
-
-  /// \brief Save the sensor info in XML format
-  protected: virtual void SaveChild(std::string &prefix, std::ostream &stream);
-
-  /// Initialize the ray
-  protected: virtual void InitChild();
-
-  ///  Update sensed values
-  protected: virtual void UpdateChild();
+  class XMLConfigNode;
+  class ImuSensor: public Sensor
+  {
+    /// \brief Constructor
+    /// \param body The IMU sensor must be attached to a body.
+    public: ImuSensor(Body *body);
   
-  /// Finalize the ray
-  protected: virtual void FiniChild();
-
-  public: Pose3d GetVelocity();
-
-  private: Pose3d prevPose;
-  private: Pose3d imuVel;
-/*
-  private: ParamT<int> *rayCountP;
-  private: ParamT<int> *rangeCountP;
-*/
+    /// \brief Destructor
+    public: virtual ~ImuSensor();
   
+    /// \param node The XMLConfig node
+    protected: virtual void LoadChild(XMLConfigNode *node);
+  
+    /// \brief Save the sensor info in XML format
+    protected: virtual void SaveChild(std::string &prefix, std::ostream 
&stream);
+  
+    /// Initialize the ray
+    protected: virtual void InitChild();
+  
+    ///  Update sensed values
+    protected: virtual void UpdateChild();
+    
+    /// Finalize the ray
+    protected: virtual void FiniChild();
+  
+    public: Pose3d GetVelocity();
+  
+    private: Pose3d prevPose;
+    private: Pose3d imuVel;
+  
+  };
+}
 
-};
-
 #endif

Modified: code/gazebo/branches/bullet2/server/sensors/ir/IRSensor.cc
===================================================================
--- code/gazebo/branches/bullet2/server/sensors/ir/IRSensor.cc  2009-10-21 
16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/sensors/ir/IRSensor.cc  2009-10-21 
23:45:08 UTC (rev 8324)
@@ -22,7 +22,7 @@
  * Author: Wenguo Liu
  * Date: 23 february 2004
  * SVN: $Id: IRSensor.cc 4436 2008-03-24 17:42:45Z robotos $
-*/
+ */
 
 #include <assert.h>
 #include <float.h>
@@ -48,7 +48,7 @@
 //////////////////////////////////////////////////////////////////////////////
 // Constructor
 IRSensor::IRSensor(Body *body)
-    : Sensor(body)
+ : Sensor(body)
 {
   this->active = false;
   this->rayCount = NULL;
@@ -77,14 +77,29 @@
     stream << "Body is NULL";
     gzthrow(stream.str());
   }
-  
+
   XMLConfigNode *iNode;
   int i =0;
-  
 
-  this->IRCount = node->GetInt("irCount",0,1);
-  
-  
+  iNode = node->GetChild("ir");
+  while (iNode)
+  {
+    laserGeom = 
World::Instance()->GetPhysicsEngine()->CreateGeom(Shape::MULTIRAY, this->body);
+    laserGeom->SetName("IR Sensor Geom");
+
+    laserShape = (MultiRayShape*)(laserGeom->GetShape());
+
+    laserShape->SetDisplayType( (**this->displayRaysP) );
+    laserShape->Load(iNode);
+    /*laserShape->Load(**verticalRayCountP, **rayCountP, 
+        **this->originP, **minRangeP, **maxRangeP, 
+        **this->verticalMinAngleP, **this->verticalMaxAngleP, 
**this->minAngleP, **this->maxAngleP);*/
+
+    iNode = iNode->GetGetChild("ir");
+  }
+
+  /*this->IRCount = node->GetInt("irCount",0,1);
+
   //Allocate memeorys
   this->rayCount = new int[this->IRCount];
   this->rangeCount = new int[this->IRCount];
@@ -93,19 +108,19 @@
   this->minRange = new double[this->IRCount];
   this->maxRange = new double[this->IRCount];
   this->origin = new Vector3[this->IRCount];
-  
-  
+
+
   //Read configuration from XML file
   for(i=0, iNode = node->GetChild("ir"); iNode;i++)
- {
-       if(i >= this->IRCount)
-       {
-               std::ostringstream stream;
-               stream<< "please check the irCount is correct!";
-               gzthrow(stream.str());
-       }
-       
-       std::string name = iNode->GetString("name","",1);
+  {
+    if(i >= this->IRCount)
+    {
+      std::ostringstream stream;
+      stream<< "please check the irCount is correct!";
+      gzthrow(stream.str());
+    }
+
+    std::string name = iNode->GetString("name","",1);
     this->rayCount[i] = iNode->GetInt("rayCount",0,1);
     this->rangeCount[i] = iNode->GetInt("rangeCount",0,1);
     this->minAngle[i] = DTOR(iNode->GetDouble("minAngle",-90,1));
@@ -114,7 +129,7 @@
     this->maxRange[i] = iNode->GetDouble("maxRange",8,1);
     this->origin[i] = iNode->GetVector3("origin", Vector3(0,0,0));
     iNode = iNode->GetNext("ir");
- }
+  }
 
   this->displayRays = node->GetBool("displayRays", true);
 
@@ -128,9 +143,11 @@
   dGeomSetCategoryBits((dGeomID) this->raySpaceId, GZ_SENSOR_COLLIDE);
   dGeomSetCollideBits((dGeomID) this->raySpaceId, ~GZ_SENSOR_COLLIDE);
 
+  */
   /* BULLET
-  this->body->SetSpaceId( this->raySpaceId );
-  */
+     this->body->SetSpaceId( this->raySpaceId );
+     */
+
 }
 
 //////////////////////////////////////////////////////////////////////////////
@@ -157,14 +174,14 @@
         angle = i * (this->maxAngle[j] - this->minAngle[j]) / 
(this->rayCount[j] - 1) + this->minAngle[j];
 
       axis.Set(cos(angle), sin(angle),0);
-      
 
+
       start = (axis * this->minRange[j]) + this->origin[j];
       end = (axis * this->maxRange[j]) + this->origin[j];
 
       /* BULLET
-      ray = new RayGeom(this->body, displayRays);
-      */
+         ray = new RayGeom(this->body, displayRays);
+         */
 
       ray->SetPoints(start, end);
 
@@ -187,38 +204,38 @@
   this->rays.clear();
   if(this->rayCount!=NULL)
   {
-       delete []this->rayCount;
-       this->rayCount=NULL;
+    delete []this->rayCount;
+    this->rayCount=NULL;
   }
   if(this->rangeCount!=NULL)
   {
-       delete []this->rangeCount;
-       this->rangeCount=NULL;
+    delete []this->rangeCount;
+    this->rangeCount=NULL;
   }
   if(this->minAngle!=NULL)
   {
-       delete []this->minAngle;
-       this->minAngle=NULL;
+    delete []this->minAngle;
+    this->minAngle=NULL;
   }
   if(this->maxAngle!=NULL)
   {
-       delete []this->maxAngle;
-       this->maxAngle=NULL;
+    delete []this->maxAngle;
+    this->maxAngle=NULL;
   }
   if(this->minRange!=NULL)
   {
-       delete []this->minRange;
-       this->minRange=NULL;
+    delete []this->minRange;
+    this->minRange=NULL;
   }
   if(this->maxRange!=NULL)
   {
-       delete []this->maxRange;
-       this->maxRange=NULL;
+    delete []this->maxRange;
+    this->maxRange=NULL;
   }
   if(this->origin!=NULL)
   {
-       delete []this->origin;
-       this->origin=NULL;
+    delete []this->origin;
+    this->origin=NULL;
   }
 }
 
@@ -272,23 +289,23 @@
   {
     std::ostringstream stream;
     stream << "index[" << index << "] out of range[0-"
-    << this->IRCount << "]";
+      << this->IRCount << "]";
     gzthrow(stream.str());
   }
-  
+
   //get the ray index range for this specific IR
   int start_index=0;
   int end_index=0;
   for(int i=0;i<index;i++)
   {
-       start_index +=this->rayCount[i];
+    start_index +=this->rayCount[i];
   }
   end_index = start_index + this->rayCount[index] - 1;
-  
+
   double range = this->maxRange[index];
   for(int i=start_index;i<=end_index;i++)
   {
-      range = std::min(this->rays[i]->GetLength(),range);  
+    range = std::min(this->rays[i]->GetLength(),range);  
   }
   return range;
 
@@ -300,10 +317,10 @@
   {
     std::ostringstream stream;
     stream << "index[" << index << "] out of range[0-"
-    << this->IRCount << "]";
+      << this->IRCount << "]";
     gzthrow(stream.str());
   }
-  
+
   Pose pose;
   pose.pos.x = this->origin[index].x;
   pose.pos.y = this->origin[index].y;
@@ -312,7 +329,7 @@
   pose.pitch = 0;
   pose.yaw = 0.5*(this->minAngle[index]+this->maxAngle[index]);
   return pose;
-       
+
 }
 
 
@@ -320,7 +337,7 @@
 // Update the sensor information
 void IRSensor::UpdateChild()
 {
-//  if (this->active)
+  //  if (this->active)
   {
     std::vector<RayGeom*>::iterator iter;
     Pose3d poseDelta;
@@ -343,19 +360,19 @@
     }
 
     /*BULLET
-    ODEPhysics *ode = 
dynamic_cast<ODEPhysics*>(World::Instance()->GetPhysicsEngine());
+      ODEPhysics *ode = 
dynamic_cast<ODEPhysics*>(World::Instance()->GetPhysicsEngine());
 
-    if (ode == NULL)
-    {
+      if (ode == NULL)
+      {
       gzthrow( "Invalid physics engine. Must use ODE." );
-    }
+      }
 
     // BULLET
     // Do collision detection
     dSpaceCollide2( ( dGeomID ) ( this->superSpaceId ),
-                    ( dGeomID ) ( ode->GetSpaceId() ),
-                    this, &UpdateCallback );
-                    */
+    ( dGeomID ) ( ode->GetSpaceId() ),
+    this, &UpdateCallback );
+    */
   }
 }
 

Modified: code/gazebo/branches/bullet2/server/sensors/ir/IRSensor.hh
===================================================================
--- code/gazebo/branches/bullet2/server/sensors/ir/IRSensor.hh  2009-10-21 
16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/sensors/ir/IRSensor.hh  2009-10-21 
23:45:08 UTC (rev 8324)
@@ -114,17 +114,19 @@
   public: Pose  GetPose(int index);
 
   /// \brief Ray-intersection callback
-  private: static void UpdateCallback( void *data, dGeomID o1, dGeomID o2 );
+  //private: static void UpdateCallback( void *data, dGeomID o1, dGeomID o2 );
   
   /// Ray space for collision detector
-  private: dSpaceID superSpaceId;
-  private: dSpaceID raySpaceId; 
+  //private: dSpaceID superSpaceId;
+  //private: dSpaceID raySpaceId; 
 
+  private: std::vector<RaySensor*> irBeams;
+
   /// Ray data
-  private: std::vector<RayGeom*> rays;
+  //private: std::vector<RayGeom*> rays;
   
 
-  private: double *minAngle, *maxAngle;
+  /*private: double *minAngle, *maxAngle;
   private: double *minRange, *maxRange;
   private: Vector3 *origin;
 
@@ -135,6 +137,7 @@
   
   /// Display rays when rendering images
   private: bool displayRays;
+  */
 
 };
 /// \}

Modified: code/gazebo/branches/bullet2/server/sensors/ray/RaySensor.cc
===================================================================
--- code/gazebo/branches/bullet2/server/sensors/ray/RaySensor.cc        
2009-10-21 16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/sensors/ray/RaySensor.cc        
2009-10-21 23:45:08 UTC (rev 8324)
@@ -47,24 +47,6 @@
   this->active = false;
 
   this->typeName = "ray";
-
-  Param::Begin(&this->parameters);
-  this->rayCountP = new ParamT<int>("rayCount",0,1);
-  this->rangeCountP = new ParamT<int>("rangeCount",0,1);
-  this->minAngleP = new ParamT<Angle>("minAngle",DTOR(-90),1);
-  this->maxAngleP = new ParamT<Angle>("maxAngle",DTOR(-90),1);
-  this->minRangeP = new ParamT<double>("minRange",0,1);
-  this->maxRangeP = new ParamT<double>("maxRange",0,1);
-  this->resRangeP = new ParamT<double>("resRange",0.1,1);
-  this->originP = new ParamT<Vector3>("origin", Vector3(0,0,0), 0);
-  this->displayRaysP = new ParamT<std::string>("displayRays", "off", 0);
-
-  // for block rays, vertical setting
-  this->verticalRayCountP = new ParamT<int>("verticalRayCount", 1, 0);
-  this->verticalRangeCountP = new ParamT<int>("verticalRangeCount", 1, 0);
-  this->verticalMinAngleP = new ParamT<Angle>("verticalMinAngle", DTOR(0), 0);
-  this->verticalMaxAngleP = new ParamT<Angle>("verticalMaxAngle", DTOR(0), 0);
-  Param::End();
 }
 
 
@@ -72,20 +54,6 @@
 // Destructor
 RaySensor::~RaySensor()
 {
-  delete this->rayCountP;
-  delete this->rangeCountP;
-  delete this->minAngleP;
-  delete this->maxAngleP;
-  delete this->minRangeP;
-  delete this->maxRangeP;
-  delete this->resRangeP;
-  delete this->originP;
-  delete this->displayRaysP;
-
-  delete this->verticalRayCountP;
-  delete this->verticalRangeCountP;
-  delete this->verticalMinAngleP;
-  delete this->verticalMaxAngleP;
 }
 
 //////////////////////////////////////////////////////////////////////////////
@@ -95,49 +63,28 @@
   if (this->body == NULL)
     gzthrow("Null body in the ray sensor");
 
-  this->rayCountP->Load(node);
-  this->rangeCountP->Load(node);
-  this->minAngleP->Load(node);
-  this->maxAngleP->Load(node);
-  this->minRangeP->Load(node);
-  this->maxRangeP->Load(node);
-  this->resRangeP->Load(node);
-  this->originP->Load(node);
-  this->displayRaysP->Load(node);
-  this->verticalRayCountP->Load(node);
-  this->verticalRangeCountP->Load(node);
-  this->verticalMinAngleP->Load(node);
-  this->verticalMaxAngleP->Load(node);
+  this->laserGeom = World::Instance()->GetPhysicsEngine()->CreateGeom(
+      Shape::MULTIRAY, this->body);
+  this->laserGeom->SetName("Ray Sensor Geom");
 
-  this->laserGeom = 
World::Instance()->GetPhysicsEngine()->CreateGeom(Shape::MULTIRAY, this->body);
   this->laserShape = (MultiRayShape*)(this->laserGeom->GetShape());
 
-  this->laserShape->SetDisplayType( (**this->displayRaysP) );
-  this->laserShape->Load(**this->verticalRayCountP, **this->rayCountP, 
+  //this->laserShape->SetDisplayType( (**this->displayRaysP) );
+  this->laserShape->Load( node );
+  /*this->laserShape->Load(**this->verticalRayCountP, **this->rayCountP, 
       **this->originP, **this->minRangeP, **this->maxRangeP, 
       **this->verticalMinAngleP, **this->verticalMaxAngleP, **this->minAngleP, 
       **this->maxAngleP);
+      */
 }
 
 //////////////////////////////////////////////////////////////////////////////
 /// Save the sensor info in XML format
 void RaySensor::SaveChild(std::string &prefix, std::ostream &stream)
 {
-  stream << prefix << "  " << *(this->minAngleP) << "\n";
-  stream << prefix << "  " << *(this->maxAngleP) << "\n";
-  stream << prefix << "  " << *(this->minRangeP) << "\n";
-  stream << prefix << "  " << *(this->maxRangeP) << "\n";
-  stream << prefix << "  " << *(this->resRangeP) << "\n";
-  stream << prefix << "  " << *(this->originP) << "\n";
-  stream << prefix << "  " << *(this->rayCountP) << "\n";
-  stream << prefix << "  " << *(this->rangeCountP) << "\n";
-  stream << prefix << "  " << *(this->displayRaysP) << "\n";
-  stream << prefix << "  " << *(this->verticalRayCountP) << "\n";
-  stream << prefix << "  " << *(this->verticalRangeCountP) << "\n";
-  stream << prefix << "  " << *(this->verticalMinAngleP) << "\n";
-  stream << prefix << "  " << *(this->verticalMaxAngleP) << "\n";
-}
 
+  this->laserShape->Save(prefix, stream);}
+
 //////////////////////////////////////////////////////////////////////////////
 // Init the ray
 void RaySensor::InitChild()
@@ -158,77 +105,77 @@
 /// Get the minimum angle
 Angle RaySensor::GetMinAngle() const
 {
-  return **(this->minAngleP);
+  return this->laserShape->GetMinAngle();//**(this->minAngleP);
 }
 
 //////////////////////////////////////////////////////////////////////////////
 /// Get the maximum angle
 Angle RaySensor::GetMaxAngle() const
 {
-  return **(this->maxAngleP);
+  return this->laserShape->GetMaxAngle();//**(this->maxAngleP);
 }
 
 //////////////////////////////////////////////////////////////////////////////
 /// Get the minimum range
 double RaySensor::GetMinRange() const
 {
-  return this->minRangeP->GetValue();
+  return this->laserShape->GetMinRange();
 }
 
 //////////////////////////////////////////////////////////////////////////////
 ///  Get the maximum range
 double RaySensor::GetMaxRange() const
 {
-  return this->maxRangeP->GetValue();
+  return this->laserShape->GetMaxRange();
 }
 
 //////////////////////////////////////////////////////////////////////////////
 ///  Get the range resolution
 double RaySensor::GetResRange() const
 {
-  return this->resRangeP->GetValue();
+  return this->laserShape->GetResRange();
 }
 
 //////////////////////////////////////////////////////////////////////////////
 /// Get the ray count
 int RaySensor::GetRayCount() const
 {
-  return this->rayCountP->GetValue();
+  return this->laserShape->GetRayCount();
 }
 
 //////////////////////////////////////////////////////////////////////////////
 /// Get the range count
 int RaySensor::GetRangeCount() const
 {
-  return this->rangeCountP->GetValue();
+  return this->laserShape->GetRangeCount();
 }
 
 //////////////////////////////////////////////////////////////////////////////
 /// Get the vertical scan line count
 int RaySensor::GetVerticalRayCount() const
 {
-  return this->verticalRayCountP->GetValue();
+  return this->laserShape->GetVerticalRayCount();
 }
 
 //////////////////////////////////////////////////////////////////////////////
 /// Get the vertical scan line count
 int RaySensor::GetVerticalRangeCount() const
 {
-  return this->verticalRangeCountP->GetValue();
+  return this->laserShape->GetVerticalRangeCount();
 }
 
 //////////////////////////////////////////////////////////////////////////////
 /// Get the vertical min angle
 Angle RaySensor::GetVerticalMinAngle() const
 {
-  return this->verticalMinAngleP->GetValue();
+  return this->laserShape->GetVerticalMinAngle();
 }
 
 //////////////////////////////////////////////////////////////////////////////
 /// Get the vertical max angle
 Angle RaySensor::GetVerticalMaxAngle() const
 {
-  return this->verticalMaxAngleP->GetValue();
+  return this->laserShape->GetVerticalMaxAngle();
 }
 
 //////////////////////////////////////////////////////////////////////////////
@@ -238,7 +185,6 @@
   return this->laserShape->GetRange(index);
 }
 
-
 //////////////////////////////////////////////////////////////////////////////
 // Get detected retro (intensity) value for a ray.
 double RaySensor::GetRetro(int index)

Modified: code/gazebo/branches/bullet2/server/sensors/ray/RaySensor.hh
===================================================================
--- code/gazebo/branches/bullet2/server/sensors/ray/RaySensor.hh        
2009-10-21 16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/server/sensors/ray/RaySensor.hh        
2009-10-21 23:45:08 UTC (rev 8324)
@@ -131,12 +131,13 @@
     /// \brief Get detected fiducial value for a ray.
     public: int GetFiducial(int index);   
   
-    private: ParamT<Angle> *minAngleP, *maxAngleP;
+    /*private: ParamT<Angle> *minAngleP, *maxAngleP;
     private: ParamT<double> *minRangeP, *maxRangeP, *resRangeP;
     private: ParamT<Vector3> *originP;
+    */
   
     private: Pose3d prevPose;
-    private: ParamT<int> *rayCountP;
+    /*private: ParamT<int> *rayCountP;
     private: ParamT<int> *rangeCountP;
     
     /// Display rays when rendering images
@@ -147,6 +148,7 @@
     private: ParamT<int> *verticalRangeCountP;
     private: ParamT<Angle> *verticalMinAngleP;
     private: ParamT<Angle> *verticalMaxAngleP;
+    */
 
     private: Geom *laserGeom;
     private: MultiRayShape *laserShape;

Modified: code/gazebo/branches/bullet2/worlds/pioneer2dx.world
===================================================================
--- code/gazebo/branches/bullet2/worlds/pioneer2dx.world        2009-10-21 
16:29:07 UTC (rev 8323)
+++ code/gazebo/branches/bullet2/worlds/pioneer2dx.world        2009-10-21 
23:45:08 UTC (rev 8324)
@@ -52,6 +52,7 @@
     <grid>false</grid>
 
     <shadowTechnique>stencilModulative</shadowTechnique>
+    <!--<shadowTechnique>none</shadowTechnique>-->
   </rendering:ogre>
 
    <!-- Ground Plane -->
@@ -72,7 +73,7 @@
   </model:physical>
 
   <model:physical name="sphere1_model">
-    <xyz>2.15 -1.68 1.3</xyz>
+    <xyz>2.15 -1.68 1.2</xyz>
     <rpy>0.0 0.0 0.0</rpy>
     <static>false</static>
     <laserFiducialId>1</laserFiducialId>
@@ -80,10 +81,10 @@
 
     <body:sphere name="sphere1_body">
       <geom:sphere name="sphere1_geom">
-        <size>0.1</size>
+        <size>0.2</size>
         <mass>1</mass>
         <visual>
-          <scale>0.1 0.1 0.1</scale>
+          <scale>0.2 0.2 0.2</scale>
           <mesh>unit_sphere</mesh>
           <material>Gazebo/Rocky</material>
         </visual>
@@ -104,7 +105,6 @@
   <model:physical name="pioneer2dx_model1">
     <xyz>0 0 .145</xyz>
     <rpy>0.0 0.0 90.0</rpy>
-    <!--<collide>all</collide>-->
 
     <model:physical name="laser">
       <xyz>0.15 0 0.18</xyz>
@@ -147,7 +147,7 @@
     </include>
   </model:physical>
 
-  <!--<model:physical name="box1_model">
+  <model:physical name="box1_model">
     <xyz>1 1.5 0.5</xyz>
     <canonicalBody>box1_body</canonicalBody>
     <static>true</static>
@@ -161,12 +161,11 @@
         <visual>
           <size>1 1 1</size>
           <mesh>unit_box</mesh>
-          <material>Gazebo/SmileyHappy</material>
+          <material>Gazebo/Grey</material>
         </visual>
       </geom:box>
     </body:box>
   </model:physical>
-  -->
 
 
   <!-- Directional  light -->


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

------------------------------------------------------------------------------
Come build with us! The BlackBerry(R) Developer Conference in SF, CA
is the only developer event you need to attend this year. Jumpstart your
developing skills, take BlackBerry mobile applications to market and stay 
ahead of the curve. Join us from November 9 - 12, 2009. Register now!
http://p.sf.net/sfu/devconference
_______________________________________________
Playerstage-commit mailing list
Playerstage-commit@lists.sourceforge.net
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to