Revision: 6433 http://playerstage.svn.sourceforge.net/playerstage/?rev=6433&view=rev Author: robotos Date: 2008-05-12 09:51:48 -0700 (Mon, 12 May 2008)
Log Message: ----------- Making gcc extra verbose helps finding unused variables and some bugs! Also relax the debugging level, gdb don't need so much information and we save 25% of file sizes, my HD will be happy... Modified Paths: -------------- code/gazebo/trunk/server/GazeboMessage.cc code/gazebo/trunk/server/Simulator.cc code/gazebo/trunk/server/controllers/actarray/bandit/Bandit_Actarray.cc code/gazebo/trunk/server/controllers/camera/generic/Generic_Camera.cc code/gazebo/trunk/server/controllers/laser/sicklms200/SickLMS200_Laser.cc code/gazebo/trunk/server/controllers/position2d/differential/Differential_Position2d.cc code/gazebo/trunk/server/controllers/ptz/generic/Generic_PTZ.cc code/gazebo/trunk/server/gui/Gui.cc code/gazebo/trunk/server/physics/Body.cc code/gazebo/trunk/server/physics/TrimeshGeom.cc code/gazebo/trunk/server/physics/UniversalJoint.cc code/gazebo/trunk/server/physics/ode/ODEPhysics.cc code/gazebo/trunk/server/rendering/MovableText.cc code/gazebo/trunk/server/rendering/OgreAdaptor.cc code/gazebo/trunk/server/rendering/OgreCreator.cc code/gazebo/trunk/server/rendering/OgreDynamicRenderable.cc code/gazebo/trunk/server/rendering/OgreSimpleShape.cc code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc Modified: code/gazebo/trunk/server/GazeboMessage.cc =================================================================== --- code/gazebo/trunk/server/GazeboMessage.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/GazeboMessage.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -62,7 +62,6 @@ void GazeboMessage::Load(XMLConfigNode *node) { - bool logData; char logFilename[50]; if (!node) Modified: code/gazebo/trunk/server/Simulator.cc =================================================================== --- code/gazebo/trunk/server/Simulator.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/Simulator.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -196,7 +196,7 @@ //Initialize the world if (gazebo::World::Instance()->Init() != 0) return -1; - + return 0; } //////////////////////////////////////////////////////////////////////////////// Modified: code/gazebo/trunk/server/controllers/actarray/bandit/Bandit_Actarray.cc =================================================================== --- code/gazebo/trunk/server/controllers/actarray/bandit/Bandit_Actarray.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/controllers/actarray/bandit/Bandit_Actarray.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -98,14 +98,13 @@ { HingeJoint *joint = NULL; float angle; - float hiStop, loStop; this->myIface->Lock(1); this->myIface->data->head.time = Simulator::Instance()->GetSimTime(); this->myIface->data->actuators_count = 16; - for (int i=0; i<16; i++) + for (unsigned int i=0; i<16; i++) { double cmdAngle = this->myIface->data->cmd_pos[i]; joint = dynamic_cast<HingeJoint*>(this->joints[i]); Modified: code/gazebo/trunk/server/controllers/camera/generic/Generic_Camera.cc =================================================================== --- code/gazebo/trunk/server/controllers/camera/generic/Generic_Camera.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/controllers/camera/generic/Generic_Camera.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -95,7 +95,6 @@ CameraData *data = this->cameraIface->data; const unsigned char *src; unsigned char *dst; - int i, j, k; Pose3d cameraPose; this->cameraIface->Lock(1); @@ -129,6 +128,7 @@ memcpy(dst, src, data->image_size); + //unsigned int i, j, k; // OGRE image data is A8 B8 G8 R8. Must convert to R8 G8 B8 /* for (i=0; i<data->height; i++) for (j=0; j<data->width; j++) Modified: code/gazebo/trunk/server/controllers/laser/sicklms200/SickLMS200_Laser.cc =================================================================== --- code/gazebo/trunk/server/controllers/laser/sicklms200/SickLMS200_Laser.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/controllers/laser/sicklms200/SickLMS200_Laser.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -196,10 +196,11 @@ double maxAngle = this->myParent->GetMaxAngle(); double minAngle = this->myParent->GetMinAngle(); - double maxRange = this->myParent->GetMaxRange(); +//TODO: implement max range and rangeCount +// double maxRange = this->myParent->GetMaxRange(); double minRange = this->myParent->GetMinRange(); int rayCount = this->myParent->GetRayCount(); - int rangeCount = this->myParent->GetRangeCount(); +// int rangeCount = this->myParent->GetRangeCount(); if (this->fiducialIface->Lock(1)) { Modified: code/gazebo/trunk/server/controllers/position2d/differential/Differential_Position2d.cc =================================================================== --- code/gazebo/trunk/server/controllers/position2d/differential/Differential_Position2d.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/controllers/position2d/differential/Differential_Position2d.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -133,8 +133,6 @@ // Update the controller void Differential_Position2d::UpdateChild(UpdateParams ¶ms) { - bool opened = false; - // TODO: Step should be in a parameter of this function double wd, ws; double d1, d2; Modified: code/gazebo/trunk/server/controllers/ptz/generic/Generic_PTZ.cc =================================================================== --- code/gazebo/trunk/server/controllers/ptz/generic/Generic_PTZ.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/controllers/ptz/generic/Generic_PTZ.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -165,7 +165,6 @@ void Generic_PTZ::PutPTZData() { PTZData *data = this->ptzIface->data; - int i, j, k; this->ptzIface->Lock(1); Modified: code/gazebo/trunk/server/gui/Gui.cc =================================================================== --- code/gazebo/trunk/server/gui/Gui.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/gui/Gui.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -48,8 +48,9 @@ //////////////////////////////////////////////////////////////////////////////// /// Constructor FLTKGui::FLTKGui (int x, int y, int width, int height, const std::string &t) - : Fl_Window(x, y, width+200, height+60, t.c_str()), Gui(x,y,width,height, t) -{ + : Gui(x,y,width,height, t), + Fl_Window(x, y, width+200, height+60, t.c_str()) + { this->windowId = -1; this->visual = NULL; this->display = NULL; @@ -57,7 +58,7 @@ Fl::scheme("plastic"); // Create a main menu - MainMenu *mainMenu = new MainMenu(0,0,w(),30,(char *)"MainMenu"); + new MainMenu(0,0,w(),30,(char *)"MainMenu"); // Create the Rendering window this->glWindow = new GLWindow(0, 30, w()-200, h()-60,"GL Window"); Modified: code/gazebo/trunk/server/physics/Body.cc =================================================================== --- code/gazebo/trunk/server/physics/Body.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/physics/Body.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -467,7 +467,6 @@ */ void Body::UpdateCoM() { - int i; const dMass *lmass; Pose3d oldPose, newPose, pose; std::vector< Geom* >::iterator giter; Modified: code/gazebo/trunk/server/physics/TrimeshGeom.cc =================================================================== --- code/gazebo/trunk/server/physics/TrimeshGeom.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/physics/TrimeshGeom.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -91,7 +91,7 @@ Ogre::SubMesh* subMesh; Ogre::MeshPtr mesh; - int i,j,k; + unsigned int i,j; unsigned int numVertices = 0; unsigned int numIndices = 0; const Ogre::VertexElement* elem; Modified: code/gazebo/trunk/server/physics/UniversalJoint.cc =================================================================== --- code/gazebo/trunk/server/physics/UniversalJoint.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/physics/UniversalJoint.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -68,7 +68,7 @@ // Perform this three step ordering to ensure the parameters are set // properly. This is taken from the ODE wiki. this->SetParam(dParamHiStop2, hiStop2); - this->SetParam(dParamLoStop2, loStop1); + this->SetParam(dParamLoStop2, loStop2); this->SetParam(dParamHiStop2, hiStop2); } Modified: code/gazebo/trunk/server/physics/ode/ODEPhysics.cc =================================================================== --- code/gazebo/trunk/server/physics/ode/ODEPhysics.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/physics/ode/ODEPhysics.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -257,8 +257,8 @@ else geom2 = (Geom*) dGeomGetData(o2); - - if (numc = dCollide (o1,o2,64, contactGeoms, sizeof(contactGeoms[0]))) + numc = dCollide(o1,o2,64, contactGeoms, sizeof(contactGeoms[0])); + if (numc == 0) { for (i=0; i<numc; i++) { Modified: code/gazebo/trunk/server/rendering/MovableText.cc =================================================================== --- code/gazebo/trunk/server/rendering/MovableText.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/rendering/MovableText.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -22,14 +22,14 @@ MovableText::MovableText() : camera(NULL), renderWindow(NULL) , + viewportAspectCoef (0.75), font(NULL) , spaceWidth(0) , updateColors(true) , + vertAlign(V_BELOW) , + horizAlign(H_LEFT) , onTop(false) , - horizAlign(H_LEFT) , - vertAlign(V_BELOW) , - baseline(0.0) , - viewportAspectCoef (0.75) + baseline(0.0) { this->renderOp.vertexData = NULL; } Modified: code/gazebo/trunk/server/rendering/OgreAdaptor.cc =================================================================== --- code/gazebo/trunk/server/rendering/OgreAdaptor.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/rendering/OgreAdaptor.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -291,8 +291,9 @@ rnode->SetValue("ambient", this->backgroundColor); //TODO: BSP (when bsp are definitely integrated) - - if (cnode=node->GetChild("fog")) + // + cnode = rnode->GetChild("fog"); + if (cnode) OgreCreator::SaveFog(cnode); } Modified: code/gazebo/trunk/server/rendering/OgreCreator.cc =================================================================== --- code/gazebo/trunk/server/rendering/OgreCreator.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/rendering/OgreCreator.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -236,7 +236,7 @@ Ogre::ColourValue color=OgreAdaptor::Instance()->sceneMgr->getFogColour(); Ogre::Real start = OgreAdaptor::Instance()->sceneMgr->getFogStart(); Ogre::Real end = OgreAdaptor::Instance()->sceneMgr->getFogEnd(); - Ogre::Real density = OgreAdaptor::Instance()->sceneMgr->getFogDensity(); + //Ogre::Real density = OgreAdaptor::Instance()->sceneMgr->getFogDensity(); std::string fogMode=""; switch (OgreAdaptor::Instance()->sceneMgr->getFogMode()) @@ -251,6 +251,9 @@ //case default: fogMode="linear"; break; + case Ogre::FOG_NONE: + fogMode="none"; + break; } node->SetValue("type", fogMode); node->SetValue("color", &color); Modified: code/gazebo/trunk/server/rendering/OgreDynamicRenderable.cc =================================================================== --- code/gazebo/trunk/server/rendering/OgreDynamicRenderable.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/rendering/OgreDynamicRenderable.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -76,26 +76,28 @@ // Get the render operation type OgreDynamicRenderable::OperationType OgreDynamicRenderable::GetOperationType() const { + OperationType type = OT_POINT_LIST; switch (this->mRenderOp.operationType) { case Ogre::RenderOperation::OT_POINT_LIST: - return OT_POINT_LIST; + type = OT_POINT_LIST; case Ogre::RenderOperation::OT_LINE_LIST: - return OT_LINE_LIST; + type = OT_LINE_LIST; case Ogre::RenderOperation::OT_LINE_STRIP: - return OT_LINE_STRIP; + type = OT_LINE_STRIP; case Ogre::RenderOperation::OT_TRIANGLE_LIST: - return OT_TRIANGLE_LIST; + type = OT_TRIANGLE_LIST; case Ogre::RenderOperation::OT_TRIANGLE_STRIP: - return OT_TRIANGLE_STRIP; + type = OT_TRIANGLE_STRIP; case Ogre::RenderOperation::OT_TRIANGLE_FAN: - return OT_TRIANGLE_FAN; + type = OT_TRIANGLE_FAN; } + return type; } //////////////////////////////////////////////////////////////////////////////// Modified: code/gazebo/trunk/server/rendering/OgreSimpleShape.cc =================================================================== --- code/gazebo/trunk/server/rendering/OgreSimpleShape.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/rendering/OgreSimpleShape.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -173,7 +173,6 @@ float *vertices; unsigned short *indices; Vector3 vert, norm; - unsigned short verticeIndex = 0; size_t currOffset = 0; int i,j,k; @@ -351,7 +350,7 @@ Vector3 vert, norm; unsigned short verticeIndex = 0; size_t currOffset = 0; - int i,j; + unsigned int i,j; int ring, seg; float deltaSegAngle = (2.0 * M_PI / segments); Modified: code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc =================================================================== --- code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc 2008-05-12 06:24:20 UTC (rev 6432) +++ code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc 2008-05-12 16:51:48 UTC (rev 6433) @@ -89,7 +89,6 @@ { Ogre::Viewport *cviewport; Ogre::MaterialPtr matPtr; - Ogre::TextureUnitState *texUnit; Ogre::HardwarePixelBufferSharedPtr mBuffer; int i; @@ -187,7 +186,6 @@ Ogre::Viewport *vp = NULL; Ogre::SceneManager *sceneMgr = adapt->sceneMgr; Ogre::Pass *pass; - Ogre::Pass *prev_pass; Ogre::SceneNode *gridNode = sceneMgr->getSceneNode("__OGRE_GRID_NODE__"); int i; @@ -351,13 +349,13 @@ fprintf( fp, "P6\n# Gazebo\n%d %d\n255\n", this->imageWidth, this->imageHeight); - for (int i = 0; i<this->imageHeight; i++) + for (unsigned int i = 0; i<this->imageHeight; i++) { - for (int j =0; j<this->imageWidth; j++) + for (unsigned int j =0; j<this->imageWidth; j++) { float f = this->depthBuffer[0][i*this->imageWidth+j]; - - unsigned char value = f * 255; + + unsigned char value = static_cast<unsigned char>((double)f * 255); fwrite( &value, 1, 1, fp ); fwrite( &value, 1, 1, fp ); fwrite( &value, 1, 1, fp ); This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. ------------------------------------------------------------------------- This SF.net email is sponsored by the 2008 JavaOne(SM) Conference Don't miss this year's exciting event. There's still time to save $100. Use priority code J8TL2D2. http://ad.doubleclick.net/clk;198757673;13503038;p?http://java.sun.com/javaone _______________________________________________ Playerstage-commit mailing list Playerstage-commit@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/playerstage-commit