From 8e2e017c0a038975a48e54a03b656661717fde15 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 14:00:48 +0100 Subject: [PATCH 01/57] Compiler warnings - unused parameters, variable, function, private-field --- Extras/ConvexDecomposition/ConvexBuilder.cpp | 2 +- .../ConvexDecomposition/ConvexDecomposition.h | 8 +- Extras/ConvexDecomposition/cd_hull.cpp | 10 +- Extras/ConvexDecomposition/cd_wavefront.cpp | 4 +- Extras/ConvexDecomposition/concavity.cpp | 8 +- Extras/ConvexDecomposition/meshvolume.cpp | 2 +- Extras/ConvexDecomposition/splitplane.cpp | 7 +- .../btGImpactConvexDecompositionShape.cpp | 2 +- Extras/InverseDynamics/DillCreator.cpp | 2 +- Extras/Serialize/BulletFileLoader/bDNA.cpp | 2 +- Extras/Serialize/BulletFileLoader/bFile.cpp | 4 + .../BulletFileLoader/btBulletFile.cpp | 1 + .../btMultiBodyWorldImporter.cpp | 12 +- .../BulletWorldImporter/btWorldImporter.cpp | 5 +- .../btBulletXmlWorldImporter.cpp | 2 +- Extras/VHACD/inc/vhacdMutex.h | 1 + Extras/VHACD/inc/vhacdVolume.h | 4 +- Extras/VHACD/src/VHACD.cpp | 6 +- Extras/VHACD/src/vhacdVolume.cpp | 21 +- Extras/VHACD/test/src/main_vhacd.cpp | 2 +- examples/BasicDemo/main.cpp | 2 +- examples/Benchmarks/BenchmarkDemo.cpp | 4 +- examples/BulletRobotics/BoxStack.cpp | 5 +- examples/BulletRobotics/FixJointBoxes.cpp | 5 +- examples/BulletRobotics/JointLimit.cpp | 5 +- examples/Collision/CollisionSdkC_Api.cpp | 2 +- .../Collision/CollisionTutorialBullet2.cpp | 13 +- .../Internal/Bullet2CollisionSdk.cpp | 14 +- .../Internal/RealTimeBullet3CollisionSdk.cpp | 18 +- .../CommonInterfaces/CommonExampleInterface.h | 10 +- .../CommonGUIHelperInterface.h | 118 ++++---- .../CommonGraphicsAppInterface.h | 10 +- .../CommonInterfaces/CommonMultiBodyBase.h | 1 + .../CommonInterfaces/CommonRenderInterface.h | 12 +- .../CommonInterfaces/CommonRigidBodyBase.h | 1 + examples/Constraints/ConstraintDemo.cpp | 3 +- examples/Constraints/TestHingeTorque.cpp | 2 +- examples/DeformableDemo/DeformableContact.cpp | 2 +- .../DeformableDemo/DeformableMultibody.cpp | 1 - examples/DeformableDemo/DeformableRigid.cpp | 2 +- examples/DeformableDemo/GraspDeformable.cpp | 4 +- examples/DeformableDemo/LoadDeformed.cpp | 9 +- examples/DeformableDemo/Pinch.cpp | 2 + examples/DeformableDemo/PinchFriction.cpp | 4 +- examples/DeformableDemo/SplitImpulse.cpp | 2 +- examples/Evolution/NN3DWalkers.cpp | 2 +- examples/Evolution/NN3DWalkersTimeWarpBase.h | 16 +- examples/ExampleBrowser/EmptyExample.h | 10 +- examples/ExampleBrowser/GL_ShapeDrawer.cpp | 2 +- .../GwenGUISupport/GwenParameterInterface.cpp | 2 +- .../GwenGUISupport/GwenTextureWindow.cpp | 2 +- .../GwenGUISupport/gwenUserInterface.cpp | 6 +- .../InProcessExampleBrowser.cpp | 3 +- .../ExampleBrowser/OpenGLExampleBrowser.cpp | 14 +- examples/ExampleBrowser/OpenGLGuiHelper.cpp | 22 +- examples/ExampleBrowser/OpenGLGuiHelper.h | 8 +- examples/ExtendedTutorials/InclinedPlane.cpp | 4 +- examples/ExtendedTutorials/MultiPendulum.cpp | 2 +- examples/ExtendedTutorials/NewtonsCradle.cpp | 2 +- .../ExtendedTutorials/NewtonsRopeCradle.cpp | 2 +- examples/ForkLift/ForkLiftDemo.cpp | 13 +- examples/FractureDemo/btFractureBody.cpp | 2 +- .../FractureDemo/btFractureDynamicsWorld.cpp | 1 + examples/Heightfield/HeightfieldExample.cpp | 16 +- examples/HelloWorld/HelloWorld.cpp | 2 +- examples/Importers/ImportBsp/BspLoader.cpp | 2 +- .../Importers/ImportBsp/ImportBspExample.cpp | 5 +- .../ImportMJCFDemo/BulletMJCFImporter.cpp | 22 +- .../ImportMJCFDemo/BulletMJCFImporter.h | 5 +- .../ImportMJCFDemo/ImportMJCFSetup.cpp | 2 +- .../ImportURDFDemo/BulletUrdfImporter.cpp | 2 +- .../MultiBodyCreationInterface.h | 4 +- .../ImportURDFDemo/MyMultiBodyCreator.cpp | 10 +- .../Importers/ImportURDFDemo/URDF2Bullet.cpp | 8 +- .../ImportURDFDemo/URDFImporterInterface.h | 32 +-- .../Importers/ImportURDFDemo/UrdfParser.cpp | 4 +- .../ImportURDFDemo/UrdfRenderingInterface.h | 6 +- .../InverseDynamicsExample.cpp | 4 +- .../InverseKinematicsExample.cpp | 20 +- .../MultiBody/InvertedPendulumPDControl.cpp | 2 +- .../MultiBody/MultiBodyConstraintFeedback.cpp | 2 +- examples/MultiBody/Pendulum.cpp | 1 + examples/MultiBody/TestJointTorqueSetup.cpp | 2 +- .../CommonRigidBodyMTBase.cpp | 42 +-- .../MultiThreadedDemo/CommonRigidBodyMTBase.h | 1 + .../MultiThreadedDemo/MultiThreadedDemo.cpp | 2 +- .../MultiThreading/MultiThreadingExample.cpp | 12 +- .../MultiThreading/b3PosixThreadSupport.cpp | 7 +- .../MultiThreading/b3PosixThreadSupport.h | 2 +- .../MultiThreading/b3ThreadSupportInterface.h | 2 +- examples/OpenGLWindow/EGLOpenGLWindow.cpp | 10 +- .../OpenGLWindow/GLInstancingRenderer.cpp | 16 +- examples/OpenGLWindow/GLPrimitiveRenderer.cpp | 2 +- examples/OpenGLWindow/GLRenderToTexture.cpp | 2 +- .../OpenGLWindow/GwenOpenGL3CoreRenderer.h | 6 +- examples/OpenGLWindow/SimpleOpenGL2App.cpp | 8 +- examples/OpenGLWindow/SimpleOpenGL2App.h | 2 +- .../OpenGLWindow/SimpleOpenGL2Renderer.cpp | 32 +-- examples/OpenGLWindow/SimpleOpenGL2Renderer.h | 18 +- examples/OpenGLWindow/SimpleOpenGL3App.cpp | 17 +- examples/OpenGLWindow/TwFonts.cpp | 2 +- examples/OpenGLWindow/Win32OpenGLWindow.cpp | 5 +- examples/OpenGLWindow/Win32Window.cpp | 20 +- examples/OpenGLWindow/X11OpenGLWindow.cpp | 4 +- examples/OpenGLWindow/fontstash.cpp | 6 +- .../opengl_fontstashcallbacks.cpp | 2 +- .../OpenGLWindow/opengl_fontstashcallbacks.h | 6 +- .../ConservationTest.cpp | 7 +- examples/ReducedDeformableDemo/FreeFall.cpp | 4 +- .../ReducedDeformableDemo/FrictionSlope.cpp | 5 +- .../ReducedDeformableDemo/ModeVisualizer.cpp | 2 +- .../ReducedBenchmark.cpp | 4 +- .../ReducedDeformableDemo/ReducedCollide.cpp | 2 +- .../ReducedDeformableDemo/ReducedGrasp.cpp | 2 +- .../ReducedMotorGrasp.cpp | 4 +- .../ReducedDeformableDemo/Springboard.cpp | 4 +- .../CoordinateSystemDemo.cpp | 10 +- .../DynamicTexturedCubeDemo.cpp | 8 +- examples/RenderingExamples/RaytracerSetup.cpp | 18 +- .../RenderInstancingDemo.cpp | 10 +- .../RenderingExamples/TimeSeriesCanvas.cpp | 2 +- .../RenderingExamples/TimeSeriesExample.cpp | 10 +- .../RenderingExamples/TinyRendererSetup.cpp | 16 +- examples/RenderingExamples/TinyVRGui.cpp | 12 +- .../RigidBody/KinematicRigidBodyExample.cpp | 2 +- examples/RigidBody/RigidBodySoftContact.cpp | 1 + .../RobotSimulator/HelloBulletRobotics.cpp | 2 +- .../RobotSimulator/RobotSimulatorMain.cpp | 4 +- .../b3RobotSimulatorClientAPI.cpp | 3 + .../RoboticsLearning/GripperGraspExample.cpp | 3 +- .../RoboticsLearning/KukaGraspExample.cpp | 7 +- .../RoboticsLearning/R2D2GraspExample.cpp | 10 +- .../SharedMemory/GraphicsClientExample.cpp | 12 +- .../SharedMemory/GraphicsServerExample.cpp | 36 +-- examples/SharedMemory/IKTrajectoryHelper.cpp | 4 +- examples/SharedMemory/InProcessMemory.cpp | 2 +- examples/SharedMemory/PhysicsClientC_API.cpp | 10 +- .../SharedMemory/PhysicsClientExample.cpp | 13 +- .../PhysicsClientSharedMemory.cpp | 2 +- examples/SharedMemory/PhysicsClientTCP.cpp | 8 +- examples/SharedMemory/PhysicsClientUDP.cpp | 12 +- examples/SharedMemory/PhysicsDirect.cpp | 7 +- examples/SharedMemory/PhysicsDirectC_API.cpp | 1 + .../SharedMemory/PhysicsLoopBackC_API.cpp | 1 + examples/SharedMemory/PhysicsServer.h | 12 +- .../PhysicsServerCommandProcessor.cpp | 263 ++++++++++-------- .../PhysicsServerCommandProcessor.h | 2 +- .../SharedMemory/PhysicsServerExample.cpp | 32 ++- .../PhysicsServerSharedMemory.cpp | 4 +- examples/SharedMemory/PosixSharedMemory.cpp | 7 +- examples/SharedMemory/RemoteGUIHelper.cpp | 42 +-- examples/SharedMemory/RemoteGUIHelperTCP.cpp | 41 +-- .../SharedMemoryCommandProcessor.cpp | 10 +- examples/SharedMemory/Win32SharedMemory.cpp | 2 +- examples/SharedMemory/b3PluginManager.cpp | 7 +- .../b3RobotSimulatorClientAPI_NoDirect.cpp | 43 ++- .../b3RobotSimulatorClientAPI_NoGUI.cpp | 7 +- .../collisionFilterPlugin.cpp | 2 +- .../pdControlPlugin/pdControlPlugin.cpp | 6 +- .../stablePDPlugin/BulletConversion.cpp | 6 +- .../plugins/stablePDPlugin/KinTree.cpp | 22 +- .../plugins/stablePDPlugin/RBDUtil.cpp | 54 ++-- .../TinyRendererVisualShapeConverter.cpp | 15 +- .../tinyRendererPlugin/tinyRendererPlugin.cpp | 2 +- examples/SoftDemo/SoftDemo.cpp | 16 +- .../StandaloneMain/hellovr_opengl_main.cpp | 4 +- examples/ThirdPartyLibs/BussIK/MathMisc.h | 2 +- examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp | 2 +- examples/ThirdPartyLibs/Gwen/BaseRender.h | 23 +- .../ThirdPartyLibs/Gwen/Controls/Base.cpp | 2 +- .../ThirdPartyLibs/Gwen/Controls/Button.h | 2 +- .../Gwen/Controls/TabControl.cpp | 4 +- .../ThirdPartyLibs/Gwen/Platforms/Null.cpp | 6 +- .../Gwen/Renderers/OpenGL_DebugFont.h | 2 +- examples/ThirdPartyLibs/Gwen/Skins/Simple.h | 16 +- .../Wavefront/tiny_obj_loader.cpp | 4 +- .../clsocket/src/PassiveSocket.cpp | 5 +- .../clsocket/src/SimpleSocket.cpp | 7 +- .../clsocket/src/SimpleSocket.h | 2 +- .../openvr/samples/shared/pathtools.cpp | 1 + .../openvr/samples/shared/strtools.h | 4 +- .../ThirdPartyLibs/stb_image/stb_image.cpp | 2 +- examples/TinyRenderer/TinyRenderer.cpp | 2 +- examples/TinyRenderer/our_gl.cpp | 2 +- examples/Tutorial/Tutorial.cpp | 16 +- examples/Utils/ChromeTraceUtil.cpp | 2 +- examples/Utils/b3BulletDefaultFileIO.h | 1 + examples/Utils/b3ResourcePath.cpp | 2 +- examples/Vehicles/Hinge2Vehicle.cpp | 7 +- .../btConvexConvexMprAlgorithm.cpp | 4 +- .../b3DynamicBvhBroadphase.cpp | 2 +- .../b3OverlappingPairCache.cpp | 6 +- .../NarrowPhaseCollision/b3ConvexUtility.cpp | 2 +- .../NarrowPhaseCollision/b3CpuNarrowPhase.cpp | 4 +- .../shared/b3BvhTraversal.h | 2 +- .../NarrowPhaseCollision/shared/b3ClipFaces.h | 2 +- .../shared/b3ContactConvexConvexSAT.h | 14 +- .../shared/b3FindConcaveSatAxis.h | 27 +- .../shared/b3FindSeparatingAxis.h | 6 +- .../shared/b3MprPenetration.h | 8 +- src/Bullet3Common/b3FileUtils.h | 3 +- src/Bullet3Common/b3Logging.cpp | 2 +- src/Bullet3Common/b3Scalar.h | 10 +- .../shared/b3PlatformDefinitions.h | 2 +- .../ConstraintSolver/b3FixedConstraint.cpp | 2 +- .../ConstraintSolver/b3FixedConstraint.h | 4 +- .../b3Generic6DofConstraint.cpp | 2 +- .../ConstraintSolver/b3PgsJacobiSolver.cpp | 30 +- .../ConstraintSolver/b3PgsJacobiSolver.h | 2 +- .../b3Point2PointConstraint.cpp | 2 +- .../b3CpuRigidBodyPipeline.cpp | 4 +- .../shared/b3ConvertConstraint4.h | 2 +- .../b3GpuGridBroadphase.cpp | 4 +- .../b3GpuParallelLinearBvh.cpp | 1 + .../b3GpuParallelLinearBvh.h | 2 - .../b3GpuParallelLinearBvhBroadphase.cpp | 6 +- .../b3GpuSapBroadphase.cpp | 6 +- .../Initialize/b3OpenCLUtils.cpp | 14 +- .../b3ConvexHullContact.cpp | 66 +++-- .../NarrowphaseCollision/b3GjkEpa.cpp | 4 +- .../NarrowphaseCollision/b3QuantizedBvh.cpp | 4 +- .../b3StridingMeshInterface.cpp | 2 +- .../NarrowphaseCollision/b3SupportMappings.h | 2 +- .../NarrowphaseCollision/kernels/mprKernels.h | 2 +- .../kernels/primitiveContacts.h | 2 +- .../kernels/satClipHullContacts.h | 2 +- .../kernels/satConcaveKernels.h | 2 +- .../NarrowphaseCollision/kernels/satKernels.h | 2 +- .../ParallelPrimitives/b3BoundSearchCL.cpp | 12 +- .../ParallelPrimitives/b3LauncherCL.cpp | 4 +- .../ParallelPrimitives/b3RadixSort32CL.cpp | 4 +- src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp | 4 +- .../RigidBody/b3GpuGenericConstraint.cpp | 2 +- .../RigidBody/b3GpuJacobiContactSolver.cpp | 6 +- .../RigidBody/b3GpuNarrowPhase.cpp | 4 +- .../RigidBody/b3GpuPgsConstraintSolver.cpp | 4 +- .../RigidBody/b3GpuPgsContactSolver.cpp | 16 +- .../RigidBody/b3GpuRigidBodyPipeline.cpp | 2 +- src/Bullet3OpenCL/RigidBody/b3GpuSolverBody.h | 2 +- src/Bullet3OpenCL/RigidBody/b3Solver.cpp | 26 +- .../RigidBody/kernels/batchingKernels.h | 2 +- .../RigidBody/kernels/batchingKernelsNew.h | 2 +- .../RigidBody/kernels/integrateKernel.h | 2 +- .../RigidBody/kernels/solverSetup.h | 2 +- .../RigidBody/kernels/solverSetup2.h | 2 +- .../RigidBody/kernels/solverUtils.h | 2 +- .../RigidBody/kernels/updateAabbsKernel.h | 2 +- .../Bullet2FileLoader/b3BulletFile.cpp | 1 + .../Bullet2FileLoader/b3DNA.cpp | 2 +- .../Bullet2FileLoader/b3File.cpp | 5 +- .../Bullet2FileLoader/b3Serializer.h | 2 +- .../BroadphaseCollision/btDbvtBroadphase.cpp | 2 +- .../btOverlappingPairCache.cpp | 2 +- .../BroadphaseCollision/btQuantizedBvh.cpp | 6 +- .../btSimpleBroadphase.cpp | 4 +- .../SphereTriangleDetector.cpp | 2 +- .../btBox2dBox2dCollisionAlgorithm.cpp | 6 +- .../btCollisionDispatcherMt.cpp | 2 +- .../CollisionDispatch/btCollisionWorld.cpp | 2 +- .../btCollisionWorldImporter.cpp | 2 +- .../btCompoundCompoundCollisionAlgorithm.cpp | 2 +- .../btConvexConcaveCollisionAlgorithm.cpp | 2 +- .../btConvexConvexAlgorithm.cpp | 8 +- .../btConvexPlaneCollisionAlgorithm.cpp | 2 +- .../btEmptyCollisionAlgorithm.h | 2 +- .../CollisionDispatch/btGhostObject.cpp | 4 +- .../btInternalEdgeUtility.cpp | 4 +- .../btSimulationIslandManager.cpp | 2 - .../CollisionShapes/btBox2dShape.h | 9 +- .../CollisionShapes/btBoxShape.h | 9 +- .../btConvexPointCloudShape.cpp | 2 +- .../CollisionShapes/btConvexShape.cpp | 8 +- .../CollisionShapes/btMiniSDF.cpp | 4 +- .../btPolyhedralConvexShape.cpp | 2 +- .../btScaledBvhTriangleMeshShape.cpp | 2 +- .../CollisionShapes/btSdfCollisionShape.cpp | 4 +- .../btStridingMeshInterface.cpp | 2 +- src/BulletCollision/Gimpact/btGImpactBvh.cpp | 4 +- .../Gimpact/btGImpactCollisionAlgorithm.cpp | 6 +- .../Gimpact/btGImpactQuantizedBvh.cpp | 2 +- .../Gimpact/btGImpactShape.cpp | 2 +- .../btComputeGjkEpaPenetration.h | 3 +- .../NarrowPhaseCollision/btMprPenetration.h | 6 +- .../btPolyhedralContactClipping.cpp | 10 +- .../btKinematicCharacterController.cpp | 4 +- .../ConstraintSolver/btBatchedConstraints.cpp | 20 +- .../btConeTwistConstraint.cpp | 2 +- .../ConstraintSolver/btConstraintSolver.h | 4 +- .../ConstraintSolver/btContactConstraint.cpp | 4 +- .../btGeneric6DofSpring2Constraint.cpp | 2 +- .../btSequentialImpulseConstraintSolver.cpp | 22 +- .../btSequentialImpulseConstraintSolverMt.cpp | 28 +- .../Dynamics/btDiscreteDynamicsWorld.cpp | 2 +- src/BulletDynamics/Dynamics/btRigidBody.cpp | 2 +- .../Dynamics/btSimpleDynamicsWorld.cpp | 4 +- .../Dynamics/btSimulationIslandManagerMt.cpp | 4 +- .../Featherstone/btMultiBody.cpp | 2 +- .../Featherstone/btMultiBodyConstraint.cpp | 2 +- .../Featherstone/btMultiBodyConstraint.h | 12 +- .../btMultiBodyConstraintSolver.cpp | 8 +- .../Featherstone/btMultiBodyDynamicsWorld.cpp | 2 +- .../btMultiBodyGearConstraint.cpp | 12 +- .../Featherstone/btMultiBodyGearConstraint.h | 2 +- .../btMultiBodyJointLimitConstraint.h | 2 +- .../Featherstone/btMultiBodyJointMotor.h | 2 +- .../btMultiBodySphericalJointLimit.cpp | 16 +- .../btMultiBodySphericalJointMotor.cpp | 14 +- .../btMultiBodySphericalJointMotor.h | 2 +- .../MLCPSolvers/btDantzigLCP.cpp | 4 +- .../MLCPSolvers/btDantzigSolver.h | 3 +- .../MLCPSolvers/btLemkeAlgorithm.cpp | 2 +- .../MLCPSolvers/btLemkeSolver.h | 6 +- .../details/IDLinearMathInterface.hpp | 2 +- .../btReducedDeformableBody.cpp | 6 +- .../btReducedDeformableBodyHelpers.cpp | 4 +- .../btReducedDeformableBodySolver.cpp | 8 +- .../btReducedDeformableContactConstraint.cpp | 8 +- .../btReducedDeformableContactConstraint.h | 4 +- src/BulletSoftBody/btCGProjection.h | 2 +- .../btDefaultSoftBodySolver.cpp | 6 +- src/BulletSoftBody/btDeformableBodySolver.cpp | 10 +- src/BulletSoftBody/btDeformableBodySolver.h | 10 +- .../btDeformableContactConstraint.cpp | 6 +- .../btDeformableContactConstraint.h | 14 +- .../btDeformableCorotatedForce.h | 8 +- src/BulletSoftBody/btDeformableGravityForce.h | 12 +- .../btDeformableLagrangianForce.h | 8 +- .../btDeformableLinearElasticityForce.h | 10 +- .../btDeformableMassSpringForce.h | 2 +- .../btDeformableMousePickingForce.h | 4 +- .../btDeformableMultiBodyConstraintSolver.cpp | 8 +- .../btDeformableMultiBodyDynamicsWorld.cpp | 2 +- .../btDeformableNeoHookeanForce.h | 6 +- src/BulletSoftBody/btPreconditioner.h | 2 +- src/BulletSoftBody/btSoftBody.cpp | 32 +-- src/BulletSoftBody/btSoftBody.h | 4 +- .../btSoftBodyConcaveCollisionAlgorithm.h | 2 +- src/BulletSoftBody/btSoftBodyHelpers.cpp | 17 +- src/BulletSoftBody/btSoftBodyInternals.h | 16 +- .../btSoftRigidCollisionAlgorithm.h | 2 +- .../TaskScheduler/btTaskScheduler.cpp | 3 +- .../TaskScheduler/btThreadSupportPosix.cpp | 4 +- src/LinearMath/btAlignedObjectArray.h | 6 +- src/LinearMath/btImplicitQRSVD.h | 2 + src/LinearMath/btMatrixX.h | 4 +- src/LinearMath/btQuickprof.cpp | 6 +- src/LinearMath/btScalar.h | 10 +- src/LinearMath/btThreads.cpp | 10 +- .../test_invdyn_kinematics.cpp | 2 +- test/SharedMemory/gtestwrap.cpp | 2 +- test/SharedMemory/test.c | 2 + test/collision/main.cpp | 32 +-- 352 files changed, 1514 insertions(+), 1296 deletions(-) diff --git a/Extras/ConvexDecomposition/ConvexBuilder.cpp b/Extras/ConvexDecomposition/ConvexBuilder.cpp index de48d94851..3db94604b7 100644 --- a/Extras/ConvexDecomposition/ConvexBuilder.cpp +++ b/Extras/ConvexDecomposition/ConvexBuilder.cpp @@ -76,7 +76,7 @@ bool ConvexBuilder::isDuplicate(unsigned int i1, unsigned int i2, unsigned int i return dcount == 3; } -void ConvexBuilder::getMesh(const ConvexDecomposition::ConvexResult &cr, VertexLookup vc, UintVector &indices) +void ConvexBuilder::getMesh(const ConvexDecomposition::ConvexResult &cr, VertexLookup vc, UintVector & /*indices*/) { unsigned int *src = cr.mHullIndices; diff --git a/Extras/ConvexDecomposition/ConvexDecomposition.h b/Extras/ConvexDecomposition/ConvexDecomposition.h index ad5c1f9605..044668fedb 100644 --- a/Extras/ConvexDecomposition/ConvexDecomposition.h +++ b/Extras/ConvexDecomposition/ConvexDecomposition.h @@ -141,10 +141,10 @@ class ConvexDecompInterface { public: virtual ~ConvexDecompInterface(){}; - virtual void ConvexDebugTri(const float *p1, const float *p2, const float *p3, unsigned int color){}; - virtual void ConvexDebugPoint(const float *p, float dist, unsigned int color){}; - virtual void ConvexDebugBound(const float *bmin, const float *bmax, unsigned int color){}; - virtual void ConvexDebugOBB(const float *sides, const float *matrix, unsigned int color){}; + virtual void ConvexDebugTri(const float * /*p1*/, const float * /*p2*/, const float * /*p3*/, unsigned int /*color*/){}; + virtual void ConvexDebugPoint(const float * /*p*/, float /*dist*/, unsigned int /*color*/){}; + virtual void ConvexDebugBound(const float * /*bmin*/, const float * /*bmax*/, unsigned int /*color*/){}; + virtual void ConvexDebugOBB(const float * /*sides*/, const float * /*matrix*/, unsigned int /*color*/){}; virtual void ConvexDecompResult(ConvexResult &result) = 0; }; diff --git a/Extras/ConvexDecomposition/cd_hull.cpp b/Extras/ConvexDecomposition/cd_hull.cpp index f97514e8e9..b26bfa9838 100644 --- a/Extras/ConvexDecomposition/cd_hull.cpp +++ b/Extras/ConvexDecomposition/cd_hull.cpp @@ -979,7 +979,7 @@ float3 operator*(const Quaternion &q, const float3 &v) (2 * (qxqz - qyqw)) * v.x + (2 * (qyqz + qxqw)) * v.y + (1 - 2 * (qx2 + qy2)) * v.z); } -float3 operator*(const float3 &v, const Quaternion &q) +float3 operator*(const float3 & /*v*/, const Quaternion & /*q*/) { assert(0); // must multiply with the quat on the left return float3(0.0f, 0.0f, 0.0f); @@ -1945,7 +1945,7 @@ ConvexH *ConvexHCrop(ConvexH &convex, const Plane &slice) EdgeFlag edgeflag[512]; VertFlag vertflag[256]; - PlaneFlag planeflag[128]; + PlaneFlag planeflag[128]; (void)planeflag; HalfEdge tmpunderedges[512]; Plane tmpunderplanes[128]; Coplanar coplanaredges[512]; @@ -2140,6 +2140,7 @@ ConvexH *ConvexHCrop(ConvexH &convex, const Plane &slice) vin = tmpunderedges[nea + 1].v; assert(vin < vertcountunder); assert(vin >= vertcountunderold); // for debugging only + (void)vertcountunderold; } if (vout != -1) { @@ -2505,10 +2506,11 @@ void removeb2b(btHullTriangle *s, btHullTriangle *t, Array &tr delete t; } -void checkit(btHullTriangle *t, Array &tris) +void checkit(btHullTriangle *t, Array & tris) { int i; assert(tris[t->id] == t); + (void)tris; for (i = 0; i < 3; i++) { int i1 = (i + 1) % 3; @@ -2517,6 +2519,8 @@ void checkit(btHullTriangle *t, Array &tris) int b = (*t)[i2]; assert(a != b); assert(tris[t->n[i]]->neib(b, a) == t->id); + (void)a; + (void)b; } } void extrude(btHullTriangle *t0, int v, Array &tris) diff --git a/Extras/ConvexDecomposition/cd_wavefront.cpp b/Extras/ConvexDecomposition/cd_wavefront.cpp index 53b5784dfa..9b30bf2305 100644 --- a/Extras/ConvexDecomposition/cd_wavefront.cpp +++ b/Extras/ConvexDecomposition/cd_wavefront.cpp @@ -536,7 +536,7 @@ class GeometryVertex class GeometryInterface { public: - virtual void NodeTriangle(const GeometryVertex *v1, const GeometryVertex *v2, const GeometryVertex *v3) {} + virtual void NodeTriangle(const GeometryVertex * /*v1*/, const GeometryVertex * /*v2*/, const GeometryVertex * /*v3*/) {} virtual ~GeometryInterface() {} }; @@ -643,7 +643,7 @@ void OBJ::getVertex(GeometryVertex &v, const char *face) const } } -int OBJ::ParseLine(int lineno, int argc, const char **argv) // return TRUE to continue parsing, return FALSE to abort parsing process +int OBJ::ParseLine(int /*lineno*/, int argc, const char **argv) // return TRUE to continue parsing, return FALSE to abort parsing process { int ret = 0; diff --git a/Extras/ConvexDecomposition/concavity.cpp b/Extras/ConvexDecomposition/concavity.cpp index 023181a44a..d1c31b435c 100644 --- a/Extras/ConvexDecomposition/concavity.cpp +++ b/Extras/ConvexDecomposition/concavity.cpp @@ -318,7 +318,7 @@ class CTri return a; } - void addWeighted(WpointVector &list, ConvexDecompInterface *callback) + void addWeighted(WpointVector &list, ConvexDecompInterface * /*callback*/) { Wpoint p1(mP1, mC1); Wpoint p2(mP2, mC2); @@ -395,7 +395,7 @@ class CTri typedef std::vector CTriVector; -bool featureMatch(CTri &m, const CTriVector &tris, ConvexDecompInterface *callback, const CTriVector &input_mesh) +bool featureMatch(CTri &m, const CTriVector &tris, ConvexDecompInterface * /*callback*/, const CTriVector &input_mesh) { bool ret = false; @@ -496,7 +496,7 @@ bool featureMatch(CTri &m, const CTriVector &tris, ConvexDecompInterface *callba return ret; } -bool isFeatureTri(CTri &t, CTriVector &flist, float fc, ConvexDecompInterface *callback, unsigned int color) +bool isFeatureTri(CTri &t, CTriVector &flist, float fc, ConvexDecompInterface * /*callback*/, unsigned int /*color*/) { bool ret = false; @@ -546,7 +546,7 @@ float computeConcavity(unsigned int vcount, unsigned int tcount, const unsigned int *indices, ConvexDecompInterface *callback, - float *plane, // plane equation to split on + float * /*plane*/, // plane equation to split on float &volume) { float cret = 0; diff --git a/Extras/ConvexDecomposition/meshvolume.cpp b/Extras/ConvexDecomposition/meshvolume.cpp index c7427d5712..51633ec575 100644 --- a/Extras/ConvexDecomposition/meshvolume.cpp +++ b/Extras/ConvexDecomposition/meshvolume.cpp @@ -101,7 +101,7 @@ inline float tetVolume(const float *p0, const float *p1, const float *p2, const return volume; } -inline float det(const float *p0, const float *p1, const float *p2, const float *p3) +inline float det(const float * /*p0*/, const float *p1, const float *p2, const float *p3) { return p1[0] * p2[1] * p3[2] + p2[0] * p3[1] * p1[2] + p3[0] * p1[1] * p2[2] - p1[0] * p3[1] * p2[2] - p2[0] * p1[1] * p3[2] - p3[0] * p2[1] * p1[2]; } diff --git a/Extras/ConvexDecomposition/splitplane.cpp b/Extras/ConvexDecomposition/splitplane.cpp index 22bfdd9cee..3c949c5b0b 100644 --- a/Extras/ConvexDecomposition/splitplane.cpp +++ b/Extras/ConvexDecomposition/splitplane.cpp @@ -174,9 +174,9 @@ void splitRect(unsigned int axis, bool computeSplitPlane(unsigned int vcount, const float *vertices, - unsigned int tcount, - const unsigned int *indices, - ConvexDecompInterface *callback, + unsigned int /*tcount*/, + const unsigned int * /*indices*/, + ConvexDecompInterface * /*callback*/, float *plane) { float bmin[3] = {1e9, 1e9, 1e9}; @@ -200,6 +200,7 @@ bool computeSplitPlane(unsigned int vcount, float dz = bmax[2] - bmin[2]; float laxis = dx; + (void)laxis; unsigned int axis = 0; diff --git a/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.cpp b/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.cpp index 755021483a..68d1f937aa 100644 --- a/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.cpp +++ b/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.cpp @@ -192,7 +192,7 @@ btGImpactConvexDecompositionShape::~btGImpactConvexDecompositionShape() { delete m_decomposition; } -void btGImpactConvexDecompositionShape::processAllTriangles(btTriangleCallback* callback, const btVector3& aabbMin, const btVector3& aabbMax) const +void btGImpactConvexDecompositionShape::processAllTriangles(btTriangleCallback* callback, const btVector3& /*aabbMin*/, const btVector3& /*aabbMax*/) const { int part_count = m_trimeshInterfaces.size(); for (int part = 0; part < part_count; part++) diff --git a/Extras/InverseDynamics/DillCreator.cpp b/Extras/InverseDynamics/DillCreator.cpp index 58def07888..44876d0738 100644 --- a/Extras/InverseDynamics/DillCreator.cpp +++ b/Extras/InverseDynamics/DillCreator.cpp @@ -71,7 +71,7 @@ int DillCreator::getBody(const int body_index, int* parent_index, JointType* joi return 0; } -int DillCreator::recurseDill(const int level, const int parent, const idScalar d_DH_in, +int DillCreator::recurseDill(const int level, const int parent, const idScalar /*d_DH_in*/, const idScalar a_DH_in, const idScalar alpha_DH_in) { if (level < 0) diff --git a/Extras/Serialize/BulletFileLoader/bDNA.cpp b/Extras/Serialize/BulletFileLoader/bDNA.cpp index 8d581d2787..8abde263db 100644 --- a/Extras/Serialize/BulletFileLoader/bDNA.cpp +++ b/Extras/Serialize/BulletFileLoader/bDNA.cpp @@ -342,7 +342,7 @@ static int name_is_array(char *name, int *dim1, int *dim2) } // ----------------------------------------------------- // -void bDNA::init(char *data, int len, bool swap) +void bDNA::init(char *data, int /*len*/, bool swap) { int *intPtr = 0; short *shtPtr = 0; diff --git a/Extras/Serialize/BulletFileLoader/bFile.cpp b/Extras/Serialize/BulletFileLoader/bFile.cpp index 5f19dd5762..982a7b9b8f 100644 --- a/Extras/Serialize/BulletFileLoader/bFile.cpp +++ b/Extras/Serialize/BulletFileLoader/bFile.cpp @@ -78,6 +78,7 @@ bFile::bFile(const char *filename, const char headerString[7]) memset(mFileBuffer, 0, mFileLen+1); size_t bytesRead; bytesRead = fread(mFileBuffer, mFileLen, 1, fp); + (void)bytesRead; fclose(fp); @@ -629,6 +630,7 @@ char *bFile::readStruct(char *head, bChunkInd &dataChunk) short *oldStruct, *curStruct; char *oldType, *newType; int oldLen, curLen, reverseOld; + (void)newType; oldStruct = mFileDNA->getStruct(dataChunk.dna_nr); oldType = mFileDNA->getType(oldStruct[0]); @@ -1508,6 +1510,7 @@ void bFile::writeChunks(FILE *fp, bool fixupPointers) short *oldStruct, *curStruct; char *oldType, *newType; int curLen, reverseOld; + (void)newType; oldStruct = fileDna->getStruct(dataChunk.dna_nr); oldType = fileDna->getType(oldStruct[0]); @@ -1542,6 +1545,7 @@ void bFile::writeChunks(FILE *fp, bool fixupPointers) short int *curStruct1; curStruct1 = mMemoryDNA->getStruct(dataChunk.dna_nr); assert(curStruct1 == curStruct); + (void)curStruct1; char *cur = fixupPointers ? (char *)findLibPointer(dataChunk.oldPtr) : (char *)dataChunk.oldPtr; diff --git a/Extras/Serialize/BulletFileLoader/btBulletFile.cpp b/Extras/Serialize/BulletFileLoader/btBulletFile.cpp index 74f27c4a51..2b931438cc 100644 --- a/Extras/Serialize/BulletFileLoader/btBulletFile.cpp +++ b/Extras/Serialize/BulletFileLoader/btBulletFile.cpp @@ -419,6 +419,7 @@ void btBulletFile::addStruct(const char* structType, void* data, int len, void* elemBytes = mMemoryDNA->getLength(structInfo[0]); // int elemBytes = mMemoryDNA->getElementSize(structInfo[0],structInfo[1]); assert(len == elemBytes); + (void)elemBytes; mLibPointers.insert(dataChunk.oldPtr, (bStructHandle*)data); m_chunks.push_back(dataChunk); diff --git a/Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.cpp b/Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.cpp index f18a5d2c51..4a7f799314 100644 --- a/Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.cpp +++ b/Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.cpp @@ -64,7 +64,7 @@ void syncContactManifolds(T** contactManifolds, int numContactManifolds, btMulti { dispatcher->dispatchAllCollisionPairs(pairCache, dispatchInfo, dispatcher); } - int numExistingManifolds = m_data->m_mbDynamicsWorld->getDispatcher()->getNumManifolds(); + // int numExistingManifolds = m_data->m_mbDynamicsWorld->getDispatcher()->getNumManifolds(); btManifoldArray manifoldArray; for (int i = 0; i < pairCache->getNumOverlappingPairs(); i++) { @@ -104,10 +104,10 @@ void syncContactManifolds(T** contactManifolds, int numContactManifolds, btMulti } template -void syncMultiBody(T* mbd, btMultiBody* mb, btMultiBodyWorldImporterInternalData* m_data, btAlignedObjectArray& scratchQ, btAlignedObjectArray& scratchM) +void syncMultiBody(T* mbd, btMultiBody* mb, btMultiBodyWorldImporterInternalData* /*m_data*/, btAlignedObjectArray& scratchQ, btAlignedObjectArray& scratchM) { - bool isFixedBase = mbd->m_baseMass == 0; - bool canSleep = false; + // bool isFixedBase = mbd->m_baseMass == 0; + // bool canSleep = false; btVector3 baseInertia; baseInertia.deSerialize(mbd->m_baseInertia); @@ -477,8 +477,8 @@ bool btMultiBodyWorldImporter::convertAllObjects(bParse::btBulletFile* bulletFil { btMultiBody* mb = *ptr; mb->finalizeMultiDof(); - btVector3 linvel = mb->getBaseVel(); - btVector3 angvel = mb->getBaseOmega(); + // btVector3 linvel = mb->getBaseVel(); + // btVector3 angvel = mb->getBaseOmega(); mb->forwardKinematics(scratchQ, scratchM); } } diff --git a/Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp b/Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp index df4106596e..b531de443c 100644 --- a/Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp +++ b/Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp @@ -1602,7 +1602,7 @@ void btWorldImporter::setDynamicsWorldInfo(const btVector3& gravity, const btCon } } -btRigidBody* btWorldImporter::createRigidBody(bool isDynamic, btScalar mass, const btTransform& startTransform, btCollisionShape* shape, const char* bodyName) +btRigidBody* btWorldImporter::createRigidBody(bool /*isDynamic*/, btScalar mass, const btTransform& startTransform, btCollisionShape* shape, const char* bodyName) { btVector3 localInertia; localInertia.setZero(); @@ -1743,7 +1743,7 @@ btBvhTriangleMeshShape* btWorldImporter::createBvhTriangleMeshShape(btStridingMe m_allocatedCollisionShapes.push_back(ts); return ts; } -btCollisionShape* btWorldImporter::createConvexTriangleMeshShape(btStridingMeshInterface* trimesh) +btCollisionShape* btWorldImporter::createConvexTriangleMeshShape(btStridingMeshInterface* /*trimesh*/) { return 0; } @@ -1754,6 +1754,7 @@ btGImpactMeshShape* btWorldImporter::createGimpactShape(btStridingMeshInterface* m_allocatedCollisionShapes.push_back(shape); return shape; #else + (void)trimesh; return 0; #endif } diff --git a/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.cpp b/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.cpp index 17b1440241..62fca8ea2a 100644 --- a/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.cpp +++ b/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.cpp @@ -367,7 +367,7 @@ void btBulletXmlWorldImporter::deSerializeStaticPlaneShapeData(XMLNode* pParent) m_pointerLookup.insert(cast.m_ptr, planeData); } -void btBulletXmlWorldImporter::deSerializeDynamicsWorldData(XMLNode* pParent) +void btBulletXmlWorldImporter::deSerializeDynamicsWorldData(XMLNode* /*pParent*/) { btContactSolverInfo solverInfo; //btVector3 gravity(0,0,0); diff --git a/Extras/VHACD/inc/vhacdMutex.h b/Extras/VHACD/inc/vhacdMutex.h index 78c1113835..bfd5720256 100644 --- a/Extras/VHACD/inc/vhacdMutex.h +++ b/Extras/VHACD/inc/vhacdMutex.h @@ -97,6 +97,7 @@ class Mutex VHACD_VERIFY(pthread_mutexattr_settype(&mutexAttr, PTHREAD_MUTEX_RECURSIVE_NP) == 0); VHACD_VERIFY(pthread_mutex_init(&m_mutex, &mutexAttr) == 0); VHACD_VERIFY(pthread_mutexattr_destroy(&mutexAttr) == 0); + (void)mutexAttr; #endif } ~Mutex(void) diff --git a/Extras/VHACD/inc/vhacdVolume.h b/Extras/VHACD/inc/vhacdVolume.h index cd89ca7843..d3ec16c1ef 100644 --- a/Extras/VHACD/inc/vhacdVolume.h +++ b/Extras/VHACD/inc/vhacdVolume.h @@ -267,8 +267,8 @@ class Volume int TriBoxOverlap(const Vec3& boxcenter, const Vec3& boxhalfsize, const Vec3& triver0, const Vec3& triver1, const Vec3& triver2); template -inline void ComputeAlignedPoint(const T* const points, const unsigned int idx, const Vec3& barycenter, - const double (&rot)[3][3], Vec3& pt){}; +inline void ComputeAlignedPoint(const T* const /*points*/, const unsigned int /*idx*/, const Vec3& /*barycenter*/, + const double (& /*rot*/)[3][3], Vec3& /*pt*/){}; template <> inline void ComputeAlignedPoint(const float* const points, const unsigned int idx, const Vec3& barycenter, const double (&rot)[3][3], Vec3& pt) { diff --git a/Extras/VHACD/src/VHACD.cpp b/Extras/VHACD/src/VHACD.cpp index 2853fc56f0..80644c7229 100644 --- a/Extras/VHACD/src/VHACD.cpp +++ b/Extras/VHACD/src/VHACD.cpp @@ -212,7 +212,7 @@ IVHACD* CreateVHACD(void) { return new VHACD(); } -bool VHACD::OCLInit(void* const oclDevice, IUserLogger* const logger) +bool VHACD::OCLInit(void* const /*oclDevice*/, IUserLogger* const /*logger*/) { #ifdef CL_VERSION_1_1 m_oclDevice = (cl_device_id*)oclDevice; @@ -353,7 +353,7 @@ bool VHACD::OCLInit(void* const oclDevice, IUserLogger* const logger) return false; #endif //CL_VERSION_1_1 } -bool VHACD::OCLRelease(IUserLogger* const logger) +bool VHACD::OCLRelease(IUserLogger* const /*logger*/) { #ifdef CL_VERSION_1_1 cl_int error; @@ -743,7 +743,7 @@ inline double ComputeConcavity(const double volume, const double volumeCH, const } //#define DEBUG_TEMP -void VHACD::ComputeBestClippingPlane(const PrimitiveSet* inputPSet, const double volume, const SArray& planes, +void VHACD::ComputeBestClippingPlane(const PrimitiveSet* inputPSet, const double /*volume*/, const SArray& planes, const Vec3& preferredCuttingDirection, const double w, const double alpha, const double beta, const int convexhullDownsampling, const double progress0, const double progress1, Plane& bestPlane, double& minConcavity, const Parameters& params) diff --git a/Extras/VHACD/src/vhacdVolume.cpp b/Extras/VHACD/src/vhacdVolume.cpp index f420667b96..23627c225e 100644 --- a/Extras/VHACD/src/vhacdVolume.cpp +++ b/Extras/VHACD/src/vhacdVolume.cpp @@ -1493,23 +1493,23 @@ void TetrahedronSet::AddClippedTetrahedra(const Vec3 (&pts)[10], const i } } -void TetrahedronSet::Intersect(const Plane& plane, - SArray >* const positivePts, - SArray >* const negativePts, - const size_t sampling) const +void TetrahedronSet::Intersect(const Plane& /*plane*/, + SArray >* const /*positivePts*/, + SArray >* const /*negativePts*/, + const size_t /*sampling*/) const { const size_t nTetrahedra = m_tetrahedra.Size(); if (nTetrahedra == 0) return; } -void TetrahedronSet::ComputeExteriorPoints(const Plane& plane, - const Mesh& mesh, - SArray >* const exteriorPts) const +void TetrahedronSet::ComputeExteriorPoints(const Plane& /*plane*/, + const Mesh& /*mesh*/, + SArray >* const /*exteriorPts*/) const { } -void TetrahedronSet::ComputeClippedVolumes(const Plane& plane, - double& positiveVolume, - double& negativeVolume) const +void TetrahedronSet::ComputeClippedVolumes(const Plane& /*plane*/, + double& /*positiveVolume*/, + double& /*negativeVolume*/) const { const size_t nTetrahedra = m_tetrahedra.Size(); if (nTetrahedra == 0) @@ -1637,6 +1637,7 @@ void TetrahedronSet::Clip(const Plane& plane, else { int nnew = 0; + (void)nnew; for (int j = 0; j < 6; ++j) { if (sign[edges[j][0]] * sign[edges[j][1]] == -1) diff --git a/Extras/VHACD/test/src/main_vhacd.cpp b/Extras/VHACD/test/src/main_vhacd.cpp index b41c6df019..ad37a79395 100644 --- a/Extras/VHACD/test/src/main_vhacd.cpp +++ b/Extras/VHACD/test/src/main_vhacd.cpp @@ -640,7 +640,7 @@ bool SaveOFF(const string& fileName, const float* const& points, const int* cons } bool SaveOBJ(ofstream& fout, const double* const& points, const int* const& triangles, const unsigned int& nPoints, - const unsigned int& nTriangles, const Material& material, IVHACD::IUserLogger& logger, int convexPart, int vertexOffset) + const unsigned int& nTriangles, const Material& /*material*/, IVHACD::IUserLogger& logger, int convexPart, int vertexOffset) { if (fout.is_open()) { diff --git a/examples/BasicDemo/main.cpp b/examples/BasicDemo/main.cpp index 08ac541fe9..18c8cd6205 100644 --- a/examples/BasicDemo/main.cpp +++ b/examples/BasicDemo/main.cpp @@ -24,7 +24,7 @@ subject to the following restrictions: #include "LinearMath/btTransform.h" #include "LinearMath/btHashMap.h" -int main(int argc, char* argv[]) +int main(int /*argc*/, char* /*argv*/[]) { DummyGUIHelper noGfx; diff --git a/examples/Benchmarks/BenchmarkDemo.cpp b/examples/Benchmarks/BenchmarkDemo.cpp index d9dcdc5a3c..07a7dfdf7d 100644 --- a/examples/Benchmarks/BenchmarkDemo.cpp +++ b/examples/Benchmarks/BenchmarkDemo.cpp @@ -60,7 +60,7 @@ class BenchmarkDemo : public CommonRigidBodyMTBase //?? } - void setCameraDistance(btScalar dist) + void setCameraDistance(btScalar /*dist*/) { } void createTest1(); @@ -489,6 +489,7 @@ void BenchmarkDemo::createTest1() trans.setOrigin(pos); btRigidBody* cmbody; cmbody = createRigidBody(mass, trans, blockShape); + (void)cmbody; } } offset -= 0.05f * spacing * (size - 1); @@ -1133,6 +1134,7 @@ void BenchmarkDemo::createTest5() float offset = -size * (cubeSize * 2.0f + spacing) * 0.5f; int numBodies = 0; + (void)numBodies; for (int k = 0; k < height; k++) { diff --git a/examples/BulletRobotics/BoxStack.cpp b/examples/BulletRobotics/BoxStack.cpp index df4056465a..a5df1d98b1 100644 --- a/examples/BulletRobotics/BoxStack.cpp +++ b/examples/BulletRobotics/BoxStack.cpp @@ -29,6 +29,7 @@ class BoxStackExample : public CommonExampleInterface m_options(options) { m_app->setUpAxis(2); + (void)m_options; } virtual ~BoxStackExample() @@ -72,7 +73,7 @@ class BoxStackExample : public CommonExampleInterface { m_robotSim.disconnect(); } - virtual void stepSimulation(float deltaTime) + virtual void stepSimulation(float /*deltaTime*/) { m_robotSim.stepSimulation(); } @@ -89,7 +90,7 @@ class BoxStackExample : public CommonExampleInterface { return m_robotSim.mouseButtonCallback(button, state, x, y); } - virtual bool keyboardCallback(int key, int state) + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } diff --git a/examples/BulletRobotics/FixJointBoxes.cpp b/examples/BulletRobotics/FixJointBoxes.cpp index 51cd1842d1..565ddb36f0 100644 --- a/examples/BulletRobotics/FixJointBoxes.cpp +++ b/examples/BulletRobotics/FixJointBoxes.cpp @@ -35,6 +35,7 @@ class FixJointBoxes : public CommonExampleInterface cubeIds(numCubes, 0), solver(solverId) { + (void)m_options; } virtual ~FixJointBoxes() @@ -116,7 +117,7 @@ class FixJointBoxes : public CommonExampleInterface m_robotSim.resetBasePositionAndOrientation(cubeIds[i], pos, quar); } } - virtual void stepSimulation(float deltaTime) + virtual void stepSimulation(float /*deltaTime*/) { int newSolver = (int)(solverId + 0.5); if (newSolver != solver) @@ -151,7 +152,7 @@ class FixJointBoxes : public CommonExampleInterface { return m_robotSim.mouseButtonCallback(button, state, x, y); } - virtual bool keyboardCallback(int key, int state) + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } diff --git a/examples/BulletRobotics/JointLimit.cpp b/examples/BulletRobotics/JointLimit.cpp index 6a4d91eefb..a0fff29e24 100644 --- a/examples/BulletRobotics/JointLimit.cpp +++ b/examples/BulletRobotics/JointLimit.cpp @@ -26,6 +26,7 @@ class JointLimit : public CommonExampleInterface : m_guiHelper(helper), m_options(options) { + (void)m_options; } virtual ~JointLimit() @@ -70,7 +71,7 @@ class JointLimit : public CommonExampleInterface { m_robotSim.disconnect(); } - virtual void stepSimulation(float deltaTime) + virtual void stepSimulation(float /*deltaTime*/) { m_robotSim.stepSimulation(); } @@ -87,7 +88,7 @@ class JointLimit : public CommonExampleInterface { return m_robotSim.mouseButtonCallback(button, state, x, y); } - virtual bool keyboardCallback(int key, int state) + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } diff --git a/examples/Collision/CollisionSdkC_Api.cpp b/examples/Collision/CollisionSdkC_Api.cpp index c0541d2518..4eebf26f3d 100644 --- a/examples/Collision/CollisionSdkC_Api.cpp +++ b/examples/Collision/CollisionSdkC_Api.cpp @@ -89,7 +89,7 @@ plCollisionObjectHandle plCreateCollisionObject(plCollisionSdkHandle collisionSd return sdk->createCollisionObject(worldHandle, userData, userIndex, cshape, childPos, childOrn); } -void plDeleteCollisionObject(plCollisionSdkHandle collisionSdkHandle, plCollisionWorldHandle worldHandle, plCollisionObjectHandle body) +void plDeleteCollisionObject(plCollisionSdkHandle collisionSdkHandle, plCollisionWorldHandle /*worldHandle*/, plCollisionObjectHandle body) { CollisionSdkInterface* sdk = (CollisionSdkInterface*)collisionSdkHandle; sdk->deleteCollisionObject(body); diff --git a/examples/Collision/CollisionTutorialBullet2.cpp b/examples/Collision/CollisionTutorialBullet2.cpp index 015e539025..1edbf8bc1b 100644 --- a/examples/Collision/CollisionTutorialBullet2.cpp +++ b/examples/Collision/CollisionTutorialBullet2.cpp @@ -35,7 +35,7 @@ static btVector4 sColors[4] = btVector4(0.7, 1, 1, 1), }; -void myNearCallback(plCollisionSdkHandle sdkHandle, plCollisionWorldHandle worldHandle, void* userData, plCollisionObjectHandle objA, plCollisionObjectHandle objB) +void myNearCallback(plCollisionSdkHandle sdkHandle, plCollisionWorldHandle worldHandle, void* /*userData*/, plCollisionObjectHandle objA, plCollisionObjectHandle objB) { numNearCallbacks++; int remainingCapacity = sPointCapacity - gTotalPoints; @@ -199,6 +199,7 @@ class CollisionTutorialBullet2 : public CommonExampleInterface { int textureIndex = -1; + (void)textureIndex; if (1) { @@ -245,7 +246,7 @@ class CollisionTutorialBullet2 : public CommonExampleInterface { } - virtual void stepSimulation(float deltaTime) + virtual void stepSimulation(float /*deltaTime*/) { #ifndef BT_NO_PROFILE CProfileManager::Reset(); @@ -322,18 +323,18 @@ class CollisionTutorialBullet2 : public CommonExampleInterface } } - virtual void physicsDebugDraw(int debugDrawFlags) + virtual void physicsDebugDraw(int /*debugDrawFlags*/) { } - virtual bool mouseMoveCallback(float x, float y) + virtual bool mouseMoveCallback(float /*x*/, float /*y*/) { return false; } - virtual bool mouseButtonCallback(int button, int state, float x, float y) + virtual bool mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } - virtual bool keyboardCallback(int key, int state) + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } diff --git a/examples/Collision/Internal/Bullet2CollisionSdk.cpp b/examples/Collision/Internal/Bullet2CollisionSdk.cpp index b03d7fc98d..9fa64d40cd 100644 --- a/examples/Collision/Internal/Bullet2CollisionSdk.cpp +++ b/examples/Collision/Internal/Bullet2CollisionSdk.cpp @@ -64,7 +64,7 @@ plCollisionShapeHandle Bullet2CollisionSdk::createSphereShape(plCollisionWorldHa return (plCollisionShapeHandle)sphereShape; } -plCollisionShapeHandle Bullet2CollisionSdk::createPlaneShape(plCollisionWorldHandle worldHandle, +plCollisionShapeHandle Bullet2CollisionSdk::createPlaneShape(plCollisionWorldHandle /*worldHandle*/, plReal planeNormalX, plReal planeNormalY, plReal planeNormalZ, @@ -74,7 +74,7 @@ plCollisionShapeHandle Bullet2CollisionSdk::createPlaneShape(plCollisionWorldHan return (plCollisionShapeHandle)planeShape; } -plCollisionShapeHandle Bullet2CollisionSdk::createCapsuleShape(plCollisionWorldHandle worldHandle, +plCollisionShapeHandle Bullet2CollisionSdk::createCapsuleShape(plCollisionWorldHandle /*worldHandle*/, plReal radius, plReal height, int capsuleAxis) @@ -106,11 +106,11 @@ plCollisionShapeHandle Bullet2CollisionSdk::createCapsuleShape(plCollisionWorldH return (plCollisionShapeHandle)capsule; } -plCollisionShapeHandle Bullet2CollisionSdk::createCompoundShape(plCollisionWorldHandle worldHandle) +plCollisionShapeHandle Bullet2CollisionSdk::createCompoundShape(plCollisionWorldHandle /*worldHandle*/) { return (plCollisionShapeHandle) new btCompoundShape(); } -void Bullet2CollisionSdk::addChildShape(plCollisionWorldHandle worldHandle, plCollisionShapeHandle compoundShapeHandle, plCollisionShapeHandle childShapeHandle, plVector3 childPos, plQuaternion childOrn) +void Bullet2CollisionSdk::addChildShape(plCollisionWorldHandle /*worldHandle*/, plCollisionShapeHandle compoundShapeHandle, plCollisionShapeHandle childShapeHandle, plVector3 childPos, plQuaternion childOrn) { btCompoundShape* compound = (btCompoundShape*)compoundShapeHandle; btCollisionShape* childShape = (btCollisionShape*)childShapeHandle; @@ -147,7 +147,7 @@ void Bullet2CollisionSdk::removeCollisionObject(plCollisionWorldHandle worldHand } } -plCollisionObjectHandle Bullet2CollisionSdk::createCollisionObject(plCollisionWorldHandle worldHandle, void* userPointer, int userIndex, plCollisionShapeHandle shapeHandle, +plCollisionObjectHandle Bullet2CollisionSdk::createCollisionObject(plCollisionWorldHandle /*worldHandle*/, void* userPointer, int userIndex, plCollisionShapeHandle shapeHandle, plVector3 startPosition, plQuaternion startOrientation) { @@ -194,7 +194,7 @@ struct Bullet2ContactResultCallback : public btCollisionWorld::ContactResultCall m_pointCapacity(pointCapacity) { } - virtual btScalar addSingleResult(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap, int partId0, int index0, const btCollisionObjectWrapper* colObj1Wrap, int partId1, int index1) + virtual btScalar addSingleResult(btManifoldPoint& cp, const btCollisionObjectWrapper* /*colObj0Wrap*/, int /*partId0*/, int /*index0*/, const btCollisionObjectWrapper* /*colObj1Wrap*/, int /*partId1*/, int /*index1*/) { if (m_numContacts < m_pointCapacity) { @@ -239,7 +239,7 @@ static plCollisionWorldHandle gCollisionWorldHandle = 0; static void* gUserData = 0; -void Bullet2NearCallback(btBroadphasePair& collisionPair, btCollisionDispatcher& dispatcher, const btDispatcherInfo& dispatchInfo) +void Bullet2NearCallback(btBroadphasePair& collisionPair, btCollisionDispatcher& /*dispatcher*/, const btDispatcherInfo& /*dispatchInfo*/) { btCollisionObject* colObj0 = (btCollisionObject*)collisionPair.m_pProxy0->m_clientObject; btCollisionObject* colObj1 = (btCollisionObject*)collisionPair.m_pProxy1->m_clientObject; diff --git a/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp b/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp index 2ffff03e55..44cd49ca7e 100644 --- a/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp +++ b/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp @@ -196,10 +196,10 @@ plCollisionShapeHandle RealTimeBullet3CollisionSdk::createCompoundShape(plCollis return 0; } -void RealTimeBullet3CollisionSdk::addChildShape(plCollisionWorldHandle worldHandle, plCollisionShapeHandle compoundShape, plCollisionShapeHandle childShape, plVector3 childPos, plQuaternion childOrn) +void RealTimeBullet3CollisionSdk::addChildShape(plCollisionWorldHandle /*worldHandle*/, plCollisionShapeHandle /*compoundShape*/, plCollisionShapeHandle /*childShape*/, plVector3 /*childPos*/, plQuaternion /*childOrn*/) { } -void RealTimeBullet3CollisionSdk::deleteShape(plCollisionWorldHandle worldHandle, plCollisionShapeHandle shape) +void RealTimeBullet3CollisionSdk::deleteShape(plCollisionWorldHandle /*worldHandle*/, plCollisionShapeHandle /*shape*/) { ///todo //deleting shapes would involve a garbage collection phase, and mess up all user indices @@ -207,12 +207,12 @@ void RealTimeBullet3CollisionSdk::deleteShape(plCollisionWorldHandle worldHandle //for now, we don't delete and eventually run out-of-shapes } -void RealTimeBullet3CollisionSdk::addCollisionObject(plCollisionWorldHandle world, plCollisionObjectHandle object) +void RealTimeBullet3CollisionSdk::addCollisionObject(plCollisionWorldHandle /*world*/, plCollisionObjectHandle /*object*/) { ///createCollisionObject already adds it to the world } -void RealTimeBullet3CollisionSdk::removeCollisionObject(plCollisionWorldHandle world, plCollisionObjectHandle object) +void RealTimeBullet3CollisionSdk::removeCollisionObject(plCollisionWorldHandle /*world*/, plCollisionObjectHandle /*object*/) { ///todo, see deleteShape } @@ -274,13 +274,13 @@ plCollisionObjectHandle RealTimeBullet3CollisionSdk::createCollisionObject(plCol return 0; } -void RealTimeBullet3CollisionSdk::deleteCollisionObject(plCollisionObjectHandle body) +void RealTimeBullet3CollisionSdk::deleteCollisionObject(plCollisionObjectHandle /*body*/) { ///todo, see deleteShape } -void RealTimeBullet3CollisionSdk::setCollisionObjectTransform(plCollisionWorldHandle world, plCollisionObjectHandle body, - plVector3 position, plQuaternion orientation) +void RealTimeBullet3CollisionSdk::setCollisionObjectTransform(plCollisionWorldHandle /*world*/, plCollisionObjectHandle /*body*/, + plVector3 /*position*/, plQuaternion /*orientation*/) { } @@ -300,6 +300,8 @@ void detectCollisionDummy(RTB3CollisionWorld* world, int colA, int shapeIndexA, (void)world; (void)colA, (void)colB; (void)contactCache; + (void)shapeIndexA; + (void)shapeIndexB; } void plVecCopy(float* dst, const b3Vector3& src) @@ -380,7 +382,7 @@ B3_FORCE_INLINE void detectCollisionSphereSphere(RTB3CollisionWorld* world, int ComputeClosestPointsSphereSphere(radiusA, spherePosAWorld, radiusB, spherePosBWorld, contactCache); } -void detectCollisionSpherePlane(RTB3CollisionWorld* world, int colA, int shapeIndexA, int colB, int shapeIndexB, +void detectCollisionSpherePlane(RTB3CollisionWorld* world, int colA, int shapeIndexA, int /*colB*/, int shapeIndexB, plContactCache* contactCache) { const b3Transform& trA = world->m_collidableTransforms[colA]; diff --git a/examples/CommonInterfaces/CommonExampleInterface.h b/examples/CommonInterfaces/CommonExampleInterface.h index fc4e05ce89..b824ab882d 100644 --- a/examples/CommonInterfaces/CommonExampleInterface.h +++ b/examples/CommonInterfaces/CommonExampleInterface.h @@ -53,12 +53,12 @@ class CommonExampleInterface virtual bool mouseButtonCallback(int button, int state, float x, float y) = 0; virtual bool keyboardCallback(int key, int state) = 0; - virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4], float analogAxis, float auxAnalogAxes[10]) {} - virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]) {} - virtual void vrHMDMoveCallback(int controllerId, float pos[4], float orientation[4]) {} - virtual void vrGenericTrackerMoveCallback(int controllerId, float pos[4], float orientation[4]) {} + virtual void vrControllerMoveCallback(int /*controllerId*/, float /*pos*/[4], float /*orientation*/[4], float /*analogAxis*/, float /*auxAnalogAxes*/[10]) {} + virtual void vrControllerButtonCallback(int /*controllerId*/, int /*button*/, int /*state*/, float /*pos*/[4], float /*orientation*/[4]) {} + virtual void vrHMDMoveCallback(int /*controllerId*/, float /*pos*/[4], float /*orientation*/[4]) {} + virtual void vrGenericTrackerMoveCallback(int /*controllerId*/, float /*pos*/[4], float /*orientation*/[4]) {} - virtual void processCommandLineArgs(int argc, char* argv[]){}; + virtual void processCommandLineArgs(int /*argc*/, char* /*argv*/[]){}; }; class ExampleEntries diff --git a/examples/CommonInterfaces/CommonGUIHelperInterface.h b/examples/CommonInterfaces/CommonGUIHelperInterface.h index 2d4500374d..05e0f08e6a 100644 --- a/examples/CommonInterfaces/CommonGUIHelperInterface.h +++ b/examples/CommonInterfaces/CommonGUIHelperInterface.h @@ -31,8 +31,8 @@ struct GUIHelperInterface virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape) = 0; virtual void syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWorld) = 0; - virtual void syncPhysicsToGraphics2(const btDiscreteDynamicsWorld* rbWorld) {} - virtual void syncPhysicsToGraphics2(const GUISyncPosition* positions, int numPositions) {} + virtual void syncPhysicsToGraphics2(const btDiscreteDynamicsWorld* /*rbWorld*/) {} + virtual void syncPhysicsToGraphics2(const GUISyncPosition* /*positions*/, int /*numPositions*/) {} virtual void render(const btDiscreteDynamicsWorld* rbWorld) = 0; @@ -42,17 +42,17 @@ struct GUIHelperInterface virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices, int primitiveType, int textureId) = 0; virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling) = 0; virtual void removeAllGraphicsInstances() = 0; - virtual void removeGraphicsInstance(int graphicsUid) {} - virtual void changeInstanceFlags(int instanceUid, int flags) {} - virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4]) {} - virtual void changeScaling(int instanceUid, const double scaling[3]) {} - virtual void changeSpecularColor(int instanceUid, const double specularColor[3]) {} - virtual void changeTexture(int textureUniqueId, const unsigned char* rgbTexels, int width, int height) {} - virtual void updateShape(int shapeIndex, float* vertices, int numVertices) {} - virtual int getShapeIndexFromInstance(int instanceUid) { return -1; } - virtual void replaceTexture(int shapeIndex, int textureUid) {} - virtual void removeTexture(int textureUid) {} - virtual void setBackgroundColor(const double rgbBackground[3]) {} + virtual void removeGraphicsInstance(int /*graphicsUid*/) {} + virtual void changeInstanceFlags(int /*instanceUid*/, int /*flags*/) {} + virtual void changeRGBAColor(int /*instanceUid*/, const double /*rgbaColor*/[4]) {} + virtual void changeScaling(int /*instanceUid*/, const double /*scaling*/[3]) {} + virtual void changeSpecularColor(int /*instanceUid*/, const double /*specularColor*/[3]) {} + virtual void changeTexture(int /*textureUniqueId*/, const unsigned char* /*rgbTexels*/, int /*width*/, int /*height*/) {} + virtual void updateShape(int /*shapeIndex*/, float* /*vertices*/, int /*numVertices*/) {} + virtual int getShapeIndexFromInstance(int /*instanceUid*/) { return -1; } + virtual void replaceTexture(int /*shapeIndex*/, int /*textureUid*/) {} + virtual void removeTexture(int /*textureUid*/) {} + virtual void setBackgroundColor(const double /*rgbBackground*/[3]) {} virtual Common2dCanvasInterface* get2dCanvasInterface() = 0; @@ -72,12 +72,12 @@ struct GUIHelperInterface virtual void resetCamera(float camDist, float yaw, float pitch, float camPosX, float camPosY, float camPosZ) = 0; - virtual bool getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3], float hor[3], float vert[3], float* yaw, float* pitch, float* camDist, float camTarget[3]) const + virtual bool getCameraInfo(int* /*width*/, int* /*height*/, float /*viewMatrix*/[16], float /*projectionMatrix*/[16], float /*camUp*/[3], float /*camForward*/[3], float /*hor*/[3], float /*vert*/[3], float* /*yaw*/, float* /*pitch*/, float* /*camDist*/, float /*camTarget*/[3]) const { return false; } - virtual void setVisualizerFlag(int flag, int enable){}; + virtual void setVisualizerFlag(int /*flag*/, int /*enable*/){}; virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, @@ -96,34 +96,34 @@ struct GUIHelperInterface float* depthBuffer, int depthBufferSizeInPixels, int* segmentationMaskBuffer, int segmentationMaskBufferSizeInPixels, int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied) = 0; - virtual void debugDisplayCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], - unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, - float* depthBuffer, int depthBufferSizeInPixels, - int* segmentationMaskBuffer, int segmentationMaskBufferSizeInPixels, - int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied) {} + virtual void debugDisplayCameraImageData(const float /*viewMatrix*/[16], const float /*projectionMatrix*/[16], + unsigned char* /*pixelsRGBA*/, int /*rgbaBufferSizeInPixels*/, + float* /*depthBuffer*/, int /*depthBufferSizeInPixels*/, + int* /*segmentationMaskBuffer*/, int /*segmentationMaskBufferSizeInPixels*/, + int /*startPixelIndex*/, int /*destinationWidth*/, int /*destinationHeight*/, int* /*numPixelsCopied*/) {} - virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]) {} - virtual void setProjectiveTexture(bool useProjectiveTexture) {} + virtual void setProjectiveTextureMatrices(const float /*viewMatrix*/[16], const float /*projectionMatrix*/[16]) {} + virtual void setProjectiveTexture(bool /*useProjectiveTexture*/) {} virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) = 0; - virtual void drawText3D(const char* txt, float posX, float posY, float posZ, float size) {} - virtual void drawText3D(const char* txt, float position[3], float orientation[4], float color[4], float size, int optionFlag) {} + virtual void drawText3D(const char* /*txt*/, float /*posX*/, float /*posY*/, float /*posZ*/, float /*size*/) {} + virtual void drawText3D(const char* /*txt*/, float /*position*/[3], float /*orientation*/[4], float /*color*/[4], float /*size*/, int /*optionFlag*/) {} - virtual int addUserDebugText3D(const char* txt, const double positionXYZ[3], const double orientation[4], const double textColorRGB[3], double size, double lifeTime, int trackingVisualShapeIndex, int optionFlags, int replaceItemUid) { return -1; } - virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid) { return -1; }; - virtual int addUserDebugPoints(const double debugPointPositionXYZ[], const double debugPointColorRGB[3], double pointSize, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid, int debugPointNum) { return -1; }; - virtual int addUserDebugParameter(const char* txt, double rangeMin, double rangeMax, double startValue) { return -1; }; - virtual int readUserDebugParameter(int itemUniqueId, double* value) { return 0; } + virtual int addUserDebugText3D(const char* /*txt*/, const double /*positionXYZ*/[3], const double /*orientation*/[4], const double /*textColorRGB*/[3], double /*size*/, double /*lifeTime*/, int /*trackingVisualShapeIndex*/, int /*optionFlags*/, int /*replaceItemUid*/) { return -1; } + virtual int addUserDebugLine(const double /*debugLineFromXYZ*/[3], const double /*debugLineToXYZ*/[3], const double /*debugLineColorRGB*/[3], double /*lineWidth*/, double /*lifeTime*/, int /*trackingVisualShapeIndex*/, int /*replaceItemUid*/) { return -1; }; + virtual int addUserDebugPoints(const double /*debugPointPositionXYZ*/[], const double /*debugPointColorRGB*/[3], double /*pointSize*/, double /*lifeTime*/, int /*trackingVisualShapeIndex*/, int /*replaceItemUid*/, int /*debugPointNum*/) { return -1; }; + virtual int addUserDebugParameter(const char* /*txt*/, double /*rangeMin*/, double /*rangeMax*/, double /*startValue*/) { return -1; }; + virtual int readUserDebugParameter(int /*itemUniqueId*/, double* /*value*/) { return 0; } - virtual void removeUserDebugItem(int debugItemUniqueId){}; + virtual void removeUserDebugItem(int /*debugItemUniqueId*/){}; virtual void removeAllUserDebugItems(){}; virtual void removeAllUserParameters() {}; - virtual void setVisualizerFlagCallback(VisualizerFlagCallback callback) {} + virtual void setVisualizerFlagCallback(VisualizerFlagCallback /*callback*/) {} //empty name stops dumping video - virtual void dumpFramesToVideo(const char* mp4FileName){}; + virtual void dumpFramesToVideo(const char* /*mp4FileName*/){}; virtual void drawDebugDrawerLines(){} virtual void clearLines(){} virtual bool isRemoteVisualizer() { return false; } @@ -138,25 +138,25 @@ struct DummyGUIHelper : public GUIHelperInterface } virtual ~DummyGUIHelper() {} - virtual void createRigidBodyGraphicsObject(btRigidBody* body, const btVector3& color) {} + virtual void createRigidBodyGraphicsObject(btRigidBody* /*body*/, const btVector3& /*color*/) {} - virtual void createCollisionObjectGraphicsObject(btCollisionObject* obj, const btVector3& color) {} + virtual void createCollisionObjectGraphicsObject(btCollisionObject* /*obj*/, const btVector3& /*color*/) {} - virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape) {} + virtual void createCollisionShapeGraphicsObject(btCollisionShape* /*collisionShape*/) {} - virtual void syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWorld) {} + virtual void syncPhysicsToGraphics(const btDiscreteDynamicsWorld* /*rbWorld*/) {} - virtual void render(const btDiscreteDynamicsWorld* rbWorld) {} + virtual void render(const btDiscreteDynamicsWorld* /*rbWorld*/) {} - virtual void createPhysicsDebugDrawer(btDiscreteDynamicsWorld* rbWorld) {} + virtual void createPhysicsDebugDrawer(btDiscreteDynamicsWorld* /*rbWorld*/) {} - virtual int registerTexture(const unsigned char* texels, int width, int height) { return -1; } - virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices, int primitiveType, int textureId) { return -1; } - virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling) { return -1; } + virtual int registerTexture(const unsigned char* /*texels*/, int /*width*/, int /*height*/) { return -1; } + virtual int registerGraphicsShape(const float* /*vertices*/, int /*numvertices*/, const int* /*indices*/, int /*numIndices*/, int /*primitiveType*/, int /*textureId*/) { return -1; } + virtual int registerGraphicsInstance(int /*shapeIndex*/, const float* /*position*/, const float* /*quaternion*/, const float* /*color*/, const float* /*scaling*/) { return -1; } virtual void removeAllGraphicsInstances() {} - virtual void removeGraphicsInstance(int graphicsUid) {} - virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4]) {} - virtual void changeScaling(int instanceUid, const double scaling[3]) {} + virtual void removeGraphicsInstance(int /*graphicsUid*/) {} + virtual void changeRGBAColor(int /*instanceUid*/, const double /*rgbaColor*/[4]) {} + virtual void changeScaling(int /*instanceUid*/, const double /*scaling*/[3]) {} virtual Common2dCanvasInterface* get2dCanvasInterface() { @@ -178,53 +178,53 @@ struct DummyGUIHelper : public GUIHelperInterface return 0; } - virtual void setUpAxis(int axis) + virtual void setUpAxis(int /*axis*/) { } - virtual void resetCamera(float camDist, float yaw, float pitch, float camPosX, float camPosY, float camPosZ) + virtual void resetCamera(float /*camDist*/, float /*yaw*/, float /*pitch*/, float /*camPosX*/, float /*camPosY*/, float /*camPosZ*/) { } - virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], - unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, - float* depthBuffer, int depthBufferSizeInPixels, - int* segmentationMaskBuffer, int segmentationMaskBufferSizeInPixels, - int startPixelIndex, int width, int height, int* numPixelsCopied) + virtual void copyCameraImageData(const float /*viewMatrix*/[16], const float /*projectionMatrix*/[16], + unsigned char* /*pixelsRGBA*/, int /*rgbaBufferSizeInPixels*/, + float* /*depthBuffer*/, int /*depthBufferSizeInPixels*/, + int* /*segmentationMaskBuffer*/, int /*segmentationMaskBufferSizeInPixels*/, + int /*startPixelIndex*/, int /*width*/, int /*height*/, int* numPixelsCopied) { if (numPixelsCopied) *numPixelsCopied = 0; } - virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]) + virtual void setProjectiveTextureMatrices(const float /*viewMatrix*/[16], const float /*projectionMatrix*/[16]) { } - virtual void setProjectiveTexture(bool useProjectiveTexture) + virtual void setProjectiveTexture(bool /*useProjectiveTexture*/) { } - virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) + virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* /*rbWorld*/) { } - virtual void drawText3D(const char* txt, float posX, float posZY, float posZ, float size) + virtual void drawText3D(const char* /*txt*/, float /*posX*/, float /*posZY*/, float /*posZ*/, float /*size*/) { } - virtual void drawText3D(const char* txt, float position[3], float orientation[4], float color[4], float size, int optionFlag) + virtual void drawText3D(const char* /*txt*/, float /*position*/[3], float /*orientation*/[4], float /*color*/[4], float /*size*/, int /*optionFlag*/) { } - virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid) + virtual int addUserDebugLine(const double /*debugLineFromXYZ*/[3], const double /*debugLineToXYZ*/[3], const double /*debugLineColorRGB*/[3], double /*lineWidth*/, double /*lifeTime*/, int /*trackingVisualShapeIndex*/, int /*replaceItemUid*/) { return -1; } - virtual int addUserDebugPoints(const double debugPointPositionXYZ[3], const double debugPointColorRGB[3], double pointSize, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid, int debugPointNum) + virtual int addUserDebugPoints(const double /*debugPointPositionXYZ*/[3], const double /*debugPointColorRGB*/[3], double /*pointSize*/, double /*lifeTime*/, int /*trackingVisualShapeIndex*/, int /*replaceItemUid*/, int /*debugPointNum*/) { return -1; }; - virtual void removeUserDebugItem(int debugItemUniqueId) + virtual void removeUserDebugItem(int /*debugItemUniqueId*/) { } virtual void removeAllUserDebugItems() diff --git a/examples/CommonInterfaces/CommonGraphicsAppInterface.h b/examples/CommonInterfaces/CommonGraphicsAppInterface.h index a3d9d3eac6..dc09ef9e24 100644 --- a/examples/CommonInterfaces/CommonGraphicsAppInterface.h +++ b/examples/CommonInterfaces/CommonGraphicsAppInterface.h @@ -78,11 +78,11 @@ struct CommonGraphicsApp { } - virtual void dumpNextFrameToPng(const char* pngFilename) {} - virtual void dumpFramesToVideo(const char* mp4Filename) {} + virtual void dumpNextFrameToPng(const char* /*pngFilename*/) {} + virtual void dumpFramesToVideo(const char* /*mp4Filename*/) {} - virtual void getScreenPixels(unsigned char* rgbaBuffer, int bufferSizeInBytes, float* depthBuffer, int depthBufferSizeInBytes) {} - virtual void setViewport(int width, int height) {} + virtual void getScreenPixels(unsigned char* /*rgbaBuffer*/, int /*bufferSizeInBytes*/, float* /*depthBuffer*/, int /*depthBufferSizeInBytes*/) {} + virtual void setViewport(int /*width*/, int /*height*/) {} virtual void getBackgroundColor(float* red, float* green, float* blue) const { @@ -93,7 +93,7 @@ struct CommonGraphicsApp if (blue) *blue = m_backgroundColorRGB[2]; } - virtual void setMp4Fps(int fps) {} + virtual void setMp4Fps(int /*fps*/) {} virtual void setBackgroundColor(float red, float green, float blue) { m_backgroundColorRGB[0] = red; diff --git a/examples/CommonInterfaces/CommonMultiBodyBase.h b/examples/CommonInterfaces/CommonMultiBodyBase.h index ad6c2a4c68..4457f6bd01 100644 --- a/examples/CommonInterfaces/CommonMultiBodyBase.h +++ b/examples/CommonInterfaces/CommonMultiBodyBase.h @@ -490,6 +490,7 @@ struct CommonMultiBodyBase : public CommonExampleInterface btRigidBody* createRigidBody(float mass, const btTransform& startTransform, btCollisionShape* shape, const btVector4& color = btVector4(1, 0, 0, 1)) { + (void)color; btAssert((!shape || shape->getShapeType() != INVALID_SHAPE_PROXYTYPE)); //rigidbody is dynamic if and only if mass is non zero, otherwise static diff --git a/examples/CommonInterfaces/CommonRenderInterface.h b/examples/CommonInterfaces/CommonRenderInterface.h index 01f5499edd..8a85ba94e8 100644 --- a/examples/CommonInterfaces/CommonRenderInterface.h +++ b/examples/CommonInterfaces/CommonRenderInterface.h @@ -63,11 +63,11 @@ struct CommonRenderInterface virtual void setShadowMapWorldSize(float worldSize) = 0; - virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]){}; - virtual void setProjectiveTexture(bool useProjectiveTexture){}; + virtual void setProjectiveTextureMatrices(const float /*viewMatrix*/[16], const float /*projectionMatrix*/[16]){}; + virtual void setProjectiveTexture(bool /*useProjectiveTexture*/){}; virtual void renderScene() = 0; - virtual void renderSceneInternal(int renderMode = B3_DEFAULT_RENDERMODE){}; + virtual void renderSceneInternal(int renderMode = B3_DEFAULT_RENDERMODE){ (void)renderMode; }; virtual int getScreenWidth() = 0; virtual int getScreenHeight() = 0; @@ -89,12 +89,12 @@ struct CommonRenderInterface virtual int registerTexture(const unsigned char* texels, int width, int height, bool flipPixelsY = true) = 0; virtual void updateTexture(int textureIndex, const unsigned char* texels, bool flipPixelsY = true) = 0; virtual void activateTexture(int textureIndex) = 0; - virtual void replaceTexture(int shapeIndex, int textureIndex){}; + virtual void replaceTexture(int /*shapeIndex*/, int /*textureIndex*/){}; virtual void removeTexture(int textureIndex) = 0; - virtual void setPlaneReflectionShapeIndex(int index) {} + virtual void setPlaneReflectionShapeIndex(int /*index*/) {} - virtual int getShapeIndexFromInstance(int srcIndex) { return -1; } + virtual int getShapeIndexFromInstance(int /*srcIndex*/) { return -1; } virtual bool readSingleInstanceTransformToCPU(float* position, float* orientation, int srcIndex) = 0; diff --git a/examples/CommonInterfaces/CommonRigidBodyBase.h b/examples/CommonInterfaces/CommonRigidBodyBase.h index 98352bcd3b..3c2a79965a 100644 --- a/examples/CommonInterfaces/CommonRigidBodyBase.h +++ b/examples/CommonInterfaces/CommonRigidBodyBase.h @@ -406,6 +406,7 @@ struct CommonRigidBodyBase : public CommonExampleInterface btRigidBody* createRigidBody(float mass, const btTransform& startTransform, btCollisionShape* shape, const btVector4& color = btVector4(1, 0, 0, 1)) { + (void)color; btAssert((!shape || shape->getShapeType() != INVALID_SHAPE_PROXYTYPE)); //rigidbody is dynamic if and only if mass is non zero, otherwise static diff --git a/examples/Constraints/ConstraintDemo.cpp b/examples/Constraints/ConstraintDemo.cpp index 704b9779db..2171d2ad38 100644 --- a/examples/Constraints/ConstraintDemo.cpp +++ b/examples/Constraints/ConstraintDemo.cpp @@ -102,6 +102,7 @@ void AllConstraintDemo::initPhysics() groundTransform.setOrigin(btVector3(0, -56, 0)); btRigidBody* groundBody; groundBody = createRigidBody(0, groundTransform, groundShape); + (void)groundBody; btCollisionShape* shape = new btBoxShape(btVector3(CUBE_HALF_EXTENTS, CUBE_HALF_EXTENTS, CUBE_HALF_EXTENTS)); m_collisionShapes.push_back(shape); @@ -791,7 +792,7 @@ void AllConstraintDemo::displayCallback(void) { } #endif -bool AllConstraintDemo::keyboardCallback(int key, int state) +bool AllConstraintDemo::keyboardCallback(int key, int /*state*/) { bool handled = false; diff --git a/examples/Constraints/TestHingeTorque.cpp b/examples/Constraints/TestHingeTorque.cpp index f422e219e7..55df897355 100644 --- a/examples/Constraints/TestHingeTorque.cpp +++ b/examples/Constraints/TestHingeTorque.cpp @@ -41,7 +41,7 @@ TestHingeTorque::~TestHingeTorque() } } -void TestHingeTorque::stepSimulation(float deltaTime) +void TestHingeTorque::stepSimulation(float /*deltaTime*/) { if (0) //m_once) { diff --git a/examples/DeformableDemo/DeformableContact.cpp b/examples/DeformableDemo/DeformableContact.cpp index b1ad0b67b2..73e6582c28 100644 --- a/examples/DeformableDemo/DeformableContact.cpp +++ b/examples/DeformableDemo/DeformableContact.cpp @@ -197,7 +197,7 @@ void DeformableContact::initPhysics() getDeformableDynamicsWorld()->setLineSearch(false); m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); int numInstances = m_guiHelper->getRenderInterface()->getTotalNumInstances(); - double rgbaColors[3][4] = { { 1, 0, 0, 1 } , { 0, 1, 0, 1 } ,{ 0, 0, 1, 1 } }; + // double rgbaColors[3][4] = { { 1, 0, 0, 1 } , { 0, 1, 0, 1 } ,{ 0, 0, 1, 1 } }; for (int i = 0; i < numInstances; i++) { diff --git a/examples/DeformableDemo/DeformableMultibody.cpp b/examples/DeformableDemo/DeformableMultibody.cpp index 041624b00c..043980fed0 100644 --- a/examples/DeformableDemo/DeformableMultibody.cpp +++ b/examples/DeformableDemo/DeformableMultibody.cpp @@ -24,7 +24,6 @@ #include "../CommonInterfaces/CommonRigidBodyBase.h" #include "../Utils/b3ResourcePath.h" -#include "../SoftDemo/BunnyMesh.h" #include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h" #include "BulletDynamics/Featherstone/btMultiBodyJointFeedback.h" diff --git a/examples/DeformableDemo/DeformableRigid.cpp b/examples/DeformableDemo/DeformableRigid.cpp index 7efe118a69..85e9596a71 100644 --- a/examples/DeformableDemo/DeformableRigid.cpp +++ b/examples/DeformableDemo/DeformableRigid.cpp @@ -97,7 +97,7 @@ class DeformableRigid : public CommonDeformableBodyBase // } } - void Ctor_RbUpStack(int count) + void Ctor_RbUpStack(int /*count*/) { float mass = .2; diff --git a/examples/DeformableDemo/GraspDeformable.cpp b/examples/DeformableDemo/GraspDeformable.cpp index f52f67fe98..965af9911b 100644 --- a/examples/DeformableDemo/GraspDeformable.cpp +++ b/examples/DeformableDemo/GraspDeformable.cpp @@ -167,11 +167,11 @@ class GraspDeformable : public CommonDeformableBodyBase } } - virtual bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) + virtual bool pickBody(const btVector3& /*rayFromWorld*/, const btVector3& /*rayToWorld*/) { return false; } - virtual bool movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) + virtual bool movePickedBody(const btVector3& /*rayFromWorld*/, const btVector3& /*rayToWorld*/) { return false; } diff --git a/examples/DeformableDemo/LoadDeformed.cpp b/examples/DeformableDemo/LoadDeformed.cpp index 283c428c08..9f1309a089 100644 --- a/examples/DeformableDemo/LoadDeformed.cpp +++ b/examples/DeformableDemo/LoadDeformed.cpp @@ -41,10 +41,10 @@ static inline bool isSpace(const char c) { return (c == ' ') || (c == '\t'); } -static inline bool isNewLine(const char c) -{ - return (c == '\r') || (c == '\n') || (c == '\0'); -} +//static inline bool isNewLine(const char c) +//{ +// return (c == '\r') || (c == '\n') || (c == '\0'); +//} static inline float parseFloat(const char*& token) { token += strspn(token, " \t"); @@ -187,6 +187,7 @@ class LoadDeformed : public CommonDeformableBodyBase psb = nullptr; reset_frame = 0; sim_time = 0; + (void)filename; } virtual ~LoadDeformed() { diff --git a/examples/DeformableDemo/Pinch.cpp b/examples/DeformableDemo/Pinch.cpp index dbf1e6c801..90afd5ac0e 100644 --- a/examples/DeformableDemo/Pinch.cpp +++ b/examples/DeformableDemo/Pinch.cpp @@ -256,6 +256,7 @@ void Pinch::initPhysics() // create a soft block { + /* btScalar verts[24] = {0.f, 0.f, 0.f, 1.f, 0.f, 0.f, 0.f, 1.f, 0.f, @@ -286,6 +287,7 @@ void Pinch::initPhysics() 4,5,0, 4,5,6, }; + */ // btSoftBody* psb = btSoftBodyHelpers::CreateFromTriMesh(getDeformableDynamicsWorld()->getWorldInfo(), &verts[0], &triangles[0], 20); //// btSoftBody* psb = btSoftBodyHelpers::CreateFromTetGenData(getDeformableDynamicsWorld()->getWorldInfo(), diff --git a/examples/DeformableDemo/PinchFriction.cpp b/examples/DeformableDemo/PinchFriction.cpp index 5d31331b6f..82b1780352 100644 --- a/examples/DeformableDemo/PinchFriction.cpp +++ b/examples/DeformableDemo/PinchFriction.cpp @@ -85,11 +85,11 @@ class PinchFriction : public CommonDeformableBodyBase CommonDeformableBodyBase::renderScene(); } - virtual bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) + virtual bool pickBody(const btVector3& /*rayFromWorld*/, const btVector3& /*rayToWorld*/) { return false; } - virtual bool movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) + virtual bool movePickedBody(const btVector3& /*rayFromWorld*/, const btVector3& /*rayToWorld*/) { return false; } diff --git a/examples/DeformableDemo/SplitImpulse.cpp b/examples/DeformableDemo/SplitImpulse.cpp index 962d49d668..4e4bf06eab 100644 --- a/examples/DeformableDemo/SplitImpulse.cpp +++ b/examples/DeformableDemo/SplitImpulse.cpp @@ -55,7 +55,7 @@ class SplitImpulse : public CommonDeformableBodyBase m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep); } - void Ctor_RbUpStack(int count) + void Ctor_RbUpStack(int /*count*/) { float mass = 0.2; diff --git a/examples/Evolution/NN3DWalkers.cpp b/examples/Evolution/NN3DWalkers.cpp index 6ac7d8a23b..9b53ad297a 100755 --- a/examples/Evolution/NN3DWalkers.cpp +++ b/examples/Evolution/NN3DWalkers.cpp @@ -267,7 +267,7 @@ class NNWalker transform.setIdentity(); transform.setOrigin(localRootBodyPosition); - btTransform originTransform = transform; + // btTransform originTransform = transform; m_bodies[0] = localCreateRigidBody(btScalar(bFixed ? 0. : 1.), bodyOffset * transform, m_shapes[0]); m_ownerWorld->addRigidBody(m_bodies[0]); diff --git a/examples/Evolution/NN3DWalkersTimeWarpBase.h b/examples/Evolution/NN3DWalkersTimeWarpBase.h index deef114766..55d2c7da95 100644 --- a/examples/Evolution/NN3DWalkersTimeWarpBase.h +++ b/examples/Evolution/NN3DWalkersTimeWarpBase.h @@ -150,12 +150,12 @@ inline void twxChangeFPS(float framesPerSecond, void*) gFramesPerSecond = framesPerSecond; } -inline void twxChangeERPCFM(float notUsed, void*) +inline void twxChangeERPCFM(float /*notUsed*/, void*) { // function to change ERP/CFM appropriately gChangeErpCfm = true; } -inline void changeSolver(int comboboxId, const char* item, void* userPointer) +inline void changeSolver(int /*comboboxId*/, const char* item, void* /*userPointer*/) { // function to change the solver for (int i = 0; i < NUM_SOLVERS; i++) { @@ -169,7 +169,7 @@ inline void changeSolver(int comboboxId, const char* item, void* userPointer) b3Printf("No Change"); } -inline void twxChangeSolverIterations(float notUsed, void* userPtr) +inline void twxChangeSolverIterations(float /*notUsed*/, void* /*userPtr*/) { // change the solver iterations } @@ -190,19 +190,19 @@ inline void clampToCustomSpeedNotches(float speed, void*) gSimulationSpeed = minSpeed; } -inline void switchInterpolated(int buttonId, bool buttonState, void* userPointer) +inline void switchInterpolated(int /*buttonId*/, bool /*buttonState*/, void* /*userPointer*/) { // toggle if interpolation steps are taken gInterpolate = !gInterpolate; // b3Printf("Interpolate substeps %s", gInterpolate?"on":"off"); } -inline void switchHeadless(int buttonId, bool buttonState, void* userPointer) +inline void switchHeadless(int /*buttonId*/, bool /*buttonState*/, void* /*userPointer*/) { // toggle if the demo should run headless gIsHeadless = !gIsHeadless; // b3Printf("Run headless %s", gIsHeadless?"on":"off"); } -inline void switchMaximumSpeed(int buttonId, bool buttonState, void* userPointer) +inline void switchMaximumSpeed(int /*buttonId*/, bool /*buttonState*/, void* /*userPointer*/) { // toggle it the demo should run as fast as possible // b3Printf("Run maximum speed %s", gMaximumSpeed?"on":"off"); } @@ -561,7 +561,7 @@ struct NN3DWalkersTimeWarpBase : public CommonRigidBodyBase return speedUp; } - void timeWarpSimulation(float deltaTime) // Override this + void timeWarpSimulation(float /*deltaTime*/) // Override this { } @@ -774,7 +774,7 @@ struct NN3DWalkersTimeWarpBase : public CommonRigidBodyBase m_dynamicsWorld->getSolverInfo().m_numIterations = iterations; } - void changeFPS(float framesPerSecond) + void changeFPS(float /*framesPerSecond*/) { // change the frames per second fpsStep = 1000.0f / gFramesPerSecond; } diff --git a/examples/ExampleBrowser/EmptyExample.h b/examples/ExampleBrowser/EmptyExample.h index 95ba27ffae..cd2412a3f3 100644 --- a/examples/ExampleBrowser/EmptyExample.h +++ b/examples/ExampleBrowser/EmptyExample.h @@ -16,12 +16,12 @@ class EmptyExample : public CommonExampleInterface virtual void initPhysics() {} virtual void exitPhysics() {} - virtual void stepSimulation(float deltaTime) {} + virtual void stepSimulation(float /*deltaTime*/) {} virtual void renderScene() {} - virtual void physicsDebugDraw(int debugFlags) {} - virtual bool mouseMoveCallback(float x, float y) { return false; } - virtual bool mouseButtonCallback(int button, int state, float x, float y) { return false; } - virtual bool keyboardCallback(int key, int state) { return false; } + virtual void physicsDebugDraw(int /*debugFlags*/) {} + virtual bool mouseMoveCallback(float /*x*/, float /*y*/) { return false; } + virtual bool mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } }; #endif //EMPTY_EXAMPLE_H diff --git a/examples/ExampleBrowser/GL_ShapeDrawer.cpp b/examples/ExampleBrowser/GL_ShapeDrawer.cpp index 5bc92adec9..12fa9690c7 100644 --- a/examples/ExampleBrowser/GL_ShapeDrawer.cpp +++ b/examples/ExampleBrowser/GL_ShapeDrawer.cpp @@ -831,7 +831,7 @@ void GL_ShapeDrawer::drawSceneInternal(const btDiscreteDynamicsWorld* dynamicsWo //this GL_ShapeDrawer will be removed, in the meanwhile directly access this global 'useShadoMaps' extern bool useShadowMap; -void GL_ShapeDrawer::drawScene(const btDiscreteDynamicsWorld* dynamicsWorld, bool useShadows1, int cameraUpAxis) +void GL_ShapeDrawer::drawScene(const btDiscreteDynamicsWorld* dynamicsWorld, bool /*useShadows1*/, int cameraUpAxis) { bool useShadows = useShadowMap; GLfloat light_ambient[] = {btScalar(0.2), btScalar(0.2), btScalar(0.2), btScalar(1.0)}; diff --git a/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp b/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp index d6fd7e0b41..61108c55a9 100644 --- a/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp +++ b/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp @@ -21,7 +21,7 @@ struct MyButtonEventHandler : public Gwen::Event::Handler { } - void onButtonPress(Gwen::Controls::Base* pControl) + void onButtonPress(Gwen::Controls::Base* /*pControl*/) { if (m_callback) { diff --git a/examples/ExampleBrowser/GwenGUISupport/GwenTextureWindow.cpp b/examples/ExampleBrowser/GwenGUISupport/GwenTextureWindow.cpp index 0e0a2c7327..273d9ad729 100644 --- a/examples/ExampleBrowser/GwenGUISupport/GwenTextureWindow.cpp +++ b/examples/ExampleBrowser/GwenGUISupport/GwenTextureWindow.cpp @@ -51,7 +51,7 @@ class MyMenuItems2 : public Gwen::Controls::Base { } - void MenuItemSelect(Gwen::Controls::Base* pControl) + void MenuItemSelect(Gwen::Controls::Base* /*pControl*/) { if (m_graphWindow->Hidden()) { diff --git a/examples/ExampleBrowser/GwenGUISupport/gwenUserInterface.cpp b/examples/ExampleBrowser/GwenGUISupport/gwenUserInterface.cpp index 740bcce71f..b99089de62 100644 --- a/examples/ExampleBrowser/GwenGUISupport/gwenUserInterface.cpp +++ b/examples/ExampleBrowser/GwenGUISupport/gwenUserInterface.cpp @@ -23,14 +23,14 @@ class MyMenuItems : public Gwen::Controls::Base MyMenuItems() : Gwen::Controls::Base(0), m_fileOpenCallback(0) { } - void myQuitApp(Gwen::Controls::Base* pControl) + void myQuitApp(Gwen::Controls::Base* /*pControl*/) { if (m_quitCallback) { (*m_quitCallback)(); } } - void fileOpen(Gwen::Controls::Base* pControl) + void fileOpen(Gwen::Controls::Base* /*pControl*/) { if (m_fileOpenCallback) { @@ -233,7 +233,7 @@ void GwenUserInterface::registerQuitCallback(b3QuitCallback callback) m_data->m_menuItems->m_quitCallback = callback; } -void GwenUserInterface::init(int width, int height, Gwen::Renderer::Base* renderer, float retinaScale) +void GwenUserInterface::init(int width, int height, Gwen::Renderer::Base* renderer, float /*retinaScale*/) { m_data->m_curYposition = 20; //m_data->m_primRenderer = new GLPrimitiveRenderer(width,height); diff --git a/examples/ExampleBrowser/InProcessExampleBrowser.cpp b/examples/ExampleBrowser/InProcessExampleBrowser.cpp index b2d685364f..b46f8b96e3 100644 --- a/examples/ExampleBrowser/InProcessExampleBrowser.cpp +++ b/examples/ExampleBrowser/InProcessExampleBrowser.cpp @@ -153,7 +153,7 @@ void ExampleEntriesPhysicsServer::initExampleEntries() } } -void ExampleEntriesPhysicsServer::registerExampleEntry(int menuLevel, const char* name, const char* description, CommonExampleInterface::CreateFunc* createFunc, int option) +void ExampleEntriesPhysicsServer::registerExampleEntry(int /*menuLevel*/, const char* /*name*/, const char* /*description*/, CommonExampleInterface::CreateFunc* /*createFunc*/, int /*option*/) { } @@ -403,6 +403,7 @@ btInProcessExampleBrowserMainThreadInternalData* btCreateInProcessExampleBrowser data->m_exampleBrowser->setSharedMemoryInterface(data->m_sharedMem); bool init; init = data->m_exampleBrowser->init(argc, argv); + (void)init; data->m_clock.reset(); return data; } diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index 0ff00865d7..93a54913c4 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -64,7 +64,7 @@ struct GL3TexLoader : public MyTextureLoader pTexture->m_intData = *texIdPtr; } } - virtual void FreeTexture(Gwen::Texture* pTexture) + virtual void FreeTexture(Gwen::Texture* /*pTexture*/) { } }; @@ -504,7 +504,7 @@ void selectDemo(int demoIndex) #include -static void saveCurrentSettings(int currentEntry, const char* startFileName) +static void saveCurrentSettings(int /*currentEntry*/, const char* startFileName) { FILE* f = fopen(startFileName, "w"); if (f) @@ -648,7 +648,7 @@ struct MyMenuItemHander : public Gwen::Event::Handler saveCurrentSettings(sCurrentDemoIndex, startFileName); } } - void onButtonC(Gwen::Controls::Base* pControl) + void onButtonC(Gwen::Controls::Base* /*pControl*/) { /*Gwen::Controls::Label* label = (Gwen::Controls::Label*) pControl; Gwen::UnicodeString la = label->GetText();// node->GetButton()->GetName();// GetText(); @@ -659,7 +659,7 @@ struct MyMenuItemHander : public Gwen::Event::Handler printf("onButtonC ! %s\n", ha); */ } - void onButtonD(Gwen::Controls::Base* pControl) + void onButtonD(Gwen::Controls::Base* /*pControl*/) { /* Gwen::Controls::Label* label = (Gwen::Controls::Label*) pControl; Gwen::UnicodeString la = label->GetText();// node->GetButton()->GetName();// GetText(); @@ -675,19 +675,19 @@ struct MyMenuItemHander : public Gwen::Event::Handler } } - void onButtonE(Gwen::Controls::Base* pControl) + void onButtonE(Gwen::Controls::Base* /*pControl*/) { // printf("select %d\n",m_buttonId); sCurrentHightlighted = m_buttonId; gui2->setExampleDescription(gAllExamples->getExampleDescription(sCurrentHightlighted)); } - void onButtonF(Gwen::Controls::Base* pControl) + void onButtonF(Gwen::Controls::Base* /*pControl*/) { //printf("selection changed!\n"); } - void onButtonG(Gwen::Controls::Base* pControl) + void onButtonG(Gwen::Controls::Base* /*pControl*/) { //printf("onButtonG !\n"); } diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index 7df4e932bc..a35e9a91bf 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -82,18 +82,18 @@ MyDebugDrawer : public btIDebugDraw m_lineIndices.push_back(m_lineIndices.size()); } - virtual void drawContactPoint(const btVector3& PointOnB, const btVector3& normalOnB, btScalar distance, int lifeTime, const btVector3& color) + virtual void drawContactPoint(const btVector3& PointOnB, const btVector3& normalOnB, btScalar distance, int /*lifeTime*/, const btVector3& color) { drawLine(PointOnB, PointOnB + normalOnB * distance, color); btVector3 ncolor(0, 0, 0); drawLine(PointOnB, PointOnB + normalOnB * 0.01, ncolor); } - virtual void reportErrorWarning(const char* warningString) + virtual void reportErrorWarning(const char* /*warningString*/) { } - virtual void draw3dText(const btVector3& location, const char* textString) + virtual void draw3dText(const btVector3& /*location*/, const char* /*textString*/) { } @@ -229,7 +229,7 @@ void OpenGLGuiHelper::setVRMode(bool vrMode) m_data->m_vrSkipShadowPass = 0; } -OpenGLGuiHelper::OpenGLGuiHelper(CommonGraphicsApp* glApp, bool useOpenGL2) +OpenGLGuiHelper::OpenGLGuiHelper(CommonGraphicsApp* glApp, bool /*useOpenGL2*/) { m_data = new OpenGLGuiHelperInternalData; m_data->m_glApp = glApp; @@ -280,7 +280,7 @@ class MyTriangleCollector2 : public btTriangleCallback m_pIndicesOut = 0; } - virtual void processTriangle(btVector3* tris, int partId, int triangleIndex) + virtual void processTriangle(btVector3* tris, int /*partId*/, int /*triangleIndex*/) { for (int k = 0; k < 3; k++) { @@ -295,7 +295,7 @@ class MyTriangleCollector2 : public btTriangleCallback v.normal[l] = normal[l]; } - btVector3 extents = m_aabbMax - m_aabbMin; + // btVector3 extents = m_aabbMax - m_aabbMin; v.uv[0] = (1.-((v.xyzw[0] - m_aabbMin[0]) / (m_aabbMax[0] - m_aabbMin[0])))*m_textureScaling; v.uv[1] = (1.-(v.xyzw[1] - m_aabbMin[1]) / (m_aabbMax[1] - m_aabbMin[1]))*m_textureScaling; @@ -341,7 +341,7 @@ void OpenGLGuiHelper::removeTexture(int textureUid) m_data->m_glApp->m_renderer->removeTexture(textureUid); } -void OpenGLGuiHelper::changeTexture(int textureUniqueId, const unsigned char* rgbTexels, int width, int height) +void OpenGLGuiHelper::changeTexture(int textureUniqueId, const unsigned char* rgbTexels, int /*width*/, int /*height*/) { bool flipPixelsY = true; m_data->m_glApp->m_renderer->updateTexture(textureUniqueId, rgbTexels, flipPixelsY); @@ -1107,7 +1107,7 @@ void OpenGLGuiHelper::syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWor } } -void OpenGLGuiHelper::render(const btDiscreteDynamicsWorld* rbWorld) +void OpenGLGuiHelper::render(const btDiscreteDynamicsWorld* /*rbWorld*/) { if (m_data->m_vrMode) { @@ -1206,7 +1206,7 @@ bool OpenGLGuiHelper::getCameraInfo(int* width, int* height, float viewMatrix[16 btVector3 camPos, camTarget; getRenderInterface()->getActiveCamera()->getCameraPosition(camPos); getRenderInterface()->getActiveCamera()->getCameraTargetPosition(camTarget); - btVector3 rayFrom = camPos; + // btVector3 rayFrom = camPos; btVector3 rayForward = (camTarget - camPos); rayForward.normalize(); float farPlane = 10000.f; @@ -1256,8 +1256,8 @@ void OpenGLGuiHelper::setProjectiveTexture(bool useProjectiveTexture) void OpenGLGuiHelper::copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, - float* depthBuffer, int depthBufferSizeInPixels, - int* segmentationMaskBuffer, int segmentationMaskBufferSizeInPixels, + float* depthBuffer, int /*depthBufferSizeInPixels*/, + int* segmentationMaskBuffer, int /*segmentationMaskBufferSizeInPixels*/, int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied) { diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.h b/examples/ExampleBrowser/OpenGLGuiHelper.h index c512c21b97..0cf9c9cc5a 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.h +++ b/examples/ExampleBrowser/OpenGLGuiHelper.h @@ -72,21 +72,21 @@ struct OpenGLGuiHelper : public GUIHelperInterface virtual void drawText3D(const char* txt, float posX, float posY, float posZ, float size); - virtual int addUserDebugText3D(const char* txt, const double positionXYZ[3], const double textColorRGB[3], double size, double lifeTime) + virtual int addUserDebugText3D(const char* /*txt*/, const double /*positionXYZ*/[3], const double /*textColorRGB*/[3], double /*size*/, double /*lifeTime*/) { return -1; } - virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid) + virtual int addUserDebugLine(const double /*debugLineFromXYZ*/[3], const double /*debugLineToXYZ*/[3], const double /*debugLineColorRGB*/[3], double /*lineWidth*/, double /*lifeTime*/, int /*trackingVisualShapeIndex*/, int /*replaceItemUid*/) { return -1; } - virtual int addUserDebugParameter(const char* txt, double rangeMin, double rangeMax, double startValue) + virtual int addUserDebugParameter(const char* /*txt*/, double /*rangeMin*/, double /*rangeMax*/, double /*startValue*/) { return -1; } - virtual void removeUserDebugItem(int debugItemUniqueId) + virtual void removeUserDebugItem(int /*debugItemUniqueId*/) { } virtual void removeAllUserDebugItems() diff --git a/examples/ExtendedTutorials/InclinedPlane.cpp b/examples/ExtendedTutorials/InclinedPlane.cpp index 5cccc3bd9c..f4fe71c35a 100644 --- a/examples/ExtendedTutorials/InclinedPlane.cpp +++ b/examples/ExtendedTutorials/InclinedPlane.cpp @@ -293,7 +293,7 @@ void InclinedPlaneExample::renderScene() CommonRigidBodyBase::renderScene(); } -bool InclinedPlaneExample::keyboardCallback(int key, int state) +bool InclinedPlaneExample::keyboardCallback(int key, int /*state*/) { // b3Printf("Key pressed: %d in state %d \n",key,state); @@ -346,7 +346,7 @@ void onSphereRestitutionChanged(float restitution, void*) } } -void onRampInclinationChanged(float inclination, void*) +void onRampInclinationChanged(float /*inclination*/, void*) { if (ramp) { diff --git a/examples/ExtendedTutorials/MultiPendulum.cpp b/examples/ExtendedTutorials/MultiPendulum.cpp index 3e0a7feba2..3a8c6b3cdb 100644 --- a/examples/ExtendedTutorials/MultiPendulum.cpp +++ b/examples/ExtendedTutorials/MultiPendulum.cpp @@ -351,7 +351,7 @@ void MultiPendulumExample::renderScene() CommonRigidBodyBase::renderScene(); } -bool MultiPendulumExample::keyboardCallback(int key, int state) +bool MultiPendulumExample::keyboardCallback(int key, int /*state*/) { //b3Printf("Key pressed: %d in state %d \n",key,state); diff --git a/examples/ExtendedTutorials/NewtonsCradle.cpp b/examples/ExtendedTutorials/NewtonsCradle.cpp index ed1645e7d3..ea41d6bd95 100644 --- a/examples/ExtendedTutorials/NewtonsCradle.cpp +++ b/examples/ExtendedTutorials/NewtonsCradle.cpp @@ -296,7 +296,7 @@ void NewtonsCradleExample::renderScene() CommonRigidBodyBase::renderScene(); } -bool NewtonsCradleExample::keyboardCallback(int key, int state) +bool NewtonsCradleExample::keyboardCallback(int key, int /*state*/) { //b3Printf("Key pressed: %d in state %d \n",key,state); diff --git a/examples/ExtendedTutorials/NewtonsRopeCradle.cpp b/examples/ExtendedTutorials/NewtonsRopeCradle.cpp index 5c60c55905..eedd7e1397 100644 --- a/examples/ExtendedTutorials/NewtonsRopeCradle.cpp +++ b/examples/ExtendedTutorials/NewtonsRopeCradle.cpp @@ -325,7 +325,7 @@ void NewtonsRopeCradleExample::changePendulaRestitution(btScalar restitution) } } -bool NewtonsRopeCradleExample::keyboardCallback(int key, int state) +bool NewtonsRopeCradleExample::keyboardCallback(int key, int /*state*/) { //b3Printf("Key pressed: %d in state %d \n",key,state); diff --git a/examples/ForkLift/ForkLiftDemo.cpp b/examples/ForkLift/ForkLiftDemo.cpp index 6bb03165b9..ac50e81bdf 100644 --- a/examples/ForkLift/ForkLiftDemo.cpp +++ b/examples/ForkLift/ForkLiftDemo.cpp @@ -117,21 +117,21 @@ class ForkLiftDemo : public CommonExampleInterface virtual void specialKeyboardUp(int key, int x, int y); - virtual bool mouseMoveCallback(float x, float y) + virtual bool mouseMoveCallback(float /*x*/, float /*y*/) { return false; } - virtual bool mouseButtonCallback(int button, int state, float x, float y) + virtual bool mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } - virtual bool keyboardCallback(int key, int state); + virtual bool keyboardCallback(int /*key*/, int /*state*/); virtual void renderScene(); - virtual void physicsDebugDraw(int debugFlags); + virtual void physicsDebugDraw(int /*debugFlags*/); void initPhysics(); void exitPhysics(); @@ -665,6 +665,7 @@ void ForkLiftDemo::stepSimulation(float deltaTime) int numSimSteps; numSimSteps = m_dynamicsWorld->stepSimulation(dt, maxSimSubSteps); + (void)numSimSteps; if (m_dynamicsWorld->getConstraintSolver()->getSolverType() == BT_MLCP_SOLVER) { @@ -934,14 +935,14 @@ bool ForkLiftDemo::keyboardCallback(int key, int state) return handled; } -void ForkLiftDemo::specialKeyboardUp(int key, int x, int y) +void ForkLiftDemo::specialKeyboardUp(int /*key*/, int /*x*/, int /*y*/) { #if 0 #endif } -void ForkLiftDemo::specialKeyboard(int key, int x, int y) +void ForkLiftDemo::specialKeyboard(int /*key*/, int /*x*/, int /*y*/) { #if 0 if (key==GLUT_KEY_END) diff --git a/examples/FractureDemo/btFractureBody.cpp b/examples/FractureDemo/btFractureBody.cpp index 351a9bc511..07c33d4b74 100644 --- a/examples/FractureDemo/btFractureBody.cpp +++ b/examples/FractureDemo/btFractureBody.cpp @@ -23,7 +23,7 @@ void btFractureBody::recomputeConnectivity(btCollisionWorld* world) MyContactResultCallback() : m_connected(false), m_margin(0.05) { } - virtual btScalar addSingleResult(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap, int partId0, int index0, const btCollisionObjectWrapper* colObj1Wrap, int partId1, int index1) + virtual btScalar addSingleResult(btManifoldPoint& cp, const btCollisionObjectWrapper* /*colObj0Wrap*/, int /*partId0*/, int /*index0*/, const btCollisionObjectWrapper* /*colObj1Wrap*/, int /*partId1*/, int /*index1*/) { if (cp.getDistance() <= m_margin) m_connected = true; diff --git a/examples/FractureDemo/btFractureDynamicsWorld.cpp b/examples/FractureDemo/btFractureDynamicsWorld.cpp index 91cecb5d05..2012788d06 100644 --- a/examples/FractureDemo/btFractureDynamicsWorld.cpp +++ b/examples/FractureDemo/btFractureDynamicsWorld.cpp @@ -387,6 +387,7 @@ void btFractureDynamicsWorld::breakDisconnectedParts(btFractureBody* fracObj) btAlignedObjectArray removedObjects; int numIslands = 0; + (void)numIslands; for (startIslandIndex = 0; startIslandIndex < numElem; startIslandIndex = endIslandIndex) { diff --git a/examples/Heightfield/HeightfieldExample.cpp b/examples/Heightfield/HeightfieldExample.cpp index d9b99fd9d2..a2f75aaa0b 100644 --- a/examples/Heightfield/HeightfieldExample.cpp +++ b/examples/Heightfield/HeightfieldExample.cpp @@ -439,6 +439,7 @@ getRawHeightfieldData b3BulletDefaultFileIO fileIO; char relativeFileName[1024]; int found = fileIO.findFile("heightmaps/wm_height_out.png", relativeFileName, 1024); + (void)found; b3AlignedObjectArray buffer; @@ -491,8 +492,8 @@ getRawHeightfieldData for (int i = 0; i < width; ++i) { - float x = i * s_gridSpacing; - float y = j * s_gridSpacing; + // float x = i * s_gridSpacing; + // float y = j * s_gridSpacing; float heightScaling = (14. / 256.); float z = double(image[(width - 1 - i) * 3 + width*j * 3]) * heightScaling; convertFromFloat(p, z, type); @@ -585,10 +586,10 @@ getRawHeightfieldData byte_t * p = raw; for (int i = 0; i < width; ++i) { - float x = i * s_gridSpacing; + // float x = i * s_gridSpacing; for (int j = 0; j < width; ++j) { - float y = j * s_gridSpacing; + // float y = j * s_gridSpacing; float z = allValues[i+width*j]; convertFromFloat(p, z, type); // update min/max @@ -754,7 +755,7 @@ class HeightfieldExample : public CommonRigidBodyMTBase//CommonRigidBodyBase #define HEIGHTFIELD_TYPE_COUNT 4 eTerrainModel gHeightfieldType = eRadial; -void setHeightfieldTypeComboBoxCallback(int combobox, const char* item, void* userPointer) +void setHeightfieldTypeComboBoxCallback(int /*combobox*/, const char* item, void* userPointer) { const char** items = static_cast(userPointer); for (int i = 0; i < HEIGHTFIELD_TYPE_COUNT; ++i) @@ -819,7 +820,7 @@ class MyTriangleCollector3 : public btTriangleCallback m_pIndicesOut = 0; } - virtual void processTriangle(btVector3* tris, int partId, int triangleIndex) + virtual void processTriangle(btVector3* tris, int /*partId*/, int /*triangleIndex*/) { for (int k = 0; k < 3; k++) { @@ -1088,7 +1089,7 @@ void HeightfieldExample::stepSimulation(float deltaTime) { btAlignedObjectArray gfxVertices; btAlignedObjectArray indices; - int strideInBytes = 9 * sizeof(float); + // int strideInBytes = 9 * sizeof(float); m_phase += s_deltaPhase * deltaTime; if (m_phase > 2.0 * SIMD_PI) { @@ -1197,6 +1198,7 @@ void HeightfieldExample::resetPhysics(void) b3BulletDefaultFileIO fileIO; char relativeFileName[1024]; int found = fileIO.findFile("heightmaps/gimp_overlay_out.png", relativeFileName, 1024); + (void)found; b3AlignedObjectArray buffer; buffer.reserve(1024); diff --git a/examples/HelloWorld/HelloWorld.cpp b/examples/HelloWorld/HelloWorld.cpp index 8b5fcee4c4..b3f13cd2b1 100644 --- a/examples/HelloWorld/HelloWorld.cpp +++ b/examples/HelloWorld/HelloWorld.cpp @@ -19,7 +19,7 @@ subject to the following restrictions: /// This is a Hello World program for running a basic Bullet physics simulation -int main(int argc, char** argv) +int main(int /*argc*/, char** /*argv*/) { ///-----includes_end----- diff --git a/examples/Importers/ImportBsp/BspLoader.cpp b/examples/Importers/ImportBsp/BspLoader.cpp index 140294e1a2..634881a7bb 100644 --- a/examples/Importers/ImportBsp/BspLoader.cpp +++ b/examples/Importers/ImportBsp/BspLoader.cpp @@ -665,7 +665,7 @@ void BspLoader::swapBSPFile(void) swapBlock((int *)&m_drawSurfaces[0], m_numDrawSurfaces * sizeof(m_drawSurfaces[0])); } -bool BspLoader::findVectorByName(float *outvec, const char *name) +bool BspLoader::findVectorByName(float *outvec, const char * /*name*/) { const char *cl; BSPVector3 origin; diff --git a/examples/Importers/ImportBsp/ImportBspExample.cpp b/examples/Importers/ImportBsp/ImportBspExample.cpp index 851e518564..6794834cd5 100644 --- a/examples/Importers/ImportBsp/ImportBspExample.cpp +++ b/examples/Importers/ImportBsp/ImportBspExample.cpp @@ -73,7 +73,7 @@ class BspToBulletConverter : public BspConverter { } - virtual void addConvexVerticesCollider(btAlignedObjectArray& vertices, bool isEntity, const btVector3& entityTargetLocation) + virtual void addConvexVerticesCollider(btAlignedObjectArray& vertices, bool /*isEntity*/, const btVector3& /*entityTargetLocation*/) { ///perhaps we can do something special with entities (isEntity) ///like adding a collision Triggering (as example) @@ -170,7 +170,8 @@ void BspDemo::initPhysics(const char* bspfilename) { //how to detect file size? memoryBuffer = malloc(size + 1); - fread(memoryBuffer, 1, size, file); + int len = fread(memoryBuffer, 1, size, file); + (void)len; bspLoader.loadBSPFile(memoryBuffer); BspToBulletConverter bsp2bullet(this); diff --git a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp index 7ae38f4d35..e6a697f292 100644 --- a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp +++ b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp @@ -261,7 +261,7 @@ struct BulletMJCFImporterInternalData return 0; } - void parseCompiler(XMLElement* root_xml, MJCFErrorLogger* logger) + void parseCompiler(XMLElement* root_xml, MJCFErrorLogger* /*logger*/) { const char* meshDirStr = root_xml->Attribute("meshdir"); if (meshDirStr) @@ -282,7 +282,7 @@ struct BulletMJCFImporterInternalData } } - void parseAssets(XMLElement* root_xml, MJCFErrorLogger* logger) + void parseAssets(XMLElement* root_xml, MJCFErrorLogger* /*logger*/) { // for (XMLElement* child_xml = root_xml->FirstChildElement(); child_xml; child_xml = child_xml->NextSiblingElement()) @@ -345,7 +345,7 @@ struct BulletMJCFImporterInternalData // armature="1" // damping="1" // limited="true" - if (const char* conTypeStr = child_xml->Attribute("limited")) + if (/*const char* conTypeStr =*/ child_xml->Attribute("limited")) { defaults.m_defaultJointLimited = child_xml->Attribute("limited"); } @@ -374,7 +374,7 @@ struct BulletMJCFImporterInternalData { defaults.m_defaultConDim = urdfLexicalCast(conDimS); } - int conDim = defaults.m_defaultConDim; + // int conDim = defaults.m_defaultConDim; const char* frictionS = child_xml->Attribute("friction"); if (frictionS) @@ -467,7 +467,7 @@ struct BulletMJCFImporterInternalData return true; } - bool parseJoint(MyMJCFDefaults& defaults, XMLElement* link_xml, int modelIndex, int parentLinkIndex, int linkIndex, MJCFErrorLogger* logger, const btTransform& parentToLinkTrans, btTransform& jointTransOut) + bool parseJoint(MyMJCFDefaults& /*defaults*/, XMLElement* link_xml, int modelIndex, int parentLinkIndex, int linkIndex, MJCFErrorLogger* logger, const btTransform& parentToLinkTrans, btTransform& jointTransOut) { bool jointHandled = false; const char* jType = link_xml->Attribute("type"); @@ -1002,7 +1002,7 @@ struct BulletMJCFImporterInternalData return tr; } - double computeVolume(const UrdfLink* linkPtr, MJCFErrorLogger* logger) const + double computeVolume(const UrdfLink* linkPtr, MJCFErrorLogger* /*logger*/) const { double totalVolume = 0; @@ -1436,7 +1436,7 @@ BulletMJCFImporter::~BulletMJCFImporter() delete m_data; } -bool BulletMJCFImporter::loadMJCF(const char* fileName, MJCFErrorLogger* logger, bool forceFixedBase) +bool BulletMJCFImporter::loadMJCF(const char* fileName, MJCFErrorLogger* logger, bool /*forceFixedBase*/) { if (strlen(fileName) == 0) return false; @@ -1447,7 +1447,7 @@ bool BulletMJCFImporter::loadMJCF(const char* fileName, MJCFErrorLogger* logger, b3FileUtils fu; //bool fileFound = fu.findFile(fileName, relativeFileName, 1024); - bool fileFound = (m_data->m_fileIO->findResourcePath(fileName, relativeFileName, 1024) > 0); + bool fileFound = m_data->m_fileIO->findResourcePath(fileName, relativeFileName, 1024); m_data->m_sourceFileName = relativeFileName; std::string xml_string; @@ -1612,7 +1612,7 @@ bool BulletMJCFImporter::getLinkColor2(int linkIndex, struct UrdfMaterialColor& return hasLinkColor; } -bool BulletMJCFImporter::getLinkColor(int linkIndex, btVector4& colorRGBA) const +bool BulletMJCFImporter::getLinkColor(int /*linkIndex*/, btVector4& /*colorRGBA*/) const { // UrdfLink* link = m_data->getLink(linkIndex); return false; @@ -2207,7 +2207,7 @@ int BulletMJCFImporter::convertLinkVisualShapes(int linkIndex, const char* pathP const UrdfVisual& vis = link->m_visualArray[v]; btTransform childTrans = vis.m_linkLocalFrame; btHashString matName(vis.m_materialName.c_str()); - UrdfMaterial* const* matPtr = model.m_materials[matName]; + // UrdfMaterial* const* matPtr = model.m_materials[matName]; convertURDFToVisualShapeInternal(&vis, pathPrefix, inertialFrame.inverse() * childTrans, vertices, indices, textures); } @@ -2317,7 +2317,7 @@ static btCollisionShape* MjcfCreateConvexHullFromShapes(const bt_tinyobj::attrib return compound; } -class btCompoundShape* BulletMJCFImporter::convertLinkCollisionShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame) const +class btCompoundShape* BulletMJCFImporter::convertLinkCollisionShapes(int linkIndex, const char* /*pathPrefix*/, const btTransform& localInertiaFrame) const { btCompoundShape* compound = new btCompoundShape(); m_data->m_allocatedCollisionShapes.push_back(compound); diff --git a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.h b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.h index d4de6b2825..df4eed480f 100644 --- a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.h +++ b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.h @@ -34,12 +34,13 @@ class BulletMJCFImporter : public URDFImporterInterface virtual bool loadMJCF(const char* fileName, MJCFErrorLogger* logger, bool forceFixedBase = false); - virtual bool loadURDF(const char* fileName, bool forceFixedBase = false) + virtual bool loadURDF(const char* /*fileName*/, bool forceFixedBase = false) { + (void)forceFixedBase; return false; } - virtual bool loadSDF(const char* fileName, bool forceFixedBase = false) { return false; } + virtual bool loadSDF(const char* /*fileName*/, bool forceFixedBase = false) { (void)forceFixedBase; return false; } virtual const char* getPathPrefix(); diff --git a/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp b/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp index b4853fab85..cc6ab484f5 100644 --- a/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp +++ b/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp @@ -71,7 +71,7 @@ struct ImportMJCFInternalData btRigidBody* m_rb; }; -ImportMJCFSetup::ImportMJCFSetup(struct GUIHelperInterface* helper, int option, const char* fileName) +ImportMJCFSetup::ImportMJCFSetup(struct GUIHelperInterface* helper, int /*option*/, const char* fileName) : CommonMultiBodyBase(helper), m_grav(-10), m_upAxis(2) diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index e24437d7d7..5155f2f5b5 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -240,7 +240,7 @@ void BulletURDFImporter::activateModel(int modelIndex) m_data->m_urdfParser.activateModel(modelIndex); } -bool BulletURDFImporter::loadSDF(const char* fileName, bool forceFixedBase) +bool BulletURDFImporter::loadSDF(const char* fileName, bool /*forceFixedBase*/) { //int argc=0; char relativeFileName[1024]; diff --git a/examples/Importers/ImportURDFDemo/MultiBodyCreationInterface.h b/examples/Importers/ImportURDFDemo/MultiBodyCreationInterface.h index 1acc47dd53..91a2e442b8 100644 --- a/examples/Importers/ImportURDFDemo/MultiBodyCreationInterface.h +++ b/examples/Importers/ImportURDFDemo/MultiBodyCreationInterface.h @@ -9,14 +9,14 @@ class MultiBodyCreationInterface virtual ~MultiBodyCreationInterface() {} virtual void createRigidBodyGraphicsInstance(int linkIndex, class btRigidBody* body, const btVector3& colorRgba, int graphicsIndex) = 0; - virtual void createRigidBodyGraphicsInstance2(int linkIndex, class btRigidBody* body, const btVector3& colorRgba, const btVector3& specularColor, int graphicsIndex) + virtual void createRigidBodyGraphicsInstance2(int linkIndex, class btRigidBody* body, const btVector3& colorRgba, const btVector3& /*specularColor*/, int graphicsIndex) { createRigidBodyGraphicsInstance(linkIndex, body, colorRgba, graphicsIndex); } ///optionally create some graphical representation from a collision object, usually for visual debugging purposes. virtual void createCollisionObjectGraphicsInstance(int linkIndex, class btCollisionObject* col, const btVector3& colorRgba) = 0; - virtual void createCollisionObjectGraphicsInstance2(int linkIndex, class btCollisionObject* col, const btVector4& colorRgba, const btVector3& specularColor) + virtual void createCollisionObjectGraphicsInstance2(int linkIndex, class btCollisionObject* col, const btVector4& colorRgba, const btVector3& /*specularColor*/) { createCollisionObjectGraphicsInstance(linkIndex, col, colorRgba); } diff --git a/examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp b/examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp index 815e8b9bf7..153f0ae94e 100644 --- a/examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp +++ b/examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp @@ -29,7 +29,7 @@ class btMultiBody* MyMultiBodyCreator::allocateMultiBody(int /* urdfLinkIndex */ return m_bulletMultiBody; } -class btRigidBody* MyMultiBodyCreator::allocateRigidBody(int urdfLinkIndex, btScalar mass, const btVector3& localInertiaDiagonal, const btTransform& initialWorldTrans, class btCollisionShape* colShape) +class btRigidBody* MyMultiBodyCreator::allocateRigidBody(int /*urdfLinkIndex*/, btScalar mass, const btVector3& localInertiaDiagonal, const btTransform& initialWorldTrans, class btCollisionShape* colShape) { btRigidBody::btRigidBodyConstructionInfo rbci(mass, 0, colShape, localInertiaDiagonal); rbci.m_startWorldTransform = initialWorldTrans; @@ -52,7 +52,7 @@ class btMultiBodyLinkCollider* MyMultiBodyCreator::allocateMultiBodyLinkCollider return mbCol; } -class btGeneric6DofSpring2Constraint* MyMultiBodyCreator::allocateGeneric6DofSpring2Constraint(int urdfLinkIndex, btRigidBody& rbA /*parent*/, btRigidBody& rbB, const btTransform& offsetInA, const btTransform& offsetInB, int rotateOrder) +class btGeneric6DofSpring2Constraint* MyMultiBodyCreator::allocateGeneric6DofSpring2Constraint(int /*urdfLinkIndex*/, btRigidBody& rbA /*parent*/, btRigidBody& rbB, const btTransform& offsetInA, const btTransform& offsetInB, int rotateOrder) { btGeneric6DofSpring2Constraint* c = new btGeneric6DofSpring2Constraint(rbA, rbB, offsetInA, offsetInB, (RotateOrder)rotateOrder); @@ -197,12 +197,12 @@ void MyMultiBodyCreator::addLinkMapping(int urdfLinkIndex, int mbLinkIndex) m_mb2urdfLink[mbLinkIndex] = urdfLinkIndex; } -void MyMultiBodyCreator::createRigidBodyGraphicsInstance(int linkIndex, btRigidBody* body, const btVector3& colorRgba, int graphicsIndex) +void MyMultiBodyCreator::createRigidBodyGraphicsInstance(int /*linkIndex*/, btRigidBody* body, const btVector3& colorRgba, int /*graphicsIndex*/) { m_guiHelper->createRigidBodyGraphicsObject(body, colorRgba); } -void MyMultiBodyCreator::createRigidBodyGraphicsInstance2(int linkIndex, class btRigidBody* body, const btVector3& colorRgba, const btVector3& specularColor, int graphicsIndex) +void MyMultiBodyCreator::createRigidBodyGraphicsInstance2(int /*linkIndex*/, class btRigidBody* body, const btVector3& colorRgba, const btVector3& specularColor, int /*graphicsIndex*/) { m_guiHelper->createRigidBodyGraphicsObject(body, colorRgba); int graphicsInstanceId = body->getUserIndex(); @@ -211,7 +211,7 @@ void MyMultiBodyCreator::createRigidBodyGraphicsInstance2(int linkIndex, class b m_guiHelper->changeSpecularColor(graphicsInstanceId, speculard.m_floats); } -void MyMultiBodyCreator::createCollisionObjectGraphicsInstance(int linkIndex, class btCollisionObject* colObj, const btVector3& colorRgba) +void MyMultiBodyCreator::createCollisionObjectGraphicsInstance(int /*linkIndex*/, class btCollisionObject* colObj, const btVector3& colorRgba) { m_guiHelper->createCollisionObjectGraphicsObject(colObj, colorRgba); } diff --git a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp index 571cd2199e..3962ff81fd 100644 --- a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp +++ b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp @@ -80,7 +80,7 @@ struct URDF2BulletCachedData return m_urdfLinkIndices2BulletLinkIndices[urdfIndex]; } - void registerMultiBody(int urdfLinkIndex, class btMultiBody* body, const btTransform& worldTransform, btScalar mass, const btVector3& localInertiaDiagonal, const class btCollisionShape* compound, const btTransform& localInertialFrame) + void registerMultiBody(int urdfLinkIndex, class btMultiBody* /*body*/, const btTransform& /*worldTransform*/, btScalar /*mass*/, const btVector3& /*localInertiaDiagonal*/, const class btCollisionShape* /*compound*/, const btTransform& localInertialFrame) { m_urdfLinkLocalInertialFrames[urdfLinkIndex] = localInertialFrame; } @@ -90,7 +90,7 @@ struct URDF2BulletCachedData return m_urdfLink2rigidBodies[urdfLinkIndex]; } - void registerRigidBody(int urdfLinkIndex, class btRigidBody* body, const btTransform& worldTransform, btScalar mass, const btVector3& localInertiaDiagonal, const class btCollisionShape* compound, const btTransform& localInertialFrame) + void registerRigidBody(int urdfLinkIndex, class btRigidBody* body, const btTransform& /*worldTransform*/, btScalar /*mass*/, const btVector3& /*localInertiaDiagonal*/, const class btCollisionShape* /*compound*/, const btTransform& localInertialFrame) { btAssert(m_urdfLink2rigidBodies[urdfLinkIndex] == 0); @@ -745,7 +745,7 @@ btTransform ConvertURDF2BulletInternal( } else { - int mbLinkIndex = cache.getMbIndexFromUrdfIndex(urdfLinkIndex); + // int mbLinkIndex = cache.getMbIndexFromUrdfIndex(urdfLinkIndex); //u2b.convertLinkVisualShapes2(mbLinkIndex, urdfLinkIndex, pathPrefix, localInertialFrame, col, u2b.getBodyUniqueId()); u2b.convertLinkVisualShapes2(-1, urdfLinkIndex, pathPrefix, localInertialFrame, linkRigidBody, u2b.getBodyUniqueId()); } @@ -822,7 +822,7 @@ void ConvertURDF2Bullet( URDF2BulletCachedData cache; InitURDF2BulletCache(u2b, cache, flags); int urdfLinkIndex = u2b.getRootLinkIndex(); - int rootIndex = u2b.getRootLinkIndex(); + // int rootIndex = u2b.getRootLinkIndex(); B3_PROFILE("ConvertURDF2Bullet"); UrdfVisualShapeCache cachedLinkGraphicsShapesOut; diff --git a/examples/Importers/ImportURDFDemo/URDFImporterInterface.h b/examples/Importers/ImportURDFDemo/URDFImporterInterface.h index 847452cd87..f1536dbadc 100644 --- a/examples/Importers/ImportURDFDemo/URDFImporterInterface.h +++ b/examples/Importers/ImportURDFDemo/URDFImporterInterface.h @@ -14,7 +14,7 @@ class URDFImporterInterface virtual bool loadURDF(const char* fileName, bool forceFixedBase = false) = 0; - virtual bool loadSDF(const char* fileName, bool forceFixedBase = false) { return false; } + virtual bool loadSDF(const char* /*fileName*/, bool forceFixedBase = false) { (void)forceFixedBase; return false; } virtual const char* getPathPrefix() = 0; @@ -31,22 +31,22 @@ class URDFImporterInterface } /// optional method to provide the link color. return true if the color is available and copied into colorRGBA, return false otherwise - virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const { return false; } + virtual bool getLinkColor(int /*linkIndex*/, btVector4& /*colorRGBA*/) const { return false; } - virtual bool getLinkColor2(int linkIndex, struct UrdfMaterialColor& matCol) const { return false; } - virtual void setLinkColor2(int linkIndex, struct UrdfMaterialColor& matCol) const {} + virtual bool getLinkColor2(int /*linkIndex*/, struct UrdfMaterialColor& /*matCol*/) const { return false; } + virtual void setLinkColor2(int /*linkIndex*/, struct UrdfMaterialColor& /*matCol*/) const {} - virtual int getCollisionGroupAndMask(int linkIndex, int& colGroup, int& colMask) const { return 0; } + virtual int getCollisionGroupAndMask(int /*linkIndex*/, int& /*colGroup*/, int& /*colMask*/) const { return 0; } ///this API will likely change, don't override it! - virtual bool getLinkContactInfo(int linkIndex, URDFLinkContactInfo& contactInfo) const { return false; } + virtual bool getLinkContactInfo(int /*linkIndex*/, URDFLinkContactInfo& /*contactInfo*/) const { return false; } - virtual bool getLinkAudioSource(int linkIndex, SDFAudioSource& audioSource) const { return false; } + virtual bool getLinkAudioSource(int /*linkIndex*/, SDFAudioSource& /*audioSource*/) const { return false; } virtual std::string getJointName(int linkIndex) const = 0; //fill mass and inertial data. If inertial data is missing, please initialize mass, inertia to sensitive values, and inertialFrame to identity. virtual void getMassAndInertia(int urdfLinkIndex, btScalar& mass, btVector3& localInertiaDiagonal, btTransform& inertialFrame) const = 0; - virtual void getMassAndInertia2(int urdfLinkIndex, btScalar& mass, btVector3& localInertiaDiagonal, btTransform& inertialFrame, int flags) const + virtual void getMassAndInertia2(int urdfLinkIndex, btScalar& mass, btVector3& localInertiaDiagonal, btTransform& inertialFrame, int /*flags*/) const { getMassAndInertia(urdfLinkIndex, mass, localInertiaDiagonal, inertialFrame); } @@ -72,23 +72,23 @@ class URDFImporterInterface }; virtual bool getRootTransformInWorld(btTransform& rootTransformInWorld) const = 0; - virtual void setRootTransformInWorld(const btTransform& rootTransformInWorld) {} + virtual void setRootTransformInWorld(const btTransform& /*rootTransformInWorld*/) {} ///quick hack: need to rethink the API/dependencies of this - virtual int convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame) const { return -1; } + virtual int convertLinkVisualShapes(int /*linkIndex*/, const char* /*pathPrefix*/, const btTransform& /*inertialFrame*/) const { return -1; } - virtual void convertLinkVisualShapes2(int linkIndex, int urdfIndex, const char* pathPrefix, const btTransform& inertialFrame, class btCollisionObject* colObj, int objectIndex) const {} - virtual void setBodyUniqueId(int bodyId) {} + virtual void convertLinkVisualShapes2(int /*linkIndex*/, int /*urdfIndex*/, const char* /*pathPrefix*/, const btTransform& /*inertialFrame*/, class btCollisionObject* /*colObj*/, int /*objectIndex*/) const {} + virtual void setBodyUniqueId(int /*bodyId*/) {} virtual int getBodyUniqueId() const { return 0; } //default implementation for backward compatibility virtual class btCompoundShape* convertLinkCollisionShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame) const = 0; - virtual int getUrdfFromCollisionShape(const class btCollisionShape* collisionShape, struct UrdfCollision& collision) const + virtual int getUrdfFromCollisionShape(const class btCollisionShape* /*collisionShape*/, struct UrdfCollision& /*collision*/) const { return 0; } - virtual const struct UrdfLink* getUrdfLink(int urdfLinkIndex) const + virtual const struct UrdfLink* getUrdfLink(int /*urdfLinkIndex*/) const { return 0; } @@ -102,9 +102,9 @@ class URDFImporterInterface virtual int getNumAllocatedMeshInterfaces() const { return 0; } virtual int getNumAllocatedTextures() const { return 0; } - virtual int getAllocatedTexture(int index) const { return 0; } + virtual int getAllocatedTexture(int /*index*/) const { return 0; } - virtual class btStridingMeshInterface* getAllocatedMeshInterface(int index) { return 0; } + virtual class btStridingMeshInterface* getAllocatedMeshInterface(int /*index*/) { return 0; } }; #endif //URDF_IMPORTER_INTERFACE_H diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index aea391592a..60396a604d 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -1447,7 +1447,7 @@ bool UrdfParser::parseReducedDeformable(UrdfModel& model, tinyxml2::XMLElement* return true; } -bool UrdfParser::parseJointLimits(UrdfJoint& joint, XMLElement* config, ErrorLogger* logger) +bool UrdfParser::parseJointLimits(UrdfJoint& joint, XMLElement* config, ErrorLogger* /*logger*/) { joint.m_lowerLimit = 0.f; joint.m_upperLimit = -1.f; @@ -1845,7 +1845,7 @@ bool UrdfParser::parseJoint(UrdfJoint& joint, XMLElement* config, ErrorLogger* l return true; } -bool UrdfParser::parseSensor(UrdfModel& model, UrdfLink& link, UrdfJoint& joint, XMLElement* config, ErrorLogger* logger) +bool UrdfParser::parseSensor(UrdfModel& /*model*/, UrdfLink& link, UrdfJoint& joint, XMLElement* config, ErrorLogger* logger) { // Sensors are mapped to Links with a Fixed Joints connecting to the parents. // They has no extent or mass so they will work with the existing diff --git a/examples/Importers/ImportURDFDemo/UrdfRenderingInterface.h b/examples/Importers/ImportURDFDemo/UrdfRenderingInterface.h index 460d0cf908..ed9f4be860 100644 --- a/examples/Importers/ImportURDFDemo/UrdfRenderingInterface.h +++ b/examples/Importers/ImportURDFDemo/UrdfRenderingInterface.h @@ -101,11 +101,11 @@ struct UrdfRenderingInterface ///register a texture using an in-memory pixel buffer of a given width and height virtual int registerTexture(unsigned char* texels, int width, int height) = 0; - virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]) {} - virtual void setProjectiveTexture(bool useProjectiveTexture) {} + virtual void setProjectiveTextureMatrices(const float /*viewMatrix*/[16], const float /*projectionMatrix*/[16]) {} + virtual void setProjectiveTexture(bool /*useProjectiveTexture*/) {} - virtual bool getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3], float hor[3], float vert[3], float* yaw, float* pitch, float* camDist, float cameraTarget[3]) const + virtual bool getCameraInfo(int* /*width*/, int* /*height*/, float /*viewMatrix*/[16], float /*projectionMatrix*/[16], float /*camUp*/[3], float /*camForward*/[3], float /*hor*/[3], float /*vert*/[3], float* /*yaw*/, float* /*pitch*/, float* /*camDist*/, float /*cameraTarget*/[3]) const { return false; } diff --git a/examples/InverseDynamics/InverseDynamicsExample.cpp b/examples/InverseDynamics/InverseDynamicsExample.cpp index fc112c1895..d94b9e2b44 100644 --- a/examples/InverseDynamics/InverseDynamicsExample.cpp +++ b/examples/InverseDynamics/InverseDynamicsExample.cpp @@ -62,7 +62,7 @@ static btVector4 sJointCurveColors[8] = }; -void toggleUseInverseModel(int buttonId, bool buttonState, void* userPointer) +void toggleUseInverseModel(int /*buttonId*/, bool /*buttonState*/, void* /*userPointer*/) { useInverseModel = !useInverseModel; // todo(thomas) is there a way to get a toggle button with changing text? @@ -242,7 +242,7 @@ void InverseDynamicsExample::initPhysics() m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); } -void InverseDynamicsExample::stepSimulation(float deltaTime) +void InverseDynamicsExample::stepSimulation(float /*deltaTime*/) { if (m_multiBody) { diff --git a/examples/InverseKinematics/InverseKinematicsExample.cpp b/examples/InverseKinematics/InverseKinematicsExample.cpp index 41bc2a7110..26b3af4f2e 100644 --- a/examples/InverseKinematics/InverseKinematicsExample.cpp +++ b/examples/InverseKinematics/InverseKinematicsExample.cpp @@ -71,7 +71,7 @@ void Reset(Tree& tree, Jacobian* m_ikJacobian) // Update target positions -void UpdateTargets(double T, Tree& treeY) +void UpdateTargets(double T, Tree& /*treeY*/) { targetaa[0].Set(2.0f + 1.5*sin(3 * T) * 2, -0.5 + 1.0f + 0.2*sin(7 * T) * 2, 0.3f + 0.7*sin(5 * T) * 2); targetaa[1].Set(0.5f + 0.4*sin(4 * T) * 2, -0.5 + 0.9f + 0.3*sin(4 * T) * 2, -0.2f + 1.0*sin(3 * T) * 2); @@ -163,11 +163,11 @@ class InverseKinematicsExample : public CommonExampleInterface b3Vector3 extents = b3MakeVector3(100, 100, 100); extents[m_app->getUpAxis()] = 1; - int xres = 20; - int yres = 20; + // int xres = 20; + // int yres = 20; - b3Vector4 color0 = b3MakeVector4(0.4, 0.4, 0.4, 1); - b3Vector4 color1 = b3MakeVector4(0.6, 0.6, 0.6, 1); + // b3Vector4 color0 = b3MakeVector4(0.4, 0.4, 0.4, 1); + // b3Vector4 color1 = b3MakeVector4(0.6, 0.6, 0.6, 1); //m_app->registerGrid(xres, yres, color0, color1); } @@ -191,7 +191,7 @@ class InverseKinematicsExample : public CommonExampleInterface { } - virtual void physicsDebugDraw(int debugDrawMode) + virtual void physicsDebugDraw(int /*debugDrawMode*/) { } virtual void initPhysics() @@ -244,7 +244,7 @@ class InverseKinematicsExample : public CommonExampleInterface { b3Transform act; getLocalTransform(node->right, act); - b3Transform trr = tr * act; + // b3Transform trr = tr * act; b3Transform ptrr = parentTr * act; b3Vector3 lineColor = b3MakeVector3(0, 1, 0); m_app->m_renderer->drawLine(tr.getOrigin(), ptrr.getOrigin(), lineColor, lineWidth); @@ -288,15 +288,15 @@ class InverseKinematicsExample : public CommonExampleInterface virtual void physicsDebugDraw() { } - virtual bool mouseMoveCallback(float x, float y) + virtual bool mouseMoveCallback(float /*x*/, float /*y*/) { return false; } - virtual bool mouseButtonCallback(int button, int state, float x, float y) + virtual bool mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } - virtual bool keyboardCallback(int key, int state) + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } diff --git a/examples/MultiBody/InvertedPendulumPDControl.cpp b/examples/MultiBody/InvertedPendulumPDControl.cpp index 0392c241e9..49aca185a3 100644 --- a/examples/MultiBody/InvertedPendulumPDControl.cpp +++ b/examples/MultiBody/InvertedPendulumPDControl.cpp @@ -345,7 +345,7 @@ void InvertedPendulumPDControl::initPhysics() char fileName[1024]; static btAlignedObjectArray qDesiredArray; -void InvertedPendulumPDControl::stepSimulation(float deltaTime) +void InvertedPendulumPDControl::stepSimulation(float /*deltaTime*/) { static btScalar offset = -0.1 * SIMD_PI; diff --git a/examples/MultiBody/MultiBodyConstraintFeedback.cpp b/examples/MultiBody/MultiBodyConstraintFeedback.cpp index 73b4e8dfed..fc90b04cad 100644 --- a/examples/MultiBody/MultiBodyConstraintFeedback.cpp +++ b/examples/MultiBody/MultiBodyConstraintFeedback.cpp @@ -346,7 +346,7 @@ void MultiBodyConstraintFeedbackSetup::initPhysics() } } -void MultiBodyConstraintFeedbackSetup::stepSimulation(float deltaTime) +void MultiBodyConstraintFeedbackSetup::stepSimulation(float /*deltaTime*/) { //m_multiBody->addLinkForce(0,btVector3(100,100,100)); if (/* DISABLES CODE */ (0)) //m_once) diff --git a/examples/MultiBody/Pendulum.cpp b/examples/MultiBody/Pendulum.cpp index 067c5a878c..51690432d9 100644 --- a/examples/MultiBody/Pendulum.cpp +++ b/examples/MultiBody/Pendulum.cpp @@ -164,6 +164,7 @@ void Pendulum::stepSimulation(float deltaTime) m_multiBody->addJointTorque(0, 20.0); #ifdef USE_GTEST m_dynamicsWorld->stepSimulation(1. / 1000.0, 0); + (void)deltaTime; #else m_dynamicsWorld->stepSimulation(deltaTime); #endif diff --git a/examples/MultiBody/TestJointTorqueSetup.cpp b/examples/MultiBody/TestJointTorqueSetup.cpp index 3c94e20602..d8b016da5d 100644 --- a/examples/MultiBody/TestJointTorqueSetup.cpp +++ b/examples/MultiBody/TestJointTorqueSetup.cpp @@ -353,7 +353,7 @@ void TestJointTorqueSetup::initPhysics() } } -void TestJointTorqueSetup::stepSimulation(float deltaTime) +void TestJointTorqueSetup::stepSimulation(float /*deltaTime*/) { //m_multiBody->addLinkForce(0,btVector3(100,100,100)); if (/* DISABLES CODE */ (0)) //m_once) diff --git a/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp b/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp index 5347936b6a..17e35563d1 100644 --- a/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp +++ b/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp @@ -131,12 +131,12 @@ class ProfileHelper } }; -static void profileBeginCallback(btDynamicsWorld* world, btScalar timeStep) +static void profileBeginCallback(btDynamicsWorld* /*world*/, btScalar /*timeStep*/) { gProfiler.begin(Profiler::kRecordInternalTimeStep); } -static void profileEndCallback(btDynamicsWorld* world, btScalar timeStep) +static void profileEndCallback(btDynamicsWorld* /*world*/, btScalar /*timeStep*/) { gProfiler.end(Profiler::kRecordInternalTimeStep); } @@ -355,10 +355,12 @@ static int gSolverMode = SOLVER_SIMD | // SOLVER_USE_2_FRICTION_DIRECTIONS | 0; static btScalar gSliderSolverIterations = 10.0f; // should be int +#if BT_THREADSAFE static btScalar gSliderNumThreads = 1.0f; // should be int static btScalar gSliderIslandBatchingThreshold = 0.0f; // should be int static btScalar gSliderMinBatchSize = btScalar(btSequentialImpulseConstraintSolverMt::s_minBatchSize); // should be int static btScalar gSliderMaxBatchSize = btScalar(btSequentialImpulseConstraintSolverMt::s_maxBatchSize); // should be int +#endif static btScalar gSliderLeastSquaresResidualThreshold = 0.0f; //////////////////////////////////// @@ -384,7 +386,7 @@ CommonRigidBodyMTBase::~CommonRigidBodyMTBase() { } -static void boolPtrButtonCallback(int buttonId, bool buttonState, void* userPointer) +static void boolPtrButtonCallback(int /*buttonId*/, bool /*buttonState*/, void* userPointer) { if (bool* val = static_cast(userPointer)) { @@ -411,7 +413,7 @@ static void toggleSolverModeCallback(int buttonId, bool buttonState, void* userP } } -void setSolverTypeComboBoxCallback(int combobox, const char* item, void* userPointer) +void setSolverTypeComboBoxCallback(int /*combobox*/, const char* item, void* userPointer) { const char** items = static_cast(userPointer); for (int i = 0; i < SOLVER_TYPE_COUNT; ++i) @@ -424,9 +426,9 @@ void setSolverTypeComboBoxCallback(int combobox, const char* item, void* userPoi } } +#if BT_THREADSAFE static void setNumThreads(int numThreads) { -#if BT_THREADSAFE int newNumThreads = (std::min)(numThreads, int(BT_MAX_THREAD_COUNT)); int oldNumThreads = btGetTaskScheduler()->getNumThreads(); // only call when the thread count is different @@ -434,10 +436,10 @@ static void setNumThreads(int numThreads) { btGetTaskScheduler()->setNumThreads(newNumThreads); } -#endif // #if BT_THREADSAFE } +#endif // #if BT_THREADSAFE -void setTaskSchedulerComboBoxCallback(int combobox, const char* item, void* userPointer) +void setTaskSchedulerComboBoxCallback(int /*combobox*/, const char* item, void* userPointer) { #if BT_THREADSAFE const char** items = static_cast(userPointer); @@ -452,10 +454,13 @@ void setTaskSchedulerComboBoxCallback(int combobox, const char* item, void* user break; } } +#else + (void)item; + (void)userPointer; #endif // #if BT_THREADSAFE } -void setBatchingMethodComboBoxCallback(int combobox, const char* item, void* userPointer) +void setBatchingMethodComboBoxCallback(int /*combobox*/, const char* item, void* userPointer) { #if BT_THREADSAFE const char** items = static_cast(userPointer); @@ -468,18 +473,21 @@ void setBatchingMethodComboBoxCallback(int combobox, const char* item, void* use break; } } +#else + (void)item; + (void)userPointer; #endif // #if BT_THREADSAFE } -static void setThreadCountCallback(float val, void* userPtr) -{ #if BT_THREADSAFE +static void setThreadCountCallback(float /*val*/, void* /*userPtr*/) +{ setNumThreads(int(gSliderNumThreads)); gSliderNumThreads = float(btGetTaskScheduler()->getNumThreads()); -#endif // #if BT_THREADSAFE } +#endif -static void setSolverIterationCountCallback(float val, void* userPtr) +static void setSolverIterationCountCallback(float /*val*/, void* userPtr) { if (btDiscreteDynamicsWorld* world = reinterpret_cast(userPtr)) { @@ -487,26 +495,28 @@ static void setSolverIterationCountCallback(float val, void* userPtr) } } -static void setLargeIslandManifoldCountCallback(float val, void* userPtr) +#if BT_THREADSAFE +static void setLargeIslandManifoldCountCallback(float /*val*/, void* /*userPtr*/) { btSequentialImpulseConstraintSolverMt::s_minimumContactManifoldsForBatching = int(gSliderIslandBatchingThreshold); } -static void setMinBatchSizeCallback(float val, void* userPtr) +static void setMinBatchSizeCallback(float /*val*/, void* /*userPtr*/) { gSliderMaxBatchSize = (std::max)(gSliderMinBatchSize, gSliderMaxBatchSize); btSequentialImpulseConstraintSolverMt::s_minBatchSize = int(gSliderMinBatchSize); btSequentialImpulseConstraintSolverMt::s_maxBatchSize = int(gSliderMaxBatchSize); } -static void setMaxBatchSizeCallback(float val, void* userPtr) +static void setMaxBatchSizeCallback(float /*val*/, void* /*userPtr*/) { gSliderMinBatchSize = (std::min)(gSliderMinBatchSize, gSliderMaxBatchSize); btSequentialImpulseConstraintSolverMt::s_minBatchSize = int(gSliderMinBatchSize); btSequentialImpulseConstraintSolverMt::s_maxBatchSize = int(gSliderMaxBatchSize); } +#endif -static void setLeastSquaresResidualThresholdCallback(float val, void* userPtr) +static void setLeastSquaresResidualThresholdCallback(float /*val*/, void* userPtr) { if (btDiscreteDynamicsWorld* world = reinterpret_cast(userPtr)) { diff --git a/examples/MultiThreadedDemo/CommonRigidBodyMTBase.h b/examples/MultiThreadedDemo/CommonRigidBodyMTBase.h index ff96070c3e..a75ca3a32a 100644 --- a/examples/MultiThreadedDemo/CommonRigidBodyMTBase.h +++ b/examples/MultiThreadedDemo/CommonRigidBodyMTBase.h @@ -398,6 +398,7 @@ struct CommonRigidBodyMTBase : public CommonExampleInterface btRigidBody* createRigidBody(float mass, const btTransform& startTransform, btCollisionShape* shape, const btVector4& color = btVector4(1, 0, 0, 1)) { + (void)color; btAssert((!shape || shape->getShapeType() != INVALID_SHAPE_PROXYTYPE)); //rigidbody is dynamic if and only if mass is non zero, otherwise static diff --git a/examples/MultiThreadedDemo/MultiThreadedDemo.cpp b/examples/MultiThreadedDemo/MultiThreadedDemo.cpp index b435fd3bf1..e87b2176a4 100644 --- a/examples/MultiThreadedDemo/MultiThreadedDemo.cpp +++ b/examples/MultiThreadedDemo/MultiThreadedDemo.cpp @@ -34,7 +34,7 @@ static btScalar gSliderGroundTilt = 0.0f; static btScalar gSliderRollingFriction = 0.0f; static bool gSpheresNotBoxes = false; -static void boolPtrButtonCallback(int buttonId, bool buttonState, void* userPointer) +static void boolPtrButtonCallback(int /*buttonId*/, bool /*buttonState*/, void* userPointer) { if (bool* val = static_cast(userPointer)) { diff --git a/examples/MultiThreading/MultiThreadingExample.cpp b/examples/MultiThreading/MultiThreadingExample.cpp index b9701fb7e8..562c7626f5 100644 --- a/examples/MultiThreading/MultiThreadingExample.cpp +++ b/examples/MultiThreading/MultiThreadingExample.cpp @@ -164,7 +164,7 @@ class MultiThreadingExample : public CommonExampleInterface int m_numThreads; public: - MultiThreadingExample(GUIHelperInterface* guiHelper, int tutorialIndex) + MultiThreadingExample(GUIHelperInterface* guiHelper, int /*tutorialIndex*/) : m_app(guiHelper->getAppInterface()), m_threadSupport(0), m_numThreads(8) @@ -255,22 +255,22 @@ class MultiThreadingExample : public CommonExampleInterface m_jobs.clear(); } - virtual void stepSimulation(float deltaTime) + virtual void stepSimulation(float /*deltaTime*/) { } - virtual void physicsDebugDraw(int debugDrawFlags) + virtual void physicsDebugDraw(int /*debugDrawFlags*/) { } - virtual bool mouseMoveCallback(float x, float y) + virtual bool mouseMoveCallback(float /*x*/, float /*y*/) { return false; } - virtual bool mouseButtonCallback(int button, int state, float x, float y) + virtual bool mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } - virtual bool keyboardCallback(int key, int state) + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } diff --git a/examples/MultiThreading/b3PosixThreadSupport.cpp b/examples/MultiThreading/b3PosixThreadSupport.cpp index d294156362..0a66ac5ba1 100644 --- a/examples/MultiThreading/b3PosixThreadSupport.cpp +++ b/examples/MultiThreading/b3PosixThreadSupport.cpp @@ -43,10 +43,10 @@ b3PosixThreadSupport::~b3PosixThreadSupport() #define NAMED_SEMAPHORES #endif -static sem_t* createSem(const char* baseName) +static sem_t* createSem(const char* /*baseName*/) { - static int semCount = 0; #ifdef NAMED_SEMAPHORES + static int semCount = 0; /// Named semaphore begin char name[32]; snprintf(name, 32, "/%8.s-%4.d-%4.4d", baseName, getpid(), semCount++); @@ -143,7 +143,7 @@ void b3PosixThreadSupport::runTask(int uiCommand, void* uiArgument0, int taskId) } ///non-blocking test if a task is completed. First implement all versions, and then enable this API -bool b3PosixThreadSupport::isTaskCompleted(int* puiArgument0, int* puiArgument1, int timeOutInMilliseconds) +bool b3PosixThreadSupport::isTaskCompleted(int* puiArgument0, int* puiArgument1, int /*timeOutInMilliseconds*/) { b3Assert(m_activeThreadStatus.size()); @@ -154,6 +154,7 @@ bool b3PosixThreadSupport::isTaskCompleted(int* puiArgument0, int* puiArgument1, // get at least one thread which has finished int last = -1; int status = -1; + (void)status; for (int t = 0; t < int(m_activeThreadStatus.size()); ++t) { status = m_activeThreadStatus[t].m_status; diff --git a/examples/MultiThreading/b3PosixThreadSupport.h b/examples/MultiThreading/b3PosixThreadSupport.h index f20a7f8540..15c9b4d959 100644 --- a/examples/MultiThreading/b3PosixThreadSupport.h +++ b/examples/MultiThreading/b3PosixThreadSupport.h @@ -115,7 +115,7 @@ class b3PosixThreadSupport : public b3ThreadSupportInterface ///tell the task scheduler we are done with the SPU tasks virtual void stopThreads(); - virtual void setNumTasks(int numTasks) {} + virtual void setNumTasks(int /*numTasks*/) {} virtual int getNumTasks() const { diff --git a/examples/MultiThreading/b3ThreadSupportInterface.h b/examples/MultiThreading/b3ThreadSupportInterface.h index 5f61951c56..add5e3a049 100644 --- a/examples/MultiThreading/b3ThreadSupportInterface.h +++ b/examples/MultiThreading/b3ThreadSupportInterface.h @@ -78,7 +78,7 @@ class b3ThreadSupportInterface virtual void deleteCriticalSection(b3CriticalSection* criticalSection) = 0; - virtual void* getThreadLocalMemory(int taskId) { return 0; } + virtual void* getThreadLocalMemory(int /*taskId*/) { return 0; } }; #endif //B3_THREAD_SUPPORT_INTERFACE_H diff --git a/examples/OpenGLWindow/EGLOpenGLWindow.cpp b/examples/OpenGLWindow/EGLOpenGLWindow.cpp index a10f980827..8a6e29bfb7 100644 --- a/examples/OpenGLWindow/EGLOpenGLWindow.cpp +++ b/examples/OpenGLWindow/EGLOpenGLWindow.cpp @@ -327,7 +327,7 @@ void EGLOpenGLWindow::endRendering() eglSwapBuffers(m_data->egl_display, m_data->egl_surface); } -bool EGLOpenGLWindow::isModifierKeyPressed(int key) { return false; } +bool EGLOpenGLWindow::isModifierKeyPressed(int /*key*/) { return false; } void EGLOpenGLWindow::setMouseMoveCallback(b3MouseMoveCallback mouseCallback) { @@ -380,18 +380,18 @@ b3KeyboardCallback EGLOpenGLWindow::getKeyboardCallback() return m_data->m_keyboardCallback; } -void EGLOpenGLWindow::setRenderCallback(b3RenderCallback renderCallback) {} -void EGLOpenGLWindow::setWindowTitle(const char* title) {} +void EGLOpenGLWindow::setRenderCallback(b3RenderCallback /*renderCallback*/) {} +void EGLOpenGLWindow::setWindowTitle(const char* /*title*/) {} float EGLOpenGLWindow::getRetinaScale() const { return 1.f; } -void EGLOpenGLWindow::setAllowRetina(bool allow) {} +void EGLOpenGLWindow::setAllowRetina(bool /*allow*/) {} int EGLOpenGLWindow::getWidth() const { return m_data->m_windowWidth; } int EGLOpenGLWindow::getHeight() const { return m_data->m_windowHeight; } -int EGLOpenGLWindow::fileOpenDialog(char* fileName, int maxFileNameLength) +int EGLOpenGLWindow::fileOpenDialog(char* /*fileName*/, int /*maxFileNameLength*/) { return 0; } diff --git a/examples/OpenGLWindow/GLInstancingRenderer.cpp b/examples/OpenGLWindow/GLInstancingRenderer.cpp index 66bd5bf440..a9c20b3875 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.cpp +++ b/examples/OpenGLWindow/GLInstancingRenderer.cpp @@ -283,8 +283,8 @@ struct GLInstanceRendererInternalData* GLInstancingRenderer::getInternalData() static GLuint triangleShaderProgram; static GLint triangle_mvp_location = -1; -static GLint triangle_vpos_location = -1; -static GLint triangle_vUV_location = -1; +// static GLint triangle_vpos_location = -1; +// static GLint triangle_vUV_location = -1; static GLint triangle_vcol_location = -1; static GLuint triangleVertexBufferObject = 0; static GLuint triangleVertexArrayObject = 0; @@ -527,7 +527,7 @@ void GLInstancingRenderer::writeSingleInstanceFlagsToCPU(int flags, int srcIndex { b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(srcIndex2); b3Assert(pg); - int srcIndex = pg->m_internalInstanceIndex; + // int srcIndex = pg->m_internalInstanceIndex; int shapeIndex = pg->m_shapeIndex; b3GraphicsInstance* gfxObj = m_graphicsInstances[shapeIndex]; @@ -609,7 +609,7 @@ void GLInstancingRenderer::writeSingleInstanceSpecularColorToCPU(const double* s { b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(srcIndex2); b3Assert(pg); - int graphicsIndex = pg->m_internalInstanceIndex; + // int graphicsIndex = pg->m_internalInstanceIndex; int totalNumInstances = 0; @@ -635,7 +635,7 @@ void GLInstancingRenderer::writeSingleInstanceSpecularColorToCPU(const float* sp { b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(srcIndex2); b3Assert(pg); - int srcIndex = pg->m_internalInstanceIndex; + // int srcIndex = pg->m_internalInstanceIndex; int totalNumInstances = 0; @@ -1854,9 +1854,9 @@ static void b3CreateLookAt(const b3Vector3& eye, const b3Vector3& center, const } -void GLInstancingRenderer::drawTexturedTriangleMesh(float worldPosition[3], float worldOrientation[4], const float* vertices, int numvertices, const unsigned int* indices, int numIndices, float colorRGBA[4], int textureIndex, int vertexLayout) +void GLInstancingRenderer::drawTexturedTriangleMesh(float worldPosition[3], float worldOrientation[4], const float* vertices, int numvertices, const unsigned int* indices, int numIndices, float colorRGBA[4], int textureIndex, int /*vertexLayout*/) { - int sz = sizeof(GfxVertexFormat0); + // int sz = sizeof(GfxVertexFormat0); glActiveTexture(GL_TEXTURE0); activateTexture(textureIndex); @@ -1910,7 +1910,7 @@ void GLInstancingRenderer::drawTexturedTriangleMesh(float worldPosition[3], floa checkError("glVertexAttribDivisor"); glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, triangleIndexVbo); - int indexBufferSizeInBytes = numIndices * sizeof(int); + // int indexBufferSizeInBytes = numIndices * sizeof(int); glBufferData(GL_ELEMENT_ARRAY_BUFFER, numIndices * sizeof(int), NULL, GL_DYNAMIC_DRAW); glBufferSubData(GL_ELEMENT_ARRAY_BUFFER, 0, numIndices * sizeof(int), indices); diff --git a/examples/OpenGLWindow/GLPrimitiveRenderer.cpp b/examples/OpenGLWindow/GLPrimitiveRenderer.cpp index c598bd2e82..a19d24e64f 100644 --- a/examples/OpenGLWindow/GLPrimitiveRenderer.cpp +++ b/examples/OpenGLWindow/GLPrimitiveRenderer.cpp @@ -410,7 +410,7 @@ void GLPrimitiveRenderer::drawTexturedRect3D2(PrimVertex *vertices, int numVerti b3Assert(glGetError() == GL_NO_ERROR); } -void GLPrimitiveRenderer::drawTexturedRect2a(float x0, float y0, float x1, float y1, float color[4], float u0, float v0, float u1, float v1, int useRGBA) +void GLPrimitiveRenderer::drawTexturedRect2a(float x0, float y0, float x1, float y1, float color[4], float u0, float v0, float u1, float v1, int /*useRGBA*/) { PrimVertex vertexData[4] = { PrimVertex(PrimVec4(-1.f + 2.f * x0 / float(m_screenWidth), 1.f - 2.f * y0 / float(m_screenHeight), 0.f, 1.f), PrimVec4(color[0], color[1], color[2], color[3]), PrimVec2(u0, v0)), diff --git a/examples/OpenGLWindow/GLRenderToTexture.cpp b/examples/OpenGLWindow/GLRenderToTexture.cpp index aaed0eddde..55bdb5ebcb 100644 --- a/examples/OpenGLWindow/GLRenderToTexture.cpp +++ b/examples/OpenGLWindow/GLRenderToTexture.cpp @@ -24,7 +24,7 @@ GLRenderToTexture::GLRenderToTexture() #endif //!defined(_WIN32) && !defined(__APPLE__) } -void GLRenderToTexture::init(int width, int height, GLuint textureId, int renderTextureType) +void GLRenderToTexture::init(int /*width*/, int /*height*/, GLuint textureId, int renderTextureType) { m_renderTextureType = renderTextureType; diff --git a/examples/OpenGLWindow/GwenOpenGL3CoreRenderer.h b/examples/OpenGLWindow/GwenOpenGL3CoreRenderer.h index b28a45f88d..e322a2071f 100644 --- a/examples/OpenGLWindow/GwenOpenGL3CoreRenderer.h +++ b/examples/OpenGLWindow/GwenOpenGL3CoreRenderer.h @@ -198,7 +198,7 @@ class GwenOpenGL3CoreRenderer : public Gwen::Renderer::Base // m_yOffset+=rect.h+10; } - void RenderText(Gwen::Font* pFont, Gwen::Point rasterPos, const Gwen::UnicodeString& text) + void RenderText(Gwen::Font* /*pFont*/, Gwen::Point rasterPos, const Gwen::UnicodeString& text) { // BT_PROFILE("GWEN_RenderText"); @@ -328,6 +328,10 @@ class GwenOpenGL3CoreRenderer : public Gwen::Renderer::Base virtual void DrawTexturedRect(Gwen::Texture* pTexture, Gwen::Rect rect, float u1 = 0.0f, float v1 = 0.0f, float u2 = 1.0f, float v2 = 1.0f) { + (void)u1; + (void)v1; + (void)u2; + (void)v2; // BT_PROFILE("DrawTexturedRect"); Translate(rect); diff --git a/examples/OpenGLWindow/SimpleOpenGL2App.cpp b/examples/OpenGLWindow/SimpleOpenGL2App.cpp index f7d865c81c..1c43512ab7 100644 --- a/examples/OpenGLWindow/SimpleOpenGL2App.cpp +++ b/examples/OpenGLWindow/SimpleOpenGL2App.cpp @@ -49,7 +49,7 @@ static void Simple2ResizeCallback(float widthf, float heightf) gApp2->m_renderer->resize(width, height); //*gApp2->m_window->getRetinaScale(),height*gApp2->m_window->getRetinaScale()); } -static void Simple2KeyboardCallback(int key, int state) +static void Simple2KeyboardCallback(int key, int /*state*/) { if (key == B3G_ESCAPE && gApp2 && gApp2->m_window) { @@ -300,7 +300,7 @@ void SimpleOpenGL2App::swapBuffer() m_window->startRendering(); } -void SimpleOpenGL2App::drawText(const char* txt, int posXi, int posYi, float size, float colorRGBA[4]) +void SimpleOpenGL2App::drawText(const char* /*txt*/, int /*posXi*/, int /*posYi*/, float /*size*/, float /*colorRGBA*/[4]) { } @@ -310,7 +310,7 @@ static void restoreOpenGLState() glPopAttrib(); } -static void saveOpenGLState(int screenWidth, int screenHeight) +static void saveOpenGLState(int /*screenWidth*/, int /*screenHeight*/) { glPushAttrib(GL_ALL_ATTRIB_BITS); glPushClientAttrib(GL_CLIENT_ALL_ATTRIB_BITS); @@ -332,7 +332,7 @@ static void saveOpenGLState(int screenWidth, int screenHeight) glDisable(GL_TEXTURE_2D); } -void SimpleOpenGL2App::drawText3D(const char* txt, float position[3], float orientation[4], float color[4], float size, int optionFlag) +void SimpleOpenGL2App::drawText3D(const char* /*txt*/, float /*position*/[3], float /*orientation*/[4], float /*color*/[4], float /*size*/, int /*optionFlag*/) { } diff --git a/examples/OpenGLWindow/SimpleOpenGL2App.h b/examples/OpenGLWindow/SimpleOpenGL2App.h index 467ed16986..48af6b6fa1 100644 --- a/examples/OpenGLWindow/SimpleOpenGL2App.h +++ b/examples/OpenGLWindow/SimpleOpenGL2App.h @@ -19,7 +19,7 @@ class SimpleOpenGL2App : public CommonGraphicsApp virtual void swapBuffer(); virtual void drawText(const char* txt, int posX, int posY, float size, float colorRGBA[4]); - virtual void drawTexturedRect(float x0, float y0, float x1, float y1, float color[4], float u0, float v0, float u1, float v1, int useRGBA){}; + virtual void drawTexturedRect(float /*x0*/, float /*y0*/, float /*x1*/, float /*y1*/, float /*color*/[4], float /*u0*/, float /*v0*/, float /*u1*/, float /*v1*/, int /*useRGBA*/){}; virtual void setBackgroundColor(float red, float green, float blue); virtual int registerCubeShape(float halfExtentsX, float halfExtentsY, float halfExtentsZ, int textureIndex = -1, float textureScaling = 1); diff --git a/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp b/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp index 0d005f24e9..20cd94d15a 100644 --- a/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp +++ b/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp @@ -81,15 +81,15 @@ CommonCameraInterface* SimpleOpenGL2Renderer::getActiveCamera() { return &m_data->m_camera; } -void SimpleOpenGL2Renderer::setActiveCamera(CommonCameraInterface* cam) +void SimpleOpenGL2Renderer::setActiveCamera(CommonCameraInterface* /*cam*/) { b3Assert(0); //not supported yet } -void SimpleOpenGL2Renderer::setLightPosition(const float lightPos[3]) +void SimpleOpenGL2Renderer::setLightPosition(const float /*lightPos*/[3]) { } -void SimpleOpenGL2Renderer::setLightPosition(const double lightPos[3]) +void SimpleOpenGL2Renderer::setLightPosition(const double /*lightPos*/[3]) { } @@ -137,22 +137,22 @@ void SimpleOpenGL2Renderer::removeGraphicsInstance(int instanceUid) m_data->m_graphicsInstancesPool.freeHandle(instanceUid); } -bool SimpleOpenGL2Renderer::readSingleInstanceTransformToCPU(float* position, float* orientation, int srcIndex) +bool SimpleOpenGL2Renderer::readSingleInstanceTransformToCPU(float* /*position*/, float* /*orientation*/, int /*srcIndex*/) { return false; } -void SimpleOpenGL2Renderer::writeSingleInstanceColorToCPU(const float* color, int srcIndex) +void SimpleOpenGL2Renderer::writeSingleInstanceColorToCPU(const float* /*color*/, int /*srcIndex*/) { } -void SimpleOpenGL2Renderer::writeSingleInstanceColorToCPU(const double* color, int srcIndex) +void SimpleOpenGL2Renderer::writeSingleInstanceColorToCPU(const double* /*color*/, int /*srcIndex*/) { } -void SimpleOpenGL2Renderer::writeSingleInstanceScaleToCPU(const float* scale, int srcIndex) +void SimpleOpenGL2Renderer::writeSingleInstanceScaleToCPU(const float* /*scale*/, int /*srcIndex*/) { } -void SimpleOpenGL2Renderer::writeSingleInstanceScaleToCPU(const double* scale, int srcIndex) +void SimpleOpenGL2Renderer::writeSingleInstanceScaleToCPU(const double* /*scale*/, int /*srcIndex*/) { } @@ -161,11 +161,11 @@ int SimpleOpenGL2Renderer::getTotalNumInstances() const return m_data->m_graphicsInstancesPool.getNumHandles(); } -void SimpleOpenGL2Renderer::getCameraViewMatrix(float viewMat[16]) const +void SimpleOpenGL2Renderer::getCameraViewMatrix(float /*viewMat*/[16]) const { b3Assert(0); } -void SimpleOpenGL2Renderer::getCameraProjectionMatrix(float projMat[16]) const +void SimpleOpenGL2Renderer::getCameraProjectionMatrix(float /*projMat*/[16]) const { b3Assert(0); } @@ -262,7 +262,7 @@ void SimpleOpenGL2Renderer::drawOpenGL(int instanceIndex) glPopMatrix(); } -void SimpleOpenGL2Renderer::drawSceneInternal(int pass, int cameraUpAxis) +void SimpleOpenGL2Renderer::drawSceneInternal(int /*pass*/, int /*cameraUpAxis*/) { b3AlignedObjectArray usedHandles; m_data->m_graphicsInstancesPool.getUsedHandles(usedHandles); @@ -511,7 +511,7 @@ int SimpleOpenGL2Renderer::registerGraphicsInstance(int shapeIndex, const float* return newHandle; } -void SimpleOpenGL2Renderer::drawLines(const float* positions, const float color[4], int numPoints, int pointStrideInBytes, const unsigned int* indices, int numIndices, float pointDrawSize) +void SimpleOpenGL2Renderer::drawLines(const float* positions, const float color[4], int /*numPoints*/, int pointStrideInBytes, const unsigned int* indices, int numIndices, float pointDrawSize) { int pointStrideInFloats = pointStrideInBytes / 4; glLineWidth(pointDrawSize); @@ -545,7 +545,7 @@ void SimpleOpenGL2Renderer::drawLine(const float from[4], const float to[4], con glEnd(); } -int SimpleOpenGL2Renderer::registerShape(const float* vertices, int numvertices, const int* indices, int numIndices, int primitiveType, int textureIndex) +int SimpleOpenGL2Renderer::registerShape(const float* vertices, int numvertices, const int* indices, int numIndices, int /*primitiveType*/, int textureIndex) { SimpleGL2Shape* shape = new SimpleGL2Shape(); shape->m_textureIndex = textureIndex; @@ -630,13 +630,13 @@ void SimpleOpenGL2Renderer::drawLine(const double from[4], const double to[4], c glVertex3d(to[0], to[1], to[2]); glEnd(); } -void SimpleOpenGL2Renderer::drawPoint(const float* position, const float color[4], float pointDrawSize) +void SimpleOpenGL2Renderer::drawPoint(const float* /*position*/, const float /*color*/[4], float /*pointDrawSize*/) { } -void SimpleOpenGL2Renderer::drawPoint(const double* position, const double color[4], double pointDrawSize) +void SimpleOpenGL2Renderer::drawPoint(const double* /*position*/, const double /*color*/[4], double /*pointDrawSize*/) { } -void SimpleOpenGL2Renderer::drawPoints(const float* positions, const float* colors, int numPoints, int pointStrideInBytes, float pointDrawSize) +void SimpleOpenGL2Renderer::drawPoints(const float* /*positions*/, const float* /*colors*/, int /*numPoints*/, int /*pointStrideInBytes*/, float /*pointDrawSize*/) { } diff --git a/examples/OpenGLWindow/SimpleOpenGL2Renderer.h b/examples/OpenGLWindow/SimpleOpenGL2Renderer.h index f6d30ce49a..a3f708f480 100644 --- a/examples/OpenGLWindow/SimpleOpenGL2Renderer.h +++ b/examples/OpenGLWindow/SimpleOpenGL2Renderer.h @@ -26,11 +26,11 @@ class SimpleOpenGL2Renderer : public CommonRenderInterface virtual void setLightPosition(const float lightPos[3]); virtual void setLightPosition(const double lightPos[3]); - virtual void setShadowMapResolution(int shadowMapResolution) {} - virtual void setShadowMapIntensity(double shadowMapIntensity) {} - virtual void setShadowMapWorldSize(float worldSize) {} + virtual void setShadowMapResolution(int /*shadowMapResolution*/) {} + virtual void setShadowMapIntensity(double /*shadowMapIntensity*/) {} + virtual void setShadowMapWorldSize(float /*worldSize*/) {} virtual void resize(int width, int height); - virtual void setBackgroundColor(const double rgbBackground[3]) {} + virtual void setBackgroundColor(const double /*rgbBackground*/[3]) {} virtual void removeAllInstances(); virtual void removeGraphicsInstance(int instanceUid); @@ -40,13 +40,15 @@ class SimpleOpenGL2Renderer : public CommonRenderInterface virtual void writeSingleInstanceColorToCPU(const double* color, int srcIndex); virtual void writeSingleInstanceScaleToCPU(const float* scale, int srcIndex); virtual void writeSingleInstanceScaleToCPU(const double* scale, int srcIndex); - virtual void writeSingleInstanceSpecularColorToCPU(const double* specular, int srcIndex) {} - virtual void writeSingleInstanceSpecularColorToCPU(const float* specular, int srcIndex) {} - virtual void writeSingleInstanceFlagsToCPU(int flags, int srcIndex) {} + virtual void writeSingleInstanceSpecularColorToCPU(const double* /*specular*/, int /*srcIndex*/) {} + virtual void writeSingleInstanceSpecularColorToCPU(const float* /*specular*/, int /*srcIndex*/) {} + virtual void writeSingleInstanceFlagsToCPU(int /*flags*/, int /*srcIndex*/) {} virtual void getCameraViewMatrix(float viewMat[16]) const; virtual void getCameraProjectionMatrix(float projMat[16]) const; - virtual void drawTexturedTriangleMesh(float worldPosition[3], float worldOrientation[4], const float* vertices, int numvertices, const unsigned int* indices, int numIndices, float color[4], int textureIndex = -1, int vertexLayout = 0) + virtual void drawTexturedTriangleMesh(float /*worldPosition*/[3], float /*worldOrientation*/[4], const float* /*vertices*/, int /*numvertices*/, const unsigned int* /*indices*/, int /*numIndices*/, float /*color*/[4], int textureIndex = -1, int vertexLayout = 0) { + (void)textureIndex; + (void)vertexLayout; } virtual void renderScene(); diff --git a/examples/OpenGLWindow/SimpleOpenGL3App.cpp b/examples/OpenGLWindow/SimpleOpenGL3App.cpp index 83d262af0b..39a880fe05 100644 --- a/examples/OpenGLWindow/SimpleOpenGL3App.cpp +++ b/examples/OpenGLWindow/SimpleOpenGL3App.cpp @@ -103,7 +103,7 @@ static void SimpleResizeCallback(float widthf, float heightf) gApp->m_primRenderer->setScreenSize(width, height); } -static void SimpleKeyboardCallback(int key, int state) +static void SimpleKeyboardCallback(int key, int /*state*/) { if (key == B3G_ESCAPE && gApp && gApp->m_window) { @@ -264,10 +264,11 @@ struct MyRenderCallbacks : public RenderCallbacks } int shapeId = m_instancingRenderer->registerShape(&verts[0].x, numVertices, cube_indices, numIndices, B3_GL_TRIANGLES, m_textureIndex); - b3Vector3 pos = b3MakeVector3(0, 0, 0); - b3Quaternion orn(0, 0, 0, 1); - b3Vector4 color = b3MakeVector4(1, 1, 1, 1); - b3Vector3 scaling = b3MakeVector3(.1, .1, .1); + (void)shapeId; + // b3Vector3 pos = b3MakeVector3(0, 0, 0); + // b3Quaternion orn(0, 0, 0, 1); + // b3Vector4 color = b3MakeVector4(1, 1, 1, 1); + // b3Vector3 scaling = b3MakeVector3(.1, .1, .1); //m_instancingRenderer->registerGraphicsInstance(shapeId, pos, orn, color, scaling); m_instancingRenderer->writeTransforms(); } @@ -286,9 +287,9 @@ struct MyRenderCallbacks : public RenderCallbacks } virtual void render(sth_texture* texture) { - int index = 0; + // int index = 0; - float width = 1; + // float width = 1; b3AlignedObjectArray indices; indices.resize(texture->nverts); for (int i = 0; i < indices.size(); i++) @@ -493,7 +494,7 @@ void SimpleOpenGL3App::drawText3D(const char* txt, float position[3], float orie float posX = position[0]; float posY = position[1]; - float posZ = position[2]; + float posZ = position[2]; (void)posZ; float winx, winy, winz; if (optionFlag & CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera) diff --git a/examples/OpenGLWindow/TwFonts.cpp b/examples/OpenGLWindow/TwFonts.cpp index 8a981adb71..4903e0c696 100644 --- a/examples/OpenGLWindow/TwFonts.cpp +++ b/examples/OpenGLWindow/TwFonts.cpp @@ -90,7 +90,7 @@ CTexFont *TwGenerateFont(const unsigned char *_Bitmap, int _BmWidth, int _BmHeig ++hh; // find width and position of each character - int w = 0; + int w = 0; (void)w; int x0[224], y0[224], x1[224], y1[224]; int ch = 32; int start; diff --git a/examples/OpenGLWindow/Win32OpenGLWindow.cpp b/examples/OpenGLWindow/Win32OpenGLWindow.cpp index a4e2be51ec..e56f67316b 100644 --- a/examples/OpenGLWindow/Win32OpenGLWindow.cpp +++ b/examples/OpenGLWindow/Win32OpenGLWindow.cpp @@ -77,6 +77,7 @@ void Win32OpenGLWindow::createWindow(const b3gWindowConstructionInfo& ci) printf("gladLoaderLoadGL failed!\n"); exit(-1); } + m_OpenGLInitialized=true; } Win32OpenGLWindow::Win32OpenGLWindow() @@ -114,7 +115,7 @@ void Win32OpenGLWindow::endRendering() SwapBuffers(m_data->m_hDC); } -int Win32OpenGLWindow::fileOpenDialog(char* fileName, int maxFileNameLength) +int Win32OpenGLWindow::fileOpenDialog(char* fileName, int /*maxFileNameLength*/) { #if 0 //wchar_t wideChars[1024]; @@ -125,6 +126,7 @@ int Win32OpenGLWindow::fileOpenDialog(char* fileName, int maxFileNameLength) ofn.hwndOwner = NULL ; #ifdef UNICODE + (void)fileName; WCHAR bla[1024]; ofn.lpstrFile = bla; ofn.lpstrFile[0] = '\0'; @@ -147,6 +149,7 @@ int Win32OpenGLWindow::fileOpenDialog(char* fileName, int maxFileNameLength) GetOpenFileName( &ofn ); return strlen(fileName); #else + (void)fileName; return 0; #endif } diff --git a/examples/OpenGLWindow/Win32Window.cpp b/examples/OpenGLWindow/Win32Window.cpp index a25226e447..863eda477c 100644 --- a/examples/OpenGLWindow/Win32Window.cpp +++ b/examples/OpenGLWindow/Win32Window.cpp @@ -431,8 +431,8 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam) case 0x020e: //WM_MOUSEWHEEL_LEFT_RIGHT { int zDelta = (short)HIWORD(wParam); - int xPos = LOWORD(lParam); - int yPos = HIWORD(lParam); + // int xPos = LOWORD(lParam); + // int yPos = HIWORD(lParam); //m_cameraDistance -= zDelta*0.01; if (sData && sData->m_wheelCallback) (*sData->m_wheelCallback)(-float(zDelta) * 0.05f, 0); @@ -442,8 +442,8 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam) case 0x020A: //WM_MOUSEWHEEL: { int zDelta = (short)HIWORD(wParam); - int xPos = LOWORD(lParam); - int yPos = HIWORD(lParam); + // int xPos = LOWORD(lParam); + // int yPos = HIWORD(lParam); //m_cameraDistance -= zDelta*0.01; if (sData && sData->m_wheelCallback) (*sData->m_wheelCallback)(0, float(zDelta) * 0.05f); @@ -465,8 +465,8 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam) } case WM_RBUTTONUP: { - int xPos = LOWORD(lParam); - int yPos = HIWORD(lParam); + // int xPos = LOWORD(lParam); + // int yPos = HIWORD(lParam); sData->m_mouseRButton = 1; if (sData && sData->m_mouseButtonCallback) @@ -477,8 +477,8 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam) } case WM_RBUTTONDOWN: { - int xPos = LOWORD(lParam); - int yPos = HIWORD(lParam); + // int xPos = LOWORD(lParam); + // int yPos = HIWORD(lParam); sData->m_mouseRButton = 0; if (sData && sData->m_mouseButtonCallback) (*sData->m_mouseButtonCallback)(2, 1, sData->m_mouseXpos, sData->m_mouseYpos); @@ -770,7 +770,7 @@ Win32Window::~Win32Window() delete m_data; } -void Win32Window::setRenderCallback(b3RenderCallback renderCallback) +void Win32Window::setRenderCallback(b3RenderCallback /*renderCallback*/) { } @@ -815,7 +815,7 @@ float Win32Window::getTimeInSeconds() return 0.f; } -void Win32Window::setDebugMessage(int x, int y, const char* message) +void Win32Window::setDebugMessage(int /*x*/, int /*y*/, const char* /*message*/) { } diff --git a/examples/OpenGLWindow/X11OpenGLWindow.cpp b/examples/OpenGLWindow/X11OpenGLWindow.cpp index 3d7e4de65f..6a0d7f4716 100644 --- a/examples/OpenGLWindow/X11OpenGLWindow.cpp +++ b/examples/OpenGLWindow/X11OpenGLWindow.cpp @@ -407,7 +407,7 @@ static bool isExtensionSupported(const char* extList, const char* extension) } static bool ctxErrorOccurred = false; -static int ctxErrorHandler(Display* dpy, XErrorEvent* ev) +static int ctxErrorHandler(Display* /*dpy*/, XErrorEvent* /*ev*/) { ctxErrorOccurred = true; return 0; @@ -1095,7 +1095,7 @@ void X11OpenGLWindow::setRequestExit() m_requestedExit = true; } -void X11OpenGLWindow::setRenderCallback(b3RenderCallback renderCallback) +void X11OpenGLWindow::setRenderCallback(b3RenderCallback /*renderCallback*/) { } diff --git a/examples/OpenGLWindow/fontstash.cpp b/examples/OpenGLWindow/fontstash.cpp index cc8db6500a..7b1f6cde60 100644 --- a/examples/OpenGLWindow/fontstash.cpp +++ b/examples/OpenGLWindow/fontstash.cpp @@ -491,7 +491,7 @@ static int get_quad(struct sth_stash* stash, struct sth_font* fnt, struct sth_gl return 1; } -static int get_quad3D(struct sth_stash* stash, struct sth_font* fnt, struct sth_glyph* glyph, short isize2, float* x, float* y, struct sth_quad* q, float fontSize, float textScale) +static int get_quad3D(struct sth_stash* stash, struct sth_font* fnt, struct sth_glyph* glyph, short /*isize2*/, float* x, float* y, struct sth_quad* q, float fontSize, float textScale) { short isize = 1; float rx, ry; @@ -519,7 +519,7 @@ static int get_quad3D(struct sth_stash* stash, struct sth_font* fnt, struct sth_ return 1; } -static Vertex* setv(Vertex* v, float x, float y, float s, float t, float width, float height, float colorRGBA[4]) +static Vertex* setv(Vertex* v, float x, float y, float s, float t, float width, float height, float /*colorRGBA*/[4]) { bool scale = true; if (scale) @@ -741,7 +741,7 @@ void sth_draw_text(struct sth_stash* stash, void sth_draw_text3D(struct sth_stash* stash, int idx, float fontSize, float x, float y, float z, - const char* s, float* dx, float textScale, float colorRGBA[4], int unused) + const char* s, float* dx, float textScale, float colorRGBA[4], int /*unused*/) { unsigned int codepoint; struct sth_glyph* glyph = NULL; diff --git a/examples/OpenGLWindow/opengl_fontstashcallbacks.cpp b/examples/OpenGLWindow/opengl_fontstashcallbacks.cpp index 23a55f336e..3e9c6e31cd 100644 --- a/examples/OpenGLWindow/opengl_fontstashcallbacks.cpp +++ b/examples/OpenGLWindow/opengl_fontstashcallbacks.cpp @@ -12,7 +12,7 @@ #include "stb_image/stb_image_write.h" static unsigned int s_indexData[INDEX_COUNT]; -static GLuint s_indexArrayObject, s_indexBuffer; +static GLuint /*s_indexArrayObject,*/ s_indexBuffer; static GLuint s_vertexArrayObject, s_vertexBuffer; OpenGL2RenderCallbacks::OpenGL2RenderCallbacks(GLPrimitiveRenderer* primRender) diff --git a/examples/OpenGLWindow/opengl_fontstashcallbacks.h b/examples/OpenGLWindow/opengl_fontstashcallbacks.h index f09387b41c..11ea83f546 100644 --- a/examples/OpenGLWindow/opengl_fontstashcallbacks.h +++ b/examples/OpenGLWindow/opengl_fontstashcallbacks.h @@ -40,9 +40,9 @@ struct OpenGL2RenderCallbacks : public InternalOpenGL2RenderCallbacks GLPrimitiveRenderer* m_primRender2; virtual PrimInternalData* getData(); - virtual void setWorldPosition(float pos[3]) {} - virtual void setWorldOrientation(float orn[4]) {} - virtual void setColorRGBA(float color[4]) {} + virtual void setWorldPosition(float /*pos*/[3]) {} + virtual void setWorldOrientation(float /*orn*/[4]) {} + virtual void setColorRGBA(float /*color*/[4]) {} OpenGL2RenderCallbacks(GLPrimitiveRenderer* primRender); virtual ~OpenGL2RenderCallbacks(); diff --git a/examples/ReducedDeformableDemo/ConservationTest.cpp b/examples/ReducedDeformableDemo/ConservationTest.cpp index 05b7394da6..505f3d444d 100644 --- a/examples/ReducedDeformableDemo/ConservationTest.cpp +++ b/examples/ReducedDeformableDemo/ConservationTest.cpp @@ -29,7 +29,7 @@ static btScalar damping_alpha = 0.0; static btScalar damping_beta = 0.0; -static int start_mode = 6; +// static int start_mode = 6; static int num_modes = 20; class ConservationTest : public CommonDeformableBodyBase @@ -38,8 +38,9 @@ class ConservationTest : public CommonDeformableBodyBase bool first_step; // get deformed shape - void getDeformedShape(btReducedDeformableBody* rsb, const int mode_n, const btScalar scale = 1) + void getDeformedShape(btReducedDeformableBody* rsb, const int /*mode_n*/, const btScalar scale = 1) { + (void)scale; // for (int i = 0; i < rsb->m_nodes.size(); ++i) // for (int k = 0; k < 3; ++k) // rsb->m_nodes[i].m_x[k] += rsb->m_modes[mode_n][3 * i + k] * scale; @@ -75,7 +76,7 @@ class ConservationTest : public CommonDeformableBodyBase void exitPhysics(); // TODO: disable pick force, non-interactive for now. - bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { + bool pickBody(const btVector3& /*rayFromWorld*/, const btVector3& /*rayToWorld*/) { return false; } diff --git a/examples/ReducedDeformableDemo/FreeFall.cpp b/examples/ReducedDeformableDemo/FreeFall.cpp index f63db542d8..700cb5293b 100644 --- a/examples/ReducedDeformableDemo/FreeFall.cpp +++ b/examples/ReducedDeformableDemo/FreeFall.cpp @@ -31,7 +31,7 @@ // static btScalar nu = 0.3; static btScalar damping_alpha = 0.0; static btScalar damping_beta = 0.0001; -static btScalar COLLIDING_VELOCITY = 0; +// static btScalar COLLIDING_VELOCITY = 0; static int num_modes = 40; class FreeFall : public CommonDeformableBodyBase @@ -49,7 +49,7 @@ class FreeFall : public CommonDeformableBodyBase void exitPhysics(); // TODO: disable pick force, non-interactive for now. - bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { + bool pickBody(const btVector3& /*rayFromWorld*/, const btVector3& /*rayToWorld*/) { return false; } diff --git a/examples/ReducedDeformableDemo/FrictionSlope.cpp b/examples/ReducedDeformableDemo/FrictionSlope.cpp index 20eac36e87..cceb464d34 100644 --- a/examples/ReducedDeformableDemo/FrictionSlope.cpp +++ b/examples/ReducedDeformableDemo/FrictionSlope.cpp @@ -31,7 +31,7 @@ // static btScalar nu = 0.3; static btScalar damping_alpha = 0.0; static btScalar damping_beta = 0.001; -static btScalar COLLIDING_VELOCITY = 0; +// static btScalar COLLIDING_VELOCITY = 0; static int num_modes = 20; class FrictionSlope : public CommonDeformableBodyBase @@ -48,7 +48,7 @@ class FrictionSlope : public CommonDeformableBodyBase void exitPhysics(); // TODO: disable pick force, non-interactive for now. - bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { + bool pickBody(const btVector3& /*rayFromWorld*/, const btVector3& /*rayToWorld*/) { return false; } @@ -87,6 +87,7 @@ class FrictionSlope : public CommonDeformableBodyBase btScalar mass(1e6); btRigidBody* ground = createRigidBody(mass, groundTransform, groundShape, btVector4(0,0,0,0)); // ground->setFriction(1); + (void)ground; } void stepSimulation(float deltaTime) diff --git a/examples/ReducedDeformableDemo/ModeVisualizer.cpp b/examples/ReducedDeformableDemo/ModeVisualizer.cpp index becf6bcee0..4481acd0f7 100644 --- a/examples/ReducedDeformableDemo/ModeVisualizer.cpp +++ b/examples/ReducedDeformableDemo/ModeVisualizer.cpp @@ -70,7 +70,7 @@ class ModeVisualizer : public CommonDeformableBodyBase void exitPhysics(); // disable pick force. non-interactive example. - bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { + bool pickBody(const btVector3& /*rayFromWorld*/, const btVector3& /*rayToWorld*/) { return false; } diff --git a/examples/ReducedDeformableDemo/ReducedBenchmark.cpp b/examples/ReducedDeformableDemo/ReducedBenchmark.cpp index 05ddc03623..c0670b0f41 100644 --- a/examples/ReducedDeformableDemo/ReducedBenchmark.cpp +++ b/examples/ReducedDeformableDemo/ReducedBenchmark.cpp @@ -28,7 +28,7 @@ static btScalar damping_alpha = 0.0; static btScalar damping_beta = 0.0001; -static btScalar COLLIDING_VELOCITY = 0; +// static btScalar COLLIDING_VELOCITY = 0; static int num_modes = 20; static bool run_reduced = true; @@ -48,7 +48,7 @@ class ReducedBenchmark : public CommonDeformableBodyBase void exitPhysics(); // TODO: disable pick force, non-interactive for now. - bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { + bool pickBody(const btVector3& /*rayFromWorld*/, const btVector3& /*rayToWorld*/) { return false; } diff --git a/examples/ReducedDeformableDemo/ReducedCollide.cpp b/examples/ReducedDeformableDemo/ReducedCollide.cpp index dd84946ae6..3db1fda4e9 100644 --- a/examples/ReducedDeformableDemo/ReducedCollide.cpp +++ b/examples/ReducedDeformableDemo/ReducedCollide.cpp @@ -52,7 +52,7 @@ class ReducedCollide : public CommonDeformableBodyBase void addColliders_testMultiDof(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents); // TODO: disable pick force, non-interactive for now. - bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { + bool pickBody(const btVector3& /*rayFromWorld*/, const btVector3& /*rayToWorld*/) { return false; } diff --git a/examples/ReducedDeformableDemo/ReducedGrasp.cpp b/examples/ReducedDeformableDemo/ReducedGrasp.cpp index c40e0c5544..99be45c17b 100644 --- a/examples/ReducedDeformableDemo/ReducedGrasp.cpp +++ b/examples/ReducedDeformableDemo/ReducedGrasp.cpp @@ -71,7 +71,7 @@ class ReducedGrasp : public CommonDeformableBodyBase void createGrip() { - int count = 2; + // int count = 2; float mass = 1e6; btCollisionShape* shape = new btBoxShape(btVector3(1, 1, 0.25)); { diff --git a/examples/ReducedDeformableDemo/ReducedMotorGrasp.cpp b/examples/ReducedDeformableDemo/ReducedMotorGrasp.cpp index 5dda30f97b..1b4a14c8f6 100644 --- a/examples/ReducedDeformableDemo/ReducedMotorGrasp.cpp +++ b/examples/ReducedDeformableDemo/ReducedMotorGrasp.cpp @@ -194,11 +194,11 @@ class ReducedMotorGrasp : public CommonDeformableBodyBase } } - virtual bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) + virtual bool pickBody(const btVector3& /*rayFromWorld*/, const btVector3& /*rayToWorld*/) { return false; } - virtual bool movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) + virtual bool movePickedBody(const btVector3& /*rayFromWorld*/, const btVector3& /*rayToWorld*/) { return false; } diff --git a/examples/ReducedDeformableDemo/Springboard.cpp b/examples/ReducedDeformableDemo/Springboard.cpp index 58641365eb..283e53d771 100644 --- a/examples/ReducedDeformableDemo/Springboard.cpp +++ b/examples/ReducedDeformableDemo/Springboard.cpp @@ -50,7 +50,7 @@ class Springboard : public CommonDeformableBodyBase void exitPhysics(); // TODO: disable pick force, non-interactive for now. - bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { + bool pickBody(const btVector3& /*rayFromWorld*/, const btVector3& /*rayToWorld*/) { return false; } @@ -81,7 +81,7 @@ class Springboard : public CommonDeformableBodyBase { sim_time += internalTimeStep; - btReducedDeformableBody* rsb = static_cast(getDeformableDynamicsWorld()->getSoftBodyArray()[0]); + // btReducedDeformableBody* rsb = static_cast(getDeformableDynamicsWorld()->getSoftBodyArray()[0]); // std::ofstream myfile("fixed_node.txt", std::ios_base::app); // myfile << sim_time << "\t" << rsb->m_nodes[0].m_x[0] - rsb->m_x0[0][0] << "\t" diff --git a/examples/RenderingExamples/CoordinateSystemDemo.cpp b/examples/RenderingExamples/CoordinateSystemDemo.cpp index e5b28ebc38..47905ff2e1 100644 --- a/examples/RenderingExamples/CoordinateSystemDemo.cpp +++ b/examples/RenderingExamples/CoordinateSystemDemo.cpp @@ -44,7 +44,7 @@ class CoordinateSystemDemo : public CommonExampleInterface virtual void exitPhysics() { } - virtual void stepSimulation(float deltaTime) + virtual void stepSimulation(float /*deltaTime*/) { m_x += 0.01f; m_y += 0.01f; @@ -85,7 +85,7 @@ class CoordinateSystemDemo : public CommonExampleInterface } } - virtual void physicsDebugDraw(int debugDrawFlags) + virtual void physicsDebugDraw(int /*debugDrawFlags*/) { btVector3 xUnit(1, 0, 0); btVector3 yUnit(0, 1, 0); @@ -119,15 +119,15 @@ class CoordinateSystemDemo : public CommonExampleInterface drawArc(yUnit, yUnit, toY.normalized(), radius, radius, 0.4, SIMD_2_PI, yUnit, false); drawArc(zUnit, zUnit, toZ.normalized(), radius, radius, 0.4, SIMD_2_PI, zUnit, false); } - virtual bool mouseMoveCallback(float x, float y) + virtual bool mouseMoveCallback(float /*x*/, float /*y*/) { return false; } - virtual bool mouseButtonCallback(int button, int state, float x, float y) + virtual bool mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } - virtual bool keyboardCallback(int key, int state) + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } diff --git a/examples/RenderingExamples/DynamicTexturedCubeDemo.cpp b/examples/RenderingExamples/DynamicTexturedCubeDemo.cpp index 58653e958b..b73ab2771a 100644 --- a/examples/RenderingExamples/DynamicTexturedCubeDemo.cpp +++ b/examples/RenderingExamples/DynamicTexturedCubeDemo.cpp @@ -66,7 +66,7 @@ class DynamicTexturedCubeDemo : public CommonExampleInterface delete m_tinyVrGUI; } - virtual void physicsDebugDraw(int debugDrawMode) + virtual void physicsDebugDraw(int /*debugDrawMode*/) { } virtual void initPhysics() @@ -95,15 +95,15 @@ class DynamicTexturedCubeDemo : public CommonExampleInterface virtual void physicsDebugDraw() { } - virtual bool mouseMoveCallback(float x, float y) + virtual bool mouseMoveCallback(float /*x*/, float /*y*/) { return false; } - virtual bool mouseButtonCallback(int button, int state, float x, float y) + virtual bool mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } - virtual bool keyboardCallback(int key, int state) + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } diff --git a/examples/RenderingExamples/RaytracerSetup.cpp b/examples/RenderingExamples/RaytracerSetup.cpp index 2804424254..73fa2bbd3a 100644 --- a/examples/RenderingExamples/RaytracerSetup.cpp +++ b/examples/RenderingExamples/RaytracerSetup.cpp @@ -153,19 +153,19 @@ void RaytracerPhysicsSetup::initPhysics() } ///worldRaytest performs a ray versus all objects in a collision world, returning true is a hit is found (filling in worldNormal and worldHitPoint) -bool RaytracerPhysicsSetup::worldRaytest(const btVector3& rayFrom, const btVector3& rayTo, btVector3& worldNormal, btVector3& worldHitPoint) +bool RaytracerPhysicsSetup::worldRaytest(const btVector3& /*rayFrom*/, const btVector3& /*rayTo*/, btVector3& /*worldNormal*/, btVector3& /*worldHitPoint*/) { return false; } ///singleObjectRaytest performs a ray versus one collision shape, returning true is a hit is found (filling in worldNormal and worldHitPoint) -bool RaytracerPhysicsSetup::singleObjectRaytest(const btVector3& rayFrom, const btVector3& rayTo, btVector3& worldNormal, btVector3& worldHitPoint) +bool RaytracerPhysicsSetup::singleObjectRaytest(const btVector3& /*rayFrom*/, const btVector3& /*rayTo*/, btVector3& /*worldNormal*/, btVector3& /*worldHitPoint*/) { return false; } ///lowlevelRaytest performs a ray versus convex shape, returning true is a hit is found (filling in worldNormal and worldHitPoint) -bool RaytracerPhysicsSetup::lowlevelRaytest(const btVector3& rayFrom, const btVector3& rayTo, btVector3& worldNormal, btVector3& worldHitPoint) +bool RaytracerPhysicsSetup::lowlevelRaytest(const btVector3& rayFrom, const btVector3& rayTo, btVector3& worldNormal, btVector3& /*worldHitPoint*/) { btScalar closestHitResults = 1.f; @@ -226,7 +226,7 @@ void RaytracerPhysicsSetup::exitPhysics() } } -void RaytracerPhysicsSetup::stepSimulation(float deltaTime) +void RaytracerPhysicsSetup::stepSimulation(float /*deltaTime*/) { m_internalData->updateTransforms(); @@ -332,26 +332,26 @@ void RaytracerPhysicsSetup::stepSimulation(float deltaTime) m_internalData->m_canvas->refreshImageData(m_internalData->m_canvasIndex); } -void RaytracerPhysicsSetup::physicsDebugDraw(int debugDrawFlags) +void RaytracerPhysicsSetup::physicsDebugDraw(int /*debugDrawFlags*/) { } -bool RaytracerPhysicsSetup::mouseMoveCallback(float x, float y) +bool RaytracerPhysicsSetup::mouseMoveCallback(float /*x*/, float /*y*/) { return false; } -bool RaytracerPhysicsSetup::mouseButtonCallback(int button, int state, float x, float y) +bool RaytracerPhysicsSetup::mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } -bool RaytracerPhysicsSetup::keyboardCallback(int key, int state) +bool RaytracerPhysicsSetup::keyboardCallback(int /*key*/, int /*state*/) { return false; } -void RaytracerPhysicsSetup::syncPhysicsToGraphics(GraphicsPhysicsBridge& gfxBridge) +void RaytracerPhysicsSetup::syncPhysicsToGraphics(GraphicsPhysicsBridge& /*gfxBridge*/) { } diff --git a/examples/RenderingExamples/RenderInstancingDemo.cpp b/examples/RenderingExamples/RenderInstancingDemo.cpp index 70c0f86bcf..7075d6e253 100644 --- a/examples/RenderingExamples/RenderInstancingDemo.cpp +++ b/examples/RenderingExamples/RenderInstancingDemo.cpp @@ -67,7 +67,7 @@ class RenderInstancingDemo : public CommonExampleInterface { } - virtual void physicsDebugDraw(int debugDrawMode) + virtual void physicsDebugDraw(int /*debugDrawMode*/) { } virtual void initPhysics() @@ -76,7 +76,7 @@ class RenderInstancingDemo : public CommonExampleInterface virtual void exitPhysics() { } - virtual void stepSimulation(float deltaTime) + virtual void stepSimulation(float /*deltaTime*/) { m_x += 0.01f; m_y += 0.01f; @@ -102,15 +102,15 @@ class RenderInstancingDemo : public CommonExampleInterface virtual void physicsDebugDraw() { } - virtual bool mouseMoveCallback(float x, float y) + virtual bool mouseMoveCallback(float /*x*/, float /*y*/) { return false; } - virtual bool mouseButtonCallback(int button, int state, float x, float y) + virtual bool mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } - virtual bool keyboardCallback(int key, int state) + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } diff --git a/examples/RenderingExamples/TimeSeriesCanvas.cpp b/examples/RenderingExamples/TimeSeriesCanvas.cpp index a321f5ec62..f8eed11567 100644 --- a/examples/RenderingExamples/TimeSeriesCanvas.cpp +++ b/examples/RenderingExamples/TimeSeriesCanvas.cpp @@ -102,7 +102,7 @@ void TimeSeriesCanvas::addDataSource(const char* dataSourceLabel, unsigned char m_internalData->m_dataSources.push_back(dataSource); } -void TimeSeriesCanvas::setupTimeSeries(float yScale, int ticksPerSecond, int startTime, bool clearCanvas) +void TimeSeriesCanvas::setupTimeSeries(float yScale, int ticksPerSecond, int /*startTime*/, bool clearCanvas) { if (0 == m_internalData->m_canvasInterface) return; diff --git a/examples/RenderingExamples/TimeSeriesExample.cpp b/examples/RenderingExamples/TimeSeriesExample.cpp index 56f2a170f2..c2e2d2bd9e 100644 --- a/examples/RenderingExamples/TimeSeriesExample.cpp +++ b/examples/RenderingExamples/TimeSeriesExample.cpp @@ -96,26 +96,26 @@ void TimeSeriesExample::stepSimulation(float deltaTime) m_internalData->m_timeSeriesCanvas->nextTick(); } -void TimeSeriesExample::physicsDebugDraw(int debugDrawFlags) +void TimeSeriesExample::physicsDebugDraw(int /*debugDrawFlags*/) { } -bool TimeSeriesExample::mouseMoveCallback(float x, float y) +bool TimeSeriesExample::mouseMoveCallback(float /*x*/, float /*y*/) { return false; } -bool TimeSeriesExample::mouseButtonCallback(int button, int state, float x, float y) +bool TimeSeriesExample::mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } -bool TimeSeriesExample::keyboardCallback(int key, int state) +bool TimeSeriesExample::keyboardCallback(int /*key*/, int /*state*/) { return false; } -void TimeSeriesExample::syncPhysicsToGraphics(GraphicsPhysicsBridge& gfxBridge) +void TimeSeriesExample::syncPhysicsToGraphics(GraphicsPhysicsBridge& /*gfxBridge*/) { } diff --git a/examples/RenderingExamples/TinyRendererSetup.cpp b/examples/RenderingExamples/TinyRendererSetup.cpp index 2c81995ee9..9390570749 100644 --- a/examples/RenderingExamples/TinyRendererSetup.cpp +++ b/examples/RenderingExamples/TinyRendererSetup.cpp @@ -212,7 +212,7 @@ TinyRendererSetup::~TinyRendererSetup() } const char* itemsanimate[] = {"Fixed", "Rotate"}; -void TinyRendererComboCallbackAnimate(int combobox, const char* item, void* userPointer) +void TinyRendererComboCallbackAnimate(int /*combobox*/, const char* item, void* userPointer) { TinyRendererSetup* cl = (TinyRendererSetup*)userPointer; b3Assert(cl); @@ -230,7 +230,7 @@ void TinyRendererComboCallbackAnimate(int combobox, const char* item, void* user const char* items[] = {"Software", "OpenGL"}; -void TinyRendererComboCallback(int combobox, const char* item, void* userPointer) +void TinyRendererComboCallback(int /*combobox*/, const char* item, void* userPointer) { TinyRendererSetup* cl = (TinyRendererSetup*)userPointer; b3Assert(cl); @@ -303,7 +303,7 @@ void TinyRendererSetup::exitPhysics() { } -void TinyRendererSetup::stepSimulation(float deltaTime) +void TinyRendererSetup::stepSimulation(float /*deltaTime*/) { m_internalData->updateTransforms(); } @@ -425,26 +425,26 @@ void TinyRendererSetup::renderScene() } } -void TinyRendererSetup::physicsDebugDraw(int debugDrawFlags) +void TinyRendererSetup::physicsDebugDraw(int /*debugDrawFlags*/) { } -bool TinyRendererSetup::mouseMoveCallback(float x, float y) +bool TinyRendererSetup::mouseMoveCallback(float /*x*/, float /*y*/) { return false; } -bool TinyRendererSetup::mouseButtonCallback(int button, int state, float x, float y) +bool TinyRendererSetup::mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } -bool TinyRendererSetup::keyboardCallback(int key, int state) +bool TinyRendererSetup::keyboardCallback(int /*key*/, int /*state*/) { return false; } -void TinyRendererSetup::syncPhysicsToGraphics(GraphicsPhysicsBridge& gfxBridge) +void TinyRendererSetup::syncPhysicsToGraphics(GraphicsPhysicsBridge& /*gfxBridge*/) { } diff --git a/examples/RenderingExamples/TinyVRGui.cpp b/examples/RenderingExamples/TinyVRGui.cpp index 8d01702252..c082e883a3 100644 --- a/examples/RenderingExamples/TinyVRGui.cpp +++ b/examples/RenderingExamples/TinyVRGui.cpp @@ -28,14 +28,14 @@ struct TestCanvasInterface2 : public Common2dCanvasInterface virtual ~TestCanvasInterface2() { } - virtual int createCanvas(const char* canvasName, int width, int height, int posX, int posY) + virtual int createCanvas(const char* /*canvasName*/, int /*width*/, int /*height*/, int /*posX*/, int /*posY*/) { return 0; } - virtual void destroyCanvas(int canvasId) + virtual void destroyCanvas(int /*canvasId*/) { } - virtual void setPixel(int canvasId, int x, int y, unsigned char red, unsigned char green, unsigned char blue, unsigned char alpha) + virtual void setPixel(int /*canvasId*/, int x, int y, unsigned char red, unsigned char green, unsigned char blue, unsigned char /*alpha*/) { if (x >= 0 && x < m_width && y >= 0 && y < m_height) { @@ -44,7 +44,7 @@ struct TestCanvasInterface2 : public Common2dCanvasInterface m_texelsRGB[(x + y * m_width) * 3 + 2] = blue; } } - virtual void getPixel(int canvasId, int x, int y, unsigned char& red, unsigned char& green, unsigned char& blue, unsigned char& alpha) + virtual void getPixel(int /*canvasId*/, int x, int y, unsigned char& red, unsigned char& green, unsigned char& blue, unsigned char& /*alpha*/) { if (x >= 0 && x < m_width && y >= 0 && y < m_height) { @@ -54,7 +54,7 @@ struct TestCanvasInterface2 : public Common2dCanvasInterface } } - virtual void refreshImageData(int canvasId) + virtual void refreshImageData(int /*canvasId*/) { } }; @@ -81,7 +81,7 @@ struct TinyVRGuiInternalData } }; -TinyVRGui::TinyVRGui(struct ComboBoxParams& params, struct CommonRenderInterface* renderer) +TinyVRGui::TinyVRGui(struct ComboBoxParams& /*params*/, struct CommonRenderInterface* renderer) { m_data = new TinyVRGuiInternalData; m_data->m_renderer = renderer; diff --git a/examples/RigidBody/KinematicRigidBodyExample.cpp b/examples/RigidBody/KinematicRigidBodyExample.cpp index 973814e300..2cc4f5135b 100644 --- a/examples/RigidBody/KinematicRigidBodyExample.cpp +++ b/examples/RigidBody/KinematicRigidBodyExample.cpp @@ -99,7 +99,7 @@ void KinematicRigidBodyExample::initPhysics() { btScalar mass(0.); //rigidbody is dynamic if and only if mass is non zero, otherwise static - bool isDynamic = (mass != 0.f); + // bool isDynamic = (mass != 0.f); btVector3 localInertia(0, 0, 0); diff --git a/examples/RigidBody/RigidBodySoftContact.cpp b/examples/RigidBody/RigidBodySoftContact.cpp index 807fb6c006..b8a0e20399 100644 --- a/examples/RigidBody/RigidBodySoftContact.cpp +++ b/examples/RigidBody/RigidBodySoftContact.cpp @@ -142,6 +142,7 @@ void RigidBodySoftContact::initPhysics() btRigidBody* body; body = createRigidBody(mass, startTransform, colShape); //body->setAngularVelocity(btVector3(1,1,1)); + (void)body; } } } diff --git a/examples/RobotSimulator/HelloBulletRobotics.cpp b/examples/RobotSimulator/HelloBulletRobotics.cpp index ec656be601..73659cffae 100644 --- a/examples/RobotSimulator/HelloBulletRobotics.cpp +++ b/examples/RobotSimulator/HelloBulletRobotics.cpp @@ -1,7 +1,7 @@ #include "b3RobotSimulatorClientAPI_NoGUI.h" -int main(int argc, char* argv[]) +int main(int /*argc*/, char* /*argv*/[]) { b3RobotSimulatorClientAPI_NoGUI* sim = new b3RobotSimulatorClientAPI_NoGUI(); diff --git a/examples/RobotSimulator/RobotSimulatorMain.cpp b/examples/RobotSimulator/RobotSimulatorMain.cpp index 49e0cfd2a9..afb46d914f 100644 --- a/examples/RobotSimulator/RobotSimulatorMain.cpp +++ b/examples/RobotSimulator/RobotSimulatorMain.cpp @@ -13,7 +13,7 @@ #define ASSERT_EQ(a, b) assert((a) == (b)); #include "MinitaurSetup.h" -int main(int argc, char* argv[]) +int main(int /*argc*/, char* /*argv*/[]) { #ifdef B3_USE_ROBOTSIM_GUI b3RobotSimulatorClientAPI* sim = new b3RobotSimulatorClientAPI(); @@ -64,9 +64,9 @@ int main(int argc, char* argv[]) //} b3Clock clock; +#if 0 double startTime = clock.getTimeInSeconds(); double simWallClockSeconds = 20.; -#if 0 while (clock.getTimeInSeconds()-startTime < simWallClockSeconds) { sim->stepSimulation(); diff --git a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp index 724a4cef70..ac86b1f45c 100644 --- a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp +++ b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp @@ -149,6 +149,7 @@ bool b3RobotSimulatorClientAPI::connect(int mode, const std::string& hostName, i sm = b3ConnectPhysicsUDP(hostName.c_str(), udpPort); #else + (void)udpPort; b3Warning("UDP is not enabled in this build"); #endif //BT_ENABLE_ENET @@ -164,6 +165,8 @@ bool b3RobotSimulatorClientAPI::connect(int mode, const std::string& hostName, i sm = b3ConnectPhysicsTCP(hostName.c_str(), tcpPort); #else + (void)hostName; + (void)tcpPort; b3Warning("TCP is not enabled in this pybullet build"); #endif //BT_ENABLE_CLSOCKET break; diff --git a/examples/RoboticsLearning/GripperGraspExample.cpp b/examples/RoboticsLearning/GripperGraspExample.cpp index 569c41cb0c..fa2b13a287 100644 --- a/examples/RoboticsLearning/GripperGraspExample.cpp +++ b/examples/RoboticsLearning/GripperGraspExample.cpp @@ -598,6 +598,7 @@ class GripperGraspExample : public CommonExampleInterface if (numJoints == 7) { double q_current[7] = {0, 0, 0, 0, 0, 0, 0}; + (void)q_current; b3JointStates2 jointStates; @@ -715,7 +716,7 @@ class GripperGraspExample : public CommonExampleInterface { return m_robotSim.mouseButtonCallback(button, state, x, y); } - virtual bool keyboardCallback(int key, int state) + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } diff --git a/examples/RoboticsLearning/KukaGraspExample.cpp b/examples/RoboticsLearning/KukaGraspExample.cpp index 831be36598..c4259f30b3 100644 --- a/examples/RoboticsLearning/KukaGraspExample.cpp +++ b/examples/RoboticsLearning/KukaGraspExample.cpp @@ -130,6 +130,7 @@ class KukaGraspExample : public CommonExampleInterface if (numJoints == 7) { double q_current[7] = {0, 0, 0, 0, 0, 0, 0}; + (void)q_current; b3JointStates2 jointStates; @@ -252,15 +253,15 @@ class KukaGraspExample : public CommonExampleInterface { m_robotSim.debugDraw(debugDrawMode); } - virtual bool mouseMoveCallback(float x, float y) + virtual bool mouseMoveCallback(float /*x*/, float /*y*/) { return false; } - virtual bool mouseButtonCallback(int button, int state, float x, float y) + virtual bool mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } - virtual bool keyboardCallback(int key, int state) + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } diff --git a/examples/RoboticsLearning/R2D2GraspExample.cpp b/examples/RoboticsLearning/R2D2GraspExample.cpp index f665d50810..a0d2844f08 100644 --- a/examples/RoboticsLearning/R2D2GraspExample.cpp +++ b/examples/RoboticsLearning/R2D2GraspExample.cpp @@ -43,7 +43,7 @@ class R2D2GraspExample : public CommonExampleInterface { } - virtual void physicsDebugDraw(int debugDrawMode) + virtual void physicsDebugDraw(int /*debugDrawMode*/) { } virtual void initPhysics() @@ -152,7 +152,7 @@ class R2D2GraspExample : public CommonExampleInterface { m_robotSim.disconnect(); } - virtual void stepSimulation(float deltaTime) + virtual void stepSimulation(float /*deltaTime*/) { m_robotSim.stepSimulation(); } @@ -166,15 +166,15 @@ class R2D2GraspExample : public CommonExampleInterface virtual void physicsDebugDraw() { } - virtual bool mouseMoveCallback(float x, float y) + virtual bool mouseMoveCallback(float /*x*/, float /*y*/) { return false; } - virtual bool mouseButtonCallback(int button, int state, float x, float y) + virtual bool mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } - virtual bool keyboardCallback(int key, int state) + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } diff --git a/examples/SharedMemory/GraphicsClientExample.cpp b/examples/SharedMemory/GraphicsClientExample.cpp index 7db7825592..f004185c95 100644 --- a/examples/SharedMemory/GraphicsClientExample.cpp +++ b/examples/SharedMemory/GraphicsClientExample.cpp @@ -204,22 +204,22 @@ class GraphicsClientExample : public CommonExampleInterface virtual void exitPhysics(){}; - virtual void physicsDebugDraw(int debugFlags) + virtual void physicsDebugDraw(int /*debugFlags*/) { } virtual void renderScene() { } - virtual bool mouseMoveCallback(float x, float y) + virtual bool mouseMoveCallback(float /*x*/, float /*y*/) { return false; } - virtual bool mouseButtonCallback(int button, int state, float x, float y) + virtual bool mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } - virtual bool keyboardCallback(int key, int state) + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } @@ -229,7 +229,7 @@ class GraphicsClientExample : public CommonExampleInterface -GraphicsClientExample::GraphicsClientExample(GUIHelperInterface* helper, int options) +GraphicsClientExample::GraphicsClientExample(GUIHelperInterface* helper, int /*options*/) : m_guiHelper(helper), m_waitingForServer(false), m_testBlock1(0) @@ -262,7 +262,7 @@ void GraphicsClientExample::initPhysics() } -void GraphicsClientExample::stepSimulation(float deltaTime) +void GraphicsClientExample::stepSimulation(float /*deltaTime*/) { GraphicsSharedMemoryCommand* cmd = getAvailableSharedMemoryCommand(); if (cmd) diff --git a/examples/SharedMemory/GraphicsServerExample.cpp b/examples/SharedMemory/GraphicsServerExample.cpp index 2b32480a6c..0ce0832787 100644 --- a/examples/SharedMemory/GraphicsServerExample.cpp +++ b/examples/SharedMemory/GraphicsServerExample.cpp @@ -143,7 +143,7 @@ enum TCPCommunicationEnums eTCPHasTerminated }; -void TCPThreadFunc(void* userPtr, void* lsMemory) +void TCPThreadFunc(void* userPtr, void* /*lsMemory*/) { printf("TCPThreadFunc thread started\n"); @@ -161,17 +161,17 @@ void TCPThreadFunc(void* userPtr, void* lsMemory) args->m_cs->setSharedParam(0, eTCPIsInitialized); args->m_cs->unlock(); - double deltaTimeInSeconds = 0; - int numCmdSinceSleep1ms = 0; - unsigned long long int prevTime = clock.getTimeMicroseconds(); + // double deltaTimeInSeconds = 0; + // int numCmdSinceSleep1ms = 0; + // unsigned long long int prevTime = clock.getTimeMicroseconds(); #ifdef BT_ENABLE_CLSOCKET b3Clock clock; - double timeOutInSeconds = 10; + // double timeOutInSeconds = 10; bool isPhysicsClientConnected = true; - bool exitRequested = false; + // bool exitRequested = false; if (!isPhysicsClientConnected) @@ -310,7 +310,7 @@ void TCPThreadFunc(void* userPtr, void* lsMemory) args->m_cmdPtr = 0; - int type = *(int*)&bytesReceived[0]; + // int type = *(int*)&bytesReceived[0]; if (numBytesRec == sizeof(GraphicsSharedMemoryCommand)) @@ -330,13 +330,13 @@ void TCPThreadFunc(void* userPtr, void* lsMemory) { case GFX_CMD_0: { - int axis = args->m_cmdPtr->m_upAxisYCommand.m_enableUpAxisY ? 1 : 2; + // int axis = args->m_cmdPtr->m_upAxisYCommand.m_enableUpAxisY ? 1 : 2; args->submitCommand(); while (args->isCommandOutstanding()) { clock.usleep(0); } - bool done = false; + // bool done = false; //guiHelper.setUpAxis(axis); @@ -547,8 +547,8 @@ void TCPThreadFunc(void* userPtr, void* lsMemory) } - double startTimeSeconds = clock.getTimeInSeconds(); - double curTimeSeconds = clock.getTimeInSeconds(); + // double startTimeSeconds = clock.getTimeInSeconds(); + // double curTimeSeconds = clock.getTimeInSeconds(); if (gVerboseNetworkMessagesServer) { @@ -724,7 +724,7 @@ class GraphicsServerExample : public CommonExampleInterface { } - void submitServerStatus(GraphicsSharedMemoryStatus& status, int blockIndex) + void submitServerStatus(GraphicsSharedMemoryStatus& /*status*/, int /*blockIndex*/) { } @@ -893,7 +893,7 @@ class GraphicsServerExample : public CommonExampleInterface void processClientCommands() { - int timeStamp = 0; + // int timeStamp = 0; bool hasStatus = false; if (m_args.isCommandOutstanding()) { @@ -907,7 +907,7 @@ class GraphicsServerExample : public CommonExampleInterface } } - virtual void stepSimulation(float deltaTime) + virtual void stepSimulation(float /*deltaTime*/) { B3_PROFILE("stepSimulation"); processClientCommands(); @@ -934,20 +934,20 @@ class GraphicsServerExample : public CommonExampleInterface - virtual void physicsDebugDraw(int debugDrawFlags) + virtual void physicsDebugDraw(int /*debugDrawFlags*/) { } - virtual bool mouseMoveCallback(float x, float y) + virtual bool mouseMoveCallback(float /*x*/, float /*y*/) { return false; } - virtual bool mouseButtonCallback(int button, int state, float x, float y) + virtual bool mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } - virtual bool keyboardCallback(int key, int state) + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } diff --git a/examples/SharedMemory/IKTrajectoryHelper.cpp b/examples/SharedMemory/IKTrajectoryHelper.cpp index fb002cc3aa..e74c6a51b6 100644 --- a/examples/SharedMemory/IKTrajectoryHelper.cpp +++ b/examples/SharedMemory/IKTrajectoryHelper.cpp @@ -41,8 +41,8 @@ bool IKTrajectoryHelper::computeIK(const double endEffectorTargetPosition[3], const double endEffectorTargetOrientation[4], const double endEffectorWorldPosition[3], const double endEffectorWorldOrientation[4], - const double* q_current, int numQ, int endEffectorIndex, - double* q_new, int ikMethod, const double* linear_jacobian, const double* angular_jacobian, int jacobian_size, const double dampIk[6]) + const double* q_current, int numQ, int /*endEffectorIndex*/, + double* q_new, int ikMethod, const double* linear_jacobian, const double* angular_jacobian, int /*jacobian_size*/, const double dampIk[6]) { MatrixRmn AugMat; bool useAngularPart = (ikMethod == IK2_VEL_DLS_WITH_ORIENTATION || ikMethod == IK2_VEL_DLS_WITH_ORIENTATION_NULLSPACE || ikMethod == IK2_VEL_SDLS_WITH_ORIENTATION) ? true : false; diff --git a/examples/SharedMemory/InProcessMemory.cpp b/examples/SharedMemory/InProcessMemory.cpp index dd995f9594..9c09c7d587 100644 --- a/examples/SharedMemory/InProcessMemory.cpp +++ b/examples/SharedMemory/InProcessMemory.cpp @@ -26,7 +26,7 @@ InProcessMemory::~InProcessMemory() delete m_data; } -void* InProcessMemory::allocateSharedMemory(int key, int size, bool allowCreation) +void* InProcessMemory::allocateSharedMemory(int key, int size, bool /*allowCreation*/) { void** ptrptr = m_data->m_memoryPointers[key]; if (ptrptr) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 71bdd5c544..e4642969ed 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -398,7 +398,7 @@ B3_SHARED_API int b3LoadSoftBodyAddMassSpringForce(b3SharedMemoryCommandHandle c return 0; } -B3_SHARED_API int b3LoadSoftBodyAddGravityForce(b3SharedMemoryCommandHandle commandHandle, double gravityX, double gravityY, double gravityZ) +B3_SHARED_API int b3LoadSoftBodyAddGravityForce(b3SharedMemoryCommandHandle commandHandle, double /*gravityX*/, double /*gravityY*/, double /*gravityZ*/) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; b3Assert(command->m_type == CMD_LOAD_SOFT_BODY); @@ -738,7 +738,7 @@ B3_SHARED_API int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryComman return 0; } -B3_SHARED_API int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle commandHandle, int maxNumCmdPer1ms) +B3_SHARED_API int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle /*commandHandle*/, int /*maxNumCmdPer1ms*/) { //obsolete command return 0; @@ -1400,7 +1400,7 @@ B3_SHARED_API int b3GetJointStateMultiDof(b3PhysicsClientHandle physClient, b3Sh } -B3_SHARED_API int b3GetLinkState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int linkIndex, b3LinkState* state) +B3_SHARED_API int b3GetLinkState(b3PhysicsClientHandle /*physClient*/, b3SharedMemoryStatusHandle statusHandle, int linkIndex, b3LinkState* state) { const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle; b3Assert(status); @@ -2620,7 +2620,7 @@ B3_SHARED_API int b3CreatePoseCommandSetJointVelocityMultiDof(b3PhysicsClientHan } -B3_SHARED_API int b3CreatePoseCommandSetJointVelocities(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int numJointVelocities, const double* jointVelocities) +B3_SHARED_API int b3CreatePoseCommandSetJointVelocities(b3PhysicsClientHandle /*physClient*/, b3SharedMemoryCommandHandle commandHandle, int numJointVelocities, const double* jointVelocities) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; b3Assert(command); @@ -4641,7 +4641,7 @@ B3_SHARED_API void b3ComputePositionFromViewMatrix(const float viewMatrix[16], f b3Transform tinv = t.inverse(); b3Matrix3x3 basis = tinv.getBasis(); b3Vector3 origin = tinv.getOrigin(); - b3Vector3 s = b3MakeVector3(basis[0][0], basis[1][0], basis[2][0]); + // b3Vector3 s = b3MakeVector3(basis[0][0], basis[1][0], basis[2][0]); b3Vector3 u = b3MakeVector3(basis[0][1], basis[1][1], basis[2][1]); b3Vector3 f = b3MakeVector3(-basis[0][2], -basis[1][2], -basis[2][2]); b3Vector3 eye = origin; diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index 491ac7a742..405a30562a 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -78,7 +78,7 @@ class PhysicsClientExample : public SharedMemoryCommon virtual ~PhysicsClientExample(); virtual void initPhysics(); - void selectComboBox(int comboIndex, const char* name) + void selectComboBox(int /*comboIndex*/, const char* name) { if (m_guiHelper && m_guiHelper->getParameterInterface()) { @@ -174,6 +174,7 @@ class PhysicsClientExample : public SharedMemoryCommon int uIndex = m_motorTargetPositions[i].m_uIndex; static int serial = 0; serial++; + (void)serial; // b3Printf("# motors = %d, cmd[%d] qIndex = %d, uIndex = %d, targetPos = %f", m_numMotors, serial, qIndex,uIndex,targetPos); b3JointControlSetDesiredPosition(commandHandle, qIndex, targetPos); @@ -191,9 +192,9 @@ class PhysicsClientExample : public SharedMemoryCommon m_physicsServer.physicsDebugDraw(debugFlags); } } - virtual bool mouseMoveCallback(float x, float y) { return false; }; - virtual bool mouseButtonCallback(int button, int state, float x, float y) { return false; } - virtual bool keyboardCallback(int key, int state) { return false; } + virtual bool mouseMoveCallback(float /*x*/, float /*y*/) { return false; }; + virtual bool mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } virtual void setSharedMemoryKey(int key) { @@ -501,7 +502,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) int objectUniqueId = 0; int linkIndex = -1; int shapeIndex = -1; - int textureIndex = -2; + // int textureIndex = -2; double rgbaColor[4] = {0.0, 1.0, 0.0, 1.0}; b3SharedMemoryCommandHandle commandHandle = b3InitUpdateVisualShape2(m_physicsClientHandle, objectUniqueId, linkIndex, shapeIndex); b3UpdateVisualShapeRGBAColor(commandHandle, rgbaColor); @@ -787,7 +788,7 @@ void PhysicsClientExample::initPhysics() } } -void PhysicsClientExample::stepSimulation(float deltaTime) +void PhysicsClientExample::stepSimulation(float /*deltaTime*/) { if (m_options == eCLIENTEXAMPLE_SERVER) { diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.cpp b/examples/SharedMemory/PhysicsClientSharedMemory.cpp index 1d8d966a79..23a7bafaec 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsClientSharedMemory.cpp @@ -459,7 +459,7 @@ void PhysicsClientSharedMemory::processBodyJointInfo(int bodyUniqueId, const Sha } template -void addJointInfoFromConstraint(int linkIndex, const T* con, U* bodyJoints, bool verboseOutput) +void addJointInfoFromConstraint(int linkIndex, const T* con, U* bodyJoints, bool /*verboseOutput*/) { b3JointInfo info; info.m_jointName[0] = 0; diff --git a/examples/SharedMemory/PhysicsClientTCP.cpp b/examples/SharedMemory/PhysicsClientTCP.cpp index 3a8f3fdd18..416a962280 100644 --- a/examples/SharedMemory/PhysicsClientTCP.cpp +++ b/examples/SharedMemory/PhysicsClientTCP.cpp @@ -152,7 +152,7 @@ TcpNetworkedPhysicsProcessor::~TcpNetworkedPhysicsProcessor() delete m_data; } -bool TcpNetworkedPhysicsProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool TcpNetworkedPhysicsProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& /*serverStatusOut*/, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { if (gVerboseNetworkMessagesClient2) { @@ -219,15 +219,15 @@ bool TcpNetworkedPhysicsProcessor::receiveStatus(struct SharedMemoryStatus& serv return hasStatus; } -void TcpNetworkedPhysicsProcessor::renderScene(int renderFlags) +void TcpNetworkedPhysicsProcessor::renderScene(int /*renderFlags*/) { } -void TcpNetworkedPhysicsProcessor::physicsDebugDraw(int debugDrawFlags) +void TcpNetworkedPhysicsProcessor::physicsDebugDraw(int /*debugDrawFlags*/) { } -void TcpNetworkedPhysicsProcessor::setGuiHelper(struct GUIHelperInterface* guiHelper) +void TcpNetworkedPhysicsProcessor::setGuiHelper(struct GUIHelperInterface* /*guiHelper*/) { } diff --git a/examples/SharedMemory/PhysicsClientUDP.cpp b/examples/SharedMemory/PhysicsClientUDP.cpp index 57a6b01221..7a67f5a7bc 100644 --- a/examples/SharedMemory/PhysicsClientUDP.cpp +++ b/examples/SharedMemory/PhysicsClientUDP.cpp @@ -301,7 +301,7 @@ enum UDPCommandEnums }; -void UDPThreadFunc(void* userPtr, void* lsMemory) +void UDPThreadFunc(void* userPtr, void* /*lsMemory*/) { printf("UDPThreadFunc thread started\n"); // UDPThreadLocalStorage* localStorage = (UDPThreadLocalStorage*)lsMemory; @@ -324,6 +324,7 @@ void UDPThreadFunc(void* userPtr, void* lsMemory) b3Clock::usleep(0); deltaTimeInSeconds += double(clock.getTimeMicroseconds()) / 1000000.; + (void)deltaTimeInSeconds; { clock.reset(); @@ -371,6 +372,7 @@ void UDPThreadFunc(void* userPtr, void* lsMemory) } int res; res = enet_peer_send(args->m_peer, 0, packet); + (void)res; args->m_cs->lock(); args->m_hasCommand = false; args->m_cs->unlock(); @@ -435,7 +437,7 @@ UdpNetworkedPhysicsProcessor::~UdpNetworkedPhysicsProcessor() delete m_data; } -bool UdpNetworkedPhysicsProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool UdpNetworkedPhysicsProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& /*serverStatusOut*/, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { if (gVerboseNetworkMessagesClient) { @@ -513,15 +515,15 @@ bool UdpNetworkedPhysicsProcessor::receiveStatus(struct SharedMemoryStatus& serv return hasStatus; } -void UdpNetworkedPhysicsProcessor::renderScene(int renderFlags) +void UdpNetworkedPhysicsProcessor::renderScene(int /*renderFlags*/) { } -void UdpNetworkedPhysicsProcessor::physicsDebugDraw(int debugDrawFlags) +void UdpNetworkedPhysicsProcessor::physicsDebugDraw(int /*debugDrawFlags*/) { } -void UdpNetworkedPhysicsProcessor::setGuiHelper(struct GUIHelperInterface* guiHelper) +void UdpNetworkedPhysicsProcessor::setGuiHelper(struct GUIHelperInterface* /*guiHelper*/) { } diff --git a/examples/SharedMemory/PhysicsDirect.cpp b/examples/SharedMemory/PhysicsDirect.cpp index f12057ae0b..4f6b40ff82 100644 --- a/examples/SharedMemory/PhysicsDirect.cpp +++ b/examples/SharedMemory/PhysicsDirect.cpp @@ -109,8 +109,8 @@ struct PhysicsDirectInternalData PhysicsDirect::PhysicsDirect(PhysicsCommandProcessorInterface* physSdk, bool passSdkOwnership) { - int sz = sizeof(SharedMemoryCommand); - int sz2 = sizeof(SharedMemoryStatus); + // int sz = sizeof(SharedMemoryCommand); + // int sz2 = sizeof(SharedMemoryStatus); m_data = new PhysicsDirectInternalData; m_data->m_commandProcessor = physSdk; @@ -638,6 +638,7 @@ bool PhysicsDirect::processMeshData(const struct SharedMemoryCommand& orgCommand const b3SendMeshDataArgs& args = serverCmd.m_sendMeshDataArgs; int numTotalPixels = args.m_startingVertex + args.m_numVerticesCopied + args.m_numVerticesRemaining; + (void)numTotalPixels; btVector3* verticesReceived = (btVector3*)&m_data->m_bulletStreamDataServerToClient[0]; @@ -1603,7 +1604,7 @@ bool PhysicsDirect::getJointInfo(int bodyIndex, int jointIndex, struct b3JointIn return false; } -void PhysicsDirect::setSharedMemoryKey(int key) +void PhysicsDirect::setSharedMemoryKey(int /*key*/) { } diff --git a/examples/SharedMemory/PhysicsDirectC_API.cpp b/examples/SharedMemory/PhysicsDirectC_API.cpp index 215a78cad1..bc4c602408 100644 --- a/examples/SharedMemory/PhysicsDirectC_API.cpp +++ b/examples/SharedMemory/PhysicsDirectC_API.cpp @@ -12,6 +12,7 @@ B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysicsDirect() PhysicsDirect* direct = new PhysicsDirect(sdk, true); bool connected; connected = direct->connect(); + (void)connected; return (b3PhysicsClientHandle)direct; } diff --git a/examples/SharedMemory/PhysicsLoopBackC_API.cpp b/examples/SharedMemory/PhysicsLoopBackC_API.cpp index ff053c80e3..6171de22b5 100644 --- a/examples/SharedMemory/PhysicsLoopBackC_API.cpp +++ b/examples/SharedMemory/PhysicsLoopBackC_API.cpp @@ -9,5 +9,6 @@ b3PhysicsClientHandle b3ConnectPhysicsLoopback(int key) loopBack->setSharedMemoryKey(key); bool connected; connected = loopBack->connect(); + (void)connected; return (b3PhysicsClientHandle)loopBack; } diff --git a/examples/SharedMemory/PhysicsServer.h b/examples/SharedMemory/PhysicsServer.h index 2a940abd62..1d5d31fcc6 100644 --- a/examples/SharedMemory/PhysicsServer.h +++ b/examples/SharedMemory/PhysicsServer.h @@ -20,18 +20,18 @@ class PhysicsServer //@todo(erwincoumans) Should we have shared memory commands for picking objects? ///The pickBody method will try to pick the first body along a ray, return true if succeeds, false otherwise - virtual bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { return false; } - virtual bool movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) { return false; } + virtual bool pickBody(const btVector3& /*rayFromWorld*/, const btVector3& /*rayToWorld*/) { return false; } + virtual bool movePickedBody(const btVector3& /*rayFromWorld*/, const btVector3& /*rayToWorld*/) { return false; } virtual void removePickingConstraint() {} //for physicsDebugDraw and renderScene are mainly for debugging purposes //and for physics visualization. The idea is that physicsDebugDraw can also send wireframe //to a physics client, over shared memory - virtual void physicsDebugDraw(int debugDrawFlags) {} - virtual void renderScene(int renderFlags) {} + virtual void physicsDebugDraw(int /*debugDrawFlags*/) {} + virtual void renderScene(int /*renderFlags*/) {} - virtual void enableCommandLogging(bool enable, const char* fileName) {} - virtual void replayFromLogFile(const char* fileName) {} + virtual void enableCommandLogging(bool /*enable*/, const char* /*fileName*/) {} + virtual void replayFromLogFile(const char* /*fileName*/) {} }; #endif //PHYSICS_SERVER_H diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index b8fc344337..7b5068b5b3 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -113,7 +113,6 @@ #include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" #include "BulletSoftBody/btDeformableBodySolver.h" #include "BulletSoftBody/btDeformableMultiBodyConstraintSolver.h" -#include "../SoftDemo/BunnyMesh.h" #endif //SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD #ifndef SKIP_DEFORMABLE_BODY @@ -157,7 +156,7 @@ class b3ThreadPool delete m_threadSupportInterface; } - const int numWorkers() const { return m_threadSupportInterface->getNumWorkerThreads(); } + int numWorkers() const { return m_threadSupportInterface->getNumWorkerThreads(); } void runTask(int threadIdx, btThreadSupportInterface::ThreadFunc func, void* arg) { @@ -200,15 +199,15 @@ struct SharedMemoryDebugDrawer : public btIDebugDraw : m_debugMode(0) { } - virtual void drawContactPoint(const btVector3& PointOnB, const btVector3& normalOnB, btScalar distance, int lifeTime, const btVector3& color) + virtual void drawContactPoint(const btVector3& /*PointOnB*/, const btVector3& /*normalOnB*/, btScalar /*distance*/, int /*lifeTime*/, const btVector3& /*color*/) { } - virtual void reportErrorWarning(const char* warningString) + virtual void reportErrorWarning(const char* /*warningString*/) { } - virtual void draw3dText(const btVector3& location, const char* textString) + virtual void draw3dText(const btVector3& /*location*/, const char* /*textString*/) { } @@ -559,6 +558,7 @@ struct CommandLogPlayback { size_t bytesRead; bytesRead = fread(m_header, 12, 1, m_file); + (void)bytesRead; } unsigned char c = m_header[7]; m_fileIs64bit = (c == '-'); @@ -887,7 +887,7 @@ struct VideoMP4Loggger : public InternalStateLogger { m_guiHelper->dumpFramesToVideo(0); } - virtual void logState(btScalar timeStep) + virtual void logState(btScalar /*timeStep*/) { //dumping video frames happens in another thread //we could add some overlay of timestamp here, if needed/wanted @@ -2096,33 +2096,33 @@ void logCallback(btDynamicsWorld* world, btScalar timeStep) proc->tickPlugins(timeStep, false); } -bool MyContactAddedCallback(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap, int partId0, int index0, const btCollisionObjectWrapper* colObj1Wrap, int partId1, int index1) +bool MyContactAddedCallback(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap, int /*partId0*/, int /*index0*/, const btCollisionObjectWrapper* colObj1Wrap, int partId1, int index1) { btAdjustInternalEdgeContacts(cp, colObj1Wrap, colObj0Wrap, partId1, index1); return true; } -bool MyContactDestroyedCallback(void* userPersistentData) +bool MyContactDestroyedCallback(void* /*userPersistentData*/) { //printf("destroyed\n"); return false; } -bool MyContactProcessedCallback(btManifoldPoint& cp, void* body0, void* body1) +bool MyContactProcessedCallback(btManifoldPoint& /*cp*/, void* /*body0*/, void* /*body1*/) { //printf("processed\n"); return false; } -void MyContactStartedCallback(btPersistentManifold* const& manifold) +void MyContactStartedCallback(btPersistentManifold* const& /*manifold*/) { //printf("started\n"); } -void MyContactEndedCallback(btPersistentManifold* const& manifold) +void MyContactEndedCallback(btPersistentManifold* const& /*manifold*/) { // printf("ended\n"); } -void PhysicsServerCommandProcessor::processCollisionForces(btScalar timeStep) +void PhysicsServerCommandProcessor::processCollisionForces(btScalar /*timeStep*/) { #ifdef B3_ENABLE_TINY_AUDIO //this is experimental at the moment: impulse thresholds, sound parameters will be exposed in C-API/pybullet. @@ -2246,8 +2246,9 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface { } - virtual bool loadURDF(const char* fileName, bool forceFixedBase = false) + virtual bool loadURDF(const char* /*fileName*/, bool forceFixedBase = false) { + (void)forceFixedBase; b3Assert(0); return false; } @@ -2281,7 +2282,7 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface } /// optional method to provide the link color. return true if the color is available and copied into colorRGBA, return false otherwise - virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const + virtual bool getLinkColor(int /*linkIndex*/, btVector4& /*colorRGBA*/) const { b3Assert(0); return false; @@ -2326,17 +2327,17 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface return false; } - virtual int getCollisionGroupAndMask(int linkIndex, int& colGroup, int& colMask) const + virtual int getCollisionGroupAndMask(int /*linkIndex*/, int& /*colGroup*/, int& /*colMask*/) const { return 0; } ///this API will likely change, don't override it! - virtual bool getLinkContactInfo(int linkIndex, URDFLinkContactInfo& contactInfo) const + virtual bool getLinkContactInfo(int /*linkIndex*/, URDFLinkContactInfo& /*contactInfo*/) const { return false; } - virtual bool getLinkAudioSource(int linkIndex, SDFAudioSource& audioSource) const + virtual bool getLinkAudioSource(int /*linkIndex*/, SDFAudioSource& /*audioSource*/) const { b3Assert(0); return false; @@ -2391,7 +2392,7 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface } } - virtual bool getJointInfo(int urdfLinkIndex, btTransform& parent2joint, btTransform& linkTransformInWorld, btVector3& jointAxisInJointSpace, int& jointType, btScalar& jointLowerLimit, btScalar& jointUpperLimit, btScalar& jointDamping, btScalar& jointFriction) const + virtual bool getJointInfo(int /*urdfLinkIndex*/, btTransform& /*parent2joint*/, btTransform& /*linkTransformInWorld*/, btVector3& /*jointAxisInJointSpace*/, int& /*jointType*/, btScalar& /*jointLowerLimit*/, btScalar& /*jointUpperLimit*/, btScalar& /*jointDamping*/, btScalar& /*jointFriction*/) const { return false; }; @@ -2482,7 +2483,7 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface m_createBodyArgs.m_linkOrientations[baseLinkIndex * 4 + 3])); return true; } - virtual void setRootTransformInWorld(const btTransform& rootTransformInWorld) + virtual void setRootTransformInWorld(const btTransform& /*rootTransformInWorld*/) { b3Assert(0); } @@ -2632,7 +2633,7 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface } //default implementation for backward compatibility - virtual class btCompoundShape* convertLinkCollisionShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame) const + virtual class btCompoundShape* convertLinkCollisionShapes(int linkIndex, const char* /*pathPrefix*/, const btTransform& localInertiaFrame) const { btCompoundShape* compound = new btCompoundShape(); @@ -3195,7 +3196,7 @@ void PhysicsServerCommandProcessor::addUserData(const btHashMapm_rigidBody) { - btRigidBody* rb = bodyHandle->m_rigidBody; + // btRigidBody* rb = bodyHandle->m_rigidBody; btDefaultSerializer ser(bufferSizeInBytes, (unsigned char*)bufferServerToClient); ser.startSerialization(); @@ -3771,6 +3772,7 @@ int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char* ser.registerNameForPointer(&con->getRigidBodyB(), bodyHandle->m_rigidBodyLinkNames[i].c_str()); const btRigidBody& bodyA = con->getRigidBodyA(); + (void)bodyA; int len = con->calculateSerializeBufferSize(); btChunk* chunk = ser.allocate(len, 1); @@ -3797,7 +3799,7 @@ int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char* return streamSizeInBytes; } -bool PhysicsServerCommandProcessor::processStateLoggingCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processStateLoggingCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { BT_PROFILE("CMD_STATE_LOGGING"); @@ -4364,7 +4366,7 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc return hasStatus; } -bool PhysicsServerCommandProcessor::processSaveWorldCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processSaveWorldCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = false; BT_PROFILE("CMD_SAVE_WORLD"); @@ -4623,7 +4625,7 @@ bool PhysicsServerCommandProcessor::processSaveWorldCommand(const struct SharedM #define MYLINELENGTH 16 * 32768 -static unsigned char* MyGetRawHeightfieldData(CommonFileIOInterface& fileIO, PHY_ScalarType type, const char* fileName, int& width, int& height, +static unsigned char* MyGetRawHeightfieldData(CommonFileIOInterface& fileIO, PHY_ScalarType /*type*/, const char* fileName, int& width, int& height, btScalar& minHeight, btScalar& maxHeight) { @@ -4639,6 +4641,7 @@ static unsigned char* MyGetRawHeightfieldData(CommonFileIOInterface& fileIO, PHY { char relativeFileName[1024]; int found = fileIO.findResourcePath(fileName, relativeFileName, 1024); + (void)found; b3AlignedObjectArray buffer; buffer.reserve(1024); @@ -4717,6 +4720,7 @@ static unsigned char* MyGetRawHeightfieldData(CommonFileIOInterface& fileIO, PHY { char relativePath[1024]; int found = fileIO.findResourcePath(fileName, relativePath, 1024); + (void)found; btAlignedObjectArray lineBuffer; lineBuffer.resize(MYLINELENGTH); int slot = fileIO.fileOpen(relativePath, "r"); @@ -4823,7 +4827,7 @@ class MyTriangleCollector4 : public btTriangleCallback m_pIndicesOut = 0; } - virtual void processTriangle(btVector3* tris, int partId, int triangleIndex) + virtual void processTriangle(btVector3* tris, int /*partId*/, int /*triangleIndex*/) { for (int k = 0; k < 3; k++) { @@ -4838,7 +4842,7 @@ class MyTriangleCollector4 : public btTriangleCallback v.normal[l] = normal[l]; } - btVector3 extents = m_aabbMax - m_aabbMin; + // btVector3 extents = m_aabbMax - m_aabbMin; v.uv[0] = (1. - ((v.xyzw[0] - m_aabbMin[0]) / (m_aabbMax[0] - m_aabbMin[0]))) * m_textureScaling; v.uv[1] = (1. - (v.xyzw[1] - m_aabbMin[1]) / (m_aabbMax[1] - m_aabbMin[1])) * m_textureScaling; @@ -4848,7 +4852,7 @@ class MyTriangleCollector4 : public btTriangleCallback } } }; -bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int /*bufferSizeInBytes*/) { bool hasStatus = true; serverStatusOut.m_type = CMD_CREATE_COLLISION_SHAPE_FAILED; @@ -5014,7 +5018,7 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str btAlignedObjectArray gfxVertices; btAlignedObjectArray indices; - int strideInBytes = 9 * sizeof(float); + // int strideInBytes = 9 * sizeof(float); btVector3 aabbMin, aabbMax; btTransform tr; @@ -5067,7 +5071,7 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str } else { - btScalar gridSpacing = 0.5; + // btScalar gridSpacing = 0.5; btScalar gridHeightScale = 1. / 256.; bool flipQuadEdges = false; @@ -5109,7 +5113,7 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str btAlignedObjectArray gfxVertices; btAlignedObjectArray indices; - int strideInBytes = 9 * sizeof(float); + // int strideInBytes = 9 * sizeof(float); btTransform tr; tr.setIdentity(); @@ -5172,7 +5176,7 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str clientCmd.m_createUserShapeArgs.m_shapes[i].m_meshScale[1], clientCmd.m_createUserShapeArgs.m_shapes[i].m_meshScale[2]); - const std::string& urdf_path = ""; + // const std::string& urdf_path = ""; std::string fileName = clientCmd.m_createUserShapeArgs.m_shapes[i].m_meshFileName; urdfColObj.m_geometry.m_type = URDF_GEOM_MESH; @@ -5193,7 +5197,7 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str if (clientCmd.m_createUserShapeArgs.m_shapes[i].m_numVertices) { int numVertices = clientCmd.m_createUserShapeArgs.m_shapes[i].m_numVertices; - int numIndices = clientCmd.m_createUserShapeArgs.m_shapes[i].m_numIndices; + // int numIndices = clientCmd.m_createUserShapeArgs.m_shapes[i].m_numIndices; //int totalUploadSizeInBytes = numVertices * sizeof(double) * 3 + numIndices * sizeof(int); @@ -5280,7 +5284,6 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str if (clientCmd.m_createUserShapeArgs.m_shapes[i].m_collisionFlags & GEOM_FORCE_CONCAVE_TRIMESH) { - CommonFileIOInterface* fileIO = m_data->m_pluginManager.getFileIOInterface(); if (out_type == UrdfGeometry::FILE_STL) { CommonFileIOInterface* fileIO(m_data->m_pluginManager.getFileIOInterface()); @@ -5547,17 +5550,17 @@ static void gatherVertices(const btTransform& trans, const btCollisionShape* col } } -bool PhysicsServerCommandProcessor::processResetMeshDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processResetMeshDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int /*bufferSizeInBytes*/) { bool hasStatus = true; BT_PROFILE("CMD_REQUEST_MESH_DATA"); serverStatusOut.m_type = CMD_RESET_MESH_DATA_FAILED; - int sizeInBytes = 0; + // int sizeInBytes = 0; InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(clientCmd.m_requestMeshDataArgs.m_bodyUniqueId); if (bodyHandle) { - int totalBytesPerVertex = sizeof(btVector3); + // int totalBytesPerVertex = sizeof(btVector3); double* vertexUpload = (double*)bufferServerToClient; #ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD @@ -5590,6 +5593,8 @@ bool PhysicsServerCommandProcessor::processResetMeshDataCommand(const struct Sha serverStatusOut.m_type = CMD_RESET_MESH_DATA_COMPLETED; } } +#else + (void)vertexUpload; #endif //SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD } serverStatusOut.m_numDataStreamBytes = 0; @@ -5734,8 +5739,8 @@ bool PhysicsServerCommandProcessor::processRequestTetraMeshDataCommand(const str { int totalBytesPerVertex = sizeof(btVector3); btVector3* verticesOut = (btVector3*)bufferServerToClient; - const btCollisionShape* colShape = 0; +#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD if (bodyHandle->m_softBody) { btSoftBody* psb = bodyHandle->m_softBody; @@ -5759,6 +5764,11 @@ bool PhysicsServerCommandProcessor::processRequestTetraMeshDataCommand(const str serverStatusOut.m_sendMeshDataArgs.m_startingVertex = clientCmd.m_requestMeshDataArgs.m_startingVertex; serverStatusOut.m_sendMeshDataArgs.m_numVerticesRemaining = numVerticesRemaining - verticesCopied; } +#else + (void)totalBytesPerVertex; + (void)verticesOut; + (void)bufferSizeInBytes; +#endif } serverStatusOut.m_numDataStreamBytes = sizeInBytes; @@ -5766,7 +5776,7 @@ bool PhysicsServerCommandProcessor::processRequestTetraMeshDataCommand(const str return hasStatus; } -bool PhysicsServerCommandProcessor::processCreateVisualShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processCreateVisualShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int /*bufferSizeInBytes*/) { bool hasStatus = true; serverStatusOut.m_type = CMD_CREATE_VISUAL_SHAPE_FAILED; @@ -5778,7 +5788,6 @@ bool PhysicsServerCommandProcessor::processCreateVisualShapeCommand(const struct btTransform localInertiaFrame; localInertiaFrame.setIdentity(); - const char* pathPrefix = ""; int visualShapeUniqueId = -1; UrdfVisual visualShape; @@ -6044,7 +6053,7 @@ bool PhysicsServerCommandProcessor::processCustomCommand(const struct SharedMemo return hasStatus; } -bool PhysicsServerCommandProcessor::processUserDebugDrawCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processUserDebugDrawCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -6059,8 +6068,6 @@ bool PhysicsServerCommandProcessor::processUserDebugDrawCommand(const struct Sha InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(clientCmd.m_userDebugDrawArgs.m_parentObjectUniqueId); if (bodyHandle) { - int linkIndex = -1; - if (bodyHandle->m_multiBody) { int linkIndex = clientCmd.m_userDebugDrawArgs.m_parentLinkIndex; @@ -6275,7 +6282,7 @@ bool PhysicsServerCommandProcessor::processUserDebugDrawCommand(const struct Sha return hasStatus; } -bool PhysicsServerCommandProcessor::processSetVRCameraStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processSetVRCameraStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; BT_PROFILE("CMD_SET_VR_CAMERA_STATE"); @@ -6308,7 +6315,7 @@ bool PhysicsServerCommandProcessor::processSetVRCameraStateCommand(const struct return hasStatus; } -bool PhysicsServerCommandProcessor::processRequestVREventsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processRequestVREventsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; //BT_PROFILE("CMD_REQUEST_VR_EVENTS_DATA"); @@ -6336,7 +6343,7 @@ bool PhysicsServerCommandProcessor::processRequestVREventsCommand(const struct S return hasStatus; } -bool PhysicsServerCommandProcessor::processRequestMouseEventsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processRequestMouseEventsCommand(const struct SharedMemoryCommand& /*clientCmd*/, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; serverStatusOut.m_sendMouseEvents.m_numMouseEvents = m_data->m_mouseEvents.size(); @@ -6354,7 +6361,7 @@ bool PhysicsServerCommandProcessor::processRequestMouseEventsCommand(const struc return hasStatus; } -bool PhysicsServerCommandProcessor::processRequestKeyboardEventsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processRequestKeyboardEventsCommand(const struct SharedMemoryCommand& /*clientCmd*/, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { //BT_PROFILE("CMD_REQUEST_KEYBOARD_EVENTS_DATA"); bool hasStatus = true; @@ -6525,6 +6532,7 @@ struct BatchRayCaster m_threadPool->waitForAllTasks(); } #else // BT_THREADSAFE + (void)numWorkers; castSequentially(); #endif // BT_THREADSAFE } @@ -6649,7 +6657,7 @@ void PhysicsServerCommandProcessor::createThreadPool() #endif //BT_THREADSAFE } -bool PhysicsServerCommandProcessor::processRequestRaycastIntersectionsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processRequestRaycastIntersectionsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int /*bufferSizeInBytes*/) { bool hasStatus = true; BT_PROFILE("CMD_REQUEST_RAY_CAST_INTERSECTIONS"); @@ -6692,7 +6700,6 @@ bool PhysicsServerCommandProcessor::processRequestRaycastIntersectionsCommand(co InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(clientCmd.m_requestRaycastIntersections.m_parentObjectUniqueId); if (bodyHandle) { - int linkIndex = -1; if (bodyHandle->m_multiBody) { int linkIndex = clientCmd.m_requestRaycastIntersections.m_parentLinkIndex; @@ -6808,7 +6815,7 @@ bool PhysicsServerCommandProcessor::processRequestDebugLinesCommand(const struct return hasStatus; } -bool PhysicsServerCommandProcessor::processSyncBodyInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processSyncBodyInfoCommand(const struct SharedMemoryCommand& /*clientCmd*/, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int /*bufferSizeInBytes*/) { bool hasStatus = true; BT_PROFILE("CMD_SYNC_BODY_INFO"); @@ -6849,7 +6856,7 @@ bool PhysicsServerCommandProcessor::processSyncBodyInfoCommand(const struct Shar return hasStatus; } -bool PhysicsServerCommandProcessor::processSyncUserDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processSyncUserDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int /*bufferSizeInBytes*/) { bool hasStatus = true; BT_PROFILE("CMD_SYNC_USER_DATA"); @@ -6919,7 +6926,7 @@ bool PhysicsServerCommandProcessor::processRequestUserDataCommand(const struct S return hasStatus; } -bool PhysicsServerCommandProcessor::processAddUserDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processAddUserDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int /*bufferSizeInBytes*/) { bool hasStatus = true; BT_PROFILE("CMD_ADD_USER_DATA"); @@ -6964,7 +6971,7 @@ bool PhysicsServerCommandProcessor::processAddUserDataCommand(const struct Share return hasStatus; } -bool PhysicsServerCommandProcessor::processCollisionFilterCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processCollisionFilterCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED; b3PluginCollisionInterface* collisionInterface = m_data->m_pluginManager.getCollisionInterface(); @@ -7058,7 +7065,7 @@ bool PhysicsServerCommandProcessor::processCollisionFilterCommand(const struct S return true; } -bool PhysicsServerCommandProcessor::processRemoveUserDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processRemoveUserDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; BT_PROFILE("CMD_REMOVE_USER_DATA"); @@ -7096,7 +7103,7 @@ bool PhysicsServerCommandProcessor::processRemoveUserDataCommand(const struct Sh return hasStatus; } -bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; BT_PROFILE("CMD_SEND_DESIRED_STATE"); @@ -7229,6 +7236,7 @@ bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct } int numMotors = 0; + (void)numMotors; //find the joint motors and apply the desired velocity and maximum force/torque { int dofIndex = 6; //skip the 3 linear + 3 angular degree of freedom entries of the base @@ -7288,6 +7296,7 @@ bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct //compute the force base on PD control int numMotors = 0; + (void)numMotors; //find the joint motors and apply the desired velocity and maximum force/torque { int velIndex = 6; //skip the 3 linear + 3 angular degree of freedom velocity entries of the base @@ -7672,7 +7681,7 @@ bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct for (int link = 0; link < mb->getNumLinks(); link++) { int dofCount = mb->getLink(link).m_dofCount; - int dofOffset = mb->getLink(link).m_dofOffset; + // int dofOffset = mb->getLink(link).m_dofOffset; if (dofCount == 3) { for (int dof = 0; dof < 3; dof++) @@ -7709,6 +7718,7 @@ bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct { btRigidBody* rb = body->m_rigidBody; btAssert(rb); + (void)rb; //switch (clientCmd.m_sendDesiredStateCommandArgument.m_controlMode) { @@ -7736,7 +7746,7 @@ bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct //for (int dof=0;dofgetLink(link).m_dofCount;dof++) { { - int torqueIndex = velIndex; + // int torqueIndex = velIndex; double torque = 100; bool hasDesiredTorque = false; if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_MAX_FORCE) != 0) @@ -8347,6 +8357,8 @@ bool PhysicsServerCommandProcessor::processRequestDeformableDeformableContactpoi m_data->m_cachedContactPoints.push_back(pt); } } +#else + (void)clientCmd; #endif return true; } @@ -8525,6 +8537,8 @@ bool PhysicsServerCommandProcessor::processRequestDeformableContactpointHelper(c m_data->m_cachedContactPoints.push_back(distinctContactPoints[p]); } } +#else + (void)clientCmd; #endif return true; } @@ -8870,7 +8884,7 @@ bool PhysicsServerCommandProcessor::processRequestContactpointInformationCommand { } - virtual bool needsCollision(btBroadphaseProxy* proxy0) const + virtual bool needsCollision(btBroadphaseProxy* /*proxy0*/) const { //bool collides = (proxy0->m_collisionFilterGroup & m_collisionFilterMask) != 0; //collides = collides && (m_collisionFilterGroup & proxy0->m_collisionFilterMask); @@ -8878,7 +8892,7 @@ bool PhysicsServerCommandProcessor::processRequestContactpointInformationCommand return true; } - virtual btScalar addSingleResult(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap, int partId0, int index0, const btCollisionObjectWrapper* colObj1Wrap, int partId1, int index1) + virtual btScalar addSingleResult(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap, int /*partId0*/, int /*index0*/, const btCollisionObjectWrapper* /*colObj1Wrap*/, int /*partId1*/, int /*index1*/) { const btCollisionObject* colObj = (btCollisionObject*)colObj0Wrap->getCollisionObject(); const btMultiBodyLinkCollider* mbl = btMultiBodyLinkCollider::upcast(colObj); @@ -9289,8 +9303,14 @@ void constructUrdfDeformable(const struct SharedMemoryCommand& clientCmd, UrdfDe #endif } -bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& deformable, const btVector3& pos, const btQuaternion& orn, int* bodyUniqueId, char* bufferServerToClient, int bufferSizeInBytes, btScalar scale, bool useSelfCollision) +bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& deformable, const btVector3& pos, const btQuaternion& orn, int* bodyUniqueId, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/, btScalar scale, bool useSelfCollision) { + (void)deformable; + (void)pos; + (void)orn; + (void)bodyUniqueId; + (void)scale; + (void)useSelfCollision; #ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD btSoftBody* psb = NULL; CommonFileIOInterface* fileIO(m_data->m_pluginManager.getFileIOInterface()); @@ -9306,9 +9326,11 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo int out_type(0), out_sim_type(0); bool foundFile = UrdfFindMeshFile(fileIO, pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type); + (void)foundFile; if (!deformable.m_simFileName.empty()) { bool foundSimMesh = UrdfFindMeshFile(fileIO, pathPrefix, deformable.m_simFileName, error_message_prefix, &out_found_sim_filename, &out_sim_type); + (void)foundSimMesh; } else { @@ -9433,8 +9455,6 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo if (!m_data->m_useAlternativeDeformableIndexing) { - float rgbaColor[4] = { 1,1,1,1 }; - if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal( out_found_filename.c_str(), meshData, fileIO)) { @@ -9669,7 +9689,7 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo btAlignedObjectArray gfxVertices; btAlignedObjectArray indices; - int strideInBytes = 9 * sizeof(float); + // int strideInBytes = 9 * sizeof(float); gfxVertices.resize(psb->m_faces.size() * 3); for (int i = 0; i < psb->m_faces.size(); i++) // Foreach face { @@ -9812,8 +9832,14 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo return true; } -bool PhysicsServerCommandProcessor::processReducedDeformable(const UrdfReducedDeformable& reduced_deformable, const btVector3& pos, const btQuaternion& orn, int* bodyUniqueId, char* bufferServerToClient, int bufferSizeInBytes, btScalar scale, bool useSelfCollision) +bool PhysicsServerCommandProcessor::processReducedDeformable(const UrdfReducedDeformable& reduced_deformable, const btVector3& pos, const btQuaternion& orn, int* bodyUniqueId, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/, btScalar scale, bool useSelfCollision) { + (void)reduced_deformable; + (void)pos; + (void)orn; + (void)bodyUniqueId; + (void)scale; + (void)useSelfCollision; #ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD btReducedDeformableBody* rsb = NULL; CommonFileIOInterface* fileIO(m_data->m_pluginManager.getFileIOInterface()); @@ -9829,9 +9855,11 @@ bool PhysicsServerCommandProcessor::processReducedDeformable(const UrdfReducedDe int out_type(0), out_sim_type(0); bool foundFile = UrdfFindMeshFile(fileIO, pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type); + (void)foundFile; if (!reduced_deformable.m_simFileName.empty()) { bool foundSimMesh = UrdfFindMeshFile(fileIO, pathPrefix, reduced_deformable.m_simFileName, error_message_prefix, &out_found_sim_filename, &out_sim_type); + (void)foundSimMesh; } else { @@ -9879,8 +9907,6 @@ bool PhysicsServerCommandProcessor::processReducedDeformable(const UrdfReducedDe if (!m_data->m_useAlternativeDeformableIndexing) { - float rgbaColor[4] = { 1,1,1,1 }; - if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal( out_found_filename.c_str(), meshData, fileIO)) { @@ -10110,7 +10136,7 @@ bool PhysicsServerCommandProcessor::processReducedDeformable(const UrdfReducedDe btAlignedObjectArray gfxVertices; btAlignedObjectArray indices; - int strideInBytes = 9 * sizeof(float); + // int strideInBytes = 9 * sizeof(float); gfxVertices.resize(rsb->m_faces.size() * 3); for (int i = 0; i < rsb->m_faces.size(); i++) // Foreach face { @@ -10310,11 +10336,15 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar strcpy(serverStatusOut.m_dataStreamArguments.m_bodyName, body->m_bodyName.c_str()); serverStatusOut.m_loadSoftBodyResultArguments.m_objectUniqueId = bodyUniqueId; } +#else + (void)clientCmd; + (void)bufferServerToClient; + (void)bufferSizeInBytes; #endif return hasStatus; } -bool PhysicsServerCommandProcessor::processCreateSensorCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processCreateSensorCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; BT_PROFILE("CMD_CREATE_SENSOR"); @@ -10385,7 +10415,7 @@ bool PhysicsServerCommandProcessor::processCreateSensorCommand(const struct Shar return hasStatus; } -bool PhysicsServerCommandProcessor::processProfileTimingCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processProfileTimingCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -10431,7 +10461,7 @@ void setDefaultRootWorldAABB(SharedMemoryStatus& serverCmd) serverCmd.m_sendCollisionInfoArgs.m_rootWorldAABBMax[2] = -1; } -bool PhysicsServerCommandProcessor::processRequestCollisionInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processRequestCollisionInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; SharedMemoryStatus& serverCmd = serverStatusOut; @@ -10526,17 +10556,14 @@ bool PhysicsServerCommandProcessor::processRequestCollisionInfoCommand(const str serverCmd.m_sendCollisionInfoArgs.m_rootWorldAABBMax[1] = aabbMax[1]; serverCmd.m_sendCollisionInfoArgs.m_rootWorldAABBMax[2] = aabbMax[2]; - SharedMemoryStatus& serverCmd = serverStatusOut; serverStatusOut.m_type = CMD_REQUEST_COLLISION_INFO_COMPLETED; } #endif return hasStatus; } -bool PhysicsServerCommandProcessor::performCollisionDetectionCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::performCollisionDetectionCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { - bool hasStatus = true; - BT_PROFILE("CMD_PERFORM_COLLISION_DETECTION"); if (m_data->m_verboseOutput) @@ -10551,7 +10578,7 @@ bool PhysicsServerCommandProcessor::performCollisionDetectionCommand(const struc return true; } -bool PhysicsServerCommandProcessor::processForwardDynamicsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processForwardDynamicsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -10629,7 +10656,7 @@ bool PhysicsServerCommandProcessor::processForwardDynamicsCommand(const struct S return hasStatus; } -bool PhysicsServerCommandProcessor::processRequestInternalDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processRequestInternalDataCommand(const struct SharedMemoryCommand& /*clientCmd*/, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) { bool hasStatus = true; BT_PROFILE("CMD_REQUEST_INTERNAL_DATA"); @@ -10653,7 +10680,7 @@ bool PhysicsServerCommandProcessor::processRequestInternalDataCommand(const stru return hasStatus; } -bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; BT_PROFILE("CMD_CHANGE_DYNAMICS_INFO"); @@ -10871,8 +10898,8 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_JOINT_LIMITS) { //find a joint limit - btScalar prevUpper = mb->getLink(linkIndex).m_jointUpperLimit; - btScalar prevLower = mb->getLink(linkIndex).m_jointLowerLimit; + // btScalar prevUpper = mb->getLink(linkIndex).m_jointUpperLimit; + // btScalar prevLower = mb->getLink(linkIndex).m_jointLowerLimit; btScalar lower = clientCmd.m_changeDynamicsInfoArgs.m_jointLowerLimit; btScalar upper = clientCmd.m_changeDynamicsInfoArgs.m_jointUpperLimit; bool enableLimit = lower <= upper; @@ -11015,7 +11042,7 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc { if (linkIndex >= 0 && linkIndex < body->m_rigidBodyJoints.size()) { - btRigidBody* parentRb = &body->m_rigidBodyJoints[linkIndex]->getRigidBodyA(); + // btRigidBody* parentRb = &body->m_rigidBodyJoints[linkIndex]->getRigidBodyA(); btRigidBody* childRb = &body->m_rigidBodyJoints[linkIndex]->getRigidBodyB(); rb = childRb; } @@ -11193,7 +11220,7 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc return hasStatus; } -bool PhysicsServerCommandProcessor::processSetAdditionalSearchPathCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processSetAdditionalSearchPathCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -11203,7 +11230,7 @@ bool PhysicsServerCommandProcessor::processSetAdditionalSearchPathCommand(const return hasStatus; } -bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; SharedMemoryStatus& serverCmd = serverStatusOut; @@ -11369,7 +11396,7 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S return hasStatus; } -bool PhysicsServerCommandProcessor::processRequestPhysicsSimulationParametersCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processRequestPhysicsSimulationParametersCommand(const struct SharedMemoryCommand& /*clientCmd*/, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; SharedMemoryStatus& serverCmd = serverStatusOut; @@ -11420,7 +11447,7 @@ bool PhysicsServerCommandProcessor::processRequestPhysicsSimulationParametersCom return hasStatus; } -bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -11704,7 +11731,7 @@ bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const st return hasStatus; } -bool PhysicsServerCommandProcessor::processInitPoseCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processInitPoseCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -11941,7 +11968,7 @@ bool PhysicsServerCommandProcessor::processInitPoseCommand(const struct SharedMe return hasStatus; } -bool PhysicsServerCommandProcessor::processResetSimulationCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processResetSimulationCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; BT_PROFILE("CMD_RESET_SIMULATION"); @@ -11955,7 +11982,7 @@ bool PhysicsServerCommandProcessor::processResetSimulationCommand(const struct S return hasStatus; } -bool PhysicsServerCommandProcessor::processCreateRigidBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processCreateRigidBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; SharedMemoryStatus& serverCmd = serverStatusOut; @@ -12098,7 +12125,7 @@ bool PhysicsServerCommandProcessor::processCreateRigidBodyCommand(const struct S return hasStatus; } -bool PhysicsServerCommandProcessor::processPickBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processPickBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -12116,7 +12143,7 @@ bool PhysicsServerCommandProcessor::processPickBodyCommand(const struct SharedMe return hasStatus; } -bool PhysicsServerCommandProcessor::processMovePickedBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processMovePickedBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -12134,7 +12161,7 @@ bool PhysicsServerCommandProcessor::processMovePickedBodyCommand(const struct Sh return hasStatus; } -bool PhysicsServerCommandProcessor::processRemovePickingConstraintCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processRemovePickingConstraintCommand(const struct SharedMemoryCommand& /*clientCmd*/, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -12202,7 +12229,7 @@ bool PhysicsServerCommandProcessor::processRequestAabbOverlapCommand(const struc return hasStatus; } -bool PhysicsServerCommandProcessor::processRequestOpenGLVisualizeCameraCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processRequestOpenGLVisualizeCameraCommand(const struct SharedMemoryCommand& /*clientCmd*/, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -12225,7 +12252,7 @@ bool PhysicsServerCommandProcessor::processRequestOpenGLVisualizeCameraCommand(c return hasStatus; } -bool PhysicsServerCommandProcessor::processConfigureOpenGLVisualizerCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processConfigureOpenGLVisualizerCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -12289,7 +12316,7 @@ bool PhysicsServerCommandProcessor::processConfigureOpenGLVisualizerCommand(cons return hasStatus; } -bool PhysicsServerCommandProcessor::processInverseDynamicsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processInverseDynamicsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -12412,7 +12439,7 @@ bool PhysicsServerCommandProcessor::processInverseDynamicsCommand(const struct S return hasStatus; } -bool PhysicsServerCommandProcessor::processCalculateJacobianCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processCalculateJacobianCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; BT_PROFILE("CMD_CALCULATE_JACOBIAN"); @@ -12606,7 +12633,7 @@ bool PhysicsServerCommandProcessor::processCalculateMassMatrixCommand(const stru return hasStatus; } -bool PhysicsServerCommandProcessor::processApplyExternalForceCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processApplyExternalForceCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -12720,7 +12747,7 @@ bool PhysicsServerCommandProcessor::processApplyExternalForceCommand(const struc clientCmd.m_externalForceArguments.m_positions[i * 3 + 2]); btVector3 forceWorld = isLinkFrame ? sb->getWorldTransform().getBasis() * tmpForce : tmpForce; - btVector3 relPosWorld = isLinkFrame ? sb->getWorldTransform().getBasis() * tmpPosition : tmpPosition - sb->getWorldTransform().getOrigin(); + // btVector3 relPosWorld = isLinkFrame ? sb->getWorldTransform().getBasis() * tmpPosition : tmpPosition - sb->getWorldTransform().getOrigin(); if (link >= 0 && link < sb->m_nodes.size()) { sb->addForce(forceWorld, link); @@ -12736,7 +12763,7 @@ bool PhysicsServerCommandProcessor::processApplyExternalForceCommand(const struc return hasStatus; } -bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -12815,9 +12842,9 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared delete colObj; } } - int numCollisionObjects = m_data->m_dynamicsWorld->getNumCollisionObjects(); + // int numCollisionObjects = m_data->m_dynamicsWorld->getNumCollisionObjects(); m_data->m_dynamicsWorld->removeMultiBody(bodyHandle->m_multiBody); - numCollisionObjects = m_data->m_dynamicsWorld->getNumCollisionObjects(); + // numCollisionObjects = m_data->m_dynamicsWorld->getNumCollisionObjects(); delete bodyHandle->m_multiBody; bodyHandle->m_multiBody = 0; @@ -12949,7 +12976,7 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared return hasStatus; } -bool PhysicsServerCommandProcessor::processCreateUserConstraintCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processCreateUserConstraintCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -13011,7 +13038,7 @@ bool PhysicsServerCommandProcessor::processCreateUserConstraintCommand(const str if (deformWorld) { //todo: expose those values - bool disableCollisionBetweenLinkedBodies = true; + // bool disableCollisionBetweenLinkedBodies = true; //btVector3 localPivot(0,0,0); sbodyHandle->m_softBody->appendDeformableAnchor(nodeIndex, mbodyHandle->m_rigidBody); } @@ -13454,7 +13481,7 @@ bool PhysicsServerCommandProcessor::processCreateUserConstraintCommand(const str { if (clientCmd.m_updateFlags & USER_CONSTRAINT_CHANGE_MAX_FORCE) { - btScalar maxImp = clientCmd.m_userConstraintArguments.m_maxAppliedForce * fixedTimeSubStep; + // btScalar maxImp = clientCmd.m_userConstraintArguments.m_maxAppliedForce * fixedTimeSubStep; userConstraintPtr->m_userConstraintData.m_maxAppliedForce = clientCmd.m_userConstraintArguments.m_maxAppliedForce; //userConstraintPtr->m_rbConstraint->setMaxAppliedImpulse(maxImp); } @@ -13523,7 +13550,7 @@ bool PhysicsServerCommandProcessor::processCreateUserConstraintCommand(const str return hasStatus; } -bool PhysicsServerCommandProcessor::processCalculateInverseKinematicsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processCalculateInverseKinematicsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -13765,7 +13792,7 @@ bool PhysicsServerCommandProcessor::processCalculateInverseKinematicsCommand(con //endEffectorBaseCoord = tr.inverse()*endEffectorTransformWorld; //endEffectorBaseCoord = tr.inverse()*endEffectorTransformWorld; - btQuaternion endEffectorOriBaseCoord = endEffectorBaseCoord.getRotation(); + // btQuaternion endEffectorOriBaseCoord = endEffectorBaseCoord.getRotation(); //btVector4 endEffectorOri(endEffectorOriBaseCoord.x(), endEffectorOriBaseCoord.y(), endEffectorOriBaseCoord.z(), endEffectorOriBaseCoord.w()); @@ -13825,7 +13852,7 @@ bool PhysicsServerCommandProcessor::processCalculateInverseKinematicsCommand(con return hasStatus; } -bool PhysicsServerCommandProcessor::processCalculateInverseKinematicsCommand2(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processCalculateInverseKinematicsCommand2(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -14114,7 +14141,7 @@ bool PhysicsServerCommandProcessor::processCalculateInverseKinematicsCommand2(co //endEffectorBaseCoord = tr.inverse()*endEffectorTransformWorld; //endEffectorBaseCoord = tr.inverse()*endEffectorTransformWorld; - btQuaternion endEffectorOriBaseCoord = endEffectorBaseCoord.getRotation(); + // btQuaternion endEffectorOriBaseCoord = endEffectorBaseCoord.getRotation(); //btVector4 endEffectorOri(endEffectorOriBaseCoord.x(), endEffectorOriBaseCoord.y(), endEffectorOriBaseCoord.z(), endEffectorOriBaseCoord.w()); @@ -14389,7 +14416,7 @@ bool PhysicsServerCommandProcessor::processRequestCollisionShapeInfoCommand(cons return hasStatus; } -bool PhysicsServerCommandProcessor::processRequestVisualShapeInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processRequestVisualShapeInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -14461,7 +14488,7 @@ bool PhysicsServerCommandProcessor::processRequestVisualShapeInfoCommand(const s return hasStatus; } -bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -14661,7 +14688,7 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct return hasStatus; } -bool PhysicsServerCommandProcessor::processChangeTextureCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processChangeTextureCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -14680,7 +14707,7 @@ bool PhysicsServerCommandProcessor::processChangeTextureCommand(const struct Sha return hasStatus; } -bool PhysicsServerCommandProcessor::processLoadTextureCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processLoadTextureCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -14769,7 +14796,7 @@ bool PhysicsServerCommandProcessor::processLoadTextureCommand(const struct Share return hasStatus; } -bool PhysicsServerCommandProcessor::processSaveStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processSaveStateCommand(const struct SharedMemoryCommand& /*clientCmd*/, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { BT_PROFILE("CMD_SAVE_STATE"); bool hasStatus = true; @@ -14812,7 +14839,7 @@ bool PhysicsServerCommandProcessor::processSaveStateCommand(const struct SharedM return hasStatus; } -bool PhysicsServerCommandProcessor::processRemoveStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processRemoveStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { BT_PROFILE("CMD_REMOVE_STATE"); bool hasStatus = true; @@ -14834,7 +14861,7 @@ bool PhysicsServerCommandProcessor::processRemoveStateCommand(const struct Share return hasStatus; } -bool PhysicsServerCommandProcessor::processRestoreStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processRestoreStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { BT_PROFILE("CMD_RESTORE_STATE"); @@ -14915,7 +14942,7 @@ bool PhysicsServerCommandProcessor::processRestoreStateCommand(const struct Shar return hasStatus; } -bool PhysicsServerCommandProcessor::processLoadBulletCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processLoadBulletCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { BT_PROFILE("CMD_LOAD_BULLET"); @@ -15047,7 +15074,7 @@ bool PhysicsServerCommandProcessor::processLoadMJCFCommand(const struct SharedMe return hasStatus; } -bool PhysicsServerCommandProcessor::processSaveBulletCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool PhysicsServerCommandProcessor::processSaveBulletCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { bool hasStatus = true; @@ -15076,8 +15103,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { // BT_PROFILE("processCommand"); - int sz = sizeof(SharedMemoryStatus); - int sz2 = sizeof(SharedMemoryCommand); + // int sz = sizeof(SharedMemoryStatus); + // int sz2 = sizeof(SharedMemoryCommand); bool hasStatus = false; @@ -15545,7 +15572,7 @@ struct MyResultCallback : public btCollisionWorld::ClosestRayResultCallback { } - virtual bool needsCollision(btBroadphaseProxy* proxy0) const + virtual bool needsCollision(btBroadphaseProxy* /*proxy0*/) const { return true; } diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.h b/examples/SharedMemory/PhysicsServerCommandProcessor.h index 4035d7d0cc..5481d2598d 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.h +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.h @@ -143,7 +143,7 @@ class PhysicsServerCommandProcessor : public CommandProcessorInterface virtual bool processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); - virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) + virtual bool receiveStatus(struct SharedMemoryStatus& /*serverStatusOut*/, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { return false; }; diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 52c30dee53..cfe91314da 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -237,7 +237,7 @@ struct MotionThreadLocalStorage float clampedDeltaTime = 0.2; -void MotionThreadFunc(void* userPtr, void* lsMemory) +void MotionThreadFunc(void* userPtr, void* /*lsMemory*/) { printf("MotionThreadFunc thread started\n"); //MotionThreadLocalStorage* localStorage = (MotionThreadLocalStorage*) lsMemory; @@ -257,7 +257,7 @@ void MotionThreadFunc(void* userPtr, void* lsMemory) args->m_cs->unlock(); double deltaTimeInSeconds = 0; - int numCmdSinceSleep1ms = 0; + int numCmdSinceSleep1ms = 0; (void)numCmdSinceSleep1ms; unsigned long long int prevTime = clock.getTimeMicroseconds(); do @@ -514,7 +514,7 @@ struct UserDebugParameter int m_itemUniqueId; }; -static void UserButtonToggle(int buttonId, bool buttonState, void* userPointer) +static void UserButtonToggle(int /*buttonId*/, bool /*buttonState*/, void* userPointer) { UserDebugParameter* param = (UserDebugParameter*)userPointer; param->m_value += 1; @@ -632,17 +632,17 @@ MultithreadedDebugDrawer : public btIDebugDraw } } - virtual void drawContactPoint(const btVector3& PointOnB, const btVector3& normalOnB, btScalar distance, int lifeTime, const btVector3& color) + virtual void drawContactPoint(const btVector3& PointOnB, const btVector3& normalOnB, btScalar distance, int /*lifeTime*/, const btVector3& color) { drawLine(PointOnB, PointOnB + normalOnB * distance, color); btVector3 ncolor(0, 0, 0); drawLine(PointOnB, PointOnB + normalOnB * 0.01, ncolor); } - virtual void reportErrorWarning(const char* warningString) + virtual void reportErrorWarning(const char* /*warningString*/) { } - virtual void draw3dText(const btVector3& location, const char* textString) + virtual void draw3dText(const btVector3& /*location*/, const char* /*textString*/) { } virtual void setDebugMode(int debugMode) @@ -766,7 +766,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface } } - MultiThreadedOpenGLGuiHelper(CommonGraphicsApp* app, GUIHelperInterface* guiHelper, int skipGraphicsUpdate) + MultiThreadedOpenGLGuiHelper(CommonGraphicsApp* /*app*/, GUIHelperInterface* guiHelper, int skipGraphicsUpdate) : //m_app(app), m_cs(0), m_cs2(0), @@ -895,7 +895,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface m_childGuiHelper->syncPhysicsToGraphics2(positions, numPositions); } - virtual void render(const btDiscreteDynamicsWorld* rbWorld) + virtual void render(const btDiscreteDynamicsWorld* /*rbWorld*/) { m_childGuiHelper->render(0); } @@ -1295,11 +1295,11 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface workerThreadWait(); } - virtual void drawText3D(const char* txt, float posX, float posZY, float posZ, float size) + virtual void drawText3D(const char* /*txt*/, float /*posX*/, float /*posZY*/, float /*posZ*/, float /*size*/) { } - virtual void drawText3D(const char* txt, float position[3], float orientation[4], float color[4], float size, int optionFlag) + virtual void drawText3D(const char* /*txt*/, float /*position*/[3], float /*orientation*/[4], float /*color*/[4], float /*size*/, int /*optionFlag*/) { } @@ -1892,7 +1892,7 @@ class PhysicsServerExample : public SharedMemoryCommon } }; -PhysicsServerExample::PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, CommandProcessorCreationInterface* commandProcessorCreator, SharedMemoryInterface* sharedMem, int options) +PhysicsServerExample::PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, CommandProcessorCreationInterface* commandProcessorCreator, SharedMemoryInterface* sharedMem, int /*options*/) : SharedMemoryCommon(helper), m_physicsServer(commandProcessorCreator, sharedMem, 0), m_wantsShutdown(false), @@ -2464,8 +2464,8 @@ void PhysicsServerExample::updateGraphics() int rgb = 0; btScalar frustumZNear = 0.1; btScalar frustumZFar = 30; - btScalar minDepthValue = frustumZNear; //todo: compute more reasonably min/max depth range - btScalar maxDepthValue = frustumZFar; + // btScalar minDepthValue = frustumZNear; //todo: compute more reasonably min/max depth range + // btScalar maxDepthValue = frustumZFar; float depth = depthValue; btScalar linearDepth = 255. * (2.0 * frustumZNear) / (frustumZFar + frustumZNear - depth * (frustumZFar - frustumZNear)); @@ -3078,13 +3078,14 @@ void PhysicsServerExample::renderScene() if (m_physicsServer.isRealTimeSimulationEnabled()) { static int frameCount = 0; - static btScalar prevTime = m_clock.getTimeSeconds(); frameCount++; + (void)frameCount; static char line0[1024] = {0}; static char line1[1024] = {0}; #if 0 + static btScalar prevTime = m_clock.getTimeSeconds(); static btScalar worseFps = 1000000; int numFrames = 200; @@ -3144,6 +3145,9 @@ void PhysicsServerExample::renderScene() m_tinyVrGui->tick(dt, tr); } +#else + (void)line0; + (void)line1; #endif //BT_ENABLE_VR } ///debug rendering diff --git a/examples/SharedMemory/PhysicsServerSharedMemory.cpp b/examples/SharedMemory/PhysicsServerSharedMemory.cpp index 288196bdf3..66f5b6bb9c 100644 --- a/examples/SharedMemory/PhysicsServerSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsServerSharedMemory.cpp @@ -54,13 +54,13 @@ struct PhysicsServerSharedMemoryInternalData serverCmd.m_timeStamp = timeStamp; return serverCmd; } - void submitServerStatus(SharedMemoryStatus& status, int blockIndex) + void submitServerStatus(SharedMemoryStatus& /*status*/, int blockIndex) { m_testBlocks[blockIndex]->m_numServerCommands++; } }; -PhysicsServerSharedMemory::PhysicsServerSharedMemory(CommandProcessorCreationInterface* commandProcessorCreator, SharedMemoryInterface* sharedMem, int bla) +PhysicsServerSharedMemory::PhysicsServerSharedMemory(CommandProcessorCreationInterface* commandProcessorCreator, SharedMemoryInterface* sharedMem, int /*bla*/) { m_data = new PhysicsServerSharedMemoryInternalData(); m_data->m_commandProcessorCreator = commandProcessorCreator; diff --git a/examples/SharedMemory/PosixSharedMemory.cpp b/examples/SharedMemory/PosixSharedMemory.cpp index dac21eeb40..ea677abb2a 100644 --- a/examples/SharedMemory/PosixSharedMemory.cpp +++ b/examples/SharedMemory/PosixSharedMemory.cpp @@ -113,12 +113,15 @@ void* PosixSharedMemory::allocateSharedMemory(int key, int size, bool allowCreat } } #else + (void)key; + (void)size; + (void)allowCreation; //not implemented yet btAssert(0); #endif return 0; } -void PosixSharedMemory::releaseSharedMemory(int key, int size) +void PosixSharedMemory::releaseSharedMemory(int key, int /*size*/) { #ifdef TEST_SHARED_MEMORY @@ -170,5 +173,7 @@ void PosixSharedMemory::releaseSharedMemory(int key, int size) m_internalData->m_segments.removeAtIndex(i); +#else + (void)key; #endif } diff --git a/examples/SharedMemory/RemoteGUIHelper.cpp b/examples/SharedMemory/RemoteGUIHelper.cpp index 4ef9395a14..3f90c5aea5 100644 --- a/examples/SharedMemory/RemoteGUIHelper.cpp +++ b/examples/SharedMemory/RemoteGUIHelper.cpp @@ -240,7 +240,7 @@ void RemoteGUIHelper::setVisualizerFlag(int flag, int enable) } } -void RemoteGUIHelper::createRigidBodyGraphicsObject(btRigidBody* body, const btVector3& color) +void RemoteGUIHelper::createRigidBodyGraphicsObject(btRigidBody* /*body*/, const btVector3& /*color*/) { printf("createRigidBodyGraphicsObject\n"); } @@ -305,12 +305,12 @@ void RemoteGUIHelper::createCollisionObjectGraphicsObject(btCollisionObject* bod } } -void RemoteGUIHelper::createCollisionShapeGraphicsObject(btCollisionShape* collisionShape) +void RemoteGUIHelper::createCollisionShapeGraphicsObject(btCollisionShape* /*collisionShape*/) { printf("createCollisionShapeGraphicsObject\n"); } -void RemoteGUIHelper::syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWorld) +void RemoteGUIHelper::syncPhysicsToGraphics(const btDiscreteDynamicsWorld* /*rbWorld*/) { } @@ -325,7 +325,7 @@ void RemoteGUIHelper::syncPhysicsToGraphics2(const btDiscreteDynamicsWorld* rbWo { //B3_PROFILE("writeSingleInstanceTransformToCPU"); btCollisionObject* colObj = rbWorld->getCollisionObjectArray()[i]; - btCollisionShape* collisionShape = colObj->getCollisionShape(); + // btCollisionShape* collisionShape = colObj->getCollisionShape(); btVector3 pos = colObj->getWorldTransform().getOrigin(); btQuaternion orn = colObj->getWorldTransform().getRotation(); @@ -367,11 +367,11 @@ void RemoteGUIHelper::syncPhysicsToGraphics2(const GUISyncPosition* positions, i } } -void RemoteGUIHelper::render(const btDiscreteDynamicsWorld* rbWorld) +void RemoteGUIHelper::render(const btDiscreteDynamicsWorld* /*rbWorld*/) { } -void RemoteGUIHelper::createPhysicsDebugDrawer(btDiscreteDynamicsWorld* rbWorld) +void RemoteGUIHelper::createPhysicsDebugDrawer(btDiscreteDynamicsWorld* /*rbWorld*/) { } @@ -530,7 +530,7 @@ void RemoteGUIHelper::removeGraphicsInstance(int graphicsUid) } } -void RemoteGUIHelper::changeScaling(int instanceUid, const double scaling[3]) +void RemoteGUIHelper::changeScaling(int /*instanceUid*/, const double /*scaling*/[3]) { } @@ -588,50 +588,50 @@ void RemoteGUIHelper::setUpAxis(int axis) } } } -void RemoteGUIHelper::resetCamera(float camDist, float yaw, float pitch, float camPosX, float camPosY, float camPosZ) +void RemoteGUIHelper::resetCamera(float /*camDist*/, float /*yaw*/, float /*pitch*/, float /*camPosX*/, float /*camPosY*/, float /*camPosZ*/) { } -void RemoteGUIHelper::copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], - unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, - float* depthBuffer, int depthBufferSizeInPixels, - int* segmentationMaskBuffer, int segmentationMaskBufferSizeInPixels, - int startPixelIndex, int width, int height, int* numPixelsCopied) +void RemoteGUIHelper::copyCameraImageData(const float /*viewMatrix*/[16], const float /*projectionMatrix*/[16], + unsigned char* /*pixelsRGBA*/, int /*rgbaBufferSizeInPixels*/, + float* /*depthBuffer*/, int /*depthBufferSizeInPixels*/, + int* /*segmentationMaskBuffer*/, int /*segmentationMaskBufferSizeInPixels*/, + int /*startPixelIndex*/, int /*width*/, int /*height*/, int* numPixelsCopied) { if (numPixelsCopied) *numPixelsCopied = 0; } -void RemoteGUIHelper::setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]) +void RemoteGUIHelper::setProjectiveTextureMatrices(const float /*viewMatrix*/[16], const float /*projectionMatrix*/[16]) { } -void RemoteGUIHelper::setProjectiveTexture(bool useProjectiveTexture) +void RemoteGUIHelper::setProjectiveTexture(bool /*useProjectiveTexture*/) { } -void RemoteGUIHelper::autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) +void RemoteGUIHelper::autogenerateGraphicsObjects(btDiscreteDynamicsWorld* /*rbWorld*/) { } -void RemoteGUIHelper::drawText3D(const char* txt, float posX, float posZY, float posZ, float size) +void RemoteGUIHelper::drawText3D(const char* /*txt*/, float /*posX*/, float /*posZY*/, float /*posZ*/, float /*size*/) { } -void RemoteGUIHelper::drawText3D(const char* txt, float position[3], float orientation[4], float color[4], float size, int optionFlag) +void RemoteGUIHelper::drawText3D(const char* /*txt*/, float /*position*/[3], float /*orientation*/[4], float /*color*/[4], float /*size*/, int /*optionFlag*/) { } -int RemoteGUIHelper::addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid) +int RemoteGUIHelper::addUserDebugLine(const double /*debugLineFromXYZ*/[3], const double /*debugLineToXYZ*/[3], const double /*debugLineColorRGB*/[3], double /*lineWidth*/, double /*lifeTime*/, int /*trackingVisualShapeIndex*/, int /*replaceItemUid*/) { return -1; } -int RemoteGUIHelper::addUserDebugPoints(const double debugPointPositionXYZ[3], const double debugPointColorRGB[3], double pointSize, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid, int debugPointNum) +int RemoteGUIHelper::addUserDebugPoints(const double /*debugPointPositionXYZ*/[3], const double /*debugPointColorRGB*/[3], double /*pointSize*/, double /*lifeTime*/, int /*trackingVisualShapeIndex*/, int /*replaceItemUid*/, int /*debugPointNum*/) { return -1; } -void RemoteGUIHelper::removeUserDebugItem(int debugItemUniqueId) +void RemoteGUIHelper::removeUserDebugItem(int /*debugItemUniqueId*/) { } void RemoteGUIHelper::removeAllUserDebugItems() diff --git a/examples/SharedMemory/RemoteGUIHelperTCP.cpp b/examples/SharedMemory/RemoteGUIHelperTCP.cpp index 5831f0c044..09bca39bbe 100644 --- a/examples/SharedMemory/RemoteGUIHelperTCP.cpp +++ b/examples/SharedMemory/RemoteGUIHelperTCP.cpp @@ -123,6 +123,7 @@ struct RemoteGUIHelperTCPInternalData { bool hasStatus = false; + (void)hasStatus; //int serviceResult = enet_host_service(m_client, &m_event, 0); int maxLen = 4 + sizeof(GraphicsSharedMemoryStatus) + GRAPHICS_SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE; @@ -251,7 +252,7 @@ void RemoteGUIHelperTCP::setVisualizerFlag(int flag, int enable) } } -void RemoteGUIHelperTCP::createRigidBodyGraphicsObject(btRigidBody* body, const btVector3& color) +void RemoteGUIHelperTCP::createRigidBodyGraphicsObject(btRigidBody* /*body*/, const btVector3& /*color*/) { printf("todo: createRigidBodyGraphicsObject\n"); } @@ -316,12 +317,12 @@ void RemoteGUIHelperTCP::createCollisionObjectGraphicsObject(btCollisionObject* } } -void RemoteGUIHelperTCP::createCollisionShapeGraphicsObject(btCollisionShape* collisionShape) +void RemoteGUIHelperTCP::createCollisionShapeGraphicsObject(btCollisionShape* /*collisionShape*/) { printf("todo; createCollisionShapeGraphicsObject\n"); } -void RemoteGUIHelperTCP::syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWorld) +void RemoteGUIHelperTCP::syncPhysicsToGraphics(const btDiscreteDynamicsWorld* /*rbWorld*/) { } @@ -336,7 +337,7 @@ void RemoteGUIHelperTCP::syncPhysicsToGraphics2(const btDiscreteDynamicsWorld* r { //B3_PROFILE("writeSingleInstanceTransformToCPU"); btCollisionObject* colObj = rbWorld->getCollisionObjectArray()[i]; - btCollisionShape* collisionShape = colObj->getCollisionShape(); + // btCollisionShape* collisionShape = colObj->getCollisionShape(); btVector3 pos = colObj->getWorldTransform().getOrigin(); btQuaternion orn = colObj->getWorldTransform().getRotation(); @@ -378,11 +379,11 @@ void RemoteGUIHelperTCP::syncPhysicsToGraphics2(const GUISyncPosition* positions } } -void RemoteGUIHelperTCP::render(const btDiscreteDynamicsWorld* rbWorld) +void RemoteGUIHelperTCP::render(const btDiscreteDynamicsWorld* /*rbWorld*/) { } -void RemoteGUIHelperTCP::createPhysicsDebugDrawer(btDiscreteDynamicsWorld* rbWorld) +void RemoteGUIHelperTCP::createPhysicsDebugDrawer(btDiscreteDynamicsWorld* /*rbWorld*/) { } @@ -600,50 +601,50 @@ void RemoteGUIHelperTCP::setUpAxis(int axis) } } } -void RemoteGUIHelperTCP::resetCamera(float camDist, float yaw, float pitch, float camPosX, float camPosY, float camPosZ) +void RemoteGUIHelperTCP::resetCamera(float /*camDist*/, float /*yaw*/, float /*pitch*/, float /*camPosX*/, float /*camPosY*/, float /*camPosZ*/) { } -void RemoteGUIHelperTCP::copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], - unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, - float* depthBuffer, int depthBufferSizeInPixels, - int* segmentationMaskBuffer, int segmentationMaskBufferSizeInPixels, - int startPixelIndex, int width, int height, int* numPixelsCopied) +void RemoteGUIHelperTCP::copyCameraImageData(const float /*viewMatrix*/[16], const float /*projectionMatrix*/[16], + unsigned char* /*pixelsRGBA*/, int /*rgbaBufferSizeInPixels*/, + float* /*depthBuffer*/, int /*depthBufferSizeInPixels*/, + int* /*segmentationMaskBuffer*/, int /*segmentationMaskBufferSizeInPixels*/, + int /*startPixelIndex*/, int /*width*/, int /*height*/, int* numPixelsCopied) { if (numPixelsCopied) *numPixelsCopied = 0; } -void RemoteGUIHelperTCP::setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]) +void RemoteGUIHelperTCP::setProjectiveTextureMatrices(const float /*viewMatrix*/[16], const float /*projectionMatrix*/[16]) { } -void RemoteGUIHelperTCP::setProjectiveTexture(bool useProjectiveTexture) +void RemoteGUIHelperTCP::setProjectiveTexture(bool /*useProjectiveTexture*/) { } -void RemoteGUIHelperTCP::autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) +void RemoteGUIHelperTCP::autogenerateGraphicsObjects(btDiscreteDynamicsWorld* /*rbWorld*/) { } -void RemoteGUIHelperTCP::drawText3D(const char* txt, float posX, float posZY, float posZ, float size) +void RemoteGUIHelperTCP::drawText3D(const char* /*txt*/, float /*posX*/, float /*posY*/, float /*posZ*/, float /*size*/) { } -void RemoteGUIHelperTCP::drawText3D(const char* txt, float position[3], float orientation[4], float color[4], float size, int optionFlag) +void RemoteGUIHelperTCP::drawText3D(const char* /*txt*/, float /*position*/[3], float /*orientation*/[4], float /*color*/[4], float /*size*/, int /*optionFlag*/) { } -int RemoteGUIHelperTCP::addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid) +int RemoteGUIHelperTCP::addUserDebugLine(const double /*debugLineFromXYZ*/[3], const double /*debugLineToXYZ*/[3], const double /*debugLineColorRGB*/[3], double /*lineWidth*/, double /*lifeTime*/, int /*trackingVisualShapeIndex*/, int /*replaceItemUid*/) { return -1; } -int RemoteGUIHelperTCP::addUserDebugPoints(const double debugPointPositionXYZ[3], const double debugPointColorRGB[3], double pointSize, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid, int debugPointNum) +int RemoteGUIHelperTCP::addUserDebugPoints(const double /*debugPointPositionXYZ*/[3], const double /*debugPointColorRGB*/[3], double /*pointSize*/, double /*lifeTime*/, int /*trackingVisualShapeIndex*/, int /*replaceItemUid*/, int /*debugPointNum*/) { return -1; } -void RemoteGUIHelperTCP::removeUserDebugItem(int debugItemUniqueId) +void RemoteGUIHelperTCP::removeUserDebugItem(int /*debugItemUniqueId*/) { } void RemoteGUIHelperTCP::removeAllUserDebugItems() diff --git a/examples/SharedMemory/SharedMemoryCommandProcessor.cpp b/examples/SharedMemory/SharedMemoryCommandProcessor.cpp index 952be41280..a665142634 100644 --- a/examples/SharedMemory/SharedMemoryCommandProcessor.cpp +++ b/examples/SharedMemory/SharedMemoryCommandProcessor.cpp @@ -114,7 +114,7 @@ bool SharedMemoryCommandProcessor::isConnected() const return m_data->m_isConnected; } -bool SharedMemoryCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool SharedMemoryCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& /*serverStatusOut*/, char* /*bufferServerToClient*/, int /*bufferSizeInBytes*/) { if (!m_data->m_waitingForServer) { @@ -129,7 +129,7 @@ bool SharedMemoryCommandProcessor::processCommand(const struct SharedMemoryComma return false; } -bool SharedMemoryCommandProcessor::receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +bool SharedMemoryCommandProcessor::receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int /*bufferSizeInBytes*/) { m_data->m_lastServerStatus.m_dataStream = 0; m_data->m_lastServerStatus.m_numDataStreamBytes = 0; @@ -199,15 +199,15 @@ bool SharedMemoryCommandProcessor::receiveStatus(struct SharedMemoryStatus& serv return false; } -void SharedMemoryCommandProcessor::renderScene(int renderFlags) +void SharedMemoryCommandProcessor::renderScene(int /*renderFlags*/) { } -void SharedMemoryCommandProcessor::physicsDebugDraw(int debugDrawFlags) +void SharedMemoryCommandProcessor::physicsDebugDraw(int /*debugDrawFlags*/) { } -void SharedMemoryCommandProcessor::setGuiHelper(struct GUIHelperInterface* guiHelper) +void SharedMemoryCommandProcessor::setGuiHelper(struct GUIHelperInterface* /*guiHelper*/) { } diff --git a/examples/SharedMemory/Win32SharedMemory.cpp b/examples/SharedMemory/Win32SharedMemory.cpp index 53fdad1026..766ce1f9bf 100644 --- a/examples/SharedMemory/Win32SharedMemory.cpp +++ b/examples/SharedMemory/Win32SharedMemory.cpp @@ -112,7 +112,7 @@ void* Win32SharedMemory::allocateSharedMemory(int key, int size, bool allowCreat m_internalData->m_segments.push_back(seg); return seg.m_buf; } -void Win32SharedMemory::releaseSharedMemory(int key, int size) +void Win32SharedMemory::releaseSharedMemory(int key, int /*size*/) { Win32SharedMemorySegment* seg = 0; int i = 0; diff --git a/examples/SharedMemory/b3PluginManager.cpp b/examples/SharedMemory/b3PluginManager.cpp index 3ac9d79511..f6f90a57be 100644 --- a/examples/SharedMemory/b3PluginManager.cpp +++ b/examples/SharedMemory/b3PluginManager.cpp @@ -154,7 +154,7 @@ b3PluginManager::~b3PluginManager() int* pluginUidPtr = m_data->m_pluginMap.getAtIndex(0); if (pluginUidPtr) { - int pluginUid = *pluginUidPtr; + // int pluginUid = *pluginUidPtr; unloadPlugin(*pluginUidPtr); } } @@ -213,6 +213,7 @@ int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr) context.m_physClient = (b3PhysicsClientHandle)m_data->m_physicsDirect; context.m_rpcCommandProcessorInterface = m_data->m_rpcCommandProcessorInterface; int result = plugin->m_initFunc(&context); + (void)result; plugin->m_isInitialized = true; plugin->m_userPointer = context.m_userPointer; } @@ -363,7 +364,7 @@ void b3PluginManager::unloadPlugin(int pluginUniqueId) } } -void b3PluginManager::tickPlugins(double timeStep, b3PluginManagerTickMode tickMode) +void b3PluginManager::tickPlugins(double /*timeStep*/, b3PluginManagerTickMode tickMode) { for (int i = 0; i < m_data->m_pluginMap.size(); i++) { @@ -419,6 +420,7 @@ void b3PluginManager::tickPlugins(double timeStep, b3PluginManagerTickMode tickM context.m_rpcCommandProcessorInterface = m_data->m_rpcCommandProcessorInterface; } int result = tick(&context); + (void)result; plugin->m_userPointer = context.m_userPointer; } } @@ -522,6 +524,7 @@ int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, b3Plugi context.m_physClient = (b3PhysicsClientHandle)m_data->m_physicsDirect; context.m_rpcCommandProcessorInterface = m_data->m_rpcCommandProcessorInterface; int result = pluginHandle->m_initFunc(&context); + (void)result; pluginHandle->m_isInitialized = true; pluginHandle->m_userPointer = context.m_userPointer; pluginHandle->m_returnData = 0; diff --git a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp index f2777e1291..c53ffe1bc5 100644 --- a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp +++ b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp @@ -74,7 +74,7 @@ void b3RobotSimulatorClientAPI_NoDirect::syncBodies() command = b3InitSyncBodyInfoCommand(m_data->m_physicsClientHandle); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); - statusType = b3GetStatusType(statusHandle); + statusType = b3GetStatusType(statusHandle); (void)statusType; } void b3RobotSimulatorClientAPI_NoDirect::resetSimulation() @@ -87,6 +87,7 @@ void b3RobotSimulatorClientAPI_NoDirect::resetSimulation() b3SharedMemoryStatusHandle statusHandle; statusHandle = b3SubmitClientCommandAndWaitStatus( m_data->m_physicsClientHandle, b3InitResetSimulationCommand(m_data->m_physicsClientHandle)); + (void)statusHandle; } void b3RobotSimulatorClientAPI_NoDirect::resetSimulation(int flag) @@ -100,6 +101,7 @@ void b3RobotSimulatorClientAPI_NoDirect::resetSimulation(int flag) b3SharedMemoryCommandHandle command = b3InitResetSimulationCommand(m_data->m_physicsClientHandle); b3InitResetSimulationSetFlags(command, flag); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); + (void)statusHandle; } bool b3RobotSimulatorClientAPI_NoDirect::canSubmitCommand() const @@ -126,6 +128,7 @@ void b3RobotSimulatorClientAPI_NoDirect::stepSimulation() statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, b3InitStepSimulationCommand(m_data->m_physicsClientHandle)); statusType = b3GetStatusType(statusHandle); //btAssert(statusType == CMD_STEP_FORWARD_SIMULATION_COMPLETED); + (void)statusType; } } @@ -143,6 +146,7 @@ void b3RobotSimulatorClientAPI_NoDirect::setGravity(const btVector3& gravityAcce b3PhysicsParamSetGravity(command, gravityAcceleration[0], gravityAcceleration[1], gravityAcceleration[2]); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); // btAssert(b3GetStatusType(statusHandle) == CMD_CLIENT_COMMAND_COMPLETED); + (void)statusHandle; } btQuaternion b3RobotSimulatorClientAPI_NoDirect::getQuaternionFromEuler(const btVector3& rollPitchYaw) @@ -292,6 +296,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::loadMJCF(const std::string& fileName, b results.m_uniqueObjectIds.resize(numBodies); int numBodies; numBodies = b3GetStatusBodyIndices(statusHandle, &results.m_uniqueObjectIds[0], results.m_uniqueObjectIds.size()); + (void)numBodies; } return true; @@ -308,7 +313,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::savePythonWorld(const std::string& file b3SharedMemoryStatusHandle statusHandle; int statusType; b3SharedMemoryCommandHandle command; - b3PhysicsClientHandle sm = m_data->m_physicsClientHandle; + // b3PhysicsClientHandle sm = m_data->m_physicsClientHandle; if (fileName.length() == 0) { @@ -336,7 +341,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::saveBullet(const std::string& fileName) b3SharedMemoryStatusHandle statusHandle; int statusType; b3SharedMemoryCommandHandle command; - b3PhysicsClientHandle sm = m_data->m_physicsClientHandle; + // b3PhysicsClientHandle sm = m_data->m_physicsClientHandle; if (fileName.length() == 0) { @@ -378,6 +383,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::loadBullet(const std::string& fileName, results.m_uniqueObjectIds.resize(numBodies); int numBodies; numBodies = b3GetStatusBodyIndices(statusHandle, &results.m_uniqueObjectIds[0], results.m_uniqueObjectIds.size()); + (void)numBodies; } return true; @@ -408,6 +414,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::loadSDF(const std::string& fileName, b3 results.m_uniqueObjectIds.resize(numBodies); int numBodies; numBodies = b3GetStatusBodyIndices(statusHandle, &results.m_uniqueObjectIds[0], results.m_uniqueObjectIds.size()); + (void)numBodies; } statusOk = true; } @@ -483,6 +490,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::resetBasePositionAndOrientation(int bod b3SharedMemoryStatusHandle statusHandle; statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); + (void)statusHandle; return true; } @@ -543,6 +551,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::resetBaseVelocity(int bodyUniqueId, con b3CreatePoseCommandSetBaseAngularVelocity(commandHandle, angVelDouble.m_floats); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); + (void)statusHandle; return true; } @@ -558,6 +567,7 @@ void b3RobotSimulatorClientAPI_NoDirect::setInternalSimFlags(int flags) b3SharedMemoryStatusHandle statusHandle; b3PhysicsParamSetInternalSimFlags(command, flags); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); + (void)statusHandle; } } @@ -577,6 +587,7 @@ void b3RobotSimulatorClientAPI_NoDirect::setRealTimeSimulation(bool enableRealTi statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); btAssert(b3GetStatusType(statusHandle) == CMD_CLIENT_COMMAND_COMPLETED); + (void)statusHandle; } int b3RobotSimulatorClientAPI_NoDirect::getNumJoints(int bodyUniqueId) const @@ -794,6 +805,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::resetJointState(int bodyUniqueId, int j targetValue); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); + (void)statusHandle; return false; } @@ -872,6 +884,7 @@ void b3RobotSimulatorClientAPI_NoDirect::setJointMotorControl(int bodyUniqueId, b3Error("Unknown control command in b3RobotSimulationClientAPI::setJointMotorControl"); } } + (void)statusHandle; } void b3RobotSimulatorClientAPI_NoDirect::setNumSolverIterations(int numIterations) @@ -886,6 +899,7 @@ void b3RobotSimulatorClientAPI_NoDirect::setNumSolverIterations(int numIteration b3PhysicsParamSetNumSolverIterations(command, numIterations); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); btAssert(b3GetStatusType(statusHandle) == CMD_CLIENT_COMMAND_COMPLETED); + (void)statusHandle; } void b3RobotSimulatorClientAPI_NoDirect::setContactBreakingThreshold(double threshold) @@ -900,6 +914,7 @@ void b3RobotSimulatorClientAPI_NoDirect::setContactBreakingThreshold(double thre b3PhysicsParamSetContactBreakingThreshold(command, threshold); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); btAssert(b3GetStatusType(statusHandle) == CMD_CLIENT_COMMAND_COMPLETED); + (void)statusHandle; } void b3RobotSimulatorClientAPI_NoDirect::setTimeStep(double timeStepInSeconds) @@ -914,7 +929,9 @@ void b3RobotSimulatorClientAPI_NoDirect::setTimeStep(double timeStepInSeconds) b3SharedMemoryStatusHandle statusHandle; int ret; ret = b3PhysicsParamSetTimeStep(command, timeStepInSeconds); + (void)ret; statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); + (void)statusHandle; } void b3RobotSimulatorClientAPI_NoDirect::setNumSimulationSubSteps(int numSubSteps) @@ -929,6 +946,7 @@ void b3RobotSimulatorClientAPI_NoDirect::setNumSimulationSubSteps(int numSubStep b3PhysicsParamSetNumSubSteps(command, numSubSteps); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); btAssert(b3GetStatusType(statusHandle) == CMD_CLIENT_COMMAND_COMPLETED); + (void)statusHandle; } bool b3RobotSimulatorClientAPI_NoDirect::calculateInverseKinematics(const struct b3RobotSimulatorInverseKinematicArgs& args, struct b3RobotSimulatorInverseKinematicsResults& results) @@ -1167,6 +1185,7 @@ void b3RobotSimulatorClientAPI_NoDirect::stopStateLogging(int stateLoggerUniqueI commandHandle = b3StateLoggingCommandInit(m_data->m_physicsClientHandle); b3StateLoggingStop(commandHandle, stateLoggerUniqueId); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); + (void)statusHandle; } void b3RobotSimulatorClientAPI_NoDirect::resetDebugVisualizerCamera(double cameraDistance, double cameraPitch, double cameraYaw, const btVector3& targetPos) @@ -1540,6 +1559,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::changeDynamics(int bodyUniqueId, int li b3ChangeDynamicsInfoSetFrictionAnchor(command, bodyUniqueId, linkIndex, args.m_frictionAnchor); } statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + (void)statusHandle; return true; } @@ -1612,6 +1632,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::removeUserDebugItem(int itemUniqueId) commandHandle = b3InitUserDebugDrawRemove(sm, itemUniqueId); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); + (void)statusType; return true; } @@ -1800,6 +1821,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::setJointMotorControlArray(int bodyUniqu }; } statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + (void)statusHandle; return true; } @@ -1914,6 +1936,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::setPhysicsEngineParameter(const struct } statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + (void)statusHandle; return true; } @@ -1931,6 +1954,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::applyExternalForce(int objectUniqueId, command = b3ApplyExternalForceCommandInit(sm); b3ApplyExternalForce(command, objectUniqueId, linkIndex, force, position, flags); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + (void)statusHandle; return true; } @@ -1964,6 +1988,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::applyExternalTorque(int objectUniqueId, command = b3ApplyExternalForceCommandInit(sm); b3ApplyExternalTorque(command, objectUniqueId, linkIndex, torque, flags); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + (void)statusHandle; return true; } @@ -2124,6 +2149,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::getOverlappingObjects(double* aabbMin, command = b3InitAABBOverlapQuery(sm, aabbMin, aabbMax); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + (void)statusHandle; b3GetAABBOverlapResults(sm, overlapData); return true; @@ -2395,6 +2421,7 @@ int b3RobotSimulatorClientAPI_NoDirect::createMultiBody(struct b3RobotSimulatorC } baseIndex = b3CreateMultiBodyBase(command, args.m_baseMass, args.m_baseCollisionShapeIndex, args.m_baseVisualShapeIndex, doubleBasePosition, doubleBaseOrientation, doubleBaseInertialFramePosition, doubleBaseInertialFrameOrientation); + (void)baseIndex; for (int i = 0; i < args.m_numLinks; i++) { @@ -2553,7 +2580,7 @@ void b3RobotSimulatorClientAPI_NoDirect::restoreStateFromMemory(int stateId) int statusType; b3SharedMemoryCommandHandle command; b3SharedMemoryStatusHandle statusHandle; - int physicsClientId = 0; + // int physicsClientId = 0; command = b3LoadStateCommandInit(sm); if (stateId >= 0) @@ -2567,6 +2594,7 @@ void b3RobotSimulatorClientAPI_NoDirect::restoreStateFromMemory(int stateId) statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); + (void)statusType; } void b3RobotSimulatorClientAPI_NoDirect::removeState(int stateUniqueId) @@ -2586,6 +2614,7 @@ void b3RobotSimulatorClientAPI_NoDirect::removeState(int stateUniqueId) { statusHandle = b3SubmitClientCommandAndWaitStatus(sm, b3InitRemoveStateCommand(sm, stateUniqueId)); statusType = b3GetStatusType(statusHandle); + (void)statusType; } } } @@ -2617,7 +2646,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::getVisualShapeData(int bodyUniqueId, b3 void b3RobotSimulatorClientAPI_NoDirect::setAdditionalSearchPath(const std::string& path) { - int physicsClientId = 0; + // int physicsClientId = 0; b3PhysicsClientHandle sm = m_data->m_physicsClientHandle; if (sm == 0) { @@ -2630,12 +2659,13 @@ void b3RobotSimulatorClientAPI_NoDirect::setAdditionalSearchPath(const std::stri b3SharedMemoryStatusHandle statusHandle; commandHandle = b3SetAdditionalSearchPath(sm, path.c_str()); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + (void)statusHandle; } } void b3RobotSimulatorClientAPI_NoDirect::setCollisionFilterGroupMask(int bodyUniqueIdA, int linkIndexA, int collisionFilterGroup, int collisionFilterMask) { - int physicsClientId = 0; + // int physicsClientId = 0; b3PhysicsClientHandle sm = m_data->m_physicsClientHandle; if (sm == 0) { @@ -2652,5 +2682,6 @@ void b3RobotSimulatorClientAPI_NoDirect::setCollisionFilterGroupMask(int bodyUni statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); + (void)statusType; } diff --git a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.cpp b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.cpp index 6b9132c22d..afb9349277 100644 --- a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.cpp +++ b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.cpp @@ -36,6 +36,8 @@ bool b3RobotSimulatorClientAPI_NoGUI::connect(int mode, const std::string& hostN b3PhysicsClientHandle sm = 0; int udpPort = 1234; int tcpPort = 6667; + (void)udpPort; + (void)tcpPort; int key = SHARED_MEMORY_KEY; switch (mode) @@ -59,14 +61,15 @@ bool b3RobotSimulatorClientAPI_NoGUI::connect(int mode, const std::string& hostN } case eCONNECT_UDP: { +#ifdef BT_ENABLE_ENET if (portOrKey >= 0) { udpPort = portOrKey; } -#ifdef BT_ENABLE_ENET sm = b3ConnectPhysicsUDP(hostName.c_str(), udpPort); #else + (void)hostName; b3Warning("UDP is not enabled in this build"); #endif //BT_ENABLE_ENET @@ -74,11 +77,11 @@ bool b3RobotSimulatorClientAPI_NoGUI::connect(int mode, const std::string& hostN } case eCONNECT_TCP: { +#ifdef BT_ENABLE_CLSOCKET if (portOrKey >= 0) { tcpPort = portOrKey; } -#ifdef BT_ENABLE_CLSOCKET sm = b3ConnectPhysicsTCP(hostName.c_str(), tcpPort); #else diff --git a/examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp b/examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp index 981b91caac..f5b87883ed 100644 --- a/examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp +++ b/examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp @@ -191,7 +191,7 @@ B3_SHARED_API struct b3PluginCollisionInterface* getCollisionInterface_collision return &obj->m_collisionFilter; } -B3_SHARED_API int executePluginCommand_collisionFilterPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments) +B3_SHARED_API int executePluginCommand_collisionFilterPlugin(struct b3PluginContext* /*context*/, const struct b3PluginArguments* /*arguments*/) { return 0; } diff --git a/examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp b/examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp index 5fa29e1374..385b1e7b81 100644 --- a/examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp +++ b/examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp @@ -56,7 +56,7 @@ B3_SHARED_API int preTickPluginCallback_pdControlPlugin(struct b3PluginContext* { const MyPDControl& pdControl = obj->m_controllers[i]; - int dof1 = 0; + // int dof1 = 0; b3JointSensorState actualState; if (obj->m_api.getJointState(pdControl.m_objectUniqueId, pdControl.m_linkIndex, &actualState)) { @@ -67,7 +67,7 @@ B3_SHARED_API int preTickPluginCallback_pdControlPlugin(struct b3PluginContext* btScalar qdActual = actualState.m_jointVelocity; btScalar positionError = (pdControl.m_desiredPosition - qActual); - double desiredVelocity = 0; + // double desiredVelocity = 0; btScalar velocityError = (pdControl.m_desiredVelocity - qdActual); btScalar force = pdControl.m_kp * positionError + pdControl.m_kd * velocityError; @@ -95,7 +95,7 @@ B3_SHARED_API int executePluginCommand_pdControlPlugin(struct b3PluginContext* c return -1; } - int numObj = obj->m_api.getNumBodies(); + // int numObj = obj->m_api.getNumBodies(); //printf("numObj = %d\n", numObj); //protocol: diff --git a/examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp b/examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp index cb6bacd330..dd763e3bad 100644 --- a/examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp +++ b/examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp @@ -191,7 +191,7 @@ bool btExtractJointBodyFromTempLinks(btAlignedObjectArray& links, Eige btVector3 jointAttachPointMy = links[j].m_eVector; - btVector3 jointAttachPointMyv0 = jointAttachPointMy; + // btVector3 jointAttachPointMyv0 = jointAttachPointMy; btVector3 parentBodyAttachPtMy(0, 0, 0); btQuaternion parentBodyToLink; parentBodyToLink = btQuaternion::getIdentity(); @@ -216,8 +216,8 @@ bool btExtractJointBodyFromTempLinks(btAlignedObjectArray& links, Eige } btQuaternion myparent_body_to_body(0, 0, 0, 1); btQuaternion mybody_to_parent_body(0, 0, 0, 1); - btQuaternion parent_body_to_body1 = links[i].m_zeroRotParentToThis; - btQuaternion body_to_parent_body1 = parent_body_to_body1.inverse(); + // btQuaternion parent_body_to_body1 = links[i].m_zeroRotParentToThis; + // btQuaternion body_to_parent_body1 = parent_body_to_body1.inverse(); bodyToLinkRotations[i] = body_to_this1; diff --git a/examples/SharedMemory/plugins/stablePDPlugin/KinTree.cpp b/examples/SharedMemory/plugins/stablePDPlugin/KinTree.cpp index 2aab569042..77f5f7027b 100644 --- a/examples/SharedMemory/plugins/stablePDPlugin/KinTree.cpp +++ b/examples/SharedMemory/plugins/stablePDPlugin/KinTree.cpp @@ -92,7 +92,7 @@ const std::string gDrawShapeDescKeys[cKinTree::eDrawShapeParamMax] = "MeshID" }; -int cKinTree::GetRoot(const Eigen::MatrixXd& joint_desc) +int cKinTree::GetRoot(const Eigen::MatrixXd& /*joint_desc*/) { // this should always be true right? return 0; @@ -721,10 +721,10 @@ int cKinTree::GetNumDof(const Eigen::MatrixXd& joint_mat) return num_dof; } -void cKinTree::ApplyStep(const Eigen::MatrixXd& joint_mat, const Eigen::VectorXd& step, Eigen::VectorXd& out_pose) +void cKinTree::ApplyStep(const Eigen::MatrixXd& /*joint_mat*/, const Eigen::VectorXd& step, Eigen::VectorXd& out_pose) { - int root_id = GetRoot(joint_mat); - int num_joints = cKinTree::GetNumJoints(joint_mat); + // int root_id = GetRoot(joint_mat); + // int num_joints = cKinTree::GetNumJoints(joint_mat); out_pose += step; } @@ -1610,8 +1610,8 @@ void cKinTree::PostProcessPose(const Eigen::MatrixXd& joint_mat, Eigen::VectorXd void cKinTree::LerpPoses(const Eigen::MatrixXd& joint_mat, const Eigen::VectorXd& pose0, const Eigen::VectorXd& pose1, double lerp, Eigen::VectorXd& out_pose) { int num_joints = GetNumJoints(joint_mat); - int root_id = GetRoot(joint_mat); - int root_offset = GetParamOffset(joint_mat, root_id); + // int root_id = GetRoot(joint_mat); + // int root_offset = GetParamOffset(joint_mat, root_id); out_pose.resize(pose0.size()); assert(pose0.size() == pose1.size()); @@ -1657,8 +1657,8 @@ void cKinTree::VelToPoseDiff(const Eigen::MatrixXd& joint_mat, const Eigen::Vect out_pose_diff = vel; int num_joints = GetNumJoints(joint_mat); - int root_id = GetRoot(joint_mat); - int root_offset = GetParamOffset(joint_mat, root_id); + // int root_id = GetRoot(joint_mat); + // int root_offset = GetParamOffset(joint_mat, root_id); tVector root_rot_vel = GetRootAngVel(joint_mat, vel); root_rot_vel[3] = 0; @@ -1813,7 +1813,7 @@ tMatrix cKinTree::ChildParentTransPlanar(const Eigen::MatrixXd& joint_mat, const return mat; } -tMatrix cKinTree::ChildParentTransFixed(const Eigen::MatrixXd& joint_mat, const Eigen::VectorXd& state, int joint_id) +tMatrix cKinTree::ChildParentTransFixed(const Eigen::MatrixXd& joint_mat, const Eigen::VectorXd& /*state*/, int joint_id) { tMatrix A = BuildAttachTrans(joint_mat, joint_id); tMatrix mat = A; @@ -1848,7 +1848,7 @@ tMatrix cKinTree::ChildParentTransSpherical(const Eigen::MatrixXd& joint_mat, co -void cKinTree::BuildDefaultPoseRoot(const Eigen::MatrixXd& joint_mat, Eigen::VectorXd& out_pose) +void cKinTree::BuildDefaultPoseRoot(const Eigen::MatrixXd& /*joint_mat*/, Eigen::VectorXd& out_pose) { int dim = gRootDim; out_pose = Eigen::VectorXd::Zero(dim); @@ -1887,7 +1887,7 @@ void cKinTree::BuildDefaultPoseSpherical(Eigen::VectorXd& out_pose) } -void cKinTree::BuildDefaultVelRoot(const Eigen::MatrixXd& joint_mat, Eigen::VectorXd& out_pose) +void cKinTree::BuildDefaultVelRoot(const Eigen::MatrixXd& /*joint_mat*/, Eigen::VectorXd& out_pose) { int dim = gRootDim; out_pose = Eigen::VectorXd::Zero(dim); diff --git a/examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp b/examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp index a2a93cec03..ec8919152b 100644 --- a/examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp +++ b/examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp @@ -30,6 +30,7 @@ void cRBDUtil::SolveInvDyna(const cRBDModel& model, const Eigen::VectorXd& acc, { cSpAlg::tSpTrans parent_child_trans = model.GetSpParentChildTrans(j); cSpAlg::tSpTrans world_child_trans = model.GetSpWorldJointTrans(j); + (void)world_child_trans; const Eigen::Block S = model.GetJointSubspace(j); @@ -128,7 +129,7 @@ void cRBDUtil::BuildMassMat(const cRBDModel& model, Eigen::MatrixXd& inertia_buf // use composite-rigid-body algorithm const Eigen::MatrixXd& joint_mat = model.GetJointMat(); const Eigen::MatrixXd& body_defs = model.GetBodyDefs(); - const Eigen::VectorXd& pose = model.GetPose(); + const Eigen::VectorXd& pose = model.GetPose(); (void)pose; Eigen::MatrixXd& H = out_mass_mat; int dim = model.GetNumDof(); @@ -162,6 +163,7 @@ void cRBDUtil::BuildMassMat(const cRBDModel& model, Eigen::MatrixXd& inertia_buf if (cKinTree::HasParent(joint_mat, j)) { cSpAlg::tSpTrans child_parent_trans = model.GetSpChildParentTrans(j); + (void)child_parent_trans; cSpAlg::tSpMat child_parent_mat = child_parent_mats_F.block(j * svs, 0, svs, svs); cSpAlg::tSpMat parent_child_mat = parent_child_mats_M.block(j * svs, 0, svs, svs); Is.block(parent_id * svs, 0, svs, svs) += child_parent_mat * curr_I * parent_child_mat; @@ -201,7 +203,7 @@ void cRBDUtil::BuildEndEffectorJacobian(const cRBDModel& model, int joint_id, Ei { // jacobian in world coordinates const Eigen::MatrixXd& joint_mat = model.GetJointMat(); - const Eigen::VectorXd& pose = model.GetPose(); + const Eigen::VectorXd& pose = model.GetPose(); (void)pose; int num_dofs = cKinTree::GetNumDof(joint_mat); out_J = Eigen::MatrixXd::Zero(gSpVecSize, num_dofs); @@ -273,7 +275,7 @@ Eigen::MatrixXd cRBDUtil::MultJacobianEndEff(const Eigen::MatrixXd& joint_mat, c void cRBDUtil::BuildJacobian(const cRBDModel& model, Eigen::MatrixXd& out_J) { const Eigen::MatrixXd& joint_mat = model.GetJointMat(); - const Eigen::VectorXd& pose = model.GetPose(); + const Eigen::VectorXd& pose = model.GetPose(); (void)pose; int num_dofs = model.GetNumDof(); out_J = Eigen::MatrixXd::Zero(gSpVecSize, num_dofs); @@ -312,9 +314,9 @@ Eigen::MatrixXd cRBDUtil::ExtractEndEffJacobian(const Eigen::MatrixXd& joint_mat void cRBDUtil::BuildCOMJacobian(const cRBDModel& model, Eigen::MatrixXd& out_J) { // coord frame for jacobian has origin at the com - const Eigen::MatrixXd& joint_mat = model.GetJointMat(); - const Eigen::MatrixXd& body_defs = model.GetBodyDefs(); - const Eigen::VectorXd& pose = model.GetPose(); + const Eigen::MatrixXd& joint_mat = model.GetJointMat(); (void)joint_mat; + const Eigen::MatrixXd& body_defs = model.GetBodyDefs(); (void)body_defs; + // const Eigen::VectorXd& pose = model.GetPose(); Eigen::MatrixXd J; BuildJacobian(model, J); @@ -368,7 +370,7 @@ void cRBDUtil::BuildJacobianDot(const cRBDModel& model, Eigen::MatrixXd& out_J_d { // for comput the velocity product acceleration const Eigen::MatrixXd& joint_mat = model.GetJointMat(); - const Eigen::VectorXd& pose = model.GetPose(); + // const Eigen::VectorXd& pose = model.GetPose(); const Eigen::VectorXd& vel = model.GetVel(); int num_dofs = cKinTree::GetNumDof(joint_mat); @@ -410,12 +412,12 @@ cSpAlg::tSpVec cRBDUtil::BuildCOMVelProdAccAux(const cRBDModel& model, const Eig { const Eigen::MatrixXd& joint_mat = model.GetJointMat(); const Eigen::MatrixXd& body_defs = model.GetBodyDefs(); - const Eigen::VectorXd& pose = model.GetPose(); - const Eigen::VectorXd& vel = model.GetVel(); - const tVector& gravity = model.GetGravity(); + const Eigen::VectorXd& pose = model.GetPose(); (void)pose; + const Eigen::VectorXd& vel = model.GetVel(); (void)vel; + // const tVector& gravity = model.GetGravity(); // coord frame origin at com - int num_dofs = cKinTree::GetNumDof(joint_mat); + int num_dofs = cKinTree::GetNumDof(joint_mat); (void)num_dofs; int num_joints = cKinTree::GetNumJoints(joint_mat); double total_mass = cKinTree::CalcTotalMass(body_defs); @@ -527,8 +529,8 @@ void cRBDUtil::CalcCoM(const cRBDModel& model, tVector& out_com, tVector& out_ve { const Eigen::MatrixXd& joint_mat = model.GetJointMat(); const Eigen::MatrixXd& body_defs = model.GetBodyDefs(); - const Eigen::VectorXd& pose = model.GetPose(); - const Eigen::VectorXd& vel = model.GetVel(); + const Eigen::VectorXd& pose = model.GetPose(); (void)pose; + const Eigen::VectorXd& vel = model.GetVel(); (void)vel; int num_joints = cKinTree::GetNumJoints(joint_mat); out_com.setZero(); @@ -724,8 +726,8 @@ cSpAlg::tSpMat cRBDUtil::BuildMomentInertiaCylinder(const Eigen::MatrixXd& body_ double r = 0.5 * def(cKinTree::eBodyParam0); double h = def(cKinTree::eBodyParam1); - double c_vol = M_PI * r * r * h; - double hs_vol = M_PI * 2.0 / 3.0 * r * r * r; + // double c_vol = M_PI * r * r * h; + // double hs_vol = M_PI * 2.0 / 3.0 * r * r * r; double x = mass / 12 * (3 * r * r + h * h); double y = mass * r * r / 2; @@ -754,7 +756,7 @@ cSpAlg::tSpMat cRBDUtil::BuildInertiaSpatialMat(const Eigen::MatrixXd& body_defs void cRBDUtil::CalcWorldJointTransforms(const cRBDModel& model, Eigen::MatrixXd& out_trans_arr) { const Eigen::MatrixXd& joint_mat = model.GetJointMat(); - const Eigen::VectorXd& pose = model.GetPose(); + const Eigen::VectorXd& pose = model.GetPose(); (void)pose; int num_joints = cKinTree::GetNumJoints(joint_mat); out_trans_arr.resize(num_joints * gSVTransRows, gSVTransCols); @@ -851,7 +853,7 @@ Eigen::MatrixXd cRBDUtil::BuildJointSubspaceRoot(const Eigen::MatrixXd& joint_ma return S; } -Eigen::MatrixXd cRBDUtil::BuildJointSubspaceRevolute(const Eigen::MatrixXd& joint_mat, const Eigen::VectorXd& pose, int j) +Eigen::MatrixXd cRBDUtil::BuildJointSubspaceRevolute(const Eigen::MatrixXd& /*joint_mat*/, const Eigen::VectorXd& /*pose*/, int /*j*/) { int dim = cKinTree::GetJointParamSize(cKinTree::eJointTypeRevolute); Eigen::MatrixXd S = Eigen::MatrixXd::Zero(gSpVecSize, dim); @@ -859,7 +861,7 @@ Eigen::MatrixXd cRBDUtil::BuildJointSubspaceRevolute(const Eigen::MatrixXd& join return S; } -Eigen::MatrixXd cRBDUtil::BuildJointSubspacePrismatic(const Eigen::MatrixXd& joint_mat, const Eigen::VectorXd& pose, int j) +Eigen::MatrixXd cRBDUtil::BuildJointSubspacePrismatic(const Eigen::MatrixXd& /*joint_mat*/, const Eigen::VectorXd& /*pose*/, int /*j*/) { int dim = cKinTree::GetJointParamSize(cKinTree::eJointTypePrismatic); Eigen::MatrixXd S = Eigen::MatrixXd::Zero(gSpVecSize, dim); @@ -868,7 +870,7 @@ Eigen::MatrixXd cRBDUtil::BuildJointSubspacePrismatic(const Eigen::MatrixXd& joi return S; } -Eigen::MatrixXd cRBDUtil::BuildJointSubspacePlanar(const Eigen::MatrixXd& joint_mat, const Eigen::VectorXd& pose, int j) +Eigen::MatrixXd cRBDUtil::BuildJointSubspacePlanar(const Eigen::MatrixXd& /*joint_mat*/, const Eigen::VectorXd& /*pose*/, int /*j*/) { int dim = cKinTree::GetJointParamSize(cKinTree::eJointTypePlanar); Eigen::MatrixXd S = Eigen::MatrixXd::Zero(gSpVecSize, dim); @@ -878,14 +880,14 @@ Eigen::MatrixXd cRBDUtil::BuildJointSubspacePlanar(const Eigen::MatrixXd& joint_ return S; } -Eigen::MatrixXd cRBDUtil::BuildJointSubspaceFixed(const Eigen::MatrixXd& joint_mat, const Eigen::VectorXd& pose, int j) +Eigen::MatrixXd cRBDUtil::BuildJointSubspaceFixed(const Eigen::MatrixXd& /*joint_mat*/, const Eigen::VectorXd& /*pose*/, int /*j*/) { int dim = cKinTree::GetJointParamSize(cKinTree::eJointTypeFixed); Eigen::MatrixXd S = Eigen::MatrixXd::Zero(gSpVecSize, dim); return S; } -Eigen::MatrixXd cRBDUtil::BuildJointSubspaceSpherical(const Eigen::MatrixXd& joint_mat, const Eigen::VectorXd& pose, int j) +Eigen::MatrixXd cRBDUtil::BuildJointSubspaceSpherical(const Eigen::MatrixXd& /*joint_mat*/, const Eigen::VectorXd& /*pose*/, int /*j*/) { int dim = cKinTree::GetJointParamSize(cKinTree::eJointTypeSpherical); Eigen::MatrixXd S = Eigen::MatrixXd::Zero(gSpVecSize, dim); @@ -972,27 +974,27 @@ cSpAlg::tSpVec cRBDUtil::BuildCjRoot(const Eigen::MatrixXd& joint_mat, const Eig return cj; } -cSpAlg::tSpVec cRBDUtil::BuildCjRevolute(const Eigen::MatrixXd& joint_mat, const Eigen::VectorXd& q_dot, int j) +cSpAlg::tSpVec cRBDUtil::BuildCjRevolute(const Eigen::MatrixXd& /*joint_mat*/, const Eigen::VectorXd& /*q_dot*/, int /*j*/) { return cSpAlg::tSpVec::Zero(); } -cSpAlg::tSpVec cRBDUtil::BuildCjPrismatic(const Eigen::MatrixXd& joint_mat, const Eigen::VectorXd& q_dot, int j) +cSpAlg::tSpVec cRBDUtil::BuildCjPrismatic(const Eigen::MatrixXd& /*joint_mat*/, const Eigen::VectorXd& /*q_dot*/, int /*j*/) { return cSpAlg::tSpVec::Zero(); } -cSpAlg::tSpVec cRBDUtil::BuildCjPlanar(const Eigen::MatrixXd& joint_mat, const Eigen::VectorXd& q_dot, int j) +cSpAlg::tSpVec cRBDUtil::BuildCjPlanar(const Eigen::MatrixXd& /*joint_mat*/, const Eigen::VectorXd& /*q_dot*/, int /*j*/) { return cSpAlg::tSpVec::Zero(); } -cSpAlg::tSpVec cRBDUtil::BuildCjFixed(const Eigen::MatrixXd& joint_mat, const Eigen::VectorXd& q_dot, int j) +cSpAlg::tSpVec cRBDUtil::BuildCjFixed(const Eigen::MatrixXd& /*joint_mat*/, const Eigen::VectorXd& /*q_dot*/, int /*j*/) { return cSpAlg::tSpVec::Zero(); } -cSpAlg::tSpVec cRBDUtil::BuildCjSpherical(const Eigen::MatrixXd& joint_mat, const Eigen::VectorXd& q_dot, int j) +cSpAlg::tSpVec cRBDUtil::BuildCjSpherical(const Eigen::MatrixXd& /*joint_mat*/, const Eigen::VectorXd& /*q_dot*/, int /*j*/) { return cSpAlg::tSpVec::Zero(); } diff --git a/examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp index 9cd3811c0f..8d534c43f0 100644 --- a/examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp @@ -185,7 +185,7 @@ void TinyRendererVisualShapeConverter::setLightSpecularCoeff(float specularCoeff m_data->m_hasLightSpecularCoeff = true; } -static void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray& verticesOut, btAlignedObjectArray& indicesOut, btAlignedObjectArray& texturesOut, b3VisualShapeData& visualShapeOut, struct CommonFileIOInterface* fileIO, int flags) +static void convertURDFToVisualShape(const UrdfShape* visual, const char* /*urdfPathPrefix*/, const btTransform& visualTransform, btAlignedObjectArray& verticesOut, btAlignedObjectArray& indicesOut, btAlignedObjectArray& texturesOut, b3VisualShapeData& visualShapeOut, struct CommonFileIOInterface* fileIO, int flags) { visualShapeOut.m_visualGeometryType = visual->m_geometry.m_type; visualShapeOut.m_dimensions[0] = 0; @@ -923,13 +923,13 @@ int TinyRendererVisualShapeConverter::convertVisualShapes( unsigned char* textureImage1 = 0; int textureWidth = 0; int textureHeight = 0; - bool isCached = false; + // bool isCached = false; if (textures.size()) { textureImage1 = textures[0].textureData1; textureWidth = textures[0].m_width; textureHeight = textures[0].m_height; - isCached = textures[0].m_isCached; + // isCached = textures[0].m_isCached; } { @@ -960,7 +960,7 @@ int TinyRendererVisualShapeConverter::convertVisualShapes( return uniqueId; } -int TinyRendererVisualShapeConverter::registerShapeAndInstance( const b3VisualShapeData& visualShape, const float* vertices, int numvertices, const int* indices, int numIndices, int primitiveType, int textureId, int orgGraphicsUniqueId, int bodyUniqueId, int linkIndex) +int TinyRendererVisualShapeConverter::registerShapeAndInstance( const b3VisualShapeData& visualShape, const float* vertices, int numvertices, const int* indices, int numIndices, int /*primitiveType*/, int textureId, int orgGraphicsUniqueId, int bodyUniqueId, int linkIndex) { btAlignedObjectArray* shapes1 = m_data->m_visualShapesMap[bodyUniqueId]; @@ -1084,7 +1084,6 @@ void TinyRendererVisualShapeConverter::changeInstanceFlags(int bodyUniqueId, int { return; } - int start = -1; for (int i = 0; i < m_data->m_swRenderInstances.size(); i++) { @@ -1114,7 +1113,7 @@ void TinyRendererVisualShapeConverter::changeRGBAColor(int bodyUniqueId, int lin { return; } - int start = -1; + for (int i = 0; i < shapes->size(); i++) { if (shapes->at(i).m_linkIndex == linkIndex) @@ -1384,8 +1383,8 @@ void TinyRendererVisualShapeConverter::setWidthAndHeight(int width, int height) } void TinyRendererVisualShapeConverter::copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, - float* depthBuffer, int depthBufferSizeInPixels, - int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, + float* depthBuffer, int /*depthBufferSizeInPixels*/, + int* segmentationMaskBuffer, int /*segmentationMaskSizeInPixels*/, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied) { int w = m_data->m_rgbColorBuffer.get_width(); diff --git a/examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp b/examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp index 013314380b..9e4ccf9b77 100644 --- a/examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp +++ b/examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp @@ -43,7 +43,7 @@ B3_SHARED_API int initPlugin_tinyRendererPlugin(struct b3PluginContext* context) return SHARED_MEMORY_MAGIC_NUMBER; } -B3_SHARED_API int executePluginCommand_tinyRendererPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments) +B3_SHARED_API int executePluginCommand_tinyRendererPlugin(struct b3PluginContext* context, const struct b3PluginArguments* /*arguments*/) { MyRendererPluginClass* obj = (MyRendererPluginClass*)context->m_userPointer; if (obj->m_returnData==0) diff --git a/examples/SoftDemo/SoftDemo.cpp b/examples/SoftDemo/SoftDemo.cpp index 7d65000d8f..772c9074cb 100644 --- a/examples/SoftDemo/SoftDemo.cpp +++ b/examples/SoftDemo/SoftDemo.cpp @@ -265,6 +265,7 @@ void SoftDemo::createStack(btCollisionShape* boxShape, float halfCubeSize, int s btRigidBody* body = 0; body = createRigidBody(mass, trans, boxShape); + (void)body; } } } @@ -424,7 +425,7 @@ static btRigidBody* Ctor_BigPlate(SoftDemo* pdemo, btScalar mass = 15, btScalar // // Linear stair // -static void Ctor_LinearStair(SoftDemo* pdemo, const btVector3& org, const btVector3& sizes, btScalar angle, int count) +static void Ctor_LinearStair(SoftDemo* pdemo, const btVector3& org, const btVector3& sizes, btScalar /*angle*/, int count) { btBoxShape* shape = new btBoxShape(sizes); for (int i = 0; i < count; ++i) @@ -461,7 +462,7 @@ static btSoftBody* Ctor_SoftBox(SoftDemo* pdemo, const btVector3& p, const btVec // // SoftBoulder // -static btSoftBody* Ctor_SoftBoulder(SoftDemo* pdemo, const btVector3& p, const btVector3& s, int np, int id) +/*static btSoftBody* Ctor_SoftBoulder(SoftDemo* pdemo, const btVector3& p, const btVector3& s, int np, int id) { btAlignedObjectArray pts; if (id) srand(id); @@ -474,7 +475,7 @@ static btSoftBody* Ctor_SoftBoulder(SoftDemo* pdemo, const btVector3& p, const b pdemo->getSoftDynamicsWorld()->addSoftBody(psb); return (psb); -} +}*/ //#define TRACEDEMO { pdemo->demoname=__FUNCTION__+5;printf("Launching demo: " __FUNCTION__ "\r\n"); } @@ -912,7 +913,7 @@ static void Init_Sticks(SoftDemo* pdemo) // // Bending // -static void Init_Bending(SoftDemo* pdemo) +/*static void Init_Bending(SoftDemo* pdemo) { //TRACEDEMO const btScalar s = 4; @@ -929,7 +930,7 @@ static void Init_Bending(SoftDemo* pdemo) psb->appendLink(0, 2); pdemo->getSoftDynamicsWorld()->addSoftBody(psb); -} +}*/ // // 100kg cloth locked at corners, 10 falling 10kg rb's. @@ -1064,7 +1065,7 @@ static void Init_Cutting1(SoftDemo* pdemo) // // -static void Ctor_Gear(SoftDemo* pdemo, const btVector3& pos, btScalar speed) +/*static void Ctor_Gear(SoftDemo* pdemo, const btVector3& pos, btScalar speed) { btTransform startTransform; startTransform.setIdentity(); @@ -1083,7 +1084,7 @@ static void Ctor_Gear(SoftDemo* pdemo, const btVector3& pos, btScalar speed) btHingeConstraint* hinge = new btHingeConstraint(*body, btTransform::getIdentity()); if (speed != 0) hinge->enableAngularMotor(true, speed, 3); world->addConstraint(hinge); -} +}*/ // static btSoftBody* Ctor_ClusterBunny(SoftDemo* pdemo, const btVector3& x, const btVector3& a) @@ -1414,6 +1415,7 @@ static void Init_ClusterRobot(SoftDemo* pdemo) btBoxShape* pbox = new btBoxShape(btVector3(20, 1, 40)); btRigidBody* pgrn; pgrn = pdemo->createRigidBody(0, btTransform(btQuaternion(0, -SIMD_HALF_PI / 2, 0), btVector3(0, 0, 0)), pbox); + (void)pgrn; pdemo->m_autocam = true; } diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index 0f60543bab..c8a3844754 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -260,6 +260,8 @@ class CMainApplication CMainApplication::CMainApplication(int argc, char *argv[]) : m_app(NULL), m_hasContext(false), m_nWindowWidth(1280), m_nWindowHeight(720), m_unSceneProgramID(0), m_unLensProgramID(0), m_unControllerTransformProgramID(0), m_unRenderModelProgramID(0), m_pHMD(NULL), m_pRenderModels(NULL), m_bDebugOpenGL(false), m_bVerbose(false), m_bPerf(false), m_bVblank(false), m_bGlFinishHack(true), m_glControllerVertBuffer(0), m_unControllerVAO(0), m_unLensVAO(0), m_unSceneVAO(0), m_nSceneMatrixLocation(-1), m_nControllerMatrixLocation(-1), m_nRenderModelMatrixLocation(-1), m_iTrackedControllerCount(0), m_iTrackedControllerCount_Last(-1), m_iValidPoseCount(0), m_iValidPoseCount_Last(-1), m_iSceneVolumeInit(20), m_strPoseClasses(""), m_bShowCubes(false) { + (void)m_bPerf; + for (int i = 1; i < argc; i++) { if (!stricmp(argv[i], "-gldebug")) @@ -582,7 +584,7 @@ bool CMainApplication::BInitGL() //----------------------------------------------------------------------------- bool CMainApplication::BInitCompositor() { - vr::EVRInitError peError = vr::VRInitError_None; + // vr::EVRInitError peError = vr::VRInitError_None; if (!vr::VRCompositor()) { diff --git a/examples/ThirdPartyLibs/BussIK/MathMisc.h b/examples/ThirdPartyLibs/BussIK/MathMisc.h index c5d157158a..620af548c4 100644 --- a/examples/ThirdPartyLibs/BussIK/MathMisc.h +++ b/examples/ThirdPartyLibs/BussIK/MathMisc.h @@ -66,7 +66,7 @@ const double LnTwoInv = 1.0 / log(2.0); const double OnePlusEpsilon15 = 1.0 + 1.0e-15; const double OneMinusEpsilon15 = 1.0 - 1.0e-15; -inline double ZeroValue(const double& x) +inline double ZeroValue(const double& /*x*/) { return 0.0; } diff --git a/examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp b/examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp index 5a864d3184..5e5aa3c4a9 100644 --- a/examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp +++ b/examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp @@ -906,7 +906,7 @@ void MatrixRmn::ConvertBidiagToDiagonal(MatrixRmn& U, MatrixRmn& V, VectorRn& w, // We use Givens rotations to "chase" the non-zero entry across the row; when it reaches the last // column, it is finally zeroed away. // wPtr points to the zero entry on the diagonal. sdPtr points to the non-zero superdiagonal entry on the same row. -void MatrixRmn::ClearRowWithDiagonalZero(long firstBidiagIdx, long lastBidiagIdx, MatrixRmn& U, double* wPtr, double* sdPtr, double eps) +void MatrixRmn::ClearRowWithDiagonalZero(long firstBidiagIdx, long lastBidiagIdx, MatrixRmn& U, double* wPtr, double* sdPtr, double /*eps*/) { double curSd = *sdPtr; // Value being chased across the row *sdPtr = 0.0; diff --git a/examples/ThirdPartyLibs/Gwen/BaseRender.h b/examples/ThirdPartyLibs/Gwen/BaseRender.h index f96ed70099..453ac1d7f9 100644 --- a/examples/ThirdPartyLibs/Gwen/BaseRender.h +++ b/examples/ThirdPartyLibs/Gwen/BaseRender.h @@ -41,24 +41,29 @@ class GWEN_EXPORT Base virtual void Begin(){}; virtual void End(){}; - virtual void SetDrawColor(Color color){}; + virtual void SetDrawColor(Color /*color*/){}; + + virtual void DrawLine(int /*x*/, int /*y*/, int /*a*/, int /*b*/){}; + virtual void DrawFilledRect(Gwen::Rect /*rect*/){}; - virtual void DrawLine(int x, int y, int a, int b){}; - virtual void DrawFilledRect(Gwen::Rect rect){}; - ; virtual void StartClip(){}; virtual void EndClip(){}; - virtual void LoadTexture(Gwen::Texture* pTexture){}; - virtual void FreeTexture(Gwen::Texture* pTexture){}; - virtual void DrawTexturedRect(Gwen::Texture* pTexture, Gwen::Rect pTargetRect, float u1 = 0.0f, float v1 = 0.0f, float u2 = 1.0f, float v2 = 1.0f){}; + virtual void LoadTexture(Gwen::Texture* /*pTexture*/){}; + virtual void FreeTexture(Gwen::Texture* /*pTexture*/){}; + virtual void DrawTexturedRect(Gwen::Texture* /*pTexture*/, Gwen::Rect /*pTargetRect*/, float u1 = 0.0f, float v1 = 0.0f, float u2 = 1.0f, float v2 = 1.0f){ + (void)u1; + (void)v1; + (void)u2; + (void)v2; + }; virtual void DrawMissingImage(Gwen::Rect pTargetRect); virtual ICacheToTexture* GetCTT() { return NULL; } - virtual void LoadFont(Gwen::Font* pFont){}; - virtual void FreeFont(Gwen::Font* pFont){}; + virtual void LoadFont(Gwen::Font* /*pFont*/){}; + virtual void FreeFont(Gwen::Font* /*pFont*/){}; virtual void RenderText(Gwen::Font* pFont, Gwen::Point pos, const Gwen::UnicodeString& text); virtual Gwen::Point MeasureText(Gwen::Font* pFont, const Gwen::UnicodeString& text); diff --git a/examples/ThirdPartyLibs/Gwen/Controls/Base.cpp b/examples/ThirdPartyLibs/Gwen/Controls/Base.cpp index 19cf8ac1b9..effbb2da2e 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/Base.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/Base.cpp @@ -718,7 +718,7 @@ void Base::RecurseLayout(Skin::Base* skin) { // printf("!\n"); } - int curChild = 0; + int curChild = 0; (void)curChild; for (Base::List::iterator iter = Children.begin(); iter != Children.end(); ++iter) { Base* pChild = *iter; diff --git a/examples/ThirdPartyLibs/Gwen/Controls/Button.h b/examples/ThirdPartyLibs/Gwen/Controls/Button.h index 135d06bcaf..8b37b8bbf2 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/Button.h +++ b/examples/ThirdPartyLibs/Gwen/Controls/Button.h @@ -55,7 +55,7 @@ class GWEN_EXPORT Button : public Label virtual void SizeToContents(); virtual void Layout(Skin::Base* pSkin); - virtual bool OnKeyReturn(bool bDown) + virtual bool OnKeyReturn(bool /*bDown*/) { onKeyboardReturn.Call(this); return true; diff --git a/examples/ThirdPartyLibs/Gwen/Controls/TabControl.cpp b/examples/ThirdPartyLibs/Gwen/Controls/TabControl.cpp index 6a2d79b582..a7d586e381 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/TabControl.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/TabControl.cpp @@ -230,12 +230,12 @@ void TabControl::HandleOverflow() m_pScroll[1]->SetPos(m_pScroll[0]->Right(), 5); } -void TabControl::ScrollPressLeft(Base* pFrom) +void TabControl::ScrollPressLeft(Base* /*pFrom*/) { m_iScrollOffset -= 120; } -void TabControl::ScrollPressRight(Base* pFrom) +void TabControl::ScrollPressRight(Base* /*pFrom*/) { m_iScrollOffset += 120; } \ No newline at end of file diff --git a/examples/ThirdPartyLibs/Gwen/Platforms/Null.cpp b/examples/ThirdPartyLibs/Gwen/Platforms/Null.cpp index a47f234548..73aeffcc34 100644 --- a/examples/ThirdPartyLibs/Gwen/Platforms/Null.cpp +++ b/examples/ThirdPartyLibs/Gwen/Platforms/Null.cpp @@ -13,7 +13,7 @@ static Gwen::UnicodeString gs_ClipboardEmulator; -void Gwen::Platform::SetCursor(unsigned char iCursor) +void Gwen::Platform::SetCursor(unsigned char /*iCursor*/) { // No platform independent way to do this } @@ -35,7 +35,7 @@ float Gwen::Platform::GetTimeInSeconds() return fSeconds; } -bool Gwen::Platform::FileOpen(const String& Name, const String& StartPath, const String& Extension, Gwen::Event::Handler* pHandler, Event::Handler::FunctionStr fnCallback) +bool Gwen::Platform::FileOpen(const String& /*Name*/, const String& /*StartPath*/, const String& /*Extension*/, Gwen::Event::Handler* /*pHandler*/, Event::Handler::FunctionStr /*fnCallback*/) { // No platform independent way to do this. // Ideally you would open a system dialog here @@ -43,7 +43,7 @@ bool Gwen::Platform::FileOpen(const String& Name, const String& StartPath, const return false; } -bool Gwen::Platform::FileSave(const String& Name, const String& StartPath, const String& Extension, Gwen::Event::Handler* pHandler, Gwen::Event::Handler::FunctionStr fnCallback) +bool Gwen::Platform::FileSave(const String& /*Name*/, const String& /*StartPath*/, const String& /*Extension*/, Gwen::Event::Handler* /*pHandler*/, Gwen::Event::Handler::FunctionStr /*fnCallback*/) { // No platform independent way to do this. // Ideally you would open a system dialog here diff --git a/examples/ThirdPartyLibs/Gwen/Renderers/OpenGL_DebugFont.h b/examples/ThirdPartyLibs/Gwen/Renderers/OpenGL_DebugFont.h index 9da60f58c7..f5ffe20ca8 100644 --- a/examples/ThirdPartyLibs/Gwen/Renderers/OpenGL_DebugFont.h +++ b/examples/ThirdPartyLibs/Gwen/Renderers/OpenGL_DebugFont.h @@ -50,7 +50,7 @@ class OpenGL_DebugFont : public Gwen::Renderer::Base void Flush(); void AddVert(int x, int y, float u = 0.0f, float v = 0.0f); - virtual void Resize(int width, int height) {} + virtual void Resize(int /*width*/, int /*height*/) {} protected: Gwen::Texture* m_pFontTexture; diff --git a/examples/ThirdPartyLibs/Gwen/Skins/Simple.h b/examples/ThirdPartyLibs/Gwen/Skins/Simple.h index d9c71c20de..70633d9f45 100644 --- a/examples/ThirdPartyLibs/Gwen/Skins/Simple.h +++ b/examples/ThirdPartyLibs/Gwen/Skins/Simple.h @@ -171,7 +171,7 @@ class Simple : public Gwen::Skin::Base m_Render->DrawShavedCornerRect(Gwen::Rect(0, 0, w, h), bSquared); } - virtual void DrawRadioButton(Gwen::Controls::Base* control, bool bSelected, bool bDepressed) + virtual void DrawRadioButton(Gwen::Controls::Base* control, bool bSelected, bool /*bDepressed*/) { Gwen::Rect rect = control->GetRenderBounds(); @@ -403,7 +403,7 @@ class Simple : public Gwen::Skin::Base m_Render->DrawFilledRect(rect); } - virtual void DrawScrollBar(Gwen::Controls::Base* control, bool isHorizontal, bool bDepressed) + virtual void DrawScrollBar(Gwen::Controls::Base* control, bool /*isHorizontal*/, bool bDepressed) { Gwen::Rect rect = control->GetRenderBounds(); if (bDepressed) @@ -413,7 +413,7 @@ class Simple : public Gwen::Skin::Base m_Render->DrawFilledRect(rect); } - virtual void DrawScrollBarBar(Controls::Base* control, bool bDepressed, bool isHovered, bool isHorizontal) + virtual void DrawScrollBarBar(Controls::Base* control, bool bDepressed, bool isHovered, bool /*isHorizontal*/) { //TODO: something specialized DrawButton(control, bDepressed, isHovered); @@ -500,7 +500,7 @@ class Simple : public Gwen::Skin::Base } } - virtual void DrawSlider(Gwen::Controls::Base* control, bool bIsHorizontal, int numNotches, int barSize) + virtual void DrawSlider(Gwen::Controls::Base* control, bool bIsHorizontal, int /*numNotches*/, int /*barSize*/) { Gwen::Rect rect = control->GetRenderBounds(); // Gwen::Rect notchRect = rect; @@ -537,7 +537,7 @@ class Simple : public Gwen::Skin::Base m_Render->DrawLinedRect(rect); } - virtual void DrawKeyboardHighlight(Gwen::Controls::Base* control, const Gwen::Rect& r, int iOffset) + virtual void DrawKeyboardHighlight(Gwen::Controls::Base* /*control*/, const Gwen::Rect& r, int iOffset) { Gwen::Rect rect = r; @@ -606,7 +606,7 @@ class Simple : public Gwen::Skin::Base DrawArrowRight(r); } - virtual void DrawComboBoxButton(Gwen::Controls::Base* control, bool bDepressed) + virtual void DrawComboBoxButton(Gwen::Controls::Base* control, bool /*bDepressed*/) { //DrawButton( control->Width(), control->Height(), bDepressed, false, true ); @@ -616,7 +616,7 @@ class Simple : public Gwen::Skin::Base DrawArrowDown(r); } - virtual void DrawNumericUpDownButton(Gwen::Controls::Base* control, bool bDepressed, bool bUp) + virtual void DrawNumericUpDownButton(Gwen::Controls::Base* control, bool /*bDepressed*/, bool bUp) { //DrawButton( control->Width(), control->Height(), bDepressed, false, true ); @@ -663,7 +663,7 @@ class Simple : public Gwen::Skin::Base m_Render->DrawLinedRect(rect); } - void DrawTreeNode(Controls::Base* ctrl, bool bOpen, bool bSelected, int iLabelHeight, int iLabelWidth, int iHalfWay, int iLastBranch, bool bIsRoot) + void DrawTreeNode(Controls::Base* /*ctrl*/, bool bOpen, bool bSelected, int iLabelHeight, int iLabelWidth, int iHalfWay, int iLastBranch, bool bIsRoot) { if (bSelected) { diff --git a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp index 3ad7a6f0ab..8e92be5d88 100644 --- a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp +++ b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp @@ -210,7 +210,7 @@ static bool parseTriple(const char** token, int vsize, int vnsize, int vtsize, static bool exportFaceGroupToShape(shape_t* shape, const std::vector& face_group, const material_t material, const std::string& name, - const std::vector& v) + const std::vector& /*v*/) { if (face_group.empty()) { @@ -268,7 +268,7 @@ static bool exportFaceGroupToShape(shape_t* shape, const std::vector& fa for (size_t k = 0; k < 3; k++) { ind[k] = remainingFace[(guess_vert + k) % npolys]; - size_t vi = size_t(ind[k].v_idx); + // size_t vi = size_t(ind[k].v_idx); } // this triangle is an ear { diff --git a/examples/ThirdPartyLibs/clsocket/src/PassiveSocket.cpp b/examples/ThirdPartyLibs/clsocket/src/PassiveSocket.cpp index 4df3635f08..dba88c310a 100644 --- a/examples/ThirdPartyLibs/clsocket/src/PassiveSocket.cpp +++ b/examples/ThirdPartyLibs/clsocket/src/PassiveSocket.cpp @@ -56,6 +56,7 @@ bool CPassiveSocket::BindMulticast(const char *pInterface, const char *pGroup, u in_addr_t inAddr; nReuse = IPTOS_LOWDELAY; + (void)nReuse; #endif //-------------------------------------------------------------------------- @@ -214,7 +215,7 @@ CActiveSocket *CPassiveSocket::Accept() { uint32 nSockLen; CActiveSocket *pClientSocket = NULL; - SOCKET socket = CSimpleSocket::SocketError; + SOCKET socket = (SOCKET)CSimpleSocket::SocketError; if (m_nSocketType != CSimpleSocket::SocketTypeTcp) { @@ -241,7 +242,7 @@ CActiveSocket *CPassiveSocket::Accept() errno = 0; socket = accept(m_socket, (struct sockaddr *)&m_stClientSockaddr, (socklen_t *)&nSockLen); - if (socket != -1) + if (socket != (SOCKET)-1) { pClientSocket->SetSocketHandle(socket); pClientSocket->TranslateSocketError(); diff --git a/examples/ThirdPartyLibs/clsocket/src/SimpleSocket.cpp b/examples/ThirdPartyLibs/clsocket/src/SimpleSocket.cpp index c986c331f4..6b42a7ed1e 100644 --- a/examples/ThirdPartyLibs/clsocket/src/SimpleSocket.cpp +++ b/examples/ThirdPartyLibs/clsocket/src/SimpleSocket.cpp @@ -280,7 +280,7 @@ uint32 CSimpleSocket::GetWindowSize(uint32 nOptionName) //------------------------------------------------------------------------- // no socket given, return system default allocate our own new socket //------------------------------------------------------------------------- - if (m_socket != CSimpleSocket::SocketError) + if (m_socket != (SOCKET)CSimpleSocket::SocketError) { socklen_t nLen = sizeof(nTcpWinSize); @@ -310,9 +310,10 @@ uint32 CSimpleSocket::SetWindowSize(uint32 nOptionName, uint32 nWindowSize) //------------------------------------------------------------------------- // no socket given, return system default allocate our own new socket //------------------------------------------------------------------------- - if (m_socket != CSimpleSocket::SocketError) + if (m_socket != (SOCKET)CSimpleSocket::SocketError) { nRetVal = SETSOCKOPT(m_socket, SOL_SOCKET, nOptionName, &nWindowSize, sizeof(nWindowSize)); + (void)nRetVal; TranslateSocketError(); } else @@ -488,7 +489,7 @@ bool CSimpleSocket::Close(void) // Shtudown() // //------------------------------------------------------------------------------ -bool CSimpleSocket::Shutdown(CShutdownMode nShutdown) +bool CSimpleSocket::Shutdown(CShutdownMode /*nShutdown*/) { CSocketError nRetVal = SocketEunknown; diff --git a/examples/ThirdPartyLibs/clsocket/src/SimpleSocket.h b/examples/ThirdPartyLibs/clsocket/src/SimpleSocket.h index 99cd2e1b9c..c276d7c390 100644 --- a/examples/ThirdPartyLibs/clsocket/src/SimpleSocket.h +++ b/examples/ThirdPartyLibs/clsocket/src/SimpleSocket.h @@ -201,7 +201,7 @@ class CSimpleSocket /// @return true if the socket object contains a valid socket descriptor. virtual bool IsSocketValid(void) { - return (m_socket != SocketError); + return (m_socket != (SOCKET)SocketError); }; /// Provides a standard error code for cross platform development by diff --git a/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp b/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp index 826ff24ee8..0bc0adb956 100644 --- a/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp +++ b/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp @@ -455,6 +455,7 @@ bool Path_IsAppBundle(const std::string &sPath) [bundle release]; return bisAppBundle; #else + (void)sPath; return false; #endif } diff --git a/examples/ThirdPartyLibs/openvr/samples/shared/strtools.h b/examples/ThirdPartyLibs/openvr/samples/shared/strtools.h index c3b310cc90..3595139848 100644 --- a/examples/ThirdPartyLibs/openvr/samples/shared/strtools.h +++ b/examples/ThirdPartyLibs/openvr/samples/shared/strtools.h @@ -80,13 +80,13 @@ inline errno_t strncpy_s(char *strDest, size_t numberOfElements, const char *str // truncated, but that is straightforward to fix if anybody actually needs the // return code. #include "string.h" -inline void wcsncpy_s(wchar_t *strDest, size_t numberOfElements, const wchar_t *strSource, size_t count) +inline void wcsncpy_s(wchar_t *strDest, size_t numberOfElements, const wchar_t *strSource, size_t /*count*/) { wcsncpy(strDest, strSource, numberOfElements); strDest[numberOfElements - 1] = '\0'; } -inline void strncpy_s(char *strDest, size_t numberOfElements, const char *strSource, size_t count) +inline void strncpy_s(char *strDest, size_t numberOfElements, const char *strSource, size_t /*count*/) { strncpy(strDest, strSource, numberOfElements); strDest[numberOfElements - 1] = '\0'; diff --git a/examples/ThirdPartyLibs/stb_image/stb_image.cpp b/examples/ThirdPartyLibs/stb_image/stb_image.cpp index 6702658a3a..9f140db8fb 100644 --- a/examples/ThirdPartyLibs/stb_image/stb_image.cpp +++ b/examples/ThirdPartyLibs/stb_image/stb_image.cpp @@ -1540,7 +1540,7 @@ static uint8 *resample_row_hv_2(uint8 *out, uint8 *in_near, uint8 *in_far, int w return out; } -static uint8 *resample_row_generic(uint8 *out, uint8 *in_near, uint8 *in_far, int w, int hs) +static uint8 *resample_row_generic(uint8 *out, uint8 *in_near, uint8 * /*in_far*/, int w, int hs) { // resample with nearest-neighbor int i, j; diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 4340ce822d..101e7f8059 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -435,7 +435,7 @@ TinyRenderObjectData::~TinyRenderObjectData() delete m_model; } -static bool equals(const Vec4f& vA, const Vec4f& vB) +static bool equals(const Vec4f& /*vA*/, const Vec4f& /*vB*/) { return false; } diff --git a/examples/TinyRenderer/our_gl.cpp b/examples/TinyRenderer/our_gl.cpp index 30d2024e88..ad07fd45a5 100644 --- a/examples/TinyRenderer/our_gl.cpp +++ b/examples/TinyRenderer/our_gl.cpp @@ -142,7 +142,7 @@ void triangleClipped(mat<4, 3, float> &clipc, mat<4, 3, float> &orgClipc, IShade Vec3d bc_clip2 = Vec3d(bc_screen2.x / orgScreenSpacePts[0][3], bc_screen2.y / orgScreenSpacePts[1][3], bc_screen2.z / orgScreenSpacePts[2][3]); bc_clip2 = bc_clip2 / (bc_clip2.x + bc_clip2.y + bc_clip2.z); Vec3d orgClipd(orgClipc[2].x, orgClipc[2].y, orgClipc[2].z); - double frag_depth2 = -1. * (orgClipd * bc_clip2); + // double frag_depth2 = -1. * (orgClipd * bc_clip2); Vec3f bc_clip2f(bc_clip2.x, bc_clip2.y, bc_clip2.z); bool discard = shader.fragment(bc_clip2f, color); diff --git a/examples/Tutorial/Tutorial.cpp b/examples/Tutorial/Tutorial.cpp index 439eda6ed4..85f14f6dc8 100644 --- a/examples/Tutorial/Tutorial.cpp +++ b/examples/Tutorial/Tutorial.cpp @@ -569,18 +569,18 @@ class Tutorial : public CommonExampleInterface } } - virtual void physicsDebugDraw(int debugDrawFlags) + virtual void physicsDebugDraw(int /*debugDrawFlags*/) { } - virtual bool mouseMoveCallback(float x, float y) + virtual bool mouseMoveCallback(float /*x*/, float /*y*/) { return false; } - virtual bool mouseButtonCallback(int button, int state, float x, float y) + virtual bool mouseButtonCallback(int /*button*/, int /*state*/, float /*x*/, float /*y*/) { return false; } - virtual bool keyboardCallback(int key, int state) + virtual bool keyboardCallback(int /*key*/, int /*state*/) { return false; } @@ -601,14 +601,14 @@ class Tutorial : public CommonExampleInterface } }; -void Tutorial::tutorial2Update(float deltaTime) +void Tutorial::tutorial2Update(float /*deltaTime*/) { for (int i = 0; i < m_bodies.size(); i++) { m_bodies[i]->m_gravityAcceleration.setValue(0, -10, 0); } } -void Tutorial::tutorial1Update(float deltaTime) +void Tutorial::tutorial1Update(float /*deltaTime*/) { for (int i = 0; i < m_bodies.size(); i++) { @@ -696,7 +696,7 @@ void Tutorial::tutorial1Update(float deltaTime) } } -void Tutorial::tutorialSolveContactConstraintUpdate(float deltaTime, LWContactPoint& contact) +void Tutorial::tutorialSolveContactConstraintUpdate(float /*deltaTime*/, LWContactPoint& contact) { ComputeClosestPointsSphereSphere(m_bodies[0]->m_collisionShape.m_sphere, m_bodies[0]->m_worldPose, @@ -705,7 +705,7 @@ void Tutorial::tutorialSolveContactConstraintUpdate(float deltaTime, LWContactPo contact); } -void Tutorial::tutorialCollisionUpdate(float deltaTime, LWContactPoint& contact) +void Tutorial::tutorialCollisionUpdate(float /*deltaTime*/, LWContactPoint& contact) { m_bodies[1]->m_worldPose.m_position.z = 3; diff --git a/examples/Utils/ChromeTraceUtil.cpp b/examples/Utils/ChromeTraceUtil.cpp index 68a84effb0..fbb030c3a8 100644 --- a/examples/Utils/ChromeTraceUtil.cpp +++ b/examples/Utils/ChromeTraceUtil.cpp @@ -164,7 +164,7 @@ btClock clk; bool gProfileDisabled = true; -void MyDummyEnterProfileZoneFunc(const char* msg) +void MyDummyEnterProfileZoneFunc(const char* /*msg*/) { } diff --git a/examples/Utils/b3BulletDefaultFileIO.h b/examples/Utils/b3BulletDefaultFileIO.h index 92ff34ee1b..9808e68391 100644 --- a/examples/Utils/b3BulletDefaultFileIO.h +++ b/examples/Utils/b3BulletDefaultFileIO.h @@ -134,6 +134,7 @@ struct b3BulletDefaultFileIO : public CommonFileIOInterface #ifdef _MSC_VER sprintf_s(relativeFileName, maxRelativeFileNameMaxLen, "%s%s", prefix[i], orgFileName); #else + (void)maxRelativeFileNameMaxLen; sprintf(relativeFileName, "%s%s", prefix[i], orgFileName); #endif f = fopen(relativeFileName, "rb"); diff --git a/examples/Utils/b3ResourcePath.cpp b/examples/Utils/b3ResourcePath.cpp index 070421c0a1..05995ccfbe 100644 --- a/examples/Utils/b3ResourcePath.cpp +++ b/examples/Utils/b3ResourcePath.cpp @@ -87,7 +87,7 @@ void b3ResourcePath::setAdditionalSearchPath(const char* path) } } -bool b3MyFindFile(void* userPointer, const char* orgFileName, char* relativeFileName, int maxRelativeFileNameMaxLen) +bool b3MyFindFile(void* /*userPointer*/, const char* orgFileName, char* relativeFileName, int maxRelativeFileNameMaxLen) { return b3FileUtils::findFile(orgFileName, relativeFileName, maxRelativeFileNameMaxLen); } diff --git a/examples/Vehicles/Hinge2Vehicle.cpp b/examples/Vehicles/Hinge2Vehicle.cpp index 8978156c94..a6d81d616c 100644 --- a/examples/Vehicles/Hinge2Vehicle.cpp +++ b/examples/Vehicles/Hinge2Vehicle.cpp @@ -112,7 +112,7 @@ class Hinge2Vehicle : public CommonRigidBodyBase */ }; -static btScalar maxMotorImpulse = 4000.f; +// static btScalar maxMotorImpulse = 4000.f; #ifndef M_PI @@ -420,6 +420,7 @@ void Hinge2Vehicle::stepSimulation(float deltaTime) int numSimSteps; numSimSteps = m_dynamicsWorld->stepSimulation(dt, maxSimSubSteps); + (void)numSimSteps; if (m_dynamicsWorld->getConstraintSolver()->getSolverType() == BT_MLCP_SOLVER) { @@ -583,11 +584,11 @@ bool Hinge2Vehicle::keyboardCallback(int key, int state) return handled; } -void Hinge2Vehicle::specialKeyboardUp(int key, int x, int y) +void Hinge2Vehicle::specialKeyboardUp(int /*key*/, int /*x*/, int /*y*/) { } -void Hinge2Vehicle::specialKeyboard(int key, int x, int y) +void Hinge2Vehicle::specialKeyboard(int /*key*/, int /*x*/, int /*y*/) { } diff --git a/examples/VoronoiFracture/btConvexConvexMprAlgorithm.cpp b/examples/VoronoiFracture/btConvexConvexMprAlgorithm.cpp index f9cd6bde7d..b99f5e614d 100644 --- a/examples/VoronoiFracture/btConvexConvexMprAlgorithm.cpp +++ b/examples/VoronoiFracture/btConvexConvexMprAlgorithm.cpp @@ -88,7 +88,7 @@ btVector3 btBulletShapeSupportFunc(const void* shapeAptr, const btVector3& dir, return shape->localGetSupportingVertexWithoutMargin(dir); } -btVector3 btBulletShapeCenterFunc(const void* shapeAptr) +btVector3 btBulletShapeCenterFunc(const void* /*shapeAptr*/) { return btVector3(0, 0, 0); } @@ -261,6 +261,8 @@ void btConvexConvexMprAlgorithm ::processCollision(const btCollisionObjectWrappe btScalar btConvexConvexMprAlgorithm::calculateTimeOfImpact(btCollisionObject* col0, btCollisionObject* col1, const btDispatcherInfo& dispatchInfo, btManifoldResult* resultOut) { + (void)col0; + (void)col1; (void)resultOut; (void)dispatchInfo; btAssert(0); diff --git a/src/Bullet3Collision/BroadPhaseCollision/b3DynamicBvhBroadphase.cpp b/src/Bullet3Collision/BroadPhaseCollision/b3DynamicBvhBroadphase.cpp index dea2ddb0f2..6ddc917c62 100644 --- a/src/Bullet3Collision/BroadPhaseCollision/b3DynamicBvhBroadphase.cpp +++ b/src/Bullet3Collision/BroadPhaseCollision/b3DynamicBvhBroadphase.cpp @@ -643,7 +643,7 @@ void b3DynamicBvhBroadphase::getBroadphaseAabb(b3Vector3& aabbMin, b3Vector3& aa aabbMax = bounds.Maxs(); } -void b3DynamicBvhBroadphase::resetPool(b3Dispatcher* dispatcher) +void b3DynamicBvhBroadphase::resetPool(b3Dispatcher* /*dispatcher*/) { int totalObjects = m_sets[0].m_leaves + m_sets[1].m_leaves; if (!totalObjects) diff --git a/src/Bullet3Collision/BroadPhaseCollision/b3OverlappingPairCache.cpp b/src/Bullet3Collision/BroadPhaseCollision/b3OverlappingPairCache.cpp index 19773244be..9fe9859da0 100644 --- a/src/Bullet3Collision/BroadPhaseCollision/b3OverlappingPairCache.cpp +++ b/src/Bullet3Collision/BroadPhaseCollision/b3OverlappingPairCache.cpp @@ -38,7 +38,7 @@ b3HashedOverlappingPairCache::~b3HashedOverlappingPairCache() { } -void b3HashedOverlappingPairCache::cleanOverlappingPair(b3BroadphasePair& pair, b3Dispatcher* dispatcher) +void b3HashedOverlappingPairCache::cleanOverlappingPair(b3BroadphasePair& /*pair*/, b3Dispatcher* /*dispatcher*/) { /* if (pair.m_algorithm) { @@ -485,7 +485,7 @@ b3SortedOverlappingPairCache::~b3SortedOverlappingPairCache() { } -void b3SortedOverlappingPairCache::cleanOverlappingPair(b3BroadphasePair& pair, b3Dispatcher* dispatcher) +void b3SortedOverlappingPairCache::cleanOverlappingPair(b3BroadphasePair& /*pair*/, b3Dispatcher* /*dispatcher*/) { /* if (pair.m_algorithm) { @@ -553,7 +553,7 @@ void b3SortedOverlappingPairCache::removeOverlappingPairsContainingProxy(int pro processAllOverlappingPairs(&removeCallback, dispatcher); } -void b3SortedOverlappingPairCache::sortOverlappingPairs(b3Dispatcher* dispatcher) +void b3SortedOverlappingPairCache::sortOverlappingPairs(b3Dispatcher* /*dispatcher*/) { //should already be sorted } diff --git a/src/Bullet3Collision/NarrowPhaseCollision/b3ConvexUtility.cpp b/src/Bullet3Collision/NarrowPhaseCollision/b3ConvexUtility.cpp index a5dab74a34..4872c05b0e 100644 --- a/src/Bullet3Collision/NarrowPhaseCollision/b3ConvexUtility.cpp +++ b/src/Bullet3Collision/NarrowPhaseCollision/b3ConvexUtility.cpp @@ -23,7 +23,7 @@ b3ConvexUtility::~b3ConvexUtility() { } -bool b3ConvexUtility::initializePolyhedralFeatures(const b3Vector3* orgVertices, int numPoints, bool mergeCoplanarTriangles) +bool b3ConvexUtility::initializePolyhedralFeatures(const b3Vector3* orgVertices, int numPoints, bool /*mergeCoplanarTriangles*/) { b3ConvexHullComputer conv; conv.compute(&orgVertices[0].getX(), sizeof(b3Vector3), numPoints, 0.f, 0.f); diff --git a/src/Bullet3Collision/NarrowPhaseCollision/b3CpuNarrowPhase.cpp b/src/Bullet3Collision/NarrowPhaseCollision/b3CpuNarrowPhase.cpp index e0b2161100..a04293f71e 100644 --- a/src/Bullet3Collision/NarrowPhaseCollision/b3CpuNarrowPhase.cpp +++ b/src/Bullet3Collision/NarrowPhaseCollision/b3CpuNarrowPhase.cpp @@ -50,7 +50,7 @@ b3CpuNarrowPhase::~b3CpuNarrowPhase() delete m_data; } -void b3CpuNarrowPhase::computeContacts(b3AlignedObjectArray& pairs, b3AlignedObjectArray& aabbsWorldSpace, b3AlignedObjectArray& bodies) +void b3CpuNarrowPhase::computeContacts(b3AlignedObjectArray& pairs, b3AlignedObjectArray& /*aabbsWorldSpace*/, b3AlignedObjectArray& bodies) { int nPairs = pairs.size(); int numContacts = 0; @@ -227,7 +227,7 @@ int b3CpuNarrowPhase::registerConvexHullShape(const float* vertices, int strideI return collidableIndex; } -int b3CpuNarrowPhase::registerConvexHullShapeInternal(b3ConvexUtility* convexPtr, b3Collidable& col) +int b3CpuNarrowPhase::registerConvexHullShapeInternal(b3ConvexUtility* convexPtr, b3Collidable& /*col*/) { m_data->m_convexData.resize(m_data->m_numAcceleratedShapes + 1); m_data->m_convexPolyhedra.resize(m_data->m_numAcceleratedShapes + 1); diff --git a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3BvhTraversal.h b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3BvhTraversal.h index 7c2507cc98..e46ebdf16a 100644 --- a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3BvhTraversal.h +++ b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3BvhTraversal.h @@ -17,7 +17,7 @@ void b3BvhTraversal(__global const b3Int4* pairs, __global const b3BvhSubtreeInfo* subtreeHeadersRoot, __global const b3QuantizedBvhNode* quantizedNodesRoot, __global const b3BvhInfo* bvhInfos, - int numPairs, + int /*numPairs*/, int maxNumConcavePairsCapacity, int id) { diff --git a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3ClipFaces.h b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3ClipFaces.h index 0d9b13f1d6..86bf9df82f 100644 --- a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3ClipFaces.h +++ b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3ClipFaces.h @@ -64,7 +64,7 @@ int clipFaceGlobal(__global const b3Float4* pVtxIn, int numVertsIn, b3Float4Cons return numVertsOut; } -__kernel void clipFacesAndFindContactsKernel(__global const b3Float4* separatingNormals, +__kernel void clipFacesAndFindContactsKernel(__global const b3Float4* /*separatingNormals*/, __global const int* hasSeparatingAxis, __global b3Int4* clippingFacesOut, __global b3Float4* worldVertsA1, diff --git a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3ContactConvexConvexSAT.h b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3ContactConvexConvexSAT.h index ca68f4bc4e..d7167bfa34 100644 --- a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3ContactConvexConvexSAT.h +++ b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3ContactConvexConvexSAT.h @@ -66,7 +66,7 @@ inline int b3ClipFace(const b3Float4* pVtxIn, int numVertsIn, b3Float4& planeNor inline int b3ClipFaceAgainstHull(const b3Float4& separatingNormal, const b3ConvexPolyhedronData* hullA, const b3Float4& posA, const b3Quaternion& ornA, b3Float4* worldVertsB1, int numWorldVertsB1, - b3Float4* worldVertsB2, int capacityWorldVertsB2, + b3Float4* worldVertsB2, int /*capacityWorldVertsB2*/, const float minDist, float maxDist, const b3AlignedObjectArray& verticesA, const b3AlignedObjectArray& facesA, const b3AlignedObjectArray& indicesA, //const b3Float4* verticesB, const b3GpuFace* facesB, const int* indicesB, @@ -195,7 +195,9 @@ inline int b3ClipHullAgainstHull(const b3Float4& separatingNormal, { //printf("wtf\n"); } +#ifdef BT_DEBUG_SAT_FACE static bool once = true; +#endif //printf("separatingNormal=%f,%f,%f\n",separatingNormal.x,separatingNormal.y,separatingNormal.z); for (int face = 0; face < hullB.m_numFaces; face++) @@ -212,7 +214,7 @@ inline int b3ClipHullAgainstHull(const b3Float4& separatingNormal, printf("vert[%d] = %f,%f,%f\n", i, vert.x, vert.y, vert.z); } } -#endif //BT_DEBUG_SAT_FACE \ +#endif //BT_DEBUG_SAT_FACE //if (facesB[hullB.m_faceOffset+face].m_numIndices>2) { const b3Float4 Normal = b3MakeVector3(facesB[hullB.m_faceOffset + face].m_plane.x, @@ -230,7 +232,9 @@ inline int b3ClipHullAgainstHull(const b3Float4& separatingNormal, } } } +#ifdef BT_DEBUG_SAT_FACE once = false; +#endif } b3Assert(closestFaceB >= 0); @@ -275,12 +279,12 @@ inline int b3ClipHullHullSingle( const b3AlignedObjectArray& hostConvexDataB, const b3AlignedObjectArray& verticesA, - const b3AlignedObjectArray& uniqueEdgesA, + const b3AlignedObjectArray& /*uniqueEdgesA*/, const b3AlignedObjectArray& facesA, const b3AlignedObjectArray& indicesA, const b3AlignedObjectArray& verticesB, - const b3AlignedObjectArray& uniqueEdgesB, + const b3AlignedObjectArray& /*uniqueEdgesB*/, const b3AlignedObjectArray& facesB, const b3AlignedObjectArray& indicesB, @@ -401,7 +405,7 @@ inline int b3ClipHullHullSingle( } inline int b3ContactConvexConvexSAT( - int pairIndex, + int /*pairIndex*/, int bodyIndexA, int bodyIndexB, int collidableIndexA, int collidableIndexB, const b3AlignedObjectArray& rigidBodies, diff --git a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3FindConcaveSatAxis.h b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3FindConcaveSatAxis.h index 983554eb2e..a1558e5a8f 100644 --- a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3FindConcaveSatAxis.h +++ b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3FindConcaveSatAxis.h @@ -65,14 +65,14 @@ bool b3FindSeparatingAxis(const b3ConvexPolyhedronData* hullA, __global const b3 b3Float4ConstArg DeltaC2, const b3Float4* verticesA, - const b3Float4* uniqueEdgesA, + const b3Float4* /*uniqueEdgesA*/, const b3GpuFace* facesA, - const int* indicesA, + const int* /*indicesA*/, __global const b3Float4* verticesB, - __global const b3Float4* uniqueEdgesB, - __global const b3GpuFace* facesB, - __global const int* indicesB, + __global const b3Float4* /*uniqueEdgesB*/, + __global const b3GpuFace* /*facesB*/, + __global const int* /*indicesB*/, b3Float4* sep, float* dmin) { @@ -97,6 +97,7 @@ bool b3FindSeparatingAxis(const b3ConvexPolyhedronData* hullA, __global const b3 */ int curPlaneTests = 0; + (void)curPlaneTests; { int numFacesA = hullA->m_numFaces; // Test normals from hullA @@ -297,12 +298,12 @@ bool b3FindSeparatingAxisEdgeEdge(const b3ConvexPolyhedronData* hullA, __global b3Float4ConstArg DeltaC2, const b3Float4* verticesA, const b3Float4* uniqueEdgesA, - const b3GpuFace* facesA, - const int* indicesA, + const b3GpuFace* /*facesA*/, + const int* /*indicesA*/, __global const b3Float4* verticesB, __global const b3Float4* uniqueEdgesB, - __global const b3GpuFace* facesB, - __global const int* indicesB, + __global const b3GpuFace* /*facesB*/, + __global const int* /*indicesB*/, b3Float4* sep, float* dmin, bool searchAllEdgeEdge) @@ -315,6 +316,7 @@ bool b3FindSeparatingAxisEdgeEdge(const b3ConvexPolyhedronData* hullA, __global // int curPlaneTests=0; int curEdgeEdge = 0; + (void)curEdgeEdge; // Test edges static int maxEdgeTests = 0; int curEdgeTests = hullA->m_numUniqueEdges * hullB->m_numUniqueEdges; @@ -362,6 +364,7 @@ bool b3FindSeparatingAxisEdgeEdge(const b3ConvexPolyhedronData* hullA, __global float d1 = Max1 - Min0; dist = d0 < d1 ? d0 : d1; result = true; + (void)result; } if (dist < *dmin) @@ -399,6 +402,7 @@ bool b3FindSeparatingAxisEdgeEdge(const b3ConvexPolyhedronData* hullA, __global float d1 = Max1 - Min0; dist = d0 < d1 ? d0 : d1; result = true; + (void)result; } if (dist < *dmin) @@ -425,7 +429,7 @@ inline int b3FindClippingFaces(b3Float4ConstArg separatingNormal, __global b3Float4* worldNormalsA1, __global b3Float4* worldVertsB1, int capacityWorldVerts, - const float minDist, float maxDist, + const float /*minDist*/, float /*maxDist*/, __global const b3Float4* verticesA, __global const b3GpuFace_t* facesA, __global const int* indicesA, @@ -520,7 +524,7 @@ __kernel void b3FindConcaveSeparatingAxisKernel(__global b3Int4* concavePairs, __global b3Vector3* worldVertsB1Out, __global int* hasSeparatingNormals, int vertexFaceCapacity, - int numConcavePairs, + int /*numConcavePairs*/, int pairIdx) { int i = pairIdx; @@ -550,6 +554,7 @@ __kernel void b3FindConcaveSeparatingAxisKernel(__global b3Int4* concavePairs, // int numFacesA = convexShapes[shapeIndexA].m_numFaces; int numActualConcaveConvexTests = 0; + (void)numActualConcaveConvexTests; int f = concavePairs[i].z; diff --git a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3FindSeparatingAxis.h b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3FindSeparatingAxis.h index b4981ae654..01a422586f 100644 --- a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3FindSeparatingAxis.h +++ b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3FindSeparatingAxis.h @@ -60,11 +60,11 @@ inline bool b3FindSeparatingAxis(const b3ConvexPolyhedronData& hullA, const b3Co const b3AlignedObjectArray& verticesA, const b3AlignedObjectArray& uniqueEdgesA, const b3AlignedObjectArray& facesA, - const b3AlignedObjectArray& indicesA, + const b3AlignedObjectArray& /*indicesA*/, const b3AlignedObjectArray& verticesB, const b3AlignedObjectArray& uniqueEdgesB, const b3AlignedObjectArray& facesB, - const b3AlignedObjectArray& indicesB, + const b3AlignedObjectArray& /*indicesB*/, b3Vector3& sep) { @@ -85,6 +85,7 @@ inline bool b3FindSeparatingAxis(const b3ConvexPolyhedronData& hullA, const b3Co b3Scalar dmin = FLT_MAX; int curPlaneTests = 0; + (void)curPlaneTests; int numFacesA = hullA.m_numFaces; // Test normals from hullA @@ -148,6 +149,7 @@ inline bool b3FindSeparatingAxis(const b3ConvexPolyhedronData& hullA, const b3Co // b3Vector3 edgeAstart,edgeAend,edgeBstart,edgeBend; int curEdgeEdge = 0; + (void)curEdgeEdge; // Test edges for (int e0 = 0; e0 < hullA.m_numUniqueEdges; e0++) { diff --git a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3MprPenetration.h b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3MprPenetration.h index a3bfbf2995..756d239565 100644 --- a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3MprPenetration.h +++ b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3MprPenetration.h @@ -136,11 +136,11 @@ inline b3Float4 b3LocalGetSupportVertex(b3Float4ConstArg supportVec, __global co return supVec; } -B3_STATIC void b3MprConvexSupport(int pairIndex, int bodyIndex, b3ConstArray(b3RigidBodyData_t) cpuBodyBuf, +B3_STATIC void b3MprConvexSupport(int /*pairIndex*/, int bodyIndex, b3ConstArray(b3RigidBodyData_t) cpuBodyBuf, b3ConstArray(b3ConvexPolyhedronData_t) cpuConvexData, b3ConstArray(b3Collidable_t) cpuCollidables, b3ConstArray(b3Float4) cpuVertices, - __global b3Float4 *sepAxis, + __global b3Float4 * /*sepAxis*/, const b3Float4 *_dir, b3Float4 *outp, int logme) { //dir is in worldspace, move to local space @@ -300,7 +300,7 @@ inline int portalReachTolerance(const b3MprSimplex_t *portal, return b3MprEq(dot1, B3_MPR_TOLERANCE) || dot1 < B3_MPR_TOLERANCE; } -inline int portalCanEncapsuleOrigin(const b3MprSimplex_t *portal, +inline int portalCanEncapsuleOrigin(const b3MprSimplex_t * /*portal*/, const b3MprSupport_t *v4, const b3Float4 *dir) { @@ -348,7 +348,7 @@ B3_STATIC int b3DiscoverPortal(int pairIndex, int bodyIndexA, int bodyIndexB, b3 b3ConstArray(b3Collidable_t) cpuCollidables, b3ConstArray(b3Float4) cpuVertices, __global b3Float4 *sepAxis, - __global int *hasSepAxis, + __global int * /*hasSepAxis*/, b3MprSimplex_t *portal) { b3Float4 dir, va, vb; diff --git a/src/Bullet3Common/b3FileUtils.h b/src/Bullet3Common/b3FileUtils.h index 9ded17eaaf..776c097df0 100644 --- a/src/Bullet3Common/b3FileUtils.h +++ b/src/Bullet3Common/b3FileUtils.h @@ -39,6 +39,7 @@ struct b3FileUtils #ifdef _MSC_VER sprintf_s(relativeFileName, maxRelativeFileNameMaxLen, "%s%s", prefix[i], orgFileName); #else + (void)maxRelativeFileNameMaxLen; sprintf(relativeFileName, "%s%s", prefix[i], orgFileName); #endif f = fopen(relativeFileName, "rb"); @@ -59,7 +60,7 @@ struct b3FileUtils static const char* strip2(const char* name, const char* pattern) { size_t const patlen = strlen(pattern); - size_t patcnt = 0; + size_t patcnt = 0; (void)patcnt; const char* oriptr; const char* patloc; // find how many times the pattern occurs in the original string diff --git a/src/Bullet3Common/b3Logging.cpp b/src/Bullet3Common/b3Logging.cpp index 9c9f7c09ea..d79c9b1611 100644 --- a/src/Bullet3Common/b3Logging.cpp +++ b/src/Bullet3Common/b3Logging.cpp @@ -114,7 +114,7 @@ void b3OutputErrorMessageVarArgsInternal(const char* str, ...) va_end(argList); } -void b3EnterProfileZoneDefault(const char* name) +void b3EnterProfileZoneDefault(const char* /*name*/) { } void b3LeaveProfileZoneDefault() diff --git a/src/Bullet3Common/b3Scalar.h b/src/Bullet3Common/b3Scalar.h index eeb70ed632..54ae4e1f7e 100644 --- a/src/Bullet3Common/b3Scalar.h +++ b/src/Bullet3Common/b3Scalar.h @@ -108,7 +108,7 @@ inline int b3GetVersion() #define b3Assert assert #endif //_MSC_VER #else -#define b3Assert(x) +#define b3Assert(x) (void)(x) #endif //b3FullAssert is optional, slows down a lot #define b3FullAssert(x) @@ -146,7 +146,7 @@ inline int b3GetVersion() #endif #else -#define b3Assert(x) +#define b3Assert(x) (void)(x) #endif //b3FullAssert is optional, slows down a lot #define b3FullAssert(x) @@ -168,7 +168,7 @@ inline int b3GetVersion() #ifdef B3_DEBUG #define b3Assert assert #else -#define b3Assert(x) +#define b3Assert(x) (void)(x) #endif //b3FullAssert is optional, slows down a lot #define b3FullAssert(x) @@ -231,7 +231,7 @@ inline int b3GetVersion() #define b3Assert assert #endif //defined (__i386__) || defined (__x86_64__) #else //defined(DEBUG) || defined (_DEBUG) -#define b3Assert(x) +#define b3Assert(x) (void)(x) #endif //defined(DEBUG) || defined (_DEBUG) //b3FullAssert is optional, slows down a lot @@ -256,7 +256,7 @@ inline int b3GetVersion() #if defined(DEBUG) || defined(_DEBUG) #define b3Assert assert #else -#define b3Assert(x) +#define b3Assert(x) (void)(x) #endif //b3FullAssert is optional, slows down a lot diff --git a/src/Bullet3Common/shared/b3PlatformDefinitions.h b/src/Bullet3Common/shared/b3PlatformDefinitions.h index b72bee9310..4a3c7a86a4 100644 --- a/src/Bullet3Common/shared/b3PlatformDefinitions.h +++ b/src/Bullet3Common/shared/b3PlatformDefinitions.h @@ -26,7 +26,7 @@ inline int b3AtomicAdd(volatile int *p, int val) //keep B3_LARGE_FLOAT*B3_LARGE_FLOAT < FLT_MAX #define B3_LARGE_FLOAT 1e18f #define B3_INFINITY 1e18f -#define b3Assert(a) +#define b3Assert(a) (void)(x) #define b3ConstArray(a) __global const a * #define b3AtomicInc atomic_inc #define b3AtomicAdd atomic_add diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.cpp b/src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.cpp index ace4b18388..fe79f4a956 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.cpp +++ b/src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.cpp @@ -16,7 +16,7 @@ b3FixedConstraint::~b3FixedConstraint() { } -void b3FixedConstraint::getInfo1(b3ConstraintInfo1* info, const b3RigidBodyData* bodies) +void b3FixedConstraint::getInfo1(b3ConstraintInfo1* info, const b3RigidBodyData* /*bodies*/) { info->m_numConstraintRows = 6; info->nub = 6; diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.h b/src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.h index 64809666e4..216116296f 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.h +++ b/src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.h @@ -20,11 +20,11 @@ b3FixedConstraint : public b3TypedConstraint virtual void getInfo2(b3ConstraintInfo2 * info, const b3RigidBodyData* bodies); - virtual void setParam(int num, b3Scalar value, int axis = -1) + virtual void setParam(int /*num*/, b3Scalar /*value*/, int /*axis = -1*/) { b3Assert(0); } - virtual b3Scalar getParam(int num, int axis = -1) const + virtual b3Scalar getParam(int /*num*/, int /*axis = -1*/) const { b3Assert(0); return 0.f; diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.cpp b/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.cpp index fd3e5185de..a30a1a41bd 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.cpp +++ b/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.cpp @@ -259,7 +259,7 @@ void b3Generic6DofConstraint::getInfo1(b3ConstraintInfo1* info, const b3RigidBod // printf("info->m_numConstraintRows=%d\n",info->m_numConstraintRows); } -void b3Generic6DofConstraint::getInfo1NonVirtual(b3ConstraintInfo1* info, const b3RigidBodyData* bodies) +void b3Generic6DofConstraint::getInfo1NonVirtual(b3ConstraintInfo1* info, const b3RigidBodyData* /*bodies*/) { //pre-allocate all 6 info->m_numConstraintRows = 6; diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.cpp b/src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.cpp index b7050b1070..64f8f1a5d2 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.cpp +++ b/src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.cpp @@ -454,7 +454,7 @@ b3Scalar b3PgsJacobiSolver::restitutionCurve(b3Scalar rel_vel, b3Scalar restitut return rest; } -void b3PgsJacobiSolver::setupFrictionConstraint(b3RigidBodyData* bodies, b3InertiaData* inertias, b3SolverConstraint& solverConstraint, const b3Vector3& normalAxis, int solverBodyIdA, int solverBodyIdB, b3ContactPoint& cp, const b3Vector3& rel_pos1, const b3Vector3& rel_pos2, b3RigidBodyData* colObj0, b3RigidBodyData* colObj1, b3Scalar relaxation, b3Scalar desiredVelocity, b3Scalar cfmSlip) +void b3PgsJacobiSolver::setupFrictionConstraint(b3RigidBodyData* bodies, b3InertiaData* inertias, b3SolverConstraint& solverConstraint, const b3Vector3& normalAxis, int solverBodyIdA, int solverBodyIdB, b3ContactPoint& cp, const b3Vector3& rel_pos1, const b3Vector3& rel_pos2, b3RigidBodyData* /*colObj0*/, b3RigidBodyData* /*colObj1*/, b3Scalar relaxation, b3Scalar desiredVelocity, b3Scalar cfmSlip) { solverConstraint.m_contactNormal = normalAxis; b3SolverBody& solverBodyA = m_tmpSolverBodyPool[solverBodyIdA]; @@ -545,8 +545,8 @@ b3SolverConstraint& b3PgsJacobiSolver::addFrictionConstraint(b3RigidBodyData* bo } void b3PgsJacobiSolver::setupRollingFrictionConstraint(b3RigidBodyData* bodies, b3InertiaData* inertias, b3SolverConstraint& solverConstraint, const b3Vector3& normalAxis1, int solverBodyIdA, int solverBodyIdB, - b3ContactPoint& cp, const b3Vector3& rel_pos1, const b3Vector3& rel_pos2, - b3RigidBodyData* colObj0, b3RigidBodyData* colObj1, b3Scalar relaxation, + b3ContactPoint& cp, const b3Vector3& /*rel_pos1*/, const b3Vector3& /*rel_pos2*/, + b3RigidBodyData* /*colObj0*/, b3RigidBodyData* /*colObj1*/, b3Scalar /*relaxation*/, b3Scalar desiredVelocity, b3Scalar cfmSlip) { @@ -615,7 +615,7 @@ b3SolverConstraint& b3PgsJacobiSolver::addRollingFrictionConstraint(b3RigidBodyD return solverConstraint; } -int b3PgsJacobiSolver::getOrInitSolverBody(int bodyIndex, b3RigidBodyData* bodies, b3InertiaData* inertias) +int b3PgsJacobiSolver::getOrInitSolverBody(int bodyIndex, b3RigidBodyData* bodies, b3InertiaData* /*inertias*/) { //b3Assert(bodyIndex< m_tmpSolverBodyPool.size()); @@ -626,9 +626,9 @@ int b3PgsJacobiSolver::getOrInitSolverBody(int bodyIndex, b3RigidBodyData* bodie if (m_bodyCount[bodyIndex] < 0) { curIndex = m_tmpSolverBodyPool.size(); - b3SolverBody& solverBody = m_tmpSolverBodyPool.expand(); - initSolverBody(bodyIndex, &solverBody, &body); - solverBody.m_originalBodyIndex = bodyIndex; + // b3SolverBody& solverBody = m_tmpSolverBodyPool.expand(); + // initSolverBody(bodyIndex, &solverBody, &body); + // solverBody.m_originalBodyIndex = bodyIndex; m_bodyCount[bodyIndex] = curIndex; } else @@ -641,9 +641,9 @@ int b3PgsJacobiSolver::getOrInitSolverBody(int bodyIndex, b3RigidBodyData* bodie b3Assert(m_bodyCount[bodyIndex] > 0); m_bodyCountCheck[bodyIndex]++; curIndex = m_tmpSolverBodyPool.size(); - b3SolverBody& solverBody = m_tmpSolverBodyPool.expand(); - initSolverBody(bodyIndex, &solverBody, &body); - solverBody.m_originalBodyIndex = bodyIndex; + // b3SolverBody& solverBody = m_tmpSolverBodyPool.expand(); + // initSolverBody(bodyIndex, &solverBody, &body); + // solverBody.m_originalBodyIndex = bodyIndex; } b3Assert(curIndex >= 0); @@ -803,7 +803,7 @@ void b3PgsJacobiSolver::setupContactConstraint(b3RigidBodyData* bodies, b3Inerti } } -void b3PgsJacobiSolver::setFrictionConstraintImpulse(b3RigidBodyData* bodies, b3InertiaData* inertias, b3SolverConstraint& solverConstraint, +void b3PgsJacobiSolver::setFrictionConstraintImpulse(b3RigidBodyData* bodies, b3InertiaData* /*inertias*/, b3SolverConstraint& solverConstraint, int solverBodyIdA, int solverBodyIdB, b3ContactPoint& cp, const b3ContactSolverInfo& infoGlobal) { @@ -988,7 +988,7 @@ b3Scalar b3PgsJacobiSolver::solveGroupCacheFriendlySetup(b3RigidBodyData* bodies m_maxOverrideNumSolverIterations = 0; - m_tmpSolverBodyPool.resize(0); + // m_tmpSolverBodyPool.resize(0); m_bodyCount.resize(0); m_bodyCount.resize(numBodies, 0); @@ -1278,7 +1278,7 @@ b3Scalar b3PgsJacobiSolver::solveGroupCacheFriendlySetup(b3RigidBodyData* bodies return 0.f; } -b3Scalar b3PgsJacobiSolver::solveSingleIteration(int iteration, b3TypedConstraint** constraints, int numConstraints, const b3ContactSolverInfo& infoGlobal) +b3Scalar b3PgsJacobiSolver::solveSingleIteration(int iteration, b3TypedConstraint** /*constraints*/, int /*numConstraints*/, const b3ContactSolverInfo& infoGlobal) { int numNonContactPool = m_tmpSolverNonContactConstraintPool.size(); int numConstraintPool = m_tmpSolverContactConstraintPool.size(); @@ -1485,7 +1485,7 @@ b3Scalar b3PgsJacobiSolver::solveSingleIteration(int iteration, b3TypedConstrain return 0.f; } -void b3PgsJacobiSolver::solveGroupCacheFriendlySplitImpulseIterations(b3TypedConstraint** constraints, int numConstraints, const b3ContactSolverInfo& infoGlobal) +void b3PgsJacobiSolver::solveGroupCacheFriendlySplitImpulseIterations(b3TypedConstraint** /*constraints*/, int /*numConstraints*/, const b3ContactSolverInfo& infoGlobal) { int iteration; if (infoGlobal.m_splitImpulse) @@ -1586,7 +1586,7 @@ void b3PgsJacobiSolver::averageVelocities() } } -b3Scalar b3PgsJacobiSolver::solveGroupCacheFriendlyFinish(b3RigidBodyData* bodies, b3InertiaData* inertias, int numBodies, const b3ContactSolverInfo& infoGlobal) +b3Scalar b3PgsJacobiSolver::solveGroupCacheFriendlyFinish(b3RigidBodyData* bodies, b3InertiaData* /*inertias*/, int /*numBodies*/, const b3ContactSolverInfo& infoGlobal) { B3_PROFILE("solveGroupCacheFriendlyFinish"); int numPoolConstraints = m_tmpSolverContactConstraintPool.size(); diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.h b/src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.h index 5b616541d9..a6c2194f17 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.h +++ b/src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.h @@ -41,7 +41,7 @@ class b3PgsJacobiSolver int m_numSplitImpulseRecoveries; - b3Scalar getContactProcessingThreshold(b3Contact4* contact) + b3Scalar getContactProcessingThreshold(b3Contact4* /*contact*/) { return 0.02f; } diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.cpp b/src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.cpp index f9b103e34a..b64d610b3d 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.cpp +++ b/src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.cpp @@ -38,7 +38,7 @@ void b3Point2PointConstraint::getInfo1(b3ConstraintInfo1* info, const b3RigidBod getInfo1NonVirtual(info, bodies); } -void b3Point2PointConstraint::getInfo1NonVirtual(b3ConstraintInfo1* info, const b3RigidBodyData* bodies) +void b3Point2PointConstraint::getInfo1NonVirtual(b3ConstraintInfo1* info, const b3RigidBodyData* /*bodies*/) { info->m_numConstraintRows = 3; info->nub = 3; diff --git a/src/Bullet3Dynamics/b3CpuRigidBodyPipeline.cpp b/src/Bullet3Dynamics/b3CpuRigidBodyPipeline.cpp index f1080d9d5e..a4716a0e08 100644 --- a/src/Bullet3Dynamics/b3CpuRigidBodyPipeline.cpp +++ b/src/Bullet3Dynamics/b3CpuRigidBodyPipeline.cpp @@ -237,7 +237,7 @@ struct b3SolveTask // : public ThreadPool::Task unsigned short int getType() { return 0; } - void run(int tIdx) + void run(int /*tIdx*/) { b3AlignedObjectArray usedBodies; //printf("run..............\n"); @@ -394,7 +394,7 @@ void b3CpuRigidBodyPipeline::integrate(float deltaTime) } } -int b3CpuRigidBodyPipeline::registerPhysicsInstance(float mass, const float* position, const float* orientation, int collidableIndex, int userData) +int b3CpuRigidBodyPipeline::registerPhysicsInstance(float mass, const float* position, const float* orientation, int collidableIndex, int /*userData*/) { b3RigidBodyData body; int bodyIndex = m_data->m_rigidBodies.size(); diff --git a/src/Bullet3Dynamics/shared/b3ConvertConstraint4.h b/src/Bullet3Dynamics/shared/b3ConvertConstraint4.h index 3e72f1c3f2..a9c1e5ff49 100644 --- a/src/Bullet3Dynamics/shared/b3ConvertConstraint4.h +++ b/src/Bullet3Dynamics/shared/b3ConvertConstraint4.h @@ -48,7 +48,7 @@ float calcRelVel(b3Float4ConstArg l0, b3Float4ConstArg l1, b3Float4ConstArg a0, return b3Dot3F4(l0, linVel0) + b3Dot3F4(a0, angVel0) + b3Dot3F4(l1, linVel1) + b3Dot3F4(a1, angVel1); } -float calcJacCoeff(b3Float4ConstArg linear0, b3Float4ConstArg linear1, b3Float4ConstArg angular0, b3Float4ConstArg angular1, +float calcJacCoeff(b3Float4ConstArg /*linear0*/, b3Float4ConstArg /*linear1*/, b3Float4ConstArg angular0, b3Float4ConstArg angular1, float invMass0, const b3Mat3x3* invInertia0, float invMass1, const b3Mat3x3* invInertia1) { // linear0,1 are normlized diff --git a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.cpp b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.cpp index e714fadac3..5b4bd486a1 100644 --- a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.cpp +++ b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.cpp @@ -91,7 +91,7 @@ b3GpuGridBroadphase::~b3GpuGridBroadphase() delete m_sorter; } -void b3GpuGridBroadphase::createProxy(const b3Vector3& aabbMin, const b3Vector3& aabbMax, int userPtr, int collisionFilterGroup, int collisionFilterMask) +void b3GpuGridBroadphase::createProxy(const b3Vector3& aabbMin, const b3Vector3& aabbMax, int userPtr, int /*collisionFilterGroup*/, int /*collisionFilterMask*/) { b3SapAabb aabb; aabb.m_minVec = aabbMin; @@ -102,7 +102,7 @@ void b3GpuGridBroadphase::createProxy(const b3Vector3& aabbMin, const b3Vector3& m_allAabbsCPU1.push_back(aabb); } -void b3GpuGridBroadphase::createLargeProxy(const b3Vector3& aabbMin, const b3Vector3& aabbMax, int userPtr, int collisionFilterGroup, int collisionFilterMask) +void b3GpuGridBroadphase::createLargeProxy(const b3Vector3& aabbMin, const b3Vector3& aabbMax, int userPtr, int /*collisionFilterGroup*/, int /*collisionFilterMask*/) { b3SapAabb aabb; aabb.m_minVec = aabbMin; diff --git a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvh.cpp b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvh.cpp index 616fc34f3a..637b1f106a 100644 --- a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvh.cpp +++ b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvh.cpp @@ -15,6 +15,7 @@ subject to the following restrictions: #include "Bullet3OpenCL/ParallelPrimitives/b3LauncherCL.h" #include "b3GpuParallelLinearBvh.h" +#include "kernels/parallelLinearBvhKernels.h" b3GpuParallelLinearBvh::b3GpuParallelLinearBvh(cl_context context, cl_device_id device, cl_command_queue queue) : m_queue(queue), m_radixSorter(context, device, queue), diff --git a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvh.h b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvh.h index b390775129..ad0420456d 100644 --- a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvh.h +++ b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvh.h @@ -24,8 +24,6 @@ subject to the following restrictions: #include "Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.h" #include "Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.h" -#include "Bullet3OpenCL/BroadphaseCollision/kernels/parallelLinearBvhKernels.h" - #define b3Int64 cl_long ///@brief GPU Parallel Linearized Bounding Volume Heirarchy(LBVH) that is reconstructed every frame diff --git a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvhBroadphase.cpp b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvhBroadphase.cpp index 62ea7a32df..37c846c305 100644 --- a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvhBroadphase.cpp +++ b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvhBroadphase.cpp @@ -23,7 +23,7 @@ b3GpuParallelLinearBvhBroadphase::b3GpuParallelLinearBvhBroadphase(cl_context co { } -void b3GpuParallelLinearBvhBroadphase::createProxy(const b3Vector3& aabbMin, const b3Vector3& aabbMax, int userPtr, int collisionFilterGroup, int collisionFilterMask) +void b3GpuParallelLinearBvhBroadphase::createProxy(const b3Vector3& aabbMin, const b3Vector3& aabbMax, int userPtr, int /*collisionFilterGroup*/, int /*collisionFilterMask*/) { int newAabbIndex = m_aabbsCpu.size(); @@ -38,7 +38,7 @@ void b3GpuParallelLinearBvhBroadphase::createProxy(const b3Vector3& aabbMin, con m_aabbsCpu.push_back(aabb); } -void b3GpuParallelLinearBvhBroadphase::createLargeProxy(const b3Vector3& aabbMin, const b3Vector3& aabbMax, int userPtr, int collisionFilterGroup, int collisionFilterMask) +void b3GpuParallelLinearBvhBroadphase::createLargeProxy(const b3Vector3& aabbMin, const b3Vector3& aabbMax, int userPtr, int /*collisionFilterGroup*/, int /*collisionFilterMask*/) { int newAabbIndex = m_aabbsCpu.size(); @@ -63,7 +63,7 @@ void b3GpuParallelLinearBvhBroadphase::calculateOverlappingPairs(int maxPairs) m_overlappingPairsGpu.resize(maxPairs); m_plbvh.calculateOverlappingPairs(m_overlappingPairsGpu); } -void b3GpuParallelLinearBvhBroadphase::calculateOverlappingPairsHost(int maxPairs) +void b3GpuParallelLinearBvhBroadphase::calculateOverlappingPairsHost(int /*maxPairs*/) { b3Assert(0); //CPU version not implemented } diff --git a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.cpp b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.cpp index 4126d03ed0..d63b139a38 100644 --- a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.cpp +++ b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.cpp @@ -812,7 +812,7 @@ void b3GpuSapBroadphase::calculateOverlappingPairsHostIncremental3Sap() prevPair.x = -1; prevPair.y = -1; - int uniqueAddedPairs = 0; + int uniqueAddedPairs = 0; (void)uniqueAddedPairs; b3AlignedObjectArray actualAddedPairs; { @@ -1238,7 +1238,7 @@ void b3GpuSapBroadphase::writeAabbsToGpu() m_allAabbsGPU.copyFromHost(m_allAabbsCPU); //might not be necessary, the 'setupGpuAabbsFull' already takes care of this } -void b3GpuSapBroadphase::createLargeProxy(const b3Vector3& aabbMin, const b3Vector3& aabbMax, int userPtr, int collisionFilterGroup, int collisionFilterMask) +void b3GpuSapBroadphase::createLargeProxy(const b3Vector3& aabbMin, const b3Vector3& aabbMax, int userPtr, int /*collisionFilterGroup*/, int /*collisionFilterMask*/) { int index = userPtr; b3SapAabb aabb; @@ -1254,7 +1254,7 @@ void b3GpuSapBroadphase::createLargeProxy(const b3Vector3& aabbMin, const b3Vect m_allAabbsCPU.push_back(aabb); } -void b3GpuSapBroadphase::createProxy(const b3Vector3& aabbMin, const b3Vector3& aabbMax, int userPtr, int collisionFilterGroup, int collisionFilterMask) +void b3GpuSapBroadphase::createProxy(const b3Vector3& aabbMin, const b3Vector3& aabbMax, int userPtr, int /*collisionFilterGroup*/, int /*collisionFilterMask*/) { int index = userPtr; b3SapAabb aabb; diff --git a/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp b/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp index fe54ea5ec9..df06177a7e 100644 --- a/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp +++ b/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp @@ -72,9 +72,9 @@ static const char* spPlatformVendor = #endif void MyFatalBreakAPPLE(const char* errstr, - const void* private_info, - size_t cb, - void* user_data) + const void* /*private_info*/, + size_t /*cb*/, + void* /*user_data*/) { const char* patloc = strstr(errstr, "Warning"); //find out if it is a warning or error, exit if error @@ -208,7 +208,7 @@ void b3OpenCLUtils_printPlatformInfo(cl_platform_id platform) b3Printf(" CL_PLATFORM_VERSION: \t\t\t%s\n", platformInfo.m_platformVersion); } -cl_context b3OpenCLUtils_createContextFromPlatform(cl_platform_id platform, cl_device_type deviceType, cl_int* pErrNum, void* pGLContext, void* pGLDC, int preferredDeviceIndex, int preferredPlatformIndex) +cl_context b3OpenCLUtils_createContextFromPlatform(cl_platform_id platform, cl_device_type deviceType, cl_int* pErrNum, void* pGLContext, void* /*pGLDC*/, int preferredDeviceIndex, int /*preferredPlatformIndex*/) { cl_context retContext = 0; cl_int ciErrNum = 0; @@ -564,7 +564,7 @@ void b3OpenCLUtils_printDeviceInfo(cl_device_id device) static const char* strip2(const char* name, const char* pattern) { size_t const patlen = strlen(pattern); - size_t patcnt = 0; + size_t patcnt = 0; (void)patcnt; const char* oriptr; const char* patloc; // find how many times the pattern occurs in the original string @@ -613,8 +613,6 @@ cl_program b3OpenCLUtils_compileCLProgramFromString(cl_context clContext, cl_dev if (clFileNameForCaching && !(disableBinaryCaching || gDebugSkipLoadingBinary || gDebugForceLoadingFromSource)) { #ifdef _WIN32 - char* bla = 0; - //printf("searching for %s\n", binaryFileName); FILETIME modtimeBinary; @@ -760,6 +758,7 @@ cl_program b3OpenCLUtils_compileCLProgramFromString(cl_context clContext, cl_dev binary = (char*)malloc(sizeof(char) * binarySize); int bytesRead; bytesRead = fread(binary, sizeof(char), binarySize, file); + (void)bytesRead; fclose(file); m_cpProgram = clCreateProgramWithBinary(clContext, 1, &device, &binarySize, (const unsigned char**)&binary, 0, &status); @@ -828,6 +827,7 @@ cl_program b3OpenCLUtils_compileCLProgramFromString(cl_context clContext, cl_dev kernelSrc = (char*)malloc(kernelSize + 1); int readBytes; readBytes = fread((void*)kernelSrc, 1, kernelSize, file); + (void)readBytes; kernelSrc[kernelSize] = 0; fclose(file); kernelSource = kernelSrc; diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexHullContact.cpp b/src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexHullContact.cpp index 54a104c5c8..66e3f35f91 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexHullContact.cpp +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexHullContact.cpp @@ -329,7 +329,7 @@ struct MyTriangleCallback : public b3NodeOverlapCallback int m_bodyIndexA; int m_bodyIndexB; - virtual void processNode(int subPart, int triangleIndex) + virtual void processNode(int /*subPart*/, int triangleIndex) { printf("bodyIndexA %d, bodyIndexB %d\n", m_bodyIndexA, m_bodyIndexB); printf("triangleIndex %d\n", triangleIndex); @@ -567,11 +567,11 @@ static bool findSeparatingAxis(const b3ConvexPolyhedronData& hullA, const b3Conv const b3AlignedObjectArray& verticesA, const b3AlignedObjectArray& uniqueEdgesA, const b3AlignedObjectArray& facesA, - const b3AlignedObjectArray& indicesA, + const b3AlignedObjectArray& /*indicesA*/, const b3AlignedObjectArray& verticesB, const b3AlignedObjectArray& uniqueEdgesB, const b3AlignedObjectArray& facesB, - const b3AlignedObjectArray& indicesB, + const b3AlignedObjectArray& /*indicesB*/, b3Vector3& sep) { @@ -592,6 +592,7 @@ static bool findSeparatingAxis(const b3ConvexPolyhedronData& hullA, const b3Conv b3Scalar dmin = FLT_MAX; int curPlaneTests = 0; + (void)curPlaneTests; int numFacesA = hullA.m_numFaces; // Test normals from hullA @@ -653,6 +654,7 @@ static bool findSeparatingAxis(const b3ConvexPolyhedronData& hullA, const b3Conv } int curEdgeEdge = 0; + (void)curEdgeEdge; // Test edges for (int e0 = 0; e0 < hullA.m_numUniqueEdges; e0++) { @@ -707,8 +709,8 @@ bool findSeparatingAxisEdgeEdge(__global const b3ConvexPolyhedronData* hullA, __ const b3Float4& DeltaC2, __global const b3AlignedObjectArray& vertices, __global const b3AlignedObjectArray& uniqueEdges, - __global const b3AlignedObjectArray& faces, - __global const b3AlignedObjectArray& indices, + __global const b3AlignedObjectArray& /*faces*/, + __global const b3AlignedObjectArray& /*indices*/, float4* sep, float* dmin) { @@ -722,6 +724,7 @@ bool findSeparatingAxisEdgeEdge(__global const b3ConvexPolyhedronData* hullA, __ //int curPlaneTests=0; int curEdgeEdge = 0; + (void)curEdgeEdge; // Test edges for (int e0 = 0; e0 < hullA->m_numUniqueEdges; e0++) { @@ -757,6 +760,7 @@ bool findSeparatingAxisEdgeEdge(__global const b3ConvexPolyhedronData* hullA, __ float d1 = Max1 - Min0; dist = d0 < d1 ? d0 : d1; result = true; + (void)result; } if (dist < *dmin) @@ -833,7 +837,7 @@ int clipFace(const float4* pVtxIn, int numVertsIn, float4& planeNormalWS, float int clipFaceAgainstHull(const float4& separatingNormal, const b3ConvexPolyhedronData* hullA, const float4& posA, const b3Quaternion& ornA, float4* worldVertsB1, int numWorldVertsB1, - float4* worldVertsB2, int capacityWorldVertsB2, + float4* worldVertsB2, int /*capacityWorldVertsB2*/, const float minDist, float maxDist, const b3AlignedObjectArray& verticesA, const b3AlignedObjectArray& facesA, const b3AlignedObjectArray& indicesA, //const float4* verticesB, const b3GpuFace* facesB, const int* indicesB, @@ -962,7 +966,9 @@ static int clipHullAgainstHull(const float4& separatingNormal, { //printf("wtf\n"); } +#ifdef BT_DEBUG_SAT_FACE static bool once = true; +#endif //printf("separatingNormal=%f,%f,%f\n",separatingNormal.x,separatingNormal.y,separatingNormal.z); for (int face = 0; face < hullB.m_numFaces; face++) @@ -979,7 +985,7 @@ static int clipHullAgainstHull(const float4& separatingNormal, printf("vert[%d] = %f,%f,%f\n", i, vert.x, vert.y, vert.z); } } -#endif //BT_DEBUG_SAT_FACE \ +#endif //BT_DEBUG_SAT_FACE //if (facesB[hullB.m_faceOffset+face].m_numIndices>2) { const float4 Normal = b3MakeVector3(facesB[hullB.m_faceOffset + face].m_plane.x, @@ -997,7 +1003,9 @@ static int clipHullAgainstHull(const float4& separatingNormal, } } } +#ifdef BT_DEBUG_SAT_FACE once = false; +#endif } b3Assert(closestFaceB >= 0); @@ -1145,12 +1153,12 @@ int clipHullHullSingle( const b3AlignedObjectArray& hostConvexDataB, const b3AlignedObjectArray& verticesA, - const b3AlignedObjectArray& uniqueEdgesA, + const b3AlignedObjectArray& /*uniqueEdgesA*/, const b3AlignedObjectArray& facesA, const b3AlignedObjectArray& indicesA, const b3AlignedObjectArray& verticesB, - const b3AlignedObjectArray& uniqueEdgesB, + const b3AlignedObjectArray& /*uniqueEdgesB*/, const b3AlignedObjectArray& facesB, const b3AlignedObjectArray& indicesB, @@ -1276,7 +1284,7 @@ void computeContactPlaneConvex(int pairIndex, const b3Collidable* collidables, const b3ConvexPolyhedronData* convexShapes, const b3Vector3* convexVertices, - const int* convexIndices, + const int* /*convexIndices*/, const b3GpuFace* faces, b3Contact4* globalContactsOut, int& nGlobalContactsOut, @@ -1313,7 +1321,7 @@ void computeContactPlaneConvex(int pairIndex, b3Vector3 planeNormalInConvex = planeInConvex.getBasis() * -planeNormal; float maxDot = -1e30; - int hitVertex = -1; + int hitVertex = -1; (void)hitVertex; b3Vector3 hitVtx; #define MAX_PLANE_CONVEX_POINTS 64 @@ -1417,7 +1425,7 @@ int maxDepth = 0; // work-in-progress __kernel void findCompoundPairsKernel( - int pairIndex, + int /*pairIndex*/, int bodyIndexA, int bodyIndexB, int collidableIndexA, @@ -1425,8 +1433,8 @@ __kernel void findCompoundPairsKernel( __global const b3RigidBodyData* rigidBodies, __global const b3Collidable* collidables, __global const b3ConvexPolyhedronData* convexShapes, - __global const b3AlignedObjectArray& vertices, - __global const b3AlignedObjectArray& aabbsWorldSpace, + __global const b3AlignedObjectArray& /*vertices*/, + __global const b3AlignedObjectArray& /*aabbsWorldSpace*/, __global const b3AlignedObjectArray& aabbsLocalSpace, __global const b3GpuChildShape* gpuChildShapes, __global b3Int4* gpuCompoundPairsOut, @@ -1782,7 +1790,7 @@ __kernel void processCompoundPairsKernel(__global const b3Int4* gpuCompoundPairs __global const b3AlignedObjectArray& uniqueEdges, __global const b3AlignedObjectArray& faces, __global const b3AlignedObjectArray& indices, - __global b3Aabb* aabbs, + __global b3Aabb* /*aabbs*/, __global const b3GpuChildShape* gpuChildShapes, __global b3AlignedObjectArray& gpuCompoundSepNormalsOut, __global b3AlignedObjectArray& gpuHasCompoundSepNormalsOut, @@ -1888,6 +1896,7 @@ __kernel void processCompoundPairsKernel(__global const b3Int4* gpuCompoundPairs } //sepEE } //(!sepB) } //(!sepA) + (void)hasSeparatingAxis; } } @@ -1896,7 +1905,7 @@ __kernel void clipCompoundsHullHullKernel(__global const b3Int4* gpuCompoundPair __global const b3Collidable* collidables, __global const b3ConvexPolyhedronData* convexShapes, __global const b3AlignedObjectArray& vertices, - __global const b3AlignedObjectArray& uniqueEdges, + __global const b3AlignedObjectArray& /*uniqueEdges*/, __global const b3AlignedObjectArray& faces, __global const b3AlignedObjectArray& indices, __global const b3GpuChildShape* gpuChildShapes, @@ -2046,6 +2055,7 @@ void computeContactCompoundCompound(int pairIndex, { int shapeTypeB = collidables[collidableIndexB].m_shapeType; b3Assert(shapeTypeB == SHAPE_COMPOUND_OF_CONVEX_HULLS); + (void)shapeTypeB; b3AlignedObjectArray cpuCompoundPairsOut; int numCompoundPairsOut = 0; @@ -2187,7 +2197,7 @@ void computeContactPlaneCompound(int pairIndex, const b3ConvexPolyhedronData* convexShapes, const b3GpuChildShape* cpuChildShapes, const b3Vector3* convexVertices, - const int* convexIndices, + const int* /*convexIndices*/, const b3GpuFace* faces, b3Contact4* globalContactsOut, @@ -2196,6 +2206,7 @@ void computeContactPlaneCompound(int pairIndex, { int shapeTypeB = collidables[collidableIndexB].m_shapeType; b3Assert(shapeTypeB == SHAPE_COMPOUND_OF_CONVEX_HULLS); + (void)shapeTypeB; int numChildrenB = collidables[collidableIndexB].m_numChildShapes; for (int c = 0; c < numChildrenB; c++) @@ -2240,7 +2251,7 @@ void computeContactPlaneCompound(int pairIndex, b3Vector3 planeNormalInConvex = planeInConvex.getBasis() * -planeNormal; float maxDot = -1e30; - int hitVertex = -1; + int hitVertex = -1; (void)hitVertex; b3Vector3 hitVtx; #define MAX_PLANE_CONVEX_POINTS 64 @@ -2322,7 +2333,7 @@ void computeContactPlaneCompound(int pairIndex, void computeContactSphereConvex(int pairIndex, int bodyIndexA, int bodyIndexB, - int collidableIndexA, int collidableIndexB, + int collidableIndexA, int /*collidableIndexB*/, const b3RigidBodyData* rigidBodies, const b3Collidable* collidables, const b3ConvexPolyhedronData* convexShapes, @@ -2335,7 +2346,7 @@ void computeContactSphereConvex(int pairIndex, { float radius = collidables[collidableIndexA].m_radius; float4 spherePos1 = rigidBodies[bodyIndexA].m_pos; - b3Quaternion sphereOrn = rigidBodies[bodyIndexA].m_quat; + // b3Quaternion sphereOrn = rigidBodies[bodyIndexA].m_quat; float4 pos = rigidBodies[bodyIndexB].m_pos; @@ -2431,6 +2442,7 @@ void computeContactSphereConvex(int pairIndex, } static int numChecks = 0; numChecks++; + (void)numChecks; if (bCollide && minDist > -10000) { @@ -2467,10 +2479,11 @@ void computeContactSphereConvex(int pairIndex, } //if (dstIdx < numPairs) } } //if (hasCollision) + (void)region; } int computeContactConvexConvex2( - int pairIndex, + int /*pairIndex*/, int bodyIndexA, int bodyIndexB, int collidableIndexA, int collidableIndexB, const b3AlignedObjectArray& rigidBodies, @@ -2483,7 +2496,7 @@ int computeContactConvexConvex2( b3AlignedObjectArray& globalContactsOut, int& nGlobalContactsOut, int maxContactCapacity, - const b3AlignedObjectArray& oldContacts) + const b3AlignedObjectArray& /*oldContacts*/) { int contactIndex = -1; b3Vector3 posA = rigidBodies[bodyIndexA].m_pos; @@ -2558,7 +2571,7 @@ int computeContactConvexConvex2( void GpuSatCollision::computeConvexConvexContactsGPUSAT(b3OpenCLArray* pairs, int nPairs, const b3OpenCLArray* bodyBuf, b3OpenCLArray* contactOut, int& nContacts, - const b3OpenCLArray* oldContacts, + const b3OpenCLArray* /*oldContacts*/, int maxContactCapacity, int compoundPairCapacity, const b3OpenCLArray& convexData, @@ -2577,15 +2590,15 @@ void GpuSatCollision::computeConvexConvexContactsGPUSAT(b3OpenCLArray* p b3OpenCLArray& worldNormalsAGPU, b3OpenCLArray& worldVertsA1GPU, b3OpenCLArray& worldVertsB2GPU, - b3AlignedObjectArray& bvhDataUnused, + b3AlignedObjectArray& /*bvhDataUnused*/, b3OpenCLArray* treeNodesGPU, b3OpenCLArray* subTreesGPU, b3OpenCLArray* bvhInfo, - int numObjects, + int /*numObjects*/, int maxTriConvexPairCapacity, b3OpenCLArray& triangleConvexPairsOut, - int& numTriConvexPairsOut) + int& /*numTriConvexPairsOut*/) { myframecount++; @@ -3210,6 +3223,7 @@ void GpuSatCollision::computeConvexConvexContactsGPUSAT(b3OpenCLArray* p //hostSepAxis ); + (void)result; } //mpr } //hostHasSepAxis[i] = 1; } diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.cpp b/src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.cpp index 3a554fe5b4..cdf4774853 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.cpp +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.cpp @@ -859,8 +859,8 @@ struct b3EPA // static void Initialize(const b3Transform& transA, const b3Transform& transB, const b3ConvexPolyhedronData* hullA, const b3ConvexPolyhedronData* hullB, - const b3AlignedObjectArray& verticesA, - const b3AlignedObjectArray& verticesB, + const b3AlignedObjectArray& /*verticesA*/, + const b3AlignedObjectArray& /*verticesB*/, b3GjkEpaSolver2::sResults& results, tShape& shape, bool withmargins) diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3QuantizedBvh.cpp b/src/Bullet3OpenCL/NarrowphaseCollision/b3QuantizedBvh.cpp index e9a3d085bb..bac82f1b8c 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3QuantizedBvh.cpp +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3QuantizedBvh.cpp @@ -421,7 +421,7 @@ void b3QuantizedBvh::walkRecursiveQuantizedTreeAgainstQueryAabb(const b3Quantize } } -void b3QuantizedBvh::walkStacklessTreeAgainstRay(b3NodeOverlapCallback* nodeCallback, const b3Vector3& raySource, const b3Vector3& rayTarget, const b3Vector3& aabbMin, const b3Vector3& aabbMax, int startNodeIndex, int endNodeIndex) const +void b3QuantizedBvh::walkStacklessTreeAgainstRay(b3NodeOverlapCallback* nodeCallback, const b3Vector3& raySource, const b3Vector3& rayTarget, const b3Vector3& aabbMin, const b3Vector3& aabbMax, int /*startNodeIndex*/, int /*endNodeIndex*/) const { b3Assert(!m_useQuantization); @@ -1247,7 +1247,7 @@ void b3QuantizedBvh::deSerializeDouble(struct b3QuantizedBvhDoubleData& quantize } ///fills the dataBuffer and returns the struct name (and 0 on failure) -const char* b3QuantizedBvh::serialize(void* dataBuffer, b3Serializer* serializer) const +const char* b3QuantizedBvh::serialize(void* /*dataBuffer*/, b3Serializer* /*serializer*/) const { b3Assert(0); return 0; diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3StridingMeshInterface.cpp b/src/Bullet3OpenCL/NarrowphaseCollision/b3StridingMeshInterface.cpp index 6b0c941f23..6b42240d07 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3StridingMeshInterface.cpp +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3StridingMeshInterface.cpp @@ -23,7 +23,7 @@ void b3StridingMeshInterface::InternalProcessAllTriangles(b3InternalTriangleInde { (void)aabbMin; (void)aabbMax; - int numtotalphysicsverts = 0; + int numtotalphysicsverts = 0; (void)numtotalphysicsverts; int part, graphicssubparts = getNumSubParts(); const unsigned char* vertexbase; const unsigned char* indexbase; diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3SupportMappings.h b/src/Bullet3OpenCL/NarrowphaseCollision/b3SupportMappings.h index 9ca1e22949..bb80b41065 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3SupportMappings.h +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3SupportMappings.h @@ -9,7 +9,7 @@ struct b3GjkPairDetector; inline b3Vector3 localGetSupportVertexWithMargin(const float4& supportVec, const struct b3ConvexPolyhedronData* hull, - const b3AlignedObjectArray& verticesA, b3Scalar margin) + const b3AlignedObjectArray& verticesA, b3Scalar /*margin*/) { b3Vector3 supVec = b3MakeVector3(b3Scalar(0.), b3Scalar(0.), b3Scalar(0.)); b3Scalar maxDot = b3Scalar(-B3_LARGE_FLOAT); diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/kernels/mprKernels.h b/src/Bullet3OpenCL/NarrowphaseCollision/kernels/mprKernels.h index 74959a931c..b5e31975b1 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/kernels/mprKernels.h +++ b/src/Bullet3OpenCL/NarrowphaseCollision/kernels/mprKernels.h @@ -28,7 +28,7 @@ static const char* mprKernelsCL = "//keep B3_LARGE_FLOAT*B3_LARGE_FLOAT < FLT_MAX\n" "#define B3_LARGE_FLOAT 1e18f\n" "#define B3_INFINITY 1e18f\n" - "#define b3Assert(a)\n" + "#define b3Assert(a) (void)(x)\n" "#define b3ConstArray(a) __global const a*\n" "#define b3AtomicInc atomic_inc\n" "#define b3AtomicAdd atomic_add\n" diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/kernels/primitiveContacts.h b/src/Bullet3OpenCL/NarrowphaseCollision/kernels/primitiveContacts.h index b2e0a2dd47..a21bd2108d 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/kernels/primitiveContacts.h +++ b/src/Bullet3OpenCL/NarrowphaseCollision/kernels/primitiveContacts.h @@ -15,7 +15,7 @@ static const char* primitiveContactsKernelsCL = "//keep B3_LARGE_FLOAT*B3_LARGE_FLOAT < FLT_MAX\n" "#define B3_LARGE_FLOAT 1e18f\n" "#define B3_INFINITY 1e18f\n" - "#define b3Assert(a)\n" + "#define b3Assert(a) (void)(x)\n" "#define b3ConstArray(a) __global const a*\n" "#define b3AtomicInc atomic_inc\n" "#define b3AtomicAdd atomic_add\n" diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/kernels/satClipHullContacts.h b/src/Bullet3OpenCL/NarrowphaseCollision/kernels/satClipHullContacts.h index 907809d8bd..033003fbd4 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/kernels/satClipHullContacts.h +++ b/src/Bullet3OpenCL/NarrowphaseCollision/kernels/satClipHullContacts.h @@ -42,7 +42,7 @@ static const char* satClipKernelsCL = "//keep B3_LARGE_FLOAT*B3_LARGE_FLOAT < FLT_MAX\n" "#define B3_LARGE_FLOAT 1e18f\n" "#define B3_INFINITY 1e18f\n" - "#define b3Assert(a)\n" + "#define b3Assert(a) (void)(x)\n" "#define b3ConstArray(a) __global const a*\n" "#define b3AtomicInc atomic_inc\n" "#define b3AtomicAdd atomic_add\n" diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/kernels/satConcaveKernels.h b/src/Bullet3OpenCL/NarrowphaseCollision/kernels/satConcaveKernels.h index a60702ca62..1e6549666e 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/kernels/satConcaveKernels.h +++ b/src/Bullet3OpenCL/NarrowphaseCollision/kernels/satConcaveKernels.h @@ -156,7 +156,7 @@ static const char* satConcaveKernelsCL = "//keep B3_LARGE_FLOAT*B3_LARGE_FLOAT < FLT_MAX\n" "#define B3_LARGE_FLOAT 1e18f\n" "#define B3_INFINITY 1e18f\n" - "#define b3Assert(a)\n" + "#define b3Assert(a) (void)(x)\n" "#define b3ConstArray(a) __global const a*\n" "#define b3AtomicInc atomic_inc\n" "#define b3AtomicAdd atomic_add\n" diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/kernels/satKernels.h b/src/Bullet3OpenCL/NarrowphaseCollision/kernels/satKernels.h index e627af2799..7858dcb569 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/kernels/satKernels.h +++ b/src/Bullet3OpenCL/NarrowphaseCollision/kernels/satKernels.h @@ -156,7 +156,7 @@ static const char* satKernelsCL = "//keep B3_LARGE_FLOAT*B3_LARGE_FLOAT < FLT_MAX\n" "#define B3_LARGE_FLOAT 1e18f\n" "#define B3_INFINITY 1e18f\n" - "#define b3Assert(a)\n" + "#define b3Assert(a) (void)(x)\n" "#define b3ConstArray(a) __global const a*\n" "#define b3AtomicInc atomic_inc\n" "#define b3AtomicAdd atomic_add\n" diff --git a/src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.cpp b/src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.cpp index c0e11bfb26..afb0ecb059 100644 --- a/src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.cpp +++ b/src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.cpp @@ -73,9 +73,9 @@ b3BoundSearchCL::~b3BoundSearchCL() void b3BoundSearchCL::execute(b3OpenCLArray& src, int nSrc, b3OpenCLArray& dst, int nDst, Option option) { - b3Int4 constBuffer; - constBuffer.x = nSrc; - constBuffer.y = nDst; + // b3Int4 constBuffer; + // constBuffer.x = nSrc; + // constBuffer.y = nDst; if (option == BOUND_LOWER) { @@ -136,11 +136,11 @@ void b3BoundSearchCL::executeHost(b3AlignedObjectArray& src, int nSr for (int i = 0; i < nSrc - 1; i++) b3Assert(src[i].m_key <= src[i + 1].m_key); - b3SortData minData, zeroData, maxData; + b3SortData minData, /*zeroData,*/ maxData; minData.m_key = -1; minData.m_value = -1; - zeroData.m_key = 0; - zeroData.m_value = 0; + // zeroData.m_key = 0; + // zeroData.m_value = 0; maxData.m_key = nDst; maxData.m_value = nDst; diff --git a/src/Bullet3OpenCL/ParallelPrimitives/b3LauncherCL.cpp b/src/Bullet3OpenCL/ParallelPrimitives/b3LauncherCL.cpp index c97d02eb45..6068cc51ed 100644 --- a/src/Bullet3OpenCL/ParallelPrimitives/b3LauncherCL.cpp +++ b/src/Bullet3OpenCL/ParallelPrimitives/b3LauncherCL.cpp @@ -111,7 +111,7 @@ struct b3KernelArgDataUnaligned }; #include -int b3LauncherCL::deserializeArgs(unsigned char* buf, int bufSize, cl_context ctx) +int b3LauncherCL::deserializeArgs(unsigned char* buf, int /*bufSize*/, cl_context ctx) { int index = 0; @@ -151,7 +151,7 @@ int b3LauncherCL::deserializeArgs(unsigned char* buf, int bufSize, cl_context ct return index; } -int b3LauncherCL::validateResults(unsigned char* goldBuffer, int goldBufferCapacity, cl_context ctx) +int b3LauncherCL::validateResults(unsigned char* goldBuffer, int /*goldBufferCapacity*/, cl_context /*ctx*/) { int index = 0; diff --git a/src/Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.cpp b/src/Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.cpp index e86af6583f..a13d91d64f 100644 --- a/src/Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.cpp +++ b/src/Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.cpp @@ -163,8 +163,8 @@ void b3RadixSort32CL::executeHost(b3OpenCLArray& keyValuesInOut, int keyValuesInOut.copyFromHost(inout); } -void b3RadixSort32CL::execute(b3OpenCLArray& keysIn, b3OpenCLArray& keysOut, b3OpenCLArray& valuesIn, - b3OpenCLArray& valuesOut, int n, int sortBits) +void b3RadixSort32CL::execute(b3OpenCLArray& /*keysIn*/, b3OpenCLArray& /*keysOut*/, b3OpenCLArray& /*valuesIn*/, + b3OpenCLArray& /*valuesOut*/, int /*n*/, int /*sortBits*/) { } diff --git a/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp b/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp index 6571f30548..0b73e1d273 100644 --- a/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp +++ b/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp @@ -173,7 +173,7 @@ bool rayConvex(const b3Vector3& rayFromLocal, const b3Vector3& rayToLocal, const } void b3GpuRaycast::castRaysHost(const b3AlignedObjectArray& rays, b3AlignedObjectArray& hitResults, - int numBodies, const struct b3RigidBodyData* bodies, int numCollidables, const struct b3Collidable* collidables, const struct b3GpuNarrowPhaseInternalData* narrowphaseData) + int numBodies, const struct b3RigidBodyData* bodies, int /*numCollidables*/, const struct b3Collidable* collidables, const struct b3GpuNarrowPhaseInternalData* narrowphaseData) { // return castRays(rays,hitResults,numBodies,bodies,numCollidables,collidables); @@ -247,7 +247,7 @@ void b3GpuRaycast::castRaysHost(const b3AlignedObjectArray& rays, b3A } ///todo: add some acceleration structure (AABBs, tree etc) void b3GpuRaycast::castRays(const b3AlignedObjectArray& rays, b3AlignedObjectArray& hitResults, - int numBodies, const struct b3RigidBodyData* bodies, int numCollidables, const struct b3Collidable* collidables, + int numBodies, const struct b3RigidBodyData* /*bodies*/, int /*numCollidables*/, const struct b3Collidable* /*collidables*/, const struct b3GpuNarrowPhaseInternalData* narrowphaseData, class b3GpuBroadphaseInterface* broadphase) { //castRaysHost(rays,hitResults,numBodies,bodies,numCollidables,collidables,narrowphaseData); diff --git a/src/Bullet3OpenCL/RigidBody/b3GpuGenericConstraint.cpp b/src/Bullet3OpenCL/RigidBody/b3GpuGenericConstraint.cpp index a271090af4..3af375837c 100644 --- a/src/Bullet3OpenCL/RigidBody/b3GpuGenericConstraint.cpp +++ b/src/Bullet3OpenCL/RigidBody/b3GpuGenericConstraint.cpp @@ -19,7 +19,7 @@ subject to the following restrictions: #include #include "Bullet3Common/b3Transform.h" -void b3GpuGenericConstraint::getInfo1(unsigned int* info, const b3RigidBodyData* bodies) +void b3GpuGenericConstraint::getInfo1(unsigned int* info, const b3RigidBodyData* /*bodies*/) { switch (m_constraintType) { diff --git a/src/Bullet3OpenCL/RigidBody/b3GpuJacobiContactSolver.cpp b/src/Bullet3OpenCL/RigidBody/b3GpuJacobiContactSolver.cpp index 089fb1f6a6..5d172be7ea 100644 --- a/src/Bullet3OpenCL/RigidBody/b3GpuJacobiContactSolver.cpp +++ b/src/Bullet3OpenCL/RigidBody/b3GpuJacobiContactSolver.cpp @@ -44,7 +44,7 @@ struct b3GpuJacobiSolverInternalData cl_kernel m_solveFrictionKernel; }; -b3GpuJacobiContactSolver::b3GpuJacobiContactSolver(cl_context ctx, cl_device_id device, cl_command_queue queue, int pairCapacity) +b3GpuJacobiContactSolver::b3GpuJacobiContactSolver(cl_context ctx, cl_device_id device, cl_command_queue queue, int /*pairCapacity*/) : m_context(ctx), m_device(device), m_queue(queue) @@ -318,7 +318,7 @@ static inline void solveFriction(b3GpuConstraint4& cs, } } -float calcJacCoeff(const b3Vector3& linear0, const b3Vector3& linear1, const b3Vector3& angular0, const b3Vector3& angular1, +float calcJacCoeff(const b3Vector3& /*linear0*/, const b3Vector3& /*linear1*/, const b3Vector3& angular0, const b3Vector3& angular1, float invMass0, const b3Matrix3x3* invInertia0, float invMass1, const b3Matrix3x3* invInertia1, float countA, float countB) { // linear0,1 are normlized @@ -696,7 +696,7 @@ void b3GpuJacobiContactSolver::solveGroupHost(b3RigidBodyData* bodies, b3Inertia } } -void b3GpuJacobiContactSolver::solveContacts(int numBodies, cl_mem bodyBuf, cl_mem inertiaBuf, int numContacts, cl_mem contactBuf, const struct b3Config& config, int static0Index) +void b3GpuJacobiContactSolver::solveContacts(int numBodies, cl_mem bodyBuf, cl_mem inertiaBuf, int numContacts, cl_mem contactBuf, const struct b3Config& /*config*/, int static0Index) // // //void b3GpuJacobiContactSolver::solveGroup(b3OpenCLArray* bodies,b3OpenCLArray* inertias,b3OpenCLArray* manifoldPtr,const btJacobiSolverInfo& solverInfo) diff --git a/src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.cpp b/src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.cpp index 2e4f6c1572..3316491536 100644 --- a/src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.cpp +++ b/src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.cpp @@ -231,7 +231,7 @@ int b3GpuNarrowPhase::registerPlaneShape(const b3Vector3& planeNormal, float pla return collidableIndex; } -int b3GpuNarrowPhase::registerConvexHullShapeInternal(b3ConvexUtility* convexPtr, b3Collidable& col) +int b3GpuNarrowPhase::registerConvexHullShapeInternal(b3ConvexUtility* convexPtr, b3Collidable& /*col*/) { m_data->m_convexData->resize(m_data->m_numAcceleratedShapes + 1); m_data->m_convexPolyhedra.resize(m_data->m_numAcceleratedShapes + 1); @@ -604,7 +604,7 @@ int b3GpuNarrowPhase::registerConcaveMesh(b3AlignedObjectArray* verti return collidableIndex; } -int b3GpuNarrowPhase::registerConcaveMeshShape(b3AlignedObjectArray* vertices, b3AlignedObjectArray* indices, b3Collidable& col, const float* scaling1) +int b3GpuNarrowPhase::registerConcaveMeshShape(b3AlignedObjectArray* vertices, b3AlignedObjectArray* indices, b3Collidable& /*col*/, const float* scaling1) { b3Vector3 scaling = b3MakeVector3(scaling1[0], scaling1[1], scaling1[2]); diff --git a/src/Bullet3OpenCL/RigidBody/b3GpuPgsConstraintSolver.cpp b/src/Bullet3OpenCL/RigidBody/b3GpuPgsConstraintSolver.cpp index bd9d6bb04b..b0282df7e5 100644 --- a/src/Bullet3OpenCL/RigidBody/b3GpuPgsConstraintSolver.cpp +++ b/src/Bullet3OpenCL/RigidBody/b3GpuPgsConstraintSolver.cpp @@ -735,6 +735,7 @@ b3Scalar b3GpuPgsConstraintSolver::solveGroupCacheFriendlyIterations(b3OpenCLArr } //useGpu batchOffset += numConstraintsInBatch; constraintOffset += numConstraintsInBatch; + (void)constraintOffset; } } //for (int iteration... @@ -805,6 +806,7 @@ inline int b3GpuPgsConstraintSolver::sortConstraintByBatch3(b3BatchConstraint* c int curBodyUsed = 0; int numIter = 0; + (void)numIter; #if defined(_DEBUG) for (int i = 0; i < numConstraints; i++) @@ -943,7 +945,7 @@ void b3GpuPgsConstraintSolver::solveJoints(int numBodies, b3OpenCLArray testBodies; -b3Scalar b3GpuPgsConstraintSolver::solveGroupCacheFriendlyFinish(b3OpenCLArray* gpuBodies, b3OpenCLArray* gpuInertias, int numBodies, b3OpenCLArray* gpuConstraints, int numConstraints, const b3ContactSolverInfo& infoGlobal) +b3Scalar b3GpuPgsConstraintSolver::solveGroupCacheFriendlyFinish(b3OpenCLArray* gpuBodies, b3OpenCLArray* /*gpuInertias*/, int numBodies, b3OpenCLArray* gpuConstraints, int numConstraints, const b3ContactSolverInfo& infoGlobal) { B3_PROFILE("solveGroupCacheFriendlyFinish"); // int numPoolConstraints = m_tmpSolverContactConstraintPool.size(); diff --git a/src/Bullet3OpenCL/RigidBody/b3GpuPgsContactSolver.cpp b/src/Bullet3OpenCL/RigidBody/b3GpuPgsContactSolver.cpp index e3d235a4fd..0dcadd288c 100644 --- a/src/Bullet3OpenCL/RigidBody/b3GpuPgsContactSolver.cpp +++ b/src/Bullet3OpenCL/RigidBody/b3GpuPgsContactSolver.cpp @@ -255,7 +255,7 @@ struct b3ConstraintCfg }; void b3GpuPgsContactSolver::solveContactConstraintBatchSizes(const b3OpenCLArray* bodyBuf, const b3OpenCLArray* shapeBuf, - b3OpenCLArray* constraint, void* additionalData, int n, int maxNumBatches, int numIterations, const b3AlignedObjectArray* batchSizes) //const b3OpenCLArray* gpuBatchSizes) + b3OpenCLArray* constraint, void* /*additionalData*/, int /*n*/, int /*maxNumBatches*/, int numIterations, const b3AlignedObjectArray* batchSizes) //const b3OpenCLArray* gpuBatchSizes) { B3_PROFILE("solveContactConstraintBatchSizes"); int numBatches = batchSizes->size() / B3_MAX_NUM_BATCHES; @@ -313,7 +313,7 @@ void b3GpuPgsContactSolver::solveContactConstraintBatchSizes(const b3OpenCLArray } void b3GpuPgsContactSolver::solveContactConstraint(const b3OpenCLArray* bodyBuf, const b3OpenCLArray* shapeBuf, - b3OpenCLArray* constraint, void* additionalData, int n, int maxNumBatches, int numIterations, const b3AlignedObjectArray* batchSizes) //,const b3OpenCLArray* gpuBatchSizes) + b3OpenCLArray* constraint, void* /*additionalData*/, int n, int maxNumBatches, int numIterations, const b3AlignedObjectArray* /*batchSizes*/) //,const b3OpenCLArray* gpuBatchSizes) { //sort the contacts @@ -565,7 +565,7 @@ void SetSortDataCPU(b3Contact4* gContact, b3RigidBodyData* gBodies, b3SortData* } } -void b3GpuPgsContactSolver::solveContacts(int numBodies, cl_mem bodyBuf, cl_mem inertiaBuf, int numContacts, cl_mem contactBuf, const b3Config& config, int static0Index) +void b3GpuPgsContactSolver::solveContacts(int numBodies, cl_mem bodyBuf, cl_mem inertiaBuf, int numContacts, cl_mem contactBuf, const b3Config& /*config*/, int static0Index) { B3_PROFILE("solveContacts"); m_data->m_bodyBufferGPU->setFromOpenCLBuffer(bodyBuf, numBodies); @@ -946,6 +946,7 @@ void b3GpuPgsContactSolver::solveContacts(int numBodies, cl_mem bodyBuf, cl_mem } int numNonzeroGrid = 0; + (void)numNonzeroGrid; if (gUseLargeBatches) { @@ -1102,7 +1103,7 @@ void b3GpuPgsContactSolver::solveContacts(int numBodies, cl_mem bodyBuf, cl_mem } } -void b3GpuPgsContactSolver::batchContacts(b3OpenCLArray* contacts, int nContacts, b3OpenCLArray* n, b3OpenCLArray* offsets, int staticIdx) +void b3GpuPgsContactSolver::batchContacts(b3OpenCLArray* /*contacts*/, int /*nContacts*/, b3OpenCLArray* /*n*/, b3OpenCLArray* /*offsets*/, int /*staticIdx*/) { } @@ -1110,10 +1111,11 @@ b3AlignedObjectArray idxBuffer; b3AlignedObjectArray sortData; b3AlignedObjectArray old; -inline int b3GpuPgsContactSolver::sortConstraintByBatch(b3Contact4* cs, int n, int simdWidth, int staticIdx, int numBodies) +inline int b3GpuPgsContactSolver::sortConstraintByBatch(b3Contact4* cs, int n, int simdWidth, int staticIdx, int /*numBodies*/) { B3_PROFILE("sortConstraintByBatch"); int numIter = 0; + (void)numIter; sortData.resize(n); idxBuffer.resize(n); @@ -1231,7 +1233,7 @@ inline int b3GpuPgsContactSolver::sortConstraintByBatch(b3Contact4* cs, int n, i b3AlignedObjectArray bodyUsed2; -inline int b3GpuPgsContactSolver::sortConstraintByBatch2(b3Contact4* cs, int numConstraints, int simdWidth, int staticIdx, int numBodies) +inline int b3GpuPgsContactSolver::sortConstraintByBatch2(b3Contact4* cs, int numConstraints, int simdWidth, int staticIdx, int /*numBodies*/) { B3_PROFILE("sortConstraintByBatch2"); @@ -1243,6 +1245,7 @@ inline int b3GpuPgsContactSolver::sortConstraintByBatch2(b3Contact4* cs, int num int curBodyUsed = 0; int numIter = 0; + (void)numIter; m_data->m_sortData.resize(numConstraints); m_data->m_idxBuffer.resize(numConstraints); @@ -1407,6 +1410,7 @@ inline int b3GpuPgsContactSolver::sortConstraintByBatch3(b3Contact4* cs, int num int curBodyUsed = 0; int numIter = 0; + (void)numIter; m_data->m_sortData.resize(0); m_data->m_idxBuffer.resize(0); diff --git a/src/Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipeline.cpp b/src/Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipeline.cpp index fef33ad1cd..8f47ebb23e 100644 --- a/src/Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipeline.cpp +++ b/src/Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipeline.cpp @@ -600,7 +600,7 @@ void b3GpuRigidBodyPipeline::writeAllInstancesToGpu() m_data->m_gpuConstraints->copyFromHost(m_data->m_cpuConstraints); } -int b3GpuRigidBodyPipeline::registerPhysicsInstance(float mass, const float* position, const float* orientation, int collidableIndex, int userIndex, bool writeInstanceToGpu) +int b3GpuRigidBodyPipeline::registerPhysicsInstance(float mass, const float* position, const float* orientation, int collidableIndex, int /*userIndex*/, bool writeInstanceToGpu) { b3Vector3 aabbMin = b3MakeVector3(0, 0, 0), aabbMax = b3MakeVector3(0, 0, 0); diff --git a/src/Bullet3OpenCL/RigidBody/b3GpuSolverBody.h b/src/Bullet3OpenCL/RigidBody/b3GpuSolverBody.h index db815d9b31..5aa18a3cd4 100644 --- a/src/Bullet3OpenCL/RigidBody/b3GpuSolverBody.h +++ b/src/Bullet3OpenCL/RigidBody/b3GpuSolverBody.h @@ -185,7 +185,7 @@ b3GpuSolverBody } } - void writebackVelocityAndTransform(b3Scalar timeStep, b3Scalar splitImpulseTurnErp) + void writebackVelocityAndTransform(b3Scalar timeStep, b3Scalar /*splitImpulseTurnErp*/) { (void)timeStep; if (m_originalBody) diff --git a/src/Bullet3OpenCL/RigidBody/b3Solver.cpp b/src/Bullet3OpenCL/RigidBody/b3Solver.cpp index ccf67da1a8..1d0003cdc7 100644 --- a/src/Bullet3OpenCL/RigidBody/b3Solver.cpp +++ b/src/Bullet3OpenCL/RigidBody/b3Solver.cpp @@ -343,14 +343,14 @@ static __inline void solveFriction(b3GpuConstraint4& cs, struct SolveTask // : public ThreadPool::Task { SolveTask(b3AlignedObjectArray& bodies, b3AlignedObjectArray& shapes, b3AlignedObjectArray& constraints, - int start, int nConstraints, int maxNumBatches, b3AlignedObjectArray* wgUsedBodies, int curWgidx, b3AlignedObjectArray* batchSizes, int cellIndex) + int start, int nConstraints, int maxNumBatches, b3AlignedObjectArray* /*wgUsedBodies*/, int curWgidx, b3AlignedObjectArray* batchSizes, int cellIndex) : m_bodies(bodies), m_shapes(shapes), m_constraints(constraints), m_batchSizes(batchSizes), m_cellIndex(cellIndex), m_curWgidx(curWgidx), m_start(start), m_nConstraints(nConstraints), m_solveFriction(true), m_maxNumBatches(maxNumBatches) { } unsigned short int getType() { return 0; } - void run(int tIdx) + void run(int /*tIdx*/) { int offset = 0; for (int ii = 0; ii < B3_MAX_NUM_BATCHES; ii++) @@ -466,7 +466,7 @@ struct SolveTask // : public ThreadPool::Task }; void b3Solver::solveContactConstraintHost(b3OpenCLArray* bodyBuf, b3OpenCLArray* shapeBuf, - b3OpenCLArray* constraint, void* additionalData, int n, int maxNumBatches, b3AlignedObjectArray* batchSizes) + b3OpenCLArray* constraint, void* /*additionalData*/, int n, int maxNumBatches, b3AlignedObjectArray* batchSizes) { #if 0 { @@ -526,7 +526,7 @@ void b3Solver::solveContactConstraintHost(b3OpenCLArray* bodyBu //printf("------------------------\n"); b3AlignedObjectArray offsetsHost; m_offsets->copyToHost(offsetsHost); - static int frame = 0; + static int frame = 0; (void)frame; bool useBatches = true; if (useBatches) { @@ -636,8 +636,8 @@ void b3Solver::solveContactConstraintHost(b3OpenCLArray* bodyBu frame++; } -void checkConstraintBatch(const b3OpenCLArray* bodyBuf, - const b3OpenCLArray* shapeBuf, +void checkConstraintBatch(const b3OpenCLArray* /*bodyBuf*/, + const b3OpenCLArray* /*shapeBuf*/, b3OpenCLArray* constraint, b3OpenCLArray* m_numConstraints, b3OpenCLArray* m_offsets, @@ -710,7 +710,7 @@ void checkConstraintBatch(const b3OpenCLArray* bodyBuf, static bool verify = false; void b3Solver::solveContactConstraint(const b3OpenCLArray* bodyBuf, const b3OpenCLArray* shapeBuf, - b3OpenCLArray* constraint, void* additionalData, int n, int maxNumBatches) + b3OpenCLArray* constraint, void* /*additionalData*/, int n, int maxNumBatches) { b3Int4 cdata = b3MakeInt4(n, 0, 0, 0); { @@ -866,7 +866,7 @@ void b3Solver::solveContactConstraint(const b3OpenCLArray* body void b3Solver::convertToConstraints(const b3OpenCLArray* bodyBuf, const b3OpenCLArray* shapeBuf, - b3OpenCLArray* contactsIn, b3OpenCLArray* contactCOut, void* additionalData, + b3OpenCLArray* contactsIn, b3OpenCLArray* contactCOut, void* /*additionalData*/, int nContacts, const ConstraintCfg& cfg) { // b3OpenCLArray* constraintNative =0; @@ -1030,16 +1030,16 @@ void b3Solver::sortContacts( const b3OpenCLArray* bodyBuf, } */ -void b3Solver::batchContacts(b3OpenCLArray* contacts, int nContacts, b3OpenCLArray* nNative, b3OpenCLArray* offsetsNative, int staticIdx) +void b3Solver::batchContacts(b3OpenCLArray* contacts, int /*nContacts*/, b3OpenCLArray* nNative, b3OpenCLArray* offsetsNative, int staticIdx) { int numWorkItems = 64 * B3_SOLVER_N_CELLS; { B3_PROFILE("batch generation"); - b3Int4 cdata; - cdata.x = nContacts; - cdata.y = 0; - cdata.z = staticIdx; + // b3Int4 cdata; + // cdata.x = nContacts; + // cdata.y = 0; + // cdata.z = staticIdx; #ifdef BATCH_DEBUG SolverDebugInfo* debugInfo = new SolverDebugInfo[numWorkItems]; diff --git a/src/Bullet3OpenCL/RigidBody/kernels/batchingKernels.h b/src/Bullet3OpenCL/RigidBody/kernels/batchingKernels.h index 7c73c96baa..b83a1f840b 100644 --- a/src/Bullet3OpenCL/RigidBody/kernels/batchingKernels.h +++ b/src/Bullet3OpenCL/RigidBody/kernels/batchingKernels.h @@ -27,7 +27,7 @@ static const char* batchingKernelsCL = "//keep B3_LARGE_FLOAT*B3_LARGE_FLOAT < FLT_MAX\n" "#define B3_LARGE_FLOAT 1e18f\n" "#define B3_INFINITY 1e18f\n" - "#define b3Assert(a)\n" + "#define b3Assert(a) (void)(x)\n" "#define b3ConstArray(a) __global const a*\n" "#define b3AtomicInc atomic_inc\n" "#define b3AtomicAdd atomic_add\n" diff --git a/src/Bullet3OpenCL/RigidBody/kernels/batchingKernelsNew.h b/src/Bullet3OpenCL/RigidBody/kernels/batchingKernelsNew.h index 05800656cb..1317f0e7be 100644 --- a/src/Bullet3OpenCL/RigidBody/kernels/batchingKernelsNew.h +++ b/src/Bullet3OpenCL/RigidBody/kernels/batchingKernelsNew.h @@ -27,7 +27,7 @@ static const char* batchingKernelsNewCL = "//keep B3_LARGE_FLOAT*B3_LARGE_FLOAT < FLT_MAX\n" "#define B3_LARGE_FLOAT 1e18f\n" "#define B3_INFINITY 1e18f\n" - "#define b3Assert(a)\n" + "#define b3Assert(a) (void)(x)\n" "#define b3ConstArray(a) __global const a*\n" "#define b3AtomicInc atomic_inc\n" "#define b3AtomicAdd atomic_add\n" diff --git a/src/Bullet3OpenCL/RigidBody/kernels/integrateKernel.h b/src/Bullet3OpenCL/RigidBody/kernels/integrateKernel.h index 6e9c53e161..c40e6b5614 100644 --- a/src/Bullet3OpenCL/RigidBody/kernels/integrateKernel.h +++ b/src/Bullet3OpenCL/RigidBody/kernels/integrateKernel.h @@ -27,7 +27,7 @@ static const char* integrateKernelCL = "//keep B3_LARGE_FLOAT*B3_LARGE_FLOAT < FLT_MAX\n" "#define B3_LARGE_FLOAT 1e18f\n" "#define B3_INFINITY 1e18f\n" - "#define b3Assert(a)\n" + "#define b3Assert(a) (void)(x)\n" "#define b3ConstArray(a) __global const a*\n" "#define b3AtomicInc atomic_inc\n" "#define b3AtomicAdd atomic_add\n" diff --git a/src/Bullet3OpenCL/RigidBody/kernels/solverSetup.h b/src/Bullet3OpenCL/RigidBody/kernels/solverSetup.h index d53db03181..7e2d5f0e68 100644 --- a/src/Bullet3OpenCL/RigidBody/kernels/solverSetup.h +++ b/src/Bullet3OpenCL/RigidBody/kernels/solverSetup.h @@ -27,7 +27,7 @@ static const char* solverSetupCL = "//keep B3_LARGE_FLOAT*B3_LARGE_FLOAT < FLT_MAX\n" "#define B3_LARGE_FLOAT 1e18f\n" "#define B3_INFINITY 1e18f\n" - "#define b3Assert(a)\n" + "#define b3Assert(a) (void)(x)\n" "#define b3ConstArray(a) __global const a*\n" "#define b3AtomicInc atomic_inc\n" "#define b3AtomicAdd atomic_add\n" diff --git a/src/Bullet3OpenCL/RigidBody/kernels/solverSetup2.h b/src/Bullet3OpenCL/RigidBody/kernels/solverSetup2.h index 1e6e3579b6..8daef95fa1 100644 --- a/src/Bullet3OpenCL/RigidBody/kernels/solverSetup2.h +++ b/src/Bullet3OpenCL/RigidBody/kernels/solverSetup2.h @@ -27,7 +27,7 @@ static const char* solverSetup2CL = "//keep B3_LARGE_FLOAT*B3_LARGE_FLOAT < FLT_MAX\n" "#define B3_LARGE_FLOAT 1e18f\n" "#define B3_INFINITY 1e18f\n" - "#define b3Assert(a)\n" + "#define b3Assert(a) (void)(x)\n" "#define b3ConstArray(a) __global const a*\n" "#define b3AtomicInc atomic_inc\n" "#define b3AtomicAdd atomic_add\n" diff --git a/src/Bullet3OpenCL/RigidBody/kernels/solverUtils.h b/src/Bullet3OpenCL/RigidBody/kernels/solverUtils.h index f4d98d9941..a1cd366b20 100644 --- a/src/Bullet3OpenCL/RigidBody/kernels/solverUtils.h +++ b/src/Bullet3OpenCL/RigidBody/kernels/solverUtils.h @@ -27,7 +27,7 @@ static const char* solverUtilsCL = "//keep B3_LARGE_FLOAT*B3_LARGE_FLOAT < FLT_MAX\n" "#define B3_LARGE_FLOAT 1e18f\n" "#define B3_INFINITY 1e18f\n" - "#define b3Assert(a)\n" + "#define b3Assert(a) (void)(x)\n" "#define b3ConstArray(a) __global const a*\n" "#define b3AtomicInc atomic_inc\n" "#define b3AtomicAdd atomic_add\n" diff --git a/src/Bullet3OpenCL/RigidBody/kernels/updateAabbsKernel.h b/src/Bullet3OpenCL/RigidBody/kernels/updateAabbsKernel.h index bb949b2027..6f9b834436 100644 --- a/src/Bullet3OpenCL/RigidBody/kernels/updateAabbsKernel.h +++ b/src/Bullet3OpenCL/RigidBody/kernels/updateAabbsKernel.h @@ -17,7 +17,7 @@ static const char* updateAabbsKernelCL = "//keep B3_LARGE_FLOAT*B3_LARGE_FLOAT < FLT_MAX\n" "#define B3_LARGE_FLOAT 1e18f\n" "#define B3_INFINITY 1e18f\n" - "#define b3Assert(a)\n" + "#define b3Assert(a) (void)(x)\n" "#define b3ConstArray(a) __global const a*\n" "#define b3AtomicInc atomic_inc\n" "#define b3AtomicAdd atomic_add\n" diff --git a/src/Bullet3Serialize/Bullet2FileLoader/b3BulletFile.cpp b/src/Bullet3Serialize/Bullet2FileLoader/b3BulletFile.cpp index d2a7163670..73a58e87d3 100644 --- a/src/Bullet3Serialize/Bullet2FileLoader/b3BulletFile.cpp +++ b/src/Bullet3Serialize/Bullet2FileLoader/b3BulletFile.cpp @@ -394,6 +394,7 @@ void b3BulletFile::addStruct(const char* structType, void* data, int len, void* elemBytes = mMemoryDNA->getLength(structInfo[0]); // int elemBytes = mMemoryDNA->getElementSize(structInfo[0],structInfo[1]); assert(len == elemBytes); + (void)elemBytes; mLibPointers.insert(dataChunk.oldPtr, (bStructHandle*)data); m_chunks.push_back(dataChunk); diff --git a/src/Bullet3Serialize/Bullet2FileLoader/b3DNA.cpp b/src/Bullet3Serialize/Bullet2FileLoader/b3DNA.cpp index 09c8f23859..f1ac1bd647 100644 --- a/src/Bullet3Serialize/Bullet2FileLoader/b3DNA.cpp +++ b/src/Bullet3Serialize/Bullet2FileLoader/b3DNA.cpp @@ -341,7 +341,7 @@ static int name_is_array(char *name, int *dim1, int *dim2) } // ----------------------------------------------------- // -void bDNA::init(char *data, int len, bool swap) +void bDNA::init(char *data, int /*len*/, bool swap) { int *intPtr = 0; short *shtPtr = 0; diff --git a/src/Bullet3Serialize/Bullet2FileLoader/b3File.cpp b/src/Bullet3Serialize/Bullet2FileLoader/b3File.cpp index f6c779a919..2e0f5a32f7 100644 --- a/src/Bullet3Serialize/Bullet2FileLoader/b3File.cpp +++ b/src/Bullet3Serialize/Bullet2FileLoader/b3File.cpp @@ -75,6 +75,7 @@ bFile::bFile(const char *filename, const char headerString[7]) mFileBuffer = (char *)malloc(mFileLen + 1); int bytesRead; bytesRead = fread(mFileBuffer, mFileLen, 1, fp); + (void)bytesRead; fclose(fp); @@ -595,7 +596,7 @@ char *bFile::readStruct(char *head, bChunkInd &dataChunk) { // Ouch! need to rebuild the struct short *oldStruct, *curStruct; - char *oldType, *newType; + char *oldType, *newType; (void)newType; int oldLen, curLen, reverseOld; oldStruct = mFileDNA->getStruct(dataChunk.dna_nr); @@ -1476,6 +1477,7 @@ void bFile::writeChunks(FILE *fp, bool fixupPointers) char *oldType, *newType; int oldLen, curLen, reverseOld; + (void)newType; (void)oldLen; oldStruct = fileDna->getStruct(dataChunk.dna_nr); oldType = fileDna->getType(oldStruct[0]); oldLen = fileDna->getLength(oldStruct[0]); @@ -1509,6 +1511,7 @@ void bFile::writeChunks(FILE *fp, bool fixupPointers) short int *curStruct1; curStruct1 = mMemoryDNA->getStruct(dataChunk.dna_nr); assert(curStruct1 == curStruct); + (void)curStruct1; char *cur = fixupPointers ? (char *)findLibPointer(dataChunk.oldPtr) : (char *)dataChunk.oldPtr; diff --git a/src/Bullet3Serialize/Bullet2FileLoader/b3Serializer.h b/src/Bullet3Serialize/Bullet2FileLoader/b3Serializer.h index d9e153e238..448e4e07f4 100644 --- a/src/Bullet3Serialize/Bullet2FileLoader/b3Serializer.h +++ b/src/Bullet3Serialize/Bullet2FileLoader/b3Serializer.h @@ -431,7 +431,7 @@ class b3DefaultSerializer : public b3Serializer writeDNA(); //if we didn't pre-allocate a buffer, we need to create a contiguous buffer now - int mysize = 0; + int mysize = 0; (void)mysize; if (!m_totalSize) { if (m_buffer) diff --git a/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.cpp b/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.cpp index 7b39dbdc0f..5d56b1e1df 100644 --- a/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.cpp +++ b/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.cpp @@ -662,7 +662,7 @@ void btDbvtBroadphase::getBroadphaseAabb(btVector3& aabbMin, btVector3& aabbMax) aabbMax = bounds.Maxs(); } -void btDbvtBroadphase::resetPool(btDispatcher* dispatcher) +void btDbvtBroadphase::resetPool(btDispatcher* /*dispatcher*/) { int totalObjects = m_sets[0].m_leaves + m_sets[1].m_leaves; if (!totalObjects) diff --git a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp index fb36acdf69..0055bbee9f 100644 --- a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp +++ b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp @@ -605,7 +605,7 @@ void btSortedOverlappingPairCache::removeOverlappingPairsContainingProxy(btBroad processAllOverlappingPairs(&removeCallback, dispatcher); } -void btSortedOverlappingPairCache::sortOverlappingPairs(btDispatcher* dispatcher) +void btSortedOverlappingPairCache::sortOverlappingPairs(btDispatcher* /*dispatcher*/) { //should already be sorted } diff --git a/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp b/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp index e23610eb52..82fd0fa26a 100644 --- a/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp +++ b/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp @@ -385,6 +385,7 @@ void btQuantizedBvh::walkStacklessTree(btNodeOverlapCallback* nodeCallback, cons curIndex += escapeIndex; } } + (void)walkIterations; } /* @@ -439,7 +440,7 @@ void btQuantizedBvh::walkRecursiveQuantizedTreeAgainstQueryAabb(const btQuantize } } -void btQuantizedBvh::walkStacklessTreeAgainstRay(btNodeOverlapCallback* nodeCallback, const btVector3& raySource, const btVector3& rayTarget, const btVector3& aabbMin, const btVector3& aabbMax, int startNodeIndex, int endNodeIndex) const +void btQuantizedBvh::walkStacklessTreeAgainstRay(btNodeOverlapCallback* nodeCallback, const btVector3& raySource, const btVector3& rayTarget, const btVector3& aabbMin, const btVector3& aabbMax, int /*startNodeIndex*/, int /*endNodeIndex*/) const { btAssert(!m_useQuantization); @@ -525,6 +526,7 @@ void btQuantizedBvh::walkStacklessTreeAgainstRay(btNodeOverlapCallback* nodeCall curIndex += escapeIndex; } } + (void)walkIterations; } void btQuantizedBvh::walkStacklessQuantizedTreeAgainstRay(btNodeOverlapCallback* nodeCallback, const btVector3& raySource, const btVector3& rayTarget, const btVector3& aabbMin, const btVector3& aabbMax, int startNodeIndex, int endNodeIndex) const @@ -648,6 +650,7 @@ void btQuantizedBvh::walkStacklessQuantizedTreeAgainstRay(btNodeOverlapCallback* curIndex += escapeIndex; } } + (void)walkIterations; } void btQuantizedBvh::walkStacklessQuantizedTree(btNodeOverlapCallback* nodeCallback, unsigned short int* quantizedQueryAabbMin, unsigned short int* quantizedQueryAabbMax, int startNodeIndex, int endNodeIndex) const @@ -710,6 +713,7 @@ void btQuantizedBvh::walkStacklessQuantizedTree(btNodeOverlapCallback* nodeCallb curIndex += escapeIndex; } } + (void)walkIterations; } //This traversal can be called from Playstation 3 SPU diff --git a/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp b/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp index bb02df89f6..9a47e35509 100644 --- a/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp +++ b/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp @@ -145,7 +145,7 @@ void btSimpleBroadphase::setAabb(btBroadphaseProxy* proxy, const btVector3& aabb sbp->m_aabbMax = aabbMax; } -void btSimpleBroadphase::rayTest(const btVector3& rayFrom, const btVector3& rayTo, btBroadphaseRayCallback& rayCallback, const btVector3& aabbMin, const btVector3& aabbMax) +void btSimpleBroadphase::rayTest(const btVector3& /*rayFrom*/, const btVector3& /*rayTo*/, btBroadphaseRayCallback& rayCallback, const btVector3& /*aabbMin*/, const btVector3& /*aabbMax*/) { for (int i = 0; i <= m_LastHandleIndex; i++) { @@ -319,7 +319,7 @@ bool btSimpleBroadphase::testAabbOverlap(btBroadphaseProxy* proxy0, btBroadphase return aabbOverlap(p0, p1); } -void btSimpleBroadphase::resetPool(btDispatcher* dispatcher) +void btSimpleBroadphase::resetPool(btDispatcher* /*dispatcher*/) { //not yet } diff --git a/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp b/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp index 57152105fd..8cf4980bd4 100644 --- a/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp +++ b/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp @@ -93,7 +93,7 @@ bool SphereTriangleDetector::facecontains(const btVector3& p, const btVector3* v return pointInTriangle(vertices, lnormal, &lp); } -bool SphereTriangleDetector::collide(const btVector3& sphereCenter, btVector3& point, btVector3& resultNormal, btScalar& depth, btScalar& timeOfImpact, btScalar contactBreakingThreshold) +bool SphereTriangleDetector::collide(const btVector3& sphereCenter, btVector3& point, btVector3& resultNormal, btScalar& depth, btScalar& /*timeOfImpact*/, btScalar contactBreakingThreshold) { const btVector3* vertices = &m_triangle->getVertexPtr(0); diff --git a/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.cpp index 6873a95d90..c2862d11e9 100644 --- a/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.cpp @@ -50,7 +50,7 @@ btBox2dBox2dCollisionAlgorithm::~btBox2dBox2dCollisionAlgorithm() void b2CollidePolygons(btManifoldResult* manifold, const btBox2dShape* polyA, const btTransform& xfA, const btBox2dShape* polyB, const btTransform& xfB); //#include -void btBox2dBox2dCollisionAlgorithm::processCollision(const btCollisionObjectWrapper* body0Wrap, const btCollisionObjectWrapper* body1Wrap, const btDispatcherInfo& dispatchInfo, btManifoldResult* resultOut) +void btBox2dBox2dCollisionAlgorithm::processCollision(const btCollisionObjectWrapper* body0Wrap, const btCollisionObjectWrapper* body1Wrap, const btDispatcherInfo& /*dispatchInfo*/, btManifoldResult* resultOut) { if (!m_manifoldPtr) return; @@ -387,7 +387,7 @@ void b2CollidePolygons(btManifoldResult* manifold, // Now clipPoints2 contains the clipped points. btVector3 manifoldNormal = flip ? -frontNormal : frontNormal; - int pointCount = 0; + // int pointCount = 0; for (int i = 0; i < b2_maxManifoldPoints; ++i) { btScalar separation = b2Dot(frontNormal, clipPoints2[i].v) - frontOffset; @@ -403,7 +403,7 @@ void b2CollidePolygons(btManifoldResult* manifold, // cp->id = clipPoints2[i].id; // cp->id.features.flip = flip; - ++pointCount; + // ++pointCount; } } diff --git a/src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.cpp b/src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.cpp index 9b38f5c7a3..cb8b054cca 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.cpp +++ b/src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.cpp @@ -130,7 +130,7 @@ struct CollisionDispatcherUpdater : public btIParallelForBody } }; -void btCollisionDispatcherMt::dispatchAllCollisionPairs(btOverlappingPairCache* pairCache, const btDispatcherInfo& info, btDispatcher* dispatcher) +void btCollisionDispatcherMt::dispatchAllCollisionPairs(btOverlappingPairCache* pairCache, const btDispatcherInfo& info, btDispatcher* /*dispatcher*/) { const int pairCount = pairCache->getNumOverlappingPairs(); if (pairCount == 0) diff --git a/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp b/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp index 15940f5b6d..59bef19bc6 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp +++ b/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp @@ -64,7 +64,7 @@ subject to the following restrictions: #include "BulletCollision/CollisionShapes/btTriangleMeshShape.h" #include "BulletCollision/CollisionShapes/btStaticPlaneShape.h" -btCollisionWorld::btCollisionWorld(btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btCollisionConfiguration* collisionConfiguration) +btCollisionWorld::btCollisionWorld(btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btCollisionConfiguration* /*collisionConfiguration*/) : m_dispatcher1(dispatcher), m_broadphasePairCache(pairCache), m_debugDrawer(0), diff --git a/src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.cpp b/src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.cpp index e56e73dcf5..9cd876708a 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.cpp +++ b/src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.cpp @@ -987,7 +987,7 @@ btBvhTriangleMeshShape* btCollisionWorldImporter::createBvhTriangleMeshShape(btS m_allocatedCollisionShapes.push_back(ts); return ts; } -btCollisionShape* btCollisionWorldImporter::createConvexTriangleMeshShape(btStridingMeshInterface* trimesh) +btCollisionShape* btCollisionWorldImporter::createConvexTriangleMeshShape(btStridingMeshInterface* /*trimesh*/) { return 0; } diff --git a/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp index 044b60dbb1..13d380da6a 100644 --- a/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp @@ -406,7 +406,7 @@ void btCompoundCompoundCollisionAlgorithm::processCollision(const btCollisionObj } } -btScalar btCompoundCompoundCollisionAlgorithm::calculateTimeOfImpact(btCollisionObject* body0, btCollisionObject* body1, const btDispatcherInfo& dispatchInfo, btManifoldResult* resultOut) +btScalar btCompoundCompoundCollisionAlgorithm::calculateTimeOfImpact(btCollisionObject* /*body0*/, btCollisionObject* /*body1*/, const btDispatcherInfo& /*dispatchInfo*/, btManifoldResult* /*resultOut*/) { btAssert(0); return 0.f; diff --git a/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp index 95bce9e7c0..59de5f5dab 100644 --- a/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp @@ -258,7 +258,7 @@ void btConvexConcaveCollisionAlgorithm::processCollision(const btCollisionObject resultOut->setPersistentManifold(m_btConvexTriangleCallback.m_manifoldPtr); //m_btConvexTriangleCallback.m_manifoldPtr->clearManifold(); - btPolyhedralConvexShape* poly = (btPolyhedralConvexShape*)convex; + //btPolyhedralConvexShape* poly = (btPolyhedralConvexShape*)convex; for (int v = 0; v < queryVertices.size(); v++) { const btVector3& vtx = queryVertices[v]; diff --git a/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp index 8031c950b4..beb27db486 100644 --- a/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp @@ -422,8 +422,8 @@ void btConvexConvexAlgorithm ::processCollision(const btCollisionObjectWrapper* { } - virtual void setShapeIdentifiersA(int partId0, int index0) {} - virtual void setShapeIdentifiersB(int partId1, int index1) {} + virtual void setShapeIdentifiersA(int /*partId0*/, int /*index0*/) {} + virtual void setShapeIdentifiersB(int /*partId1*/, int /*index1*/) {} virtual void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorld, btScalar depth) { m_hasContact = true; @@ -450,8 +450,8 @@ void btConvexConvexAlgorithm ::processCollision(const btCollisionObjectWrapper* { } - virtual void setShapeIdentifiersA(int partId0, int index0) {} - virtual void setShapeIdentifiersB(int partId1, int index1) {} + virtual void setShapeIdentifiersA(int /*partId0*/, int /*index0*/) {} + virtual void setShapeIdentifiersB(int /*partId1*/, int /*index1*/) {} virtual void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorldOrg, btScalar depthOrg) { m_reportedDistance = depthOrg; diff --git a/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.cpp index d91d9c9768..2098e2d173 100644 --- a/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.cpp @@ -50,7 +50,7 @@ btConvexPlaneCollisionAlgorithm::~btConvexPlaneCollisionAlgorithm() } } -void btConvexPlaneCollisionAlgorithm::collideSingleContact(const btQuaternion& perturbeRot, const btCollisionObjectWrapper* body0Wrap, const btCollisionObjectWrapper* body1Wrap, const btDispatcherInfo& dispatchInfo, btManifoldResult* resultOut) +void btConvexPlaneCollisionAlgorithm::collideSingleContact(const btQuaternion& perturbeRot, const btCollisionObjectWrapper* body0Wrap, const btCollisionObjectWrapper* body1Wrap, const btDispatcherInfo& /*dispatchInfo*/, btManifoldResult* resultOut) { const btCollisionObjectWrapper* convexObjWrap = m_isSwapped ? body1Wrap : body0Wrap; const btCollisionObjectWrapper* planeObjWrap = m_isSwapped ? body0Wrap : body1Wrap; diff --git a/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h b/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h index fef2f275b7..854cd8ef1e 100644 --- a/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h +++ b/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h @@ -32,7 +32,7 @@ class btEmptyAlgorithm : public btCollisionAlgorithm virtual btScalar calculateTimeOfImpact(btCollisionObject* body0, btCollisionObject* body1, const btDispatcherInfo& dispatchInfo, btManifoldResult* resultOut); - virtual void getAllContactManifolds(btManifoldArray& manifoldArray) + virtual void getAllContactManifolds(btManifoldArray& /*manifoldArray*/) { } diff --git a/src/BulletCollision/CollisionDispatch/btGhostObject.cpp b/src/BulletCollision/CollisionDispatch/btGhostObject.cpp index 00f16fd0a8..2a21527146 100644 --- a/src/BulletCollision/CollisionDispatch/btGhostObject.cpp +++ b/src/BulletCollision/CollisionDispatch/btGhostObject.cpp @@ -29,7 +29,7 @@ btGhostObject::~btGhostObject() btAssert(!m_overlappingObjects.size()); } -void btGhostObject::addOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btBroadphaseProxy* thisProxy) +void btGhostObject::addOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btBroadphaseProxy* /*thisProxy*/) { btCollisionObject* otherObject = (btCollisionObject*)otherProxy->m_clientObject; btAssert(otherObject); @@ -42,7 +42,7 @@ void btGhostObject::addOverlappingObjectInternal(btBroadphaseProxy* otherProxy, } } -void btGhostObject::removeOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btDispatcher* dispatcher, btBroadphaseProxy* thisProxy) +void btGhostObject::removeOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btDispatcher* /*dispatcher*/, btBroadphaseProxy* /*thisProxy*/) { btCollisionObject* otherObject = (btCollisionObject*)otherProxy->m_clientObject; btAssert(otherObject); diff --git a/src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.cpp b/src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.cpp index a71700f58a..ac2e319beb 100644 --- a/src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.cpp +++ b/src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.cpp @@ -483,7 +483,7 @@ bool btClampNormal(const btVector3& edge, const btVector3& tri_normal_org, const } /// Changes a btManifoldPoint collision normal to the normal from the mesh. -void btAdjustInternalEdgeContacts(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap, const btCollisionObjectWrapper* colObj1Wrap, int partId0, int index0, int normalAdjustFlags) +void btAdjustInternalEdgeContacts(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap, const btCollisionObjectWrapper* /*colObj1Wrap*/, int partId0, int index0, int normalAdjustFlags) { //btAssert(colObj0->getCollisionShape()->getShapeType() == TRIANGLE_SHAPE_PROXYTYPE); if (colObj0Wrap->getCollisionShape()->getShapeType() != TRIANGLE_SHAPE_PROXYTYPE) @@ -570,7 +570,7 @@ void btAdjustInternalEdgeContacts(btManifoldPoint& cp, const btCollisionObjectWr bool isNearEdge = false; int numConcaveEdgeHits = 0; - int numConvexEdgeHits = 0; + int numConvexEdgeHits = 0; (void)numConvexEdgeHits; btVector3 localContactNormalOnB = colObj0Wrap->getWorldTransform().getBasis().transpose() * cp.m_normalWorldOnB; localContactNormalOnB.normalize(); //is this necessary? diff --git a/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp b/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp index 6a99e73df9..7618611d39 100644 --- a/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp +++ b/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp @@ -247,7 +247,6 @@ void btSimulationIslandManager::buildIslands(btDispatcher* dispatcher, btCollisi if (allSleeping) { - int idx; for (idx = startIslandIndex; idx < endIslandIndex; idx++) { int i = getUnionFind().getElement(idx).m_sz; @@ -267,7 +266,6 @@ void btSimulationIslandManager::buildIslands(btDispatcher* dispatcher, btCollisi } else { - int idx; for (idx = startIslandIndex; idx < endIslandIndex; idx++) { int i = getUnionFind().getElement(idx).m_sz; diff --git a/src/BulletCollision/CollisionShapes/btBox2dShape.h b/src/BulletCollision/CollisionShapes/btBox2dShape.h index 6c6e729278..98107eb982 100644 --- a/src/BulletCollision/CollisionShapes/btBox2dShape.h +++ b/src/BulletCollision/CollisionShapes/btBox2dShape.h @@ -155,10 +155,11 @@ btBox2dShape : public btPolyhedralConvexShape virtual void getPlane(btVector3 & planeNormal, btVector3 & planeSupport, int i) const { //this plane might not be aligned... - btVector4 plane; - getPlaneEquation(plane, i); - planeNormal = btVector3(plane.getX(), plane.getY(), plane.getZ()); - planeSupport = localGetSupportingVertex(-planeNormal); + // btVector4 plane; + // getPlaneEquation(plane, i); + // planeNormal = btVector3(plane.getX(), plane.getY(), plane.getZ()); + // planeSupport = localGetSupportingVertex(-planeNormal); + (void)planeNormal;(void)planeSupport; (void)i; } const btVector3& getCentroid() const diff --git a/src/BulletCollision/CollisionShapes/btBoxShape.h b/src/BulletCollision/CollisionShapes/btBoxShape.h index 3c65505d5b..00c6583622 100644 --- a/src/BulletCollision/CollisionShapes/btBoxShape.h +++ b/src/BulletCollision/CollisionShapes/btBoxShape.h @@ -107,10 +107,11 @@ btBoxShape : public btPolyhedralConvexShape virtual void getPlane(btVector3 & planeNormal, btVector3 & planeSupport, int i) const { //this plane might not be aligned... - btVector4 plane; - getPlaneEquation(plane, i); - planeNormal = btVector3(plane.getX(), plane.getY(), plane.getZ()); - planeSupport = localGetSupportingVertex(-planeNormal); + // btVector4 plane; + // getPlaneEquation(plane, i); + // planeNormal = btVector3(plane.getX(), plane.getY(), plane.getZ()); + // planeSupport = localGetSupportingVertex(-planeNormal); + (void)planeNormal; (void)planeSupport; (void)i; } virtual int getNumPlanes() const diff --git a/src/BulletCollision/CollisionShapes/btConvexPointCloudShape.cpp b/src/BulletCollision/CollisionShapes/btConvexPointCloudShape.cpp index f00a440fa3..8e9038568e 100644 --- a/src/BulletCollision/CollisionShapes/btConvexPointCloudShape.cpp +++ b/src/BulletCollision/CollisionShapes/btConvexPointCloudShape.cpp @@ -101,7 +101,7 @@ int btConvexPointCloudShape::getNumEdges() const return 0; } -void btConvexPointCloudShape::getEdge(int i, btVector3& pa, btVector3& pb) const +void btConvexPointCloudShape::getEdge(int /*i*/, btVector3& /*pa*/, btVector3& /*pb*/) const { btAssert(0); } diff --git a/src/BulletCollision/CollisionShapes/btConvexShape.cpp b/src/BulletCollision/CollisionShapes/btConvexShape.cpp index f8fb0aa9fd..c08b8dba8c 100644 --- a/src/BulletCollision/CollisionShapes/btConvexShape.cpp +++ b/src/BulletCollision/CollisionShapes/btConvexShape.cpp @@ -300,8 +300,8 @@ btVector3 btConvexShape::localGetSupportVertexWithoutMarginNonVirtual(const btVe } // should never reach here - btAssert(0); - return btVector3(btScalar(0.0f), btScalar(0.0f), btScalar(0.0f)); + // btAssert(0); + // return btVector3(btScalar(0.0f), btScalar(0.0f), btScalar(0.0f)); } btVector3 btConvexShape::localGetSupportVertexNonVirtual(const btVector3& localDir) const @@ -367,8 +367,8 @@ btScalar btConvexShape::getMarginNonVirtual() const } // should never reach here - btAssert(0); - return btScalar(0.0f); + // btAssert(0); + // return btScalar(0.0f); } #ifndef __SPU__ void btConvexShape::getAabbNonVirtual(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const diff --git a/src/BulletCollision/CollisionShapes/btMiniSDF.cpp b/src/BulletCollision/CollisionShapes/btMiniSDF.cpp index 13c0a343f1..9f654bf4a7 100644 --- a/src/BulletCollision/CollisionShapes/btMiniSDF.cpp +++ b/src/BulletCollision/CollisionShapes/btMiniSDF.cpp @@ -44,8 +44,6 @@ struct btSdfDataStream bool btMiniSDF::load(const char* data, int size) { - int fileSize = -1; - btSdfDataStream ds(data, size); { double buf[6]; @@ -468,7 +466,7 @@ bool btMiniSDF::interpolate(unsigned int field_id, double& dist, btVector3 const btAlignedBox3d sd = subdomain(i); i = i_; - btVector3 d = sd.m_max - sd.m_min; //.diagonal().eval(); + //btVector3 d = sd.m_max - sd.m_min; //.diagonal().eval(); btVector3 denom = (sd.max() - sd.min()); btVector3 c0 = btVector3(2.0, 2.0, 2.0) / denom; diff --git a/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp b/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp index 521ecfc760..12b5d2e880 100644 --- a/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp +++ b/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp @@ -129,7 +129,7 @@ bool btPolyhedralConvexShape::initializePolyhedralFeatures(int shiftVerticesByMa combinedFace.m_indices.push_back(v1); edge = edge->getNextEdgeOfFace(); prevVertex = v1; - int v01 = edge->getSourceVertex(); + //int v01 = edge->getSourceVertex(); v1 = edge->getTargetVertex(); } diff --git a/src/BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.cpp b/src/BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.cpp index f427319974..7521a20f4e 100644 --- a/src/BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.cpp +++ b/src/BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.cpp @@ -108,7 +108,7 @@ const btVector3& btScaledBvhTriangleMeshShape::getLocalScaling() const return m_localScaling; } -void btScaledBvhTriangleMeshShape::calculateLocalInertia(btScalar mass, btVector3& inertia) const +void btScaledBvhTriangleMeshShape::calculateLocalInertia(btScalar /*mass*/, btVector3& /*inertia*/) const { ///don't make this a movable object! // btAssert(0); diff --git a/src/BulletCollision/CollisionShapes/btSdfCollisionShape.cpp b/src/BulletCollision/CollisionShapes/btSdfCollisionShape.cpp index 23c95ad3ff..9db7c9ef21 100644 --- a/src/BulletCollision/CollisionShapes/btSdfCollisionShape.cpp +++ b/src/BulletCollision/CollisionShapes/btSdfCollisionShape.cpp @@ -58,7 +58,7 @@ const btVector3& btSdfCollisionShape::getLocalScaling() const { return m_data->m_localScaling; } -void btSdfCollisionShape::calculateLocalInertia(btScalar mass, btVector3& inertia) const +void btSdfCollisionShape::calculateLocalInertia(btScalar /*mass*/, btVector3& inertia) const { inertia.setValue(0, 0, 0); } @@ -75,7 +75,7 @@ btScalar btSdfCollisionShape::getMargin() const return m_data->m_margin; } -void btSdfCollisionShape::processAllTriangles(btTriangleCallback* callback, const btVector3& aabbMin, const btVector3& aabbMax) const +void btSdfCollisionShape::processAllTriangles(btTriangleCallback* /*callback*/, const btVector3& /*aabbMin*/, const btVector3& /*aabbMax*/) const { //not yet } diff --git a/src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp b/src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp index eb288e99c9..113e7e428d 100644 --- a/src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp +++ b/src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp @@ -24,7 +24,7 @@ void btStridingMeshInterface::InternalProcessAllTriangles(btInternalTriangleInde { (void)aabbMin; (void)aabbMax; - int numtotalphysicsverts = 0; + int numtotalphysicsverts = 0; (void)numtotalphysicsverts; int part, graphicssubparts = getNumSubParts(); const unsigned char* vertexbase; const unsigned char* indexbase; diff --git a/src/BulletCollision/Gimpact/btGImpactBvh.cpp b/src/BulletCollision/Gimpact/btGImpactBvh.cpp index bb520e061d..63da03909f 100644 --- a/src/BulletCollision/Gimpact/btGImpactBvh.cpp +++ b/src/BulletCollision/Gimpact/btGImpactBvh.cpp @@ -203,7 +203,7 @@ void btBvhTree::build_tree( // initialize node count to 0 m_num_nodes = 0; // allocate nodes - m_node_array.resize(primitive_boxes.size() * 2); + // m_node_array.resize(primitive_boxes.size() * 2); _build_sub_tree(primitive_boxes, 0, primitive_boxes.size()); } @@ -254,7 +254,7 @@ void btGImpactBvh::buildSet() { //obtain primitive boxes GIM_BVH_DATA_ARRAY primitive_boxes; - primitive_boxes.resize(m_primitive_manager->get_primitive_count()); + // primitive_boxes.resize(m_primitive_manager->get_primitive_count()); for (int i = 0; i < primitive_boxes.size(); i++) { diff --git a/src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.cpp b/src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.cpp index 73e3db1010..27a490304f 100644 --- a/src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.cpp +++ b/src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.cpp @@ -207,8 +207,8 @@ void btGImpactCollisionAlgorithm::addContactPoint(const btCollisionObjectWrapper void btGImpactCollisionAlgorithm::shape_vs_shape_collision( const btCollisionObjectWrapper* body0Wrap, const btCollisionObjectWrapper* body1Wrap, - const btCollisionShape* shape0, - const btCollisionShape* shape1) + const btCollisionShape* /*shape0*/, + const btCollisionShape* /*shape1*/) { { btCollisionAlgorithm* algor = newAlgorithm(body0Wrap, body1Wrap); @@ -840,7 +840,7 @@ void btGImpactCollisionAlgorithm::processCollision(const btCollisionObjectWrappe } } -btScalar btGImpactCollisionAlgorithm::calculateTimeOfImpact(btCollisionObject* body0, btCollisionObject* body1, const btDispatcherInfo& dispatchInfo, btManifoldResult* resultOut) +btScalar btGImpactCollisionAlgorithm::calculateTimeOfImpact(btCollisionObject* /*body0*/, btCollisionObject* /*body1*/, const btDispatcherInfo& /*dispatchInfo*/, btManifoldResult* /*resultOut*/) { return 1.f; } diff --git a/src/BulletCollision/Gimpact/btGImpactQuantizedBvh.cpp b/src/BulletCollision/Gimpact/btGImpactQuantizedBvh.cpp index b81fc97044..0f64bf70d7 100644 --- a/src/BulletCollision/Gimpact/btGImpactQuantizedBvh.cpp +++ b/src/BulletCollision/Gimpact/btGImpactQuantizedBvh.cpp @@ -271,7 +271,7 @@ void btGImpactQuantizedBvh::buildSet() { //obtain primitive boxes GIM_BVH_DATA_ARRAY primitive_boxes; - primitive_boxes.resize(m_primitive_manager->get_primitive_count()); + // primitive_boxes.resize(m_primitive_manager->get_primitive_count()); for (int i = 0; i < primitive_boxes.size(); i++) { diff --git a/src/BulletCollision/Gimpact/btGImpactShape.cpp b/src/BulletCollision/Gimpact/btGImpactShape.cpp index 34c229a3ab..54cb952042 100644 --- a/src/BulletCollision/Gimpact/btGImpactShape.cpp +++ b/src/BulletCollision/Gimpact/btGImpactShape.cpp @@ -185,7 +185,7 @@ void btGImpactMeshShape::calculateLocalInertia(btScalar mass, btVector3& inertia #endif } -void btGImpactMeshShape::rayTest(const btVector3& rayFrom, const btVector3& rayTo, btCollisionWorld::RayResultCallback& resultCallback) const +void btGImpactMeshShape::rayTest(const btVector3& /*rayFrom*/, const btVector3& /*rayTo*/, btCollisionWorld::RayResultCallback& /*resultCallback*/) const { } diff --git a/src/BulletCollision/NarrowPhaseCollision/btComputeGjkEpaPenetration.h b/src/BulletCollision/NarrowPhaseCollision/btComputeGjkEpaPenetration.h index 3c82133037..ea52e6de25 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btComputeGjkEpaPenetration.h +++ b/src/BulletCollision/NarrowPhaseCollision/btComputeGjkEpaPenetration.h @@ -23,7 +23,7 @@ subject to the following restrictions: template bool btGjkEpaCalcPenDepth(const btConvexTemplate& a, const btConvexTemplate& b, - const btGjkCollisionDescription& colDesc, + const btGjkCollisionDescription& /*colDesc*/, btVector3& v, btVector3& wWitnessOnA, btVector3& wWitnessOnB) { (void)v; @@ -342,6 +342,7 @@ int btComputeGjkEpaPenetration(const btConvexTemplate& a, const btConvexTemplate { m_cachedSeparatingAxis = normalInB; m_cachedSeparatingDistance = distance; + (void)m_cachedSeparatingDistance; distInfo->m_distance = distance; distInfo->m_normalBtoA = normalInB; distInfo->m_pointOnB = pointOnB; diff --git a/src/BulletCollision/NarrowPhaseCollision/btMprPenetration.h b/src/BulletCollision/NarrowPhaseCollision/btMprPenetration.h index 534a66d3fa..f5c9ae0b37 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btMprPenetration.h +++ b/src/BulletCollision/NarrowPhaseCollision/btMprPenetration.h @@ -162,7 +162,7 @@ inline int btMprVec3Eq(const btVector3 *a, const btVector3 *b) } template -inline void btFindOrigin(const btConvexTemplate &a, const btConvexTemplate &b, const btMprCollisionDescription &colDesc, btMprSupport_t *center) +inline void btFindOrigin(const btConvexTemplate &a, const btConvexTemplate &b, const btMprCollisionDescription & /*colDesc*/, btMprSupport_t *center) { center->v1 = a.getObjectCenterInWorld(); center->v2 = b.getObjectCenterInWorld(); @@ -262,7 +262,7 @@ inline int portalReachTolerance(const btMprSimplex_t *portal, return btMprEq(dot1, BT_MPR_TOLERANCE) || dot1 < BT_MPR_TOLERANCE; } -inline int portalCanEncapsuleOrigin(const btMprSimplex_t *portal, +inline int portalCanEncapsuleOrigin(const btMprSimplex_t * /*portal*/, const btMprSupport_t *v4, const btVector3 *dir) { @@ -306,7 +306,7 @@ inline void btExpandPortal(btMprSimplex_t *portal, } template inline void btMprSupport(const btConvexTemplate &a, const btConvexTemplate &b, - const btMprCollisionDescription &colDesc, + const btMprCollisionDescription & /*colDesc*/, const btVector3 &dir, btMprSupport_t *supp) { btVector3 separatingAxisInA = dir * a.getWorldTransform().getBasis(); diff --git a/src/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.cpp b/src/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.cpp index 9d1836037d..bfbd99c86b 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.cpp @@ -244,7 +244,7 @@ bool btPolyhedralContactClipping::findSeparatingAxis(const btConvexPolyhedron& h //#endif btScalar dmin = FLT_MAX; - int curPlaneTests = 0; + // int curPlaneTests = 0; int numFacesA = hullA.m_faces.size(); // Test normals from hullA @@ -255,7 +255,7 @@ bool btPolyhedralContactClipping::findSeparatingAxis(const btConvexPolyhedron& h if (DeltaC2.dot(faceANormalWS) < 0) faceANormalWS *= -1.f; - curPlaneTests++; + // curPlaneTests++; #ifdef TEST_INTERNAL_OBJECTS gExpectedNbTests++; if (gUseInternalObject && !TestInternalObjects(transA, transB, DeltaC2, faceANormalWS, hullA, hullB, dmin)) @@ -284,7 +284,7 @@ bool btPolyhedralContactClipping::findSeparatingAxis(const btConvexPolyhedron& h if (DeltaC2.dot(WorldNormal) < 0) WorldNormal *= -1.f; - curPlaneTests++; + // curPlaneTests++; #ifdef TEST_INTERNAL_OBJECTS gExpectedNbTests++; if (gUseInternalObject && !TestInternalObjects(transA, transB, DeltaC2, WorldNormal, hullA, hullB, dmin)) @@ -311,7 +311,7 @@ bool btPolyhedralContactClipping::findSeparatingAxis(const btConvexPolyhedron& h btVector3 worldEdgeB; btVector3 witnessPointA(0, 0, 0), witnessPointB(0, 0, 0); - int curEdgeEdge = 0; + // int curEdgeEdge = 0; // Test edges for (int e0 = 0; e0 < hullA.m_uniqueEdges.size(); e0++) { @@ -323,7 +323,7 @@ bool btPolyhedralContactClipping::findSeparatingAxis(const btConvexPolyhedron& h const btVector3 WorldEdge1 = transB.getBasis() * edge1; btVector3 Cross = WorldEdge0.cross(WorldEdge1); - curEdgeEdge++; + // curEdgeEdge++; if (!IsAlmostZero(Cross)) { Cross = Cross.normalize(); diff --git a/src/BulletDynamics/Character/btKinematicCharacterController.cpp b/src/BulletDynamics/Character/btKinematicCharacterController.cpp index 2bbccb291c..1a6991d8a5 100644 --- a/src/BulletDynamics/Character/btKinematicCharacterController.cpp +++ b/src/BulletDynamics/Character/btKinematicCharacterController.cpp @@ -697,7 +697,7 @@ void btKinematicCharacterController::warp(const btVector3& origin) m_ghostObject->setWorldTransform(xform); } -void btKinematicCharacterController::preStep(btCollisionWorld* collisionWorld) +void btKinematicCharacterController::preStep(btCollisionWorld* /*collisionWorld*/) { m_currentPosition = m_ghostObject->getWorldTransform().getOrigin(); m_targetPosition = m_currentPosition; @@ -941,7 +941,7 @@ btVector3* btKinematicCharacterController::getUpAxisDirections() return sUpAxisDirection; } -void btKinematicCharacterController::debugDraw(btIDebugDraw* debugDrawer) +void btKinematicCharacterController::debugDraw(btIDebugDraw* /*debugDrawer*/) { } diff --git a/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp b/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp index 89bd067a27..0ecf3aecc3 100644 --- a/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp +++ b/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp @@ -172,7 +172,7 @@ static void debugDrawAllBatches(const btBatchedConstraints* bc, } } -static void initBatchedBodyDynamicFlags(btAlignedObjectArray* outBodyDynamicFlags, const btAlignedObjectArray& bodies) +/*static void initBatchedBodyDynamicFlags(btAlignedObjectArray* outBodyDynamicFlags, const btAlignedObjectArray& bodies) { BT_PROFILE("initBatchedBodyDynamicFlags"); btAlignedObjectArray& bodyDynamicFlags = *outBodyDynamicFlags; @@ -182,7 +182,7 @@ static void initBatchedBodyDynamicFlags(btAlignedObjectArray* outBodyDynam const btSolverBody& body = bodies[i]; bodyDynamicFlags[i] = (body.internalGetInvMass().x() > btScalar(0)); } -} +}*/ static int runLengthEncodeConstraintInfo(btBatchedConstraintInfo* outConInfos, int numConstraints) { @@ -262,7 +262,7 @@ static int initBatchedConstraintInfo(btBatchedConstraintInfo* outConInfos, btCon return numConstraints; } -static void expandConstraintRowsInPlace(int* constraintBatchIds, const btBatchedConstraintInfo* conInfos, int numConstraints, int numConstraintRows) +/*static void expandConstraintRowsInPlace(int* constraintBatchIds, const btBatchedConstraintInfo* conInfos, int numConstraints, int numConstraintRows) { BT_PROFILE("expandConstraintRowsInPlace"); if (numConstraintRows > numConstraints) @@ -281,7 +281,7 @@ static void expandConstraintRowsInPlace(int* constraintBatchIds, const btBatched } } } -} +}*/ static void expandConstraintRows(int* destConstraintBatchIds, const int* srcConstraintBatchIds, const btBatchedConstraintInfo* conInfos, int numConstraints, int numConstraintRows) { @@ -328,7 +328,7 @@ static void expandConstraintRowsMt(int* destConstraintBatchIds, const int* srcCo btParallelFor(0, numConstraints, grainSize, loop); } -static void initBatchedConstraintInfoArray(btAlignedObjectArray* outConInfos, btConstraintArray* constraints) +/*static void initBatchedConstraintInfoArray(btAlignedObjectArray* outConInfos, btConstraintArray* constraints) { BT_PROFILE("initBatchedConstraintInfoArray"); btAlignedObjectArray& conInfos = *outConInfos; @@ -337,7 +337,7 @@ static void initBatchedConstraintInfoArray(btAlignedObjectArrayat(0), constraints); conInfos.resizeNoInitialize(newSize); -} +}*/ static void mergeSmallBatches(btBatchInfo* batches, int iBeginBatch, int iEndBatch, int minBatchSize, int maxBatchSize) { @@ -555,9 +555,9 @@ static void writeOutBatches(btBatchedConstraints* bc, const btBatchInfo& batch = batches[i]; int curBatchBegin = iConstraint; constraintIdPerBatch[i] = curBatchBegin; // record the start of each batch in m_constraintIndices array - int numConstraints = batch.numConstraints; - iConstraint += numConstraints; - if (numConstraints > 0) + int numBatchConstraints = batch.numConstraints; + iConstraint += numBatchConstraints; + if (numBatchConstraints > 0) { bc->m_batches.push_back(Range(curBatchBegin, iConstraint)); } @@ -829,7 +829,7 @@ static void setupSpatialGridBatchesMt( const int maxGridChunkCount = 128; int allocNumBatchesPerPhase = maxGridChunkCount; - int minNumBatchesPerPhase = 16; + //int minNumBatchesPerPhase = 16; int allocNumBatches = allocNumBatchesPerPhase * numPhases; btVector3* bodyPositions = NULL; diff --git a/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp b/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp index ac046aa6ea..a9af4cf2da 100644 --- a/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp +++ b/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp @@ -520,7 +520,7 @@ void btConeTwistConstraint::calcAngleInfo() m_solveSwingLimit = false; btVector3 b1Axis1(0, 0, 0), b1Axis2(0, 0, 0), b1Axis3(0, 0, 0); - btVector3 b2Axis1(0, 0, 0), b2Axis2(0, 0, 0); + btVector3 b2Axis1(0, 0, 0); // b2Axis2(0, 0, 0); b1Axis1 = getRigidBodyA().getCenterOfMassTransform().getBasis() * this->m_rbAFrame.getBasis().getColumn(0); b2Axis1 = getRigidBodyB().getCenterOfMassTransform().getBasis() * this->m_rbBFrame.getBasis().getColumn(0); diff --git a/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h b/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h index 777eccf9e7..0eb1888fd9 100644 --- a/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h +++ b/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h @@ -43,12 +43,12 @@ class btConstraintSolver public: virtual ~btConstraintSolver() {} - virtual void prepareSolve(int /* numBodies */, int /* numManifolds */) { ; } + virtual void prepareSolve(int /* numBodies */, int /* numManifolds */) { } ///solve a group of constraints virtual btScalar solveGroup(btCollisionObject** bodies, int numBodies, btPersistentManifold** manifold, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& info, class btIDebugDraw* debugDrawer, btDispatcher* dispatcher) = 0; - virtual void allSolved(const btContactSolverInfo& /* info */, class btIDebugDraw* /* debugDrawer */) { ; } + virtual void allSolved(const btContactSolverInfo& /* info */, class btIDebugDraw* /* debugDrawer */) { } ///clear internal cached data and reset random seed virtual void reset() = 0; diff --git a/src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp b/src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp index e8ebe3a795..d11a252f68 100644 --- a/src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp +++ b/src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp @@ -36,11 +36,11 @@ void btContactConstraint::setContactManifold(btPersistentManifold* contactManifo m_contactManifold = *contactManifold; } -void btContactConstraint::getInfo1(btConstraintInfo1* info) +void btContactConstraint::getInfo1(btConstraintInfo1* /*info*/) { } -void btContactConstraint::getInfo2(btConstraintInfo2* info) +void btContactConstraint::getInfo2(btConstraintInfo2* /*info*/) { } diff --git a/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp b/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp index 39e0cc0ae4..b09541572e 100644 --- a/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp +++ b/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp @@ -634,7 +634,7 @@ void btGeneric6DofSpring2Constraint::calculateLinearInfo() } } -void btGeneric6DofSpring2Constraint::calculateJacobi(btRotationalLimitMotor2* limot, const btTransform& transA, const btTransform& transB, btConstraintInfo2* info, int srow, btVector3& ax1, int rotational, int rotAllowed) +void btGeneric6DofSpring2Constraint::calculateJacobi(btRotationalLimitMotor2* /*limot*/, const btTransform& transA, const btTransform& transB, btConstraintInfo2* info, int srow, btVector3& ax1, int rotational, int rotAllowed) { btScalar* J1 = rotational ? info->m_J1angularAxis : info->m_J1linearAxis; btScalar* J2 = rotational ? info->m_J2angularAxis : info->m_J2linearAxis; diff --git a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp index 419e564c40..c24feeeca4 100644 --- a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp +++ b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp @@ -313,9 +313,9 @@ static btScalar gResolveSplitPenetrationImpulse_scalar_reference( return deltaImpulse * (1. / c.m_jacDiagABInv); } +#ifdef USE_SIMD static btScalar gResolveSplitPenetrationImpulse_sse2(btSolverBody& bodyA, btSolverBody& bodyB, const btSolverConstraint& c) { -#ifdef USE_SIMD if (!c.m_rhsPenetration) return 0.f; @@ -345,10 +345,8 @@ static btScalar gResolveSplitPenetrationImpulse_sse2(btSolverBody& bodyA, btSolv bodyB.internalGetTurnVelocity().mVec128 = _mm_add_ps(bodyB.internalGetTurnVelocity().mVec128, _mm_mul_ps(c.m_angularComponentB.mVec128, impulseMagnitude)); btSimdScalar deltaImp = deltaImpulse; return deltaImp.m_floats[0] * (1. / c.m_jacDiagABInv); -#else - return gResolveSplitPenetrationImpulse_scalar_reference(bodyA, bodyB, c); -#endif } +#endif btSequentialImpulseConstraintSolver::btSequentialImpulseConstraintSolver() { @@ -515,7 +513,7 @@ void btSequentialImpulseConstraintSolver::applyAnisotropicFriction(btCollisionOb } } -void btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstraint& solverConstraint, const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB, btManifoldPoint& cp, const btVector3& rel_pos1, const btVector3& rel_pos2, btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip) +void btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstraint& solverConstraint, const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB, btManifoldPoint& cp, const btVector3& rel_pos1, const btVector3& rel_pos2, btCollisionObject* /*colObj0*/, btCollisionObject* /*colObj1*/, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip) { btSolverBody& solverBodyA = m_tmpSolverBodyPool[solverBodyIdA]; btSolverBody& solverBodyB = m_tmpSolverBodyPool[solverBodyIdB]; @@ -617,8 +615,8 @@ btSolverConstraint& btSequentialImpulseConstraintSolver::addFrictionConstraint(c } void btSequentialImpulseConstraintSolver::setupTorsionalFrictionConstraint(btSolverConstraint& solverConstraint, const btVector3& normalAxis1, int solverBodyIdA, int solverBodyIdB, - btManifoldPoint& cp, btScalar combinedTorsionalFriction, const btVector3& rel_pos1, const btVector3& rel_pos2, - btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, + btManifoldPoint& /*cp*/, btScalar combinedTorsionalFriction, const btVector3& /*rel_pos1*/, const btVector3& /*rel_pos2*/, + btCollisionObject* /*colObj0*/, btCollisionObject* /*colObj1*/, btScalar /*relaxation*/, btScalar desiredVelocity, btScalar cfmSlip) { @@ -979,8 +977,8 @@ void btSequentialImpulseConstraintSolver::setupContactConstraint(btSolverConstra } void btSequentialImpulseConstraintSolver::setFrictionConstraintImpulse(btSolverConstraint& solverConstraint, - int solverBodyIdA, int solverBodyIdB, - btManifoldPoint& cp, const btContactSolverInfo& infoGlobal) + int /*solverBodyIdA*/, int /*solverBodyIdB*/, + btManifoldPoint& /*cp*/, const btContactSolverInfo& infoGlobal) { { btSolverConstraint& frictionConstraint1 = m_tmpSolverContactFrictionConstraintPool[solverConstraint.m_frictionIndex]; @@ -1367,7 +1365,7 @@ void btSequentialImpulseConstraintSolver::convertBodies(btCollisionObject** bodi #endif // BT_THREADSAFE m_tmpSolverBodyPool.reserve(numBodies + 1); - m_tmpSolverBodyPool.resize(0); + // m_tmpSolverBodyPool.resize(0); //btSolverBody& fixedBody = m_tmpSolverBodyPool.expand(); //initSolverBody(&fixedBody,0); @@ -1694,7 +1692,7 @@ btScalar btSequentialImpulseConstraintSolver::solveSingleIteration(int iteration return leastSquaresResidual; } -void btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer) +void btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject** /*bodies*/, int /*numBodies*/, btPersistentManifold** /*manifoldPtr*/, int /*numManifolds*/, btTypedConstraint** /*constraints*/, int /*numConstraints*/, const btContactSolverInfo& infoGlobal, btIDebugDraw* /*debugDrawer*/) { BT_PROFILE("solveGroupCacheFriendlySplitImpulseIterations"); int iteration; @@ -1833,7 +1831,7 @@ void btSequentialImpulseConstraintSolver::writeBackBodies(int iBegin, int iEnd, } } -btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlyFinish(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal) +btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlyFinish(btCollisionObject** /*bodies*/, int /*numBodies*/, const btContactSolverInfo& infoGlobal) { BT_PROFILE("solveGroupCacheFriendlyFinish"); diff --git a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp index 7aa9953bbf..fafa28ab78 100644 --- a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp +++ b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp @@ -294,7 +294,7 @@ void btSequentialImpulseConstraintSolverMt::setupAllContactConstraints(const btC } } -int btSequentialImpulseConstraintSolverMt::getOrInitSolverBodyThreadsafe(btCollisionObject& body, btScalar timeStep) +int btSequentialImpulseConstraintSolverMt::getOrInitSolverBodyThreadsafe(btCollisionObject& body, btScalar /*timeStep*/) { // // getOrInitSolverBody is threadsafe only for a single thread per solver (with potentially multiple solvers) @@ -316,8 +316,8 @@ int btSequentialImpulseConstraintSolverMt::getOrInitSolverBodyThreadsafe(btColli if (solverBodyId < 0) { solverBodyId = m_tmpSolverBodyPool.size(); - btSolverBody& solverBody = m_tmpSolverBodyPool.expand(); - initSolverBody(&solverBody, &body, timeStep); + // btSolverBody& solverBody = m_tmpSolverBodyPool.expand(); + // initSolverBody(&solverBody, &body, timeStep); body.setCompanionId(solverBodyId); } m_bodySolverArrayMutex.unlock(); @@ -357,8 +357,8 @@ int btSequentialImpulseConstraintSolverMt::getOrInitSolverBodyThreadsafe(btColli { // create a table entry for this body solverBodyId = m_tmpSolverBodyPool.size(); - btSolverBody& solverBody = m_tmpSolverBodyPool.expand(); - initSolverBody(&solverBody, &body, timeStep); + // btSolverBody& solverBody = m_tmpSolverBodyPool.expand(); + // initSolverBody(&solverBody, &body, timeStep); m_kinematicBodyUniqueIdToSolverBodyTable[uniqueId] = solverBodyId; } m_bodySolverArrayMutex.unlock(); @@ -375,8 +375,8 @@ int btSequentialImpulseConstraintSolverMt::getOrInitSolverBodyThreadsafe(btColli if (m_fixedBodyId < 0) { m_fixedBodyId = m_tmpSolverBodyPool.size(); - btSolverBody& fixedBody = m_tmpSolverBodyPool.expand(); - initSolverBody(&fixedBody, 0, timeStep); + // btSolverBody& fixedBody = m_tmpSolverBodyPool.expand(); + // initSolverBody(&fixedBody, 0, timeStep); } m_bodySolverArrayMutex.unlock(); } @@ -403,8 +403,8 @@ void btSequentialImpulseConstraintSolverMt::internalCollectContactManifoldCached cachedInfo->solverBodyIds[1] = solverBodyIdB; cachedInfo->numTouchingContacts = 0; - btSolverBody* solverBodyA = &m_tmpSolverBodyPool[solverBodyIdA]; - btSolverBody* solverBodyB = &m_tmpSolverBodyPool[solverBodyIdB]; + //btSolverBody* solverBodyA = &m_tmpSolverBodyPool[solverBodyIdA]; + //btSolverBody* solverBodyB = &m_tmpSolverBodyPool[solverBodyIdB]; // A contact manifold between 2 static object should not exist! // check the collision flags of your objects if this assert fires. @@ -583,8 +583,8 @@ void btSequentialImpulseConstraintSolverMt::convertContacts(btPersistentManifold if (m_fixedBodyId < 0) { m_fixedBodyId = m_tmpSolverBodyPool.size(); - btSolverBody& fixedBody = m_tmpSolverBodyPool.expand(); - initSolverBody(&fixedBody, 0, infoGlobal.m_timeStep); + // btSolverBody& fixedBody = m_tmpSolverBodyPool.expand(); + // initSolverBody(&fixedBody, 0, infoGlobal.m_timeStep); } allocAllContactConstraints(manifoldPtr, numManifolds, infoGlobal); if (m_useBatching) @@ -893,7 +893,7 @@ struct ContactSplitPenetrationImpulseSolverLoop : public btIParallelSumBody } }; -void btSequentialImpulseConstraintSolverMt::solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer) +void btSequentialImpulseConstraintSolverMt::solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject** /*bodies*/, int /*numBodies*/, btPersistentManifold** /*manifoldPtr*/, int /*numManifolds*/, btTypedConstraint** /*constraints*/, int /*numConstraints*/, const btContactSolverInfo& infoGlobal, btIDebugDraw* /*debugDrawer*/) { BT_PROFILE("solveGroupCacheFriendlySplitImpulseIterations"); if (infoGlobal.m_splitImpulse) @@ -1101,7 +1101,7 @@ btScalar btSequentialImpulseConstraintSolverMt::resolveMultipleContactConstraint int batchEnd) { btScalar leastSquaresResidual = 0.f; - int numPoolConstraints = m_tmpSolverContactConstraintPool.size(); + //int numPoolConstraints = m_tmpSolverContactConstraintPool.size(); for (int iiCons = batchBegin; iiCons < batchEnd; iiCons++) { @@ -1522,7 +1522,7 @@ struct WriteBodiesLoop : public btIParallelForBody } }; -btScalar btSequentialImpulseConstraintSolverMt::solveGroupCacheFriendlyFinish(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal) +btScalar btSequentialImpulseConstraintSolverMt::solveGroupCacheFriendlyFinish(btCollisionObject** /*bodies*/, int /*numBodies*/, const btContactSolverInfo& infoGlobal) { BT_PROFILE("solveGroupCacheFriendlyFinish"); diff --git a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp index 9e99c154f2..907043a8b0 100644 --- a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp +++ b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp @@ -90,7 +90,7 @@ struct InplaceSolverIslandCallback : public btSimulationIslandManager::IslandCal InplaceSolverIslandCallback( btConstraintSolver* solver, - btStackAlloc* stackAlloc, + btStackAlloc* /*stackAlloc*/, btDispatcher* dispatcher) : m_solverInfo(NULL), m_solver(solver), diff --git a/src/BulletDynamics/Dynamics/btRigidBody.cpp b/src/BulletDynamics/Dynamics/btRigidBody.cpp index bf7224b165..1c8ba634ab 100644 --- a/src/BulletDynamics/Dynamics/btRigidBody.cpp +++ b/src/BulletDynamics/Dynamics/btRigidBody.cpp @@ -268,7 +268,7 @@ inline btVector3 evalEulerEqn(const btVector3& w1, const btVector3& w0, const bt return w2; } -inline btMatrix3x3 evalEulerEqnDeriv(const btVector3& w1, const btVector3& w0, const btScalar dt, +inline btMatrix3x3 evalEulerEqnDeriv(const btVector3& w1, const btVector3& /*w0*/, const btScalar dt, const btMatrix3x3& I) { btMatrix3x3 w1x, Iw1x; diff --git a/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp b/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp index 134c482e8a..87abf0eb8e 100644 --- a/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp +++ b/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp @@ -159,11 +159,11 @@ void btSimpleDynamicsWorld::debugDrawWorld() { } -void btSimpleDynamicsWorld::addAction(btActionInterface* action) +void btSimpleDynamicsWorld::addAction(btActionInterface* /*action*/) { } -void btSimpleDynamicsWorld::removeAction(btActionInterface* action) +void btSimpleDynamicsWorld::removeAction(btActionInterface* /*action*/) { } diff --git a/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp b/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp index 026c2a9717..7c6a215c99 100644 --- a/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp +++ b/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp @@ -261,7 +261,7 @@ btSimulationIslandManagerMt::Island* btSimulationIslandManagerMt::allocateIsland return island; } -void btSimulationIslandManagerMt::buildIslands(btDispatcher* dispatcher, btCollisionWorld* collisionWorld) +void btSimulationIslandManagerMt::buildIslands(btDispatcher* /*dispatcher*/, btCollisionWorld* collisionWorld) { BT_PROFILE("buildIslands"); @@ -313,7 +313,6 @@ void btSimulationIslandManagerMt::buildIslands(btDispatcher* dispatcher, btColli if (allSleeping) { - int idx; for (idx = startIslandIndex; idx < endIslandIndex; idx++) { int i = getUnionFind().getElement(idx).m_sz; @@ -333,7 +332,6 @@ void btSimulationIslandManagerMt::buildIslands(btDispatcher* dispatcher, btColli } else { - int idx; for (idx = startIslandIndex; idx < endIslandIndex; idx++) { int i = getUnionFind().getElement(idx).m_sz; diff --git a/src/BulletDynamics/Featherstone/btMultiBody.cpp b/src/BulletDynamics/Featherstone/btMultiBody.cpp index 579b7eab46..5ac73abe0d 100644 --- a/src/BulletDynamics/Featherstone/btMultiBody.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBody.cpp @@ -137,7 +137,7 @@ btMultiBody::btMultiBody(int n_links, m_cachedInertiaLowerRight.setValue(0, 0, 0, 0, 0, 0, 0, 0, 0); m_cachedInertiaValid = false; - m_links.resize(n_links); + // m_links.resize(n_links); m_matrixBuf.resize(n_links + 1); m_baseForce.setValue(0, 0, 0); diff --git a/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp b/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp index 00d5fd5609..db413cacee 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp @@ -61,7 +61,7 @@ btScalar btMultiBodyConstraint::fillMultiBodyConstraint(btMultiBodySolverConstra btScalar lowerLimit, btScalar upperLimit, bool angConstraint, btScalar relaxation, - bool isFriction, btScalar desiredVelocity, btScalar cfmSlip, + bool isFriction, btScalar desiredVelocity, btScalar /*cfmSlip*/, btScalar damping) { solverConstraint.m_multiBodyA = m_bodyA; diff --git a/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h b/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h index 7287ccc89b..f23d45801a 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h @@ -110,8 +110,8 @@ btMultiBodyConstraint return m_type; } //many constraints have setFrameInB/setPivotInB. Will use 'getConstraintType' later. - virtual void setFrameInB(const btMatrix3x3& frameInB) {} - virtual void setPivotInB(const btVector3& pivotInB) {} + virtual void setFrameInB(const btMatrix3x3& /*frameInB*/) {} + virtual void setPivotInB(const btVector3& /*pivotInB*/) {} virtual void finalizeMultiDof() = 0; @@ -206,10 +206,10 @@ btMultiBodyConstraint virtual void debugDraw(class btIDebugDraw * drawer) = 0; - virtual void setGearRatio(btScalar ratio) {} - virtual void setGearAuxLink(int gearAuxLink) {} - virtual void setRelativePositionTarget(btScalar relPosTarget) {} - virtual void setErp(btScalar erp) {} + virtual void setGearRatio(btScalar /*ratio*/) {} + virtual void setGearAuxLink(int /*gearAuxLink*/) {} + virtual void setRelativePositionTarget(btScalar /*relPosTarget*/) {} + virtual void setErp(btScalar /*erp*/) {} }; #endif //BT_MULTIBODY_CONSTRAINT_H diff --git a/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp b/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp index 2788367431..daa41c14b1 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp @@ -498,7 +498,7 @@ btScalar btMultiBodyConstraintSolver::resolveConeFrictionConstraintRows(const bt return deltaVel; } -void btMultiBodyConstraintSolver::setupMultiBodyContactConstraint(btMultiBodySolverConstraint& solverConstraint, const btVector3& contactNormal, const btScalar& appliedImpulse, btManifoldPoint& cp, const btContactSolverInfo& infoGlobal, btScalar& relaxation, bool isFriction, btScalar desiredVelocity, btScalar cfmSlip) +void btMultiBodyConstraintSolver::setupMultiBodyContactConstraint(btMultiBodySolverConstraint& solverConstraint, const btVector3& contactNormal, const btScalar& /*appliedImpulse*/, btManifoldPoint& cp, const btContactSolverInfo& infoGlobal, btScalar& relaxation, bool isFriction, btScalar /*desiredVelocity*/, btScalar /*cfmSlip*/) { BT_PROFILE("setupMultiBodyContactConstraint"); btVector3 rel_pos1; @@ -891,7 +891,7 @@ void btMultiBodyConstraintSolver::setupMultiBodyTorsionalFrictionConstraint(btMu btScalar combinedTorsionalFriction, const btContactSolverInfo& infoGlobal, btScalar& relaxation, - bool isFriction, btScalar desiredVelocity, btScalar cfmSlip) + bool isFriction, btScalar /*desiredVelocity*/, btScalar /*cfmSlip*/) { BT_PROFILE("setupMultiBodyRollingFrictionConstraint"); btVector3 rel_pos1; @@ -1072,7 +1072,7 @@ void btMultiBodyConstraintSolver::setupMultiBodyTorsionalFrictionConstraint(btMu //compute rhs and remaining solverConstraint fields btScalar restitution = 0.f; - btScalar penetration = isFriction ? 0 : cp.getDistance(); + //btScalar penetration = isFriction ? 0 : cp.getDistance(); btScalar rel_vel = 0.f; int ndofA = 0; @@ -1139,7 +1139,7 @@ void btMultiBodyConstraintSolver::setupMultiBodyTorsionalFrictionConstraint(btMu } } -btMultiBodySolverConstraint& btMultiBodyConstraintSolver::addMultiBodyFrictionConstraint(const btVector3& normalAxis, const btScalar& appliedImpulse, btPersistentManifold* manifold, int frictionIndex, btManifoldPoint& cp, btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip) +btMultiBodySolverConstraint& btMultiBodyConstraintSolver::addMultiBodyFrictionConstraint(const btVector3& normalAxis, const btScalar& /*appliedImpulse*/, btPersistentManifold* manifold, int frictionIndex, btManifoldPoint& cp, btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip) { BT_PROFILE("addMultiBodyFrictionConstraint"); btMultiBodySolverConstraint& solverConstraint = m_multiBodyFrictionContactConstraints.expandNonInitializing(); diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp index e7af332eb3..7763d4988b 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp @@ -23,7 +23,7 @@ subject to the following restrictions: #include "LinearMath/btIDebugDraw.h" #include "LinearMath/btSerializer.h" -void btMultiBodyDynamicsWorld::addMultiBody(btMultiBody* body, int group, int mask) +void btMultiBodyDynamicsWorld::addMultiBody(btMultiBody* body, int /*group*/, int /*mask*/) { m_multiBodies.push_back(body); } diff --git a/src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.cpp b/src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.cpp index ee02cf9b07..5e80d3971f 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.cpp @@ -20,7 +20,7 @@ subject to the following restrictions: #include "btMultiBodyLinkCollider.h" #include "BulletCollision/CollisionDispatch/btCollisionObject.h" -btMultiBodyGearConstraint::btMultiBodyGearConstraint(btMultiBody* bodyA, int linkA, btMultiBody* bodyB, int linkB, const btVector3& pivotInA, const btVector3& pivotInB, const btMatrix3x3& frameInA, const btMatrix3x3& frameInB) +btMultiBodyGearConstraint::btMultiBodyGearConstraint(btMultiBody* bodyA, int linkA, btMultiBody* bodyB, int linkB, const btVector3& /*pivotInA*/, const btVector3& /*pivotInB*/, const btMatrix3x3& /*frameInA*/, const btMatrix3x3& /*frameInB*/) : btMultiBodyConstraint(bodyA, bodyB, linkA, linkB, 1, false, MULTIBODY_CONSTRAINT_GEAR), m_gearRatio(1), m_gearAuxLink(-1), @@ -110,8 +110,8 @@ void btMultiBodyGearConstraint::createConstraintRows(btMultiBodyConstraintArray& btScalar posError = 0; const btVector3 dummy(0, 0, 0); - btScalar kp = 1; - btScalar kd = 1; + //btScalar kp = 1; + //btScalar kd = 1; int numRows = getNumRows(); for (int row = 0; row < numRows; row++) @@ -119,15 +119,15 @@ void btMultiBodyGearConstraint::createConstraintRows(btMultiBodyConstraintArray& btMultiBodySolverConstraint& constraintRow = constraintRows.expandNonInitializing(); int dof = 0; - btScalar currentPosition = m_bodyA->getJointPosMultiDof(m_linkA)[dof]; - btScalar currentVelocity = m_bodyA->getJointVelMultiDof(m_linkA)[dof]; + // btScalar currentPosition = m_bodyA->getJointPosMultiDof(m_linkA)[dof]; + // btScalar currentVelocity = m_bodyA->getJointVelMultiDof(m_linkA)[dof]; btScalar auxVel = 0; if (m_gearAuxLink >= 0) { auxVel = m_bodyA->getJointVelMultiDof(m_gearAuxLink)[dof]; } - currentVelocity += auxVel; + // currentVelocity += auxVel; if (m_erp != 0) { btScalar currentPositionA = m_bodyA->getJointPosMultiDof(m_linkA)[dof]; diff --git a/src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.h b/src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.h index 31888fbc68..82b0c36277 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.h @@ -89,7 +89,7 @@ class btMultiBodyGearConstraint : public btMultiBodyConstraint m_frameInB = frameInB; } - virtual void debugDraw(class btIDebugDraw* drawer) + virtual void debugDraw(class btIDebugDraw* /*drawer*/) { //todo(erwincoumans) } diff --git a/src/BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h b/src/BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h index b810692b4c..68cc5ac0cc 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h @@ -38,7 +38,7 @@ class btMultiBodyJointLimitConstraint : public btMultiBodyConstraint btMultiBodyJacobianData& data, const btContactSolverInfo& infoGlobal); - virtual void debugDraw(class btIDebugDraw* drawer) + virtual void debugDraw(class btIDebugDraw* /*drawer*/) { //todo(erwincoumans) } diff --git a/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h b/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h index 1aca36352e..e3cf42239e 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h @@ -68,7 +68,7 @@ class btMultiBodyJointMotor : public btMultiBodyConstraint { m_rhsClamp = rhsClamp; } - virtual void debugDraw(class btIDebugDraw* drawer) + virtual void debugDraw(class btIDebugDraw* /*drawer*/) { //todo(erwincoumans) } diff --git a/src/BulletDynamics/Featherstone/btMultiBodySphericalJointLimit.cpp b/src/BulletDynamics/Featherstone/btMultiBodySphericalJointLimit.cpp index 27c7520dc3..829a3f852f 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodySphericalJointLimit.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodySphericalJointLimit.cpp @@ -127,18 +127,18 @@ void btMultiBodySphericalJointLimit::createConstraintRows(btMultiBodyConstraintA if (m_maxAppliedImpulse == 0.f) return; - const btScalar posError = 0; + // const btScalar posError = 0; const btVector3 zero(0, 0, 0); - btVector3 axis[3] = { btVector3(1, 0, 0), btVector3(0, 1, 0), btVector3(0, 0, 1) }; + // btVector3 axis[3] = { btVector3(1, 0, 0), btVector3(0, 1, 0), btVector3(0, 0, 1) }; btQuaternion currentQuat(m_bodyA->getJointPosMultiDof(m_linkA)[0], m_bodyA->getJointPosMultiDof(m_linkA)[1], m_bodyA->getJointPosMultiDof(m_linkA)[2], m_bodyA->getJointPosMultiDof(m_linkA)[3]); - btQuaternion refQuat = m_desiredPosition; + // btQuaternion refQuat = m_desiredPosition; btVector3 vTwist(0,0,1); btVector3 vConeNoTwist = quatRotate(currentQuat, vTwist); @@ -199,13 +199,13 @@ void btMultiBodySphericalJointLimit::createConstraintRows(btMultiBodyConstraintA } - int dof = row; + // int dof = row; - btScalar currentVelocity = m_bodyA->getJointVelMultiDof(m_linkA)[dof]; - btScalar desiredVelocity = this->m_desiredVelocity[row]; + // btScalar currentVelocity = m_bodyA->getJointVelMultiDof(m_linkA)[dof]; + // btScalar desiredVelocity = this->m_desiredVelocity[row]; - double kd = m_use_multi_dof_params ? m_kd[row % 3] : m_kd[0]; - btScalar velocityError = (desiredVelocity - currentVelocity) * kd; + // double kd = m_use_multi_dof_params ? m_kd[row % 3] : m_kd[0]; + // btScalar velocityError = (desiredVelocity - currentVelocity) * kd; btMatrix3x3 frameAworld; frameAworld.setIdentity(); diff --git a/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.cpp b/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.cpp index 00a7ef3579..3a7d9ba4e6 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.cpp @@ -115,11 +115,11 @@ void btMultiBodySphericalJointMotor::createConstraintRows(btMultiBodyConstraintA if (m_maxAppliedImpulse == 0.f) return; - const btScalar posError = 0; + //const btScalar posError = 0; const btVector3 dummy(0, 0, 0); - btVector3 axis[3] = { btVector3(1, 0, 0), btVector3(0, 1, 0), btVector3(0, 0, 1) }; + //btVector3 axis[3] = { btVector3(1, 0, 0), btVector3(0, 1, 0), btVector3(0, 0, 1) }; btQuaternion desiredQuat = m_desiredPosition; btQuaternion currentQuat(m_bodyA->getJointPosMultiDof(m_linkA)[0], @@ -137,13 +137,13 @@ btQuaternion relRot = currentQuat.inverse() * desiredQuat; { btMultiBodySolverConstraint& constraintRow = constraintRows.expandNonInitializing(); - int dof = row; + // int dof = row; - btScalar currentVelocity = m_bodyA->getJointVelMultiDof(m_linkA)[dof]; - btScalar desiredVelocity = this->m_desiredVelocity[row]; + // btScalar currentVelocity = m_bodyA->getJointVelMultiDof(m_linkA)[dof]; + // btScalar desiredVelocity = this->m_desiredVelocity[row]; - double kd = m_use_multi_dof_params ? m_kd[row % 3] : m_kd[0]; - btScalar velocityError = (desiredVelocity - currentVelocity) * kd; + // double kd = m_use_multi_dof_params ? m_kd[row % 3] : m_kd[0]; + // btScalar velocityError = (desiredVelocity - currentVelocity) * kd; btMatrix3x3 frameAworld; frameAworld.setIdentity(); diff --git a/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.h b/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.h index bdeccc2e24..45bfde7dbb 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.h +++ b/src/BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.h @@ -109,7 +109,7 @@ class btMultiBodySphericalJointMotor : public btMultiBodyConstraint m_damping = damping; } - virtual void debugDraw(class btIDebugDraw* drawer) + virtual void debugDraw(class btIDebugDraw* /*drawer*/) { //todo(erwincoumans) } diff --git a/src/BulletDynamics/MLCPSolvers/btDantzigLCP.cpp b/src/BulletDynamics/MLCPSolvers/btDantzigLCP.cpp index 98ecdc0794..d13c39b677 100644 --- a/src/BulletDynamics/MLCPSolvers/btDantzigLCP.cpp +++ b/src/BulletDynamics/MLCPSolvers/btDantzigLCP.cpp @@ -1226,7 +1226,7 @@ struct btLCP bool *_state, int *_findex, int *p, int *c, btScalar **Arows); int getNub() const { return m_nub; } void transfer_i_to_C(int i); - void transfer_i_to_N(int i) { m_nN++; } // because we can assume C and N span 1:i-1 + void transfer_i_to_N(int /*i*/) { m_nN++; } // because we can assume C and N span 1:i-1 void transfer_i_from_N_to_C(int i); void transfer_i_from_C_to_N(int i, btAlignedObjectArray &scratch); int numC() const { return m_nC; } @@ -1597,6 +1597,8 @@ void btLDLTRemove(btScalar **A, const int *p, btScalar *L, btScalar *d, #ifdef BT_DEBUG for (int i = 0; i < n2; ++i) btAssert(p[i] >= 0 && p[i] < n1); +#else + (void)n1; #endif if (r == n2 - 1) diff --git a/src/BulletDynamics/MLCPSolvers/btDantzigSolver.h b/src/BulletDynamics/MLCPSolvers/btDantzigSolver.h index 1f669751ce..4b38868182 100644 --- a/src/BulletDynamics/MLCPSolvers/btDantzigSolver.h +++ b/src/BulletDynamics/MLCPSolvers/btDantzigSolver.h @@ -41,8 +41,9 @@ class btDantzigSolver : public btMLCPSolverInterface { } - virtual bool solveMLCP(const btMatrixXu& A, const btVectorXu& b, btVectorXu& x, const btVectorXu& lo, const btVectorXu& hi, const btAlignedObjectArray& limitDependency, int numIterations, bool useSparsity = true) + virtual bool solveMLCP(const btMatrixXu& A, const btVectorXu& b, btVectorXu& x, const btVectorXu& lo, const btVectorXu& hi, const btAlignedObjectArray& limitDependency, int /*numIterations*/, bool useSparsity = true) { + (void)useSparsity; bool result = true; int n = b.rows(); if (n) diff --git a/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.cpp b/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.cpp index 1007d04e34..b6b88311f2 100644 --- a/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.cpp +++ b/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.cpp @@ -316,7 +316,7 @@ int btLemkeAlgorithm::findLexicographicMinimum(const btMatrixXu& A, const int& p return 0; } -void btLemkeAlgorithm::GaussJordanEliminationStep(btMatrixXu& A, int pivotRowIndex, int pivotColumnIndex, const btAlignedObjectArray& basis) +void btLemkeAlgorithm::GaussJordanEliminationStep(btMatrixXu& A, int pivotRowIndex, int pivotColumnIndex, const btAlignedObjectArray& /*basis*/) { btScalar a = -1 / A(pivotRowIndex, pivotColumnIndex); #ifdef BT_DEBUG_OSTREAM diff --git a/src/BulletDynamics/MLCPSolvers/btLemkeSolver.h b/src/BulletDynamics/MLCPSolvers/btLemkeSolver.h index f18c4ea41b..8dec334daf 100644 --- a/src/BulletDynamics/MLCPSolvers/btLemkeSolver.h +++ b/src/BulletDynamics/MLCPSolvers/btLemkeSolver.h @@ -39,8 +39,9 @@ class btLemkeSolver : public btMLCPSolverInterface m_useLoHighBounds(true) { } - virtual bool solveMLCP(const btMatrixXu& A, const btVectorXu& b, btVectorXu& x, const btVectorXu& lo, const btVectorXu& hi, const btAlignedObjectArray& limitDependency, int numIterations, bool useSparsity = true) + virtual bool solveMLCP(const btMatrixXu& A, const btVectorXu& b, btVectorXu& x, const btVectorXu& lo, const btVectorXu& hi, const btAlignedObjectArray& /*limitDependency*/, int /*numIterations*/, bool useSparsity = true) { + (void)useSparsity; if (m_useLoHighBounds) { BT_PROFILE("btLemkeSolver::solveMLCP"); @@ -239,6 +240,7 @@ class btLemkeSolver : public btMLCPSolverInterface if (fail) { int m_errorCountTimes = 0; + (void)m_errorCountTimes; if (errorIndexMin < 0) errorValueMin = 0.f; if (errorIndexMax < 0) @@ -331,7 +333,7 @@ class btLemkeSolver : public btMLCPSolverInterface return !fail; } - return true; + // return true; } }; diff --git a/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp b/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp index 0c398a3727..f8793629c4 100644 --- a/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp +++ b/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp @@ -136,7 +136,7 @@ class mat3x : public matxx matxx::resize(rhs.rows(), rhs.cols()); *this = rhs; } - mat3x(int rows, int cols) : matxx(3, cols) + mat3x(int /*rows*/, int cols) : matxx(3, cols) { } void operator=(const mat3x& rhs) diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.cpp b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.cpp index feb30d5879..3497d0c9c7 100644 --- a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.cpp +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.cpp @@ -390,7 +390,7 @@ const btVector3 btReducedDeformableBody::internalComputeNodeDeltaVelocity(const return deltaV; } -void btReducedDeformableBody::proceedToTransform(btScalar dt, bool end_of_time_step) +void btReducedDeformableBody::proceedToTransform(btScalar dt, bool /*end_of_time_step*/) { btTransformUtil::integrateTransform(m_rigidTransformWorld, m_linearVelocity, m_angularVelocity, dt, m_interpolationWorldTransform); updateInertiaTensor(); @@ -491,7 +491,7 @@ void btReducedDeformableBody::scale(const btVector3& scl) internalInitialization(); } -void btReducedDeformableBody::setTotalMass(btScalar mass, bool fromfaces) +void btReducedDeformableBody::setTotalMass(btScalar mass, bool /*fromfaces*/) { // Changing the total mass after transform is applied is not allowed btAssert(!m_transform_lock); @@ -587,7 +587,7 @@ void btReducedDeformableBody::updateInertiaTensor() m_invInertiaTensorWorld = m_rigidTransformWorld.getBasis() * m_invInertiaTensorWorldInitial * m_rigidTransformWorld.getBasis().transpose(); } -void btReducedDeformableBody::applyDamping(btScalar timeStep) +void btReducedDeformableBody::applyDamping(btScalar /*timeStep*/) { m_linearVelocity *= btScalar(1) - m_linearDamping; m_angularDamping *= btScalar(1) - m_angularDamping; diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.cpp b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.cpp index 0f95bc53bf..92dae314c0 100644 --- a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.cpp +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.cpp @@ -112,8 +112,8 @@ btReducedDeformableBody* btReducedDeformableBodyHelpers::createFromVtkFile(btSof btSoftBodyHelpers::generateBoundaryFaces(rsb); rsb->initializeDmInverse(); - rsb->m_tetraScratches.resize(rsb->m_tetras.size()); - rsb->m_tetraScratchesTn.resize(rsb->m_tetras.size()); + // rsb->m_tetraScratches.resize(rsb->m_tetras.size()); + // rsb->m_tetraScratchesTn.resize(rsb->m_tetras.size()); printf("Nodes: %u\r\n", rsb->m_nodes.size()); printf("Links: %u\r\n", rsb->m_links.size()); printf("Faces: %u\r\n", rsb->m_faces.size()); diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.cpp b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.cpp index 1418cc2476..3e1c6cc14e 100644 --- a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.cpp +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.cpp @@ -95,8 +95,8 @@ void btReducedDeformableBodySolver::predictReduceDeformableMotion(btScalar solve } // clear contacts variables - rsb->m_nodeRigidContacts.resize(0); - rsb->m_faceRigidContacts.resize(0); + // rsb->m_nodeRigidContacts.resize(0); + // rsb->m_faceRigidContacts.resize(0); rsb->m_faceNodeContacts.resize(0); // calculate inverse mass matrix for all nodes @@ -239,7 +239,7 @@ void btReducedDeformableBodySolver::setConstraints(const btContactSolverInfo& in } } -btScalar btReducedDeformableBodySolver::solveContactConstraints(btCollisionObject** deformableBodies, int numDeformableBodies, const btContactSolverInfo& infoGlobal) +btScalar btReducedDeformableBodySolver::solveContactConstraints(btCollisionObject** /*deformableBodies*/, int /*numDeformableBodies*/, const btContactSolverInfo& infoGlobal) { btScalar residualSquare = 0; @@ -248,7 +248,7 @@ btScalar btReducedDeformableBodySolver::solveContactConstraints(btCollisionObjec btAlignedObjectArray m_orderNonContactConstraintPool; btAlignedObjectArray m_orderContactConstraintPool; - btReducedDeformableBody* rsb = static_cast(m_softBodies[i]); + // btReducedDeformableBody* rsb = static_cast(m_softBodies[i]); // shuffle the order of applying constraint m_orderNonContactConstraintPool.resize(m_staticConstraints[i].size()); diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp index 3c78d2d225..2835be26c9 100644 --- a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp @@ -25,7 +25,7 @@ btReducedDeformableStaticConstraint::btReducedDeformableStaticConstraint( m_rhs = (vel_error + m_erp * pos_error / m_dt) / m_impulseFactor; } -btScalar btReducedDeformableStaticConstraint::solveConstraint(const btContactSolverInfo& infoGlobal) +btScalar btReducedDeformableStaticConstraint::solveConstraint(const btContactSolverInfo& /*infoGlobal*/) { // target velocity of fixed constraint is 0 btVector3 deltaVa = getDeltaVa(); @@ -104,7 +104,7 @@ btVector3 btReducedDeformableRigidContactConstraint::getVa() const return Va; } -btScalar btReducedDeformableRigidContactConstraint::solveConstraint(const btContactSolverInfo& infoGlobal) +btScalar btReducedDeformableRigidContactConstraint::solveConstraint(const btContactSolverInfo& /*infoGlobal*/) { // btVector3 Va = getVa(); // btVector3 deltaVa = Va - m_bufferVelocityA; @@ -513,7 +513,7 @@ btVector3 btReducedDeformableNodeRigidContactConstraint::getSplitVb() const return m_node->m_splitv; } -btVector3 btReducedDeformableNodeRigidContactConstraint::getDv(const btSoftBody::Node* node) const +btVector3 btReducedDeformableNodeRigidContactConstraint::getDv(const btSoftBody::Node* /*node*/) const { return m_total_normal_dv + m_total_tangent_dv; } @@ -573,7 +573,7 @@ btVector3 btReducedDeformableFaceRigidContactConstraint::getDv(const btSoftBody: return face_dv * contact->m_weights[2]; } -void btReducedDeformableFaceRigidContactConstraint::applyImpulse(const btVector3& impulse) +void btReducedDeformableFaceRigidContactConstraint::applyImpulse(const btVector3& /*impulse*/) { // } \ No newline at end of file diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.h b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.h index 10d0938c5d..cb88d7461a 100644 --- a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.h +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.h @@ -108,9 +108,9 @@ class btReducedDeformableRigidContactConstraint : public btDeformableRigidContac const btScalar upper_limit, const btVector3& deltaV_rel); - virtual void applyImpulse(const btVector3& impulse) {} + virtual void applyImpulse(const btVector3& /*impulse*/) {} - virtual void applySplitImpulse(const btVector3& impulse) {} // TODO: may need later + virtual void applySplitImpulse(const btVector3& /*impulse*/) {} // TODO: may need later virtual btVector3 getVa() const; virtual btVector3 getDeltaVa() const = 0; diff --git a/src/BulletSoftBody/btCGProjection.h b/src/BulletSoftBody/btCGProjection.h index e05970664c..b7d4113c13 100644 --- a/src/BulletSoftBody/btCGProjection.h +++ b/src/BulletSoftBody/btCGProjection.h @@ -91,7 +91,7 @@ class btCGProjection // update the constraints virtual btScalar update() = 0; - virtual void reinitialize(bool nodeUpdated) + virtual void reinitialize(bool /*nodeUpdated*/) { } diff --git a/src/BulletSoftBody/btDefaultSoftBodySolver.cpp b/src/BulletSoftBody/btDefaultSoftBodySolver.cpp index acbf515e93..54172081d6 100644 --- a/src/BulletSoftBody/btDefaultSoftBodySolver.cpp +++ b/src/BulletSoftBody/btDefaultSoftBodySolver.cpp @@ -34,11 +34,11 @@ btDefaultSoftBodySolver::~btDefaultSoftBodySolver() } // In this case the data is already in the soft bodies so there is no need for us to do anything -void btDefaultSoftBodySolver::copyBackToSoftBodies(bool bMove) +void btDefaultSoftBodySolver::copyBackToSoftBodies(bool /*bMove*/) { } -void btDefaultSoftBodySolver::optimize(btAlignedObjectArray &softBodies, bool forceUpdate) +void btDefaultSoftBodySolver::optimize(btAlignedObjectArray &softBodies, bool /*forceUpdate*/) { m_softBodySet.copyFromArray(softBodies); } @@ -60,7 +60,7 @@ bool btDefaultSoftBodySolver::checkInitialized() return true; } -void btDefaultSoftBodySolver::solveConstraints(btScalar solverdt) +void btDefaultSoftBodySolver::solveConstraints(btScalar /*solverdt*/) { // Solve constraints for non-solver softbodies for (int i = 0; i < m_softBodySet.size(); ++i) diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index 4e9df5f83e..027e2c3598 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -296,19 +296,19 @@ void btDeformableBodySolver::updateVelocity() void btDeformableBodySolver::updateTempPosition() { - int counter = 0; + // int counter = 0; for (int i = 0; i < m_softBodies.size(); ++i) { btSoftBody* psb = m_softBodies[i]; if (!psb->isActive()) { - counter += psb->m_nodes.size(); + // counter += psb->m_nodes.size(); continue; } for (int j = 0; j < psb->m_nodes.size(); ++j) { psb->m_nodes[j].m_q = psb->m_nodes[j].m_x + m_dt * (psb->m_nodes[j].m_v + psb->m_nodes[j].m_splitv); - ++counter; + // ++counter; } psb->updateDeformation(); } @@ -409,8 +409,8 @@ void btDeformableBodySolver::predictMotion(btScalar solverdt) if (psb->isActive()) { /* Clear contacts when softbody is active*/ - psb->m_nodeRigidContacts.resize(0); - psb->m_faceRigidContacts.resize(0); + // psb->m_nodeRigidContacts.resize(0); + // psb->m_faceRigidContacts.resize(0); psb->m_faceNodeContacts.resize(0); psb->m_faceNodeContactsCCD.resize(0); // predict motion for collision detection diff --git a/src/BulletSoftBody/btDeformableBodySolver.h b/src/BulletSoftBody/btDeformableBodySolver.h index 68354f1996..479d524389 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.h +++ b/src/BulletSoftBody/btDeformableBodySolver.h @@ -70,7 +70,7 @@ class btDeformableBodySolver : public btSoftBodySolver virtual void solveDeformableConstraints(btScalar solverdt); // set gravity (get from deformable world) - virtual void setGravity(const btVector3& gravity) + virtual void setGravity(const btVector3& /*gravity*/) { // for full deformable object, we don't store gravity in the solver // this function is overriden in the reduced deformable object @@ -110,7 +110,7 @@ class btDeformableBodySolver : public btSoftBodySolver // calculate the change in dv resulting from the momentum solve when line search is turned on btScalar computeDescentStep(TVStack& ddv, const TVStack& residual, bool verbose = false); - virtual void copySoftBodyToVertexBuffer(const btSoftBody* const softBody, btVertexBufferDescriptor* vertexBuffer) {} + virtual void copySoftBodyToVertexBuffer(const btSoftBody* const /*softBody*/, btVertexBufferDescriptor* /*vertexBuffer*/) {} // process collision between deformable and rigid virtual void processCollision(btSoftBody* softBody, const btCollisionObjectWrapper* collisionObjectWrap) @@ -215,10 +215,10 @@ class btDeformableBodySolver : public btSoftBodySolver virtual void deformableBodyInternalWriteBack() {} // unused functions - virtual void optimize(btAlignedObjectArray& softBodies, bool forceUpdate = false) {} - virtual void solveConstraints(btScalar dt) {} + virtual void optimize(btAlignedObjectArray& /*softBodies*/, bool /*forceUpdate*/ = false) {} + virtual void solveConstraints(btScalar /*dt*/) {} virtual bool checkInitialized() { return true; } - virtual void copyBackToSoftBodies(bool bMove = true) {} + virtual void copyBackToSoftBodies(bool /*bMove*/ = true) {} }; #endif /* btDeformableBodySolver_h */ diff --git a/src/BulletSoftBody/btDeformableContactConstraint.cpp b/src/BulletSoftBody/btDeformableContactConstraint.cpp index 9c8e72f503..cb71f0af45 100644 --- a/src/BulletSoftBody/btDeformableContactConstraint.cpp +++ b/src/BulletSoftBody/btDeformableContactConstraint.cpp @@ -77,7 +77,7 @@ btVector3 btDeformableNodeAnchorConstraint::getVa() const return va; } -btScalar btDeformableNodeAnchorConstraint::solveConstraint(const btContactSolverInfo& infoGlobal) +btScalar btDeformableNodeAnchorConstraint::solveConstraint(const btContactSolverInfo& /*infoGlobal*/) { const btSoftBody::sCti& cti = m_anchor->m_cti; btVector3 va = getVa(); @@ -428,7 +428,7 @@ btVector3 btDeformableNodeRigidContactConstraint::getSplitVb() const return m_node->m_splitv; } -btVector3 btDeformableNodeRigidContactConstraint::getDv(const btSoftBody::Node* node) const +btVector3 btDeformableNodeRigidContactConstraint::getDv(const btSoftBody::Node* /*node*/) const { return m_total_normal_dv + m_total_tangent_dv; } @@ -630,7 +630,7 @@ btVector3 btDeformableFaceNodeContactConstraint::getDv(const btSoftBody::Node* n return dv * contact->m_weights[2]; } -btScalar btDeformableFaceNodeContactConstraint::solveConstraint(const btContactSolverInfo& infoGlobal) +btScalar btDeformableFaceNodeContactConstraint::solveConstraint(const btContactSolverInfo& /*infoGlobal*/) { btVector3 va = getVa(); btVector3 vb = getVb(); diff --git a/src/BulletSoftBody/btDeformableContactConstraint.h b/src/BulletSoftBody/btDeformableContactConstraint.h index ddecb40fcb..ceae9c2fe8 100644 --- a/src/BulletSoftBody/btDeformableContactConstraint.h +++ b/src/BulletSoftBody/btDeformableContactConstraint.h @@ -84,7 +84,7 @@ class btDeformableStaticConstraint : public btDeformableContactConstraint virtual ~btDeformableStaticConstraint() {} - virtual btScalar solveConstraint(const btContactSolverInfo& infoGlobal) + virtual btScalar solveConstraint(const btContactSolverInfo& /*infoGlobal*/) { return 0; } @@ -99,13 +99,13 @@ class btDeformableStaticConstraint : public btDeformableContactConstraint return btVector3(0, 0, 0); } - virtual btVector3 getDv(const btSoftBody::Node* n) const + virtual btVector3 getDv(const btSoftBody::Node* /*n*/) const { return btVector3(0, 0, 0); } - virtual void applyImpulse(const btVector3& impulse) {} - virtual void setPenetrationScale(btScalar scale) {} + virtual void applyImpulse(const btVector3& /*impulse*/) {} + virtual void setPenetrationScale(btScalar /*scale*/) {} }; // @@ -127,13 +127,13 @@ class btDeformableNodeAnchorConstraint : public btDeformableContactConstraint virtual btVector3 getVa() const; // get the velocity of the deformable node in contact virtual btVector3 getVb() const; - virtual btVector3 getDv(const btSoftBody::Node* n) const + virtual btVector3 getDv(const btSoftBody::Node* /*n*/) const { return btVector3(0, 0, 0); } virtual void applyImpulse(const btVector3& impulse); - virtual void setPenetrationScale(btScalar scale) {} + virtual void setPenetrationScale(btScalar /*scale*/) {} }; // @@ -279,6 +279,6 @@ class btDeformableFaceNodeContactConstraint : public btDeformableContactConstrai virtual void applyImpulse(const btVector3& impulse); - virtual void setPenetrationScale(btScalar scale) {} + virtual void setPenetrationScale(btScalar /*scale*/) {} }; #endif /* BT_DEFORMABLE_CONTACT_CONSTRAINT_H */ diff --git a/src/BulletSoftBody/btDeformableCorotatedForce.h b/src/BulletSoftBody/btDeformableCorotatedForce.h index dfd85523bc..5d337be1b9 100644 --- a/src/BulletSoftBody/btDeformableCorotatedForce.h +++ b/src/BulletSoftBody/btDeformableCorotatedForce.h @@ -48,7 +48,7 @@ class btDeformableCorotatedForce : public btDeformableLagrangianForce addScaledElasticForce(scale, force); } - virtual void addScaledDampingForce(btScalar scale, TVStack& force) + virtual void addScaledDampingForce(btScalar /*scale*/, TVStack& /*force*/) { } @@ -105,15 +105,15 @@ class btDeformableCorotatedForce : public btDeformableLagrangianForce } } - virtual void addScaledElasticForceDifferential(btScalar scale, const TVStack& dx, TVStack& df) + virtual void addScaledElasticForceDifferential(btScalar /*scale*/, const TVStack& /*dx*/, TVStack& /*df*/) { } - virtual void addScaledDampingForceDifferential(btScalar scale, const TVStack& dv, TVStack& df) + virtual void addScaledDampingForceDifferential(btScalar /*scale*/, const TVStack& /*dv*/, TVStack& /*df*/) { } - virtual void buildDampingForceDifferentialDiagonal(btScalar scale, TVStack& diagA) {} + virtual void buildDampingForceDifferentialDiagonal(btScalar /*scale*/, TVStack& /*diagA*/) {} virtual btDeformableLagrangianForceType getForceType() { diff --git a/src/BulletSoftBody/btDeformableGravityForce.h b/src/BulletSoftBody/btDeformableGravityForce.h index d91867f457..ba4c82c7de 100644 --- a/src/BulletSoftBody/btDeformableGravityForce.h +++ b/src/BulletSoftBody/btDeformableGravityForce.h @@ -38,23 +38,23 @@ class btDeformableGravityForce : public btDeformableLagrangianForce addScaledGravityForce(scale, force); } - virtual void addScaledDampingForce(btScalar scale, TVStack& force) + virtual void addScaledDampingForce(btScalar /*scale*/, TVStack& /*force*/) { } - virtual void addScaledElasticForceDifferential(btScalar scale, const TVStack& dx, TVStack& df) + virtual void addScaledElasticForceDifferential(btScalar /*scale*/, const TVStack& /*dx*/, TVStack& /*df*/) { } - virtual void addScaledDampingForceDifferential(btScalar scale, const TVStack& dv, TVStack& df) + virtual void addScaledDampingForceDifferential(btScalar /*scale*/, const TVStack& /*dv*/, TVStack& /*df*/) { } - virtual void buildDampingForceDifferentialDiagonal(btScalar scale, TVStack& diagA) {} + virtual void buildDampingForceDifferentialDiagonal(btScalar /*scale*/, TVStack& /*diagA*/) {} virtual void addScaledGravityForce(btScalar scale, TVStack& force) { - int numNodes = getNumNodes(); + int numNodes = getNumNodes(); (void)numNodes; btAssert(numNodes <= force.size()); for (int i = 0; i < m_softBodies.size(); ++i) { @@ -80,7 +80,7 @@ class btDeformableGravityForce : public btDeformableLagrangianForce } // the gravitational potential energy - virtual double totalEnergy(btScalar dt) + virtual double totalEnergy(btScalar /*dt*/) { double e = 0; for (int i = 0; i < m_softBodies.size(); ++i) diff --git a/src/BulletSoftBody/btDeformableLagrangianForce.h b/src/BulletSoftBody/btDeformableLagrangianForce.h index d58d825d1c..075ecc8166 100644 --- a/src/BulletSoftBody/btDeformableLagrangianForce.h +++ b/src/BulletSoftBody/btDeformableLagrangianForce.h @@ -66,11 +66,11 @@ class btDeformableLagrangianForce // add all damping forces virtual void addScaledDampingForce(btScalar scale, TVStack& force) = 0; - virtual void addScaledHessian(btScalar scale) {} + virtual void addScaledHessian(btScalar /*scale*/) {} virtual btDeformableLagrangianForceType getForceType() = 0; - virtual void reinitialize(bool nodeUpdated) + virtual void reinitialize(bool /*nodeUpdated*/) { } @@ -352,13 +352,13 @@ class btDeformableLagrangianForce } // - virtual double totalElasticEnergy(btScalar dt) + virtual double totalElasticEnergy(btScalar /*dt*/) { return 0; } // - virtual double totalDampingEnergy(btScalar dt) + virtual double totalDampingEnergy(btScalar /*dt*/) { return 0; } diff --git a/src/BulletSoftBody/btDeformableLinearElasticityForce.h b/src/BulletSoftBody/btDeformableLinearElasticityForce.h index 971192050b..bdc9a24aa5 100644 --- a/src/BulletSoftBody/btDeformableLinearElasticityForce.h +++ b/src/BulletSoftBody/btDeformableLinearElasticityForce.h @@ -151,7 +151,7 @@ class btDeformableLinearElasticityForce : public btDeformableLagrangianForce } } - virtual double totalElasticEnergy(btScalar dt) + virtual double totalElasticEnergy(btScalar /*dt*/) { double energy = 0; for (int i = 0; i < m_softBodies.size(); ++i) @@ -227,7 +227,9 @@ class btDeformableLinearElasticityForce : public btDeformableLagrangianForce { continue; } +#if USE_SVD btScalar max_p = psb->m_cfg.m_maxStress; +#endif for (int j = 0; j < psb->m_tetras.size(); ++j) { btSoftBody::Tetra& tetra = psb->m_tetras[j]; @@ -282,7 +284,7 @@ class btDeformableLinearElasticityForce : public btDeformableLagrangianForce } } - virtual void buildDampingForceDifferentialDiagonal(btScalar scale, TVStack& diagA) {} + virtual void buildDampingForceDifferentialDiagonal(btScalar /*scale*/, TVStack& /*diagA*/) {} // The damping matrix is calculated using the time n state as described in https://www.math.ucla.edu/~jteran/papers/GSSJT15.pdf to allow line search virtual void addScaledDampingForceDifferential(btScalar scale, const TVStack& dv, TVStack& df) @@ -398,7 +400,7 @@ class btDeformableLinearElasticityForce : public btDeformableLagrangianForce // Let P be the first piola stress. // This function calculates the dP = dP/dF * dF - void firstPiolaDifferential(const btSoftBody::TetraScratch& s, const btMatrix3x3& dF, btMatrix3x3& dP) + void firstPiolaDifferential(const btSoftBody::TetraScratch& /*s*/, const btMatrix3x3& dF, btMatrix3x3& dP) { btScalar trace = (dF[0][0] + dF[1][1] + dF[2][2]); dP = (dF + dF.transpose()) * m_mu + btMatrix3x3::getIdentity() * m_lambda * trace; @@ -406,7 +408,7 @@ class btDeformableLinearElasticityForce : public btDeformableLagrangianForce // Let Q be the damping stress. // This function calculates the dP = dQ/dF * dF - void firstPiolaDampingDifferential(const btSoftBody::TetraScratch& s, const btMatrix3x3& dF, btMatrix3x3& dP) + void firstPiolaDampingDifferential(const btSoftBody::TetraScratch& /*s*/, const btMatrix3x3& dF, btMatrix3x3& dP) { btScalar mu_damp = m_damping_beta * m_mu; btScalar lambda_damp = m_damping_beta * m_lambda; diff --git a/src/BulletSoftBody/btDeformableMassSpringForce.h b/src/BulletSoftBody/btDeformableMassSpringForce.h index 8c97bd1ba8..0a4b67ba73 100644 --- a/src/BulletSoftBody/btDeformableMassSpringForce.h +++ b/src/BulletSoftBody/btDeformableMassSpringForce.h @@ -196,7 +196,7 @@ class btDeformableMassSpringForce : public btDeformableLagrangianForce } } - virtual double totalElasticEnergy(btScalar dt) + virtual double totalElasticEnergy(btScalar /*dt*/) { double energy = 0; for (int i = 0; i < m_softBodies.size(); ++i) diff --git a/src/BulletSoftBody/btDeformableMousePickingForce.h b/src/BulletSoftBody/btDeformableMousePickingForce.h index 697408355c..1023dd9378 100644 --- a/src/BulletSoftBody/btDeformableMousePickingForce.h +++ b/src/BulletSoftBody/btDeformableMousePickingForce.h @@ -90,9 +90,9 @@ class btDeformableMousePickingForce : public btDeformableLagrangianForce } } - virtual void buildDampingForceDifferentialDiagonal(btScalar scale, TVStack& diagA) {} + virtual void buildDampingForceDifferentialDiagonal(btScalar /*scale*/, TVStack& /*diagA*/) {} - virtual double totalElasticEnergy(btScalar dt) + virtual double totalElasticEnergy(btScalar /*dt*/) { double energy = 0; for (int i = 0; i < 3; ++i) diff --git a/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp b/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp index 0f3005417e..d46eba7a2e 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp +++ b/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp @@ -70,7 +70,7 @@ btScalar btDeformableMultiBodyConstraintSolver::solveDeformableGroupIterations(b return 0.f; } -void btDeformableMultiBodyConstraintSolver::solveDeformableBodyGroup(btCollisionObject** bodies, int numBodies, btCollisionObject** deformableBodies, int numDeformableBodies, btPersistentManifold** manifold, int numManifolds, btTypedConstraint** constraints, int numConstraints, btMultiBodyConstraint** multiBodyConstraints, int numMultiBodyConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* dispatcher) +void btDeformableMultiBodyConstraintSolver::solveDeformableBodyGroup(btCollisionObject** bodies, int numBodies, btCollisionObject** deformableBodies, int numDeformableBodies, btPersistentManifold** manifold, int numManifolds, btTypedConstraint** constraints, int numConstraints, btMultiBodyConstraint** multiBodyConstraints, int numMultiBodyConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* /*dispatcher*/) { m_tmpMultiBodyConstraints = multiBodyConstraints; m_tmpNumMultiBodyConstraints = numMultiBodyConstraints; @@ -110,7 +110,7 @@ void btDeformableMultiBodyConstraintSolver::writeToSolverBody(btCollisionObject* } } -void btDeformableMultiBodyConstraintSolver::solverBodyWriteBack(const btContactSolverInfo& infoGlobal) +void btDeformableMultiBodyConstraintSolver::solverBodyWriteBack(const btContactSolverInfo& /*infoGlobal*/) { // reduced soft body solver directly modifies the solver body if (m_deformableSolver->isReducedSolver()) @@ -130,7 +130,7 @@ void btDeformableMultiBodyConstraintSolver::solverBodyWriteBack(const btContactS } -void btDeformableMultiBodyConstraintSolver::pairDeformableAndSolverBody(btCollisionObject** bodies, int numBodies, int numDeformableBodies, const btContactSolverInfo& infoGlobal) +void btDeformableMultiBodyConstraintSolver::pairDeformableAndSolverBody(btCollisionObject** bodies, int /*numBodies*/, int numDeformableBodies, const btContactSolverInfo& infoGlobal) { if (!m_deformableSolver->isReducedSolver()) { @@ -176,7 +176,7 @@ void btDeformableMultiBodyConstraintSolver::pairDeformableAndSolverBody(btCollis } } -void btDeformableMultiBodyConstraintSolver::solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject** bodies, int numBodies, btCollisionObject** deformableBodies, int numDeformableBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer) +void btDeformableMultiBodyConstraintSolver::solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject** /*bodies*/, int /*numBodies*/, btCollisionObject** deformableBodies, int numDeformableBodies, btPersistentManifold** /*manifoldPtr*/, int /*numManifolds*/, btTypedConstraint** /*constraints*/, int /*numConstraints*/, const btContactSolverInfo& infoGlobal, btIDebugDraw* /*debugDrawer*/) { BT_PROFILE("solveGroupCacheFriendlySplitImpulseIterations"); int iteration; diff --git a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp index 030cbaf90f..b230ecdd33 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp +++ b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp @@ -602,7 +602,7 @@ void btDeformableMultiBodyDynamicsWorld::beforeSolverCallbacks(btScalar timeStep } } -void btDeformableMultiBodyDynamicsWorld::afterSolverCallbacks(btScalar timeStep) +void btDeformableMultiBodyDynamicsWorld::afterSolverCallbacks(btScalar /*timeStep*/) { if (0 != m_solverCallback) { diff --git a/src/BulletSoftBody/btDeformableNeoHookeanForce.h b/src/BulletSoftBody/btDeformableNeoHookeanForce.h index 60798c5bcd..6b810750f3 100644 --- a/src/BulletSoftBody/btDeformableNeoHookeanForce.h +++ b/src/BulletSoftBody/btDeformableNeoHookeanForce.h @@ -138,7 +138,7 @@ class btDeformableNeoHookeanForce : public btDeformableLagrangianForce } } - virtual double totalElasticEnergy(btScalar dt) + virtual double totalElasticEnergy(btScalar /*dt*/) { double energy = 0; for (int i = 0; i < m_softBodies.size(); ++i) @@ -213,7 +213,9 @@ class btDeformableNeoHookeanForce : public btDeformableLagrangianForce { continue; } +#ifdef USE_SVD btScalar max_p = psb->m_cfg.m_maxStress; +#endif for (int j = 0; j < psb->m_tetras.size(); ++j) { btSoftBody::Tetra& tetra = psb->m_tetras[j]; @@ -313,7 +315,7 @@ class btDeformableNeoHookeanForce : public btDeformableLagrangianForce } } - virtual void buildDampingForceDifferentialDiagonal(btScalar scale, TVStack& diagA) {} + virtual void buildDampingForceDifferentialDiagonal(btScalar /*scale*/, TVStack& /*diagA*/) {} virtual void addScaledElasticForceDifferential(btScalar scale, const TVStack& dx, TVStack& df) { diff --git a/src/BulletSoftBody/btPreconditioner.h b/src/BulletSoftBody/btPreconditioner.h index 21c1106a42..4e2ee2e150 100644 --- a/src/BulletSoftBody/btPreconditioner.h +++ b/src/BulletSoftBody/btPreconditioner.h @@ -34,7 +34,7 @@ class DefaultPreconditioner : public Preconditioner for (int i = 0; i < b.size(); ++i) b[i] = x[i]; } - virtual void reinitialize(bool nodeUpdated) + virtual void reinitialize(bool /*nodeUpdated*/) { } diff --git a/src/BulletSoftBody/btSoftBody.cpp b/src/BulletSoftBody/btSoftBody.cpp index c873099b49..9c9e3bd5c6 100644 --- a/src/BulletSoftBody/btSoftBody.cpp +++ b/src/BulletSoftBody/btSoftBody.cpp @@ -142,7 +142,7 @@ btSoftBody::btSoftBody(btSoftBodyWorldInfo* worldInfo, int node_count, const btV /* Nodes */ const btScalar margin = getCollisionShape()->getMargin(); - m_nodes.resize(node_count); + // m_nodes.resize(node_count); m_X.resize(node_count); for (int i = 0, ni = node_count; i < ni; ++i) { @@ -1716,7 +1716,7 @@ void btSoftBody::refine(ImplicitFn* ifn, btScalar accurary, bool cut) const Node* nbase = &m_nodes[0]; int ncount = m_nodes.size(); btSymMatrix edges(ncount, -2); - int newnodes = 0; + // int newnodes = 0; int i, j, k, ni; /* Filter out */ @@ -1792,7 +1792,7 @@ void btSoftBody::refine(ImplicitFn* ifn, btScalar accurary, bool cut) appendNode(x, m); edges(i, j) = m_nodes.size() - 1; m_nodes[edges(i, j)].m_v = v; - ++newnodes; + // ++newnodes; } } } @@ -2196,7 +2196,7 @@ void btSoftBody::predictMotion(btScalar dt) } } /* Clear contacts */ - m_rcontacts.resize(0); + // m_rcontacts.resize(0); m_scontacts.resize(0); /* Optimize dbvt's */ m_ndbvt.optimizeIncremental(1); @@ -2381,7 +2381,7 @@ void btSoftBody::RayFromToCaster::Process(const btDbvtNode* leaf) // btScalar btSoftBody::RayFromToCaster::rayFromToTriangle(const btVector3& rayFrom, - const btVector3& rayTo, + const btVector3& /*rayTo*/, const btVector3& rayNormalizedDirection, const btVector3& a, const btVector3& b, @@ -3577,7 +3577,7 @@ void btSoftBody::advanceDeformation() } } // -void btSoftBody::Joint::Prepare(btScalar dt, int) +void btSoftBody::Joint::Prepare(btScalar /*dt*/, int) { m_bodies[0].activate(); m_bodies[1].activate(); @@ -3604,7 +3604,7 @@ void btSoftBody::LJoint::Prepare(btScalar dt, int iterations) } // -void btSoftBody::LJoint::Solve(btScalar dt, btScalar sor) +void btSoftBody::LJoint::Solve(btScalar /*dt*/, btScalar sor) { const btVector3 va = m_bodies[0].velocity(m_rpos[0]); const btVector3 vb = m_bodies[1].velocity(m_rpos[1]); @@ -3617,7 +3617,7 @@ void btSoftBody::LJoint::Solve(btScalar dt, btScalar sor) } // -void btSoftBody::LJoint::Terminate(btScalar dt) +void btSoftBody::LJoint::Terminate(btScalar /*dt*/) { if (m_split > 0) { @@ -3647,7 +3647,7 @@ void btSoftBody::AJoint::Prepare(btScalar dt, int iterations) } // -void btSoftBody::AJoint::Solve(btScalar dt, btScalar sor) +void btSoftBody::AJoint::Solve(btScalar /*dt*/, btScalar sor) { const btVector3 va = m_bodies[0].angularVelocity(); const btVector3 vb = m_bodies[1].angularVelocity(); @@ -3662,7 +3662,7 @@ void btSoftBody::AJoint::Solve(btScalar dt, btScalar sor) } // -void btSoftBody::AJoint::Terminate(btScalar dt) +void btSoftBody::AJoint::Terminate(btScalar /*dt*/) { if (m_split > 0) { @@ -3694,7 +3694,7 @@ void btSoftBody::CJoint::Prepare(btScalar dt, int iterations) } // -void btSoftBody::CJoint::Solve(btScalar dt, btScalar sor) +void btSoftBody::CJoint::Solve(btScalar /*dt*/, btScalar sor) { const btVector3 va = m_bodies[0].velocity(m_rpos[0]); const btVector3 vb = m_bodies[1].velocity(m_rpos[1]); @@ -3737,7 +3737,7 @@ void btSoftBody::CJoint::Solve(btScalar dt, btScalar sor) } // -void btSoftBody::CJoint::Terminate(btScalar dt) +void btSoftBody::CJoint::Terminate(btScalar /*dt*/) { if (m_split > 0) { @@ -3870,7 +3870,7 @@ void btSoftBody::setCollisionQuadrature(int N) } // -void btSoftBody::PSolve_Anchors(btSoftBody* psb, btScalar kst, btScalar ti) +void btSoftBody::PSolve_Anchors(btSoftBody* psb, btScalar kst, btScalar /*ti*/) { BT_PROFILE("PSolve_Anchors"); const btScalar kAHR = psb->m_cfg.kAHR * kst; @@ -3891,7 +3891,7 @@ void btSoftBody::PSolve_Anchors(btSoftBody* psb, btScalar kst, btScalar ti) } // -void btSoftBody::PSolve_RContacts(btSoftBody* psb, btScalar kst, btScalar ti) +void btSoftBody::PSolve_RContacts(btSoftBody* psb, btScalar kst, btScalar /*ti*/) { BT_PROFILE("PSolve_RContacts"); const btScalar dt = psb->m_sst.sdt; @@ -3966,7 +3966,7 @@ void btSoftBody::PSolve_RContacts(btSoftBody* psb, btScalar kst, btScalar ti) } // -void btSoftBody::PSolve_SContacts(btSoftBody* psb, btScalar, btScalar ti) +void btSoftBody::PSolve_SContacts(btSoftBody* psb, btScalar, btScalar /*ti*/) { BT_PROFILE("PSolve_SContacts"); @@ -4001,7 +4001,7 @@ void btSoftBody::PSolve_SContacts(btSoftBody* psb, btScalar, btScalar ti) } // -void btSoftBody::PSolve_Links(btSoftBody* psb, btScalar kst, btScalar ti) +void btSoftBody::PSolve_Links(btSoftBody* psb, btScalar kst, btScalar /*ti*/) { BT_PROFILE("PSolve_Links"); for (int i = 0, ni = psb->m_links.size(); i < ni; ++i) diff --git a/src/BulletSoftBody/btSoftBody.h b/src/BulletSoftBody/btSoftBody.h index 27705e6009..5aad271ae7 100644 --- a/src/BulletSoftBody/btSoftBody.h +++ b/src/BulletSoftBody/btSoftBody.h @@ -891,7 +891,7 @@ class btSoftBody : public btCollisionObject } ///@todo: avoid internal softbody shape hack and move collision code to collision library - virtual void setCollisionShape(btCollisionShape* collisionShape) + virtual void setCollisionShape(btCollisionShape* /*collisionShape*/) { } @@ -1106,7 +1106,7 @@ class btSoftBody : public btCollisionObject void setZeroVelocity(); bool wantsSleeping(); - virtual btMatrix3x3 getImpulseFactor(int n_node) + virtual btMatrix3x3 getImpulseFactor(int /*n_node*/) { btMatrix3x3 tmp; tmp.setIdentity(); diff --git a/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.h b/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.h index 0dbceebf37..7647fdf907 100644 --- a/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.h +++ b/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.h @@ -118,7 +118,7 @@ class btSoftBodyConcaveCollisionAlgorithm : public btCollisionAlgorithm btScalar calculateTimeOfImpact(btCollisionObject* body0, btCollisionObject* body1, const btDispatcherInfo& dispatchInfo, btManifoldResult* resultOut); - virtual void getAllContactManifolds(btManifoldArray& manifoldArray) + virtual void getAllContactManifolds(btManifoldArray& /*manifoldArray*/) { //we don't add any manifolds } diff --git a/src/BulletSoftBody/btSoftBodyHelpers.cpp b/src/BulletSoftBody/btSoftBodyHelpers.cpp index fbb7298306..d596e3e3f3 100644 --- a/src/BulletSoftBody/btSoftBodyHelpers.cpp +++ b/src/BulletSoftBody/btSoftBodyHelpers.cpp @@ -1140,11 +1140,11 @@ static int nextLine(const char* buffer) /* Create from TetGen .ele, .face, .node data */ btSoftBody* btSoftBodyHelpers::CreateFromTetGenData(btSoftBodyWorldInfo& worldInfo, const char* ele, - const char* face, + const char* /*face*/, const char* node, - bool bfacelinks, + bool /*bfacelinks*/, bool btetralinks, - bool bfacesfromtetras) + bool /*bfacesfromtetras*/) { btAlignedObjectArray pos; int nnode = 0; @@ -1153,6 +1153,7 @@ btSoftBody* btSoftBodyHelpers::CreateFromTetGenData(btSoftBodyWorldInfo& worldIn int hasbounds = 0; int result = sscanf(node, "%d %d %d %d", &nnode, &ndims, &nattrb, &hasbounds); result = sscanf(node, "%d %d %d %d", &nnode, &ndims, &nattrb, &hasbounds); + (void)result; node += nextLine(node); pos.resize(nnode); @@ -1235,8 +1236,8 @@ if(face&&face[0]) } } psb->initializeDmInverse(); - psb->m_tetraScratches.resize(psb->m_tetras.size()); - psb->m_tetraScratchesTn.resize(psb->m_tetras.size()); + // psb->m_tetraScratches.resize(psb->m_tetras.size()); + // psb->m_tetraScratchesTn.resize(psb->m_tetras.size()); printf("Nodes: %u\r\n", psb->m_nodes.size()); printf("Links: %u\r\n", psb->m_links.size()); printf("Faces: %u\r\n", psb->m_faces.size()); @@ -1340,8 +1341,8 @@ btSoftBody* btSoftBodyHelpers::CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, generateBoundaryFaces(psb); psb->initializeDmInverse(); - psb->m_tetraScratches.resize(psb->m_tetras.size()); - psb->m_tetraScratchesTn.resize(psb->m_tetras.size()); + // psb->m_tetraScratches.resize(psb->m_tetras.size()); + // psb->m_tetraScratchesTn.resize(psb->m_tetras.size()); printf("Nodes: %u\r\n", psb->m_nodes.size()); printf("Links: %u\r\n", psb->m_links.size()); printf("Faces: %u\r\n", psb->m_faces.size()); @@ -1519,7 +1520,7 @@ void btSoftBodyHelpers::writeState(const char* file, const btSoftBody* psb) fs.close(); } -void btSoftBodyHelpers::duplicateFaces(const char* filename, const btSoftBody* psb) +void btSoftBodyHelpers::duplicateFaces(const char* filename, const btSoftBody* /*psb*/) { std::ifstream fs_read; fs_read.open(filename); diff --git a/src/BulletSoftBody/btSoftBodyInternals.h b/src/BulletSoftBody/btSoftBodyInternals.h index 137258675b..d0de7952d2 100644 --- a/src/BulletSoftBody/btSoftBodyInternals.h +++ b/src/BulletSoftBody/btSoftBodyInternals.h @@ -220,7 +220,7 @@ static SIMD_FORCE_INLINE bool getSigns(bool type_c, const btScalar& k0, const bt return false; } -static SIMD_FORCE_INLINE void getBernsteinCoeff(const btSoftBody::Face* face, const btSoftBody::Node* node, const btScalar& dt, btScalar& k0, btScalar& k1, btScalar& k2, btScalar& k3) +static SIMD_FORCE_INLINE void getBernsteinCoeff(const btSoftBody::Face* face, const btSoftBody::Node* node, const btScalar& /*dt*/, btScalar& k0, btScalar& k1, btScalar& k2, btScalar& k3) { const btVector3& n0 = face->m_n0; const btVector3& n1 = face->m_n1; @@ -753,15 +753,15 @@ class btSoftClusterCollisionShape : public btConvexInternalShape return (localGetSupportingVertex(vec)); } //notice that the vectors should be unit length - virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const + virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* /*vectors*/, btVector3* /*supportVerticesOut*/, int /*numVectors*/) const { } - virtual void calculateLocalInertia(btScalar mass, btVector3& inertia) const + virtual void calculateLocalInertia(btScalar /*mass*/, btVector3& /*inertia*/) const { } - virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const + virtual void getAabb(const btTransform& /*t*/, btVector3& /*aabbMin*/, btVector3& /*aabbMax*/) const { } @@ -1584,8 +1584,8 @@ struct btSoftColliders } else { - static int count = 0; - count++; + // static int count = 0; + // count++; //printf("count=%d\n",count); } } @@ -2000,7 +2000,9 @@ struct btSoftColliders } } #endif +#ifdef REPEL_NEIGHBOR bool skip = false; +#endif for (int node_id = 0; node_id < 3; ++node_id) { btSoftBody::Node* node = f1->m_n[node_id]; @@ -2097,7 +2099,9 @@ struct btSoftColliders } } #endif +#ifdef REPEL_NEIGHBOR bool skip = false; +#endif for (int node_id = 0; node_id < 3; ++node_id) { btSoftBody::Node* node = f1->m_n[node_id]; diff --git a/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.h b/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.h index 7b2454590c..57e3e97496 100644 --- a/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.h +++ b/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.h @@ -46,7 +46,7 @@ class btSoftRigidCollisionAlgorithm : public btCollisionAlgorithm virtual btScalar calculateTimeOfImpact(btCollisionObject* body0, btCollisionObject* body1, const btDispatcherInfo& dispatchInfo, btManifoldResult* resultOut); - virtual void getAllContactManifolds(btManifoldArray& manifoldArray) + virtual void getAllContactManifolds(btManifoldArray& /*manifoldArray*/) { //we don't add any manifolds } diff --git a/src/LinearMath/TaskScheduler/btTaskScheduler.cpp b/src/LinearMath/TaskScheduler/btTaskScheduler.cpp index 5f1115c402..2ef4ca0657 100644 --- a/src/LinearMath/TaskScheduler/btTaskScheduler.cpp +++ b/src/LinearMath/TaskScheduler/btTaskScheduler.cpp @@ -114,7 +114,7 @@ class ParallelForJob : public IJob m_begin = iBegin; m_end = iEnd; } - virtual void executeJob(int threadId) BT_OVERRIDE + virtual void executeJob(int /*threadId*/) BT_OVERRIDE { BT_PROFILE("executeJob"); @@ -200,6 +200,7 @@ JobQueue m_headIndex = 0; m_tailIndex = 0; m_useSpinMutex = false; + (void)m_cachePadding; } ~JobQueue() { diff --git a/src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp b/src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp index a03f6dc570..d906fdcc45 100644 --- a/src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp +++ b/src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp @@ -136,10 +136,10 @@ btThreadSupportPosix::~btThreadSupportPosix() #define NAMED_SEMAPHORES #endif -static sem_t* createSem(const char* baseName) +static sem_t* createSem(const char* /*baseName*/) { - static int semCount = 0; #ifdef NAMED_SEMAPHORES + static int semCount = 0; /// Named semaphore begin char name[32]; snprintf(name, 32, "/%8.s-%4.d-%4.4d", baseName, getpid(), semCount++); diff --git a/src/LinearMath/btAlignedObjectArray.h b/src/LinearMath/btAlignedObjectArray.h index ac3e189eb6..ebdc91833e 100644 --- a/src/LinearMath/btAlignedObjectArray.h +++ b/src/LinearMath/btAlignedObjectArray.h @@ -134,7 +134,7 @@ class btAlignedObjectArray init(); int otherSize = otherArray.size(); - resize(otherSize); + // resize(otherSize); otherArray.copy(0, otherSize, m_data); } @@ -222,6 +222,8 @@ class btAlignedObjectArray { new (&m_data[i]) T(fillData); } +#else + (void)fillData; #endif //BT_USE_PLACEMENT_NEW } @@ -249,6 +251,8 @@ class btAlignedObjectArray m_size++; #ifdef BT_USE_PLACEMENT_NEW new (&m_data[sz]) T(fillValue); //use the in-place new (not really allocating heap memory) +#else + (void)fillValue; #endif return m_data[sz]; diff --git a/src/LinearMath/btImplicitQRSVD.h b/src/LinearMath/btImplicitQRSVD.h index aaedc964f6..011a47cfbf 100644 --- a/src/LinearMath/btImplicitQRSVD.h +++ b/src/LinearMath/btImplicitQRSVD.h @@ -473,6 +473,7 @@ inline void singularValueDecomposition( GivensRotation& V, const btScalar tol = 64 * std::numeric_limits::epsilon()) { + (void)tol; btMatrix2x2& sigma = const_cast(Sigma); sigma.setIdentity(); btMatrix2x2 S_Sym; @@ -553,6 +554,7 @@ inline void singularValueDecomposition( const btMatrix2x2& V, const btScalar tol = 64 * std::numeric_limits::epsilon()) { + (void)tol; GivensRotation gv(0, 1); GivensRotation gu(0, 1); singularValueDecomposition(A, gu, Sigma, gv); diff --git a/src/LinearMath/btMatrixX.h b/src/LinearMath/btMatrixX.h index bb0f0dd259..ae9f060d14 100644 --- a/src/LinearMath/btMatrixX.h +++ b/src/LinearMath/btMatrixX.h @@ -242,13 +242,13 @@ struct btMatrixX void copyLowerToUpperTriangle() { - int count = 0; + // int count = 0; for (int row = 0; row < rows(); row++) { for (int col = 0; col < row; col++) { setElem(col, row, (*this)(row, col)); - count++; + // count++; } } //printf("copyLowerToUpperTriangle copied %d elements out of %dx%d=%d\n", count,rows(),cols(),cols()*rows()); diff --git a/src/LinearMath/btQuickprof.cpp b/src/LinearMath/btQuickprof.cpp index 33b51eb763..2e17e7d9ad 100644 --- a/src/LinearMath/btQuickprof.cpp +++ b/src/LinearMath/btQuickprof.cpp @@ -703,7 +703,7 @@ void btLeaveProfileZoneDefault() } #else -void btEnterProfileZoneDefault(const char* name) +void btEnterProfileZoneDefault(const char* /*name*/) { } void btLeaveProfileZoneDefault() @@ -740,14 +740,14 @@ void btLeaveProfileZoneDefault() unsigned int btQuickprofGetCurrentThreadIndex2() { - const unsigned int kNullIndex = ~0U; - #if BT_THREADSAFE return btGetCurrentThreadIndex(); #else #if defined(BT_HAVE_TLS) + const unsigned int kNullIndex = ~0U; static __thread unsigned int sThreadIndex = kNullIndex; #elif defined(_WIN32) + const unsigned int kNullIndex = ~0U; __declspec(thread) static unsigned int sThreadIndex = kNullIndex; #else unsigned int sThreadIndex = 0; diff --git a/src/LinearMath/btScalar.h b/src/LinearMath/btScalar.h index 5fbccaa868..10b95d9254 100644 --- a/src/LinearMath/btScalar.h +++ b/src/LinearMath/btScalar.h @@ -150,7 +150,7 @@ inline int btIsDoublePrecision() #define btAssert assert #endif//_MSC_VER #else - #define btAssert(x) + #define btAssert(x) (void)(x) #endif //btFullAssert is optional, slows down a lot #define btFullAssert(x) @@ -178,7 +178,7 @@ inline int btIsDoublePrecision() #endif #else//BT_DEBUG - #define btAssert(x) + #define btAssert(x) (void)(x) #endif//BT_DEBUG //btFullAssert is optional, slows down a lot #define btFullAssert(x) @@ -200,7 +200,7 @@ inline int btIsDoublePrecision() #ifdef BT_DEBUG #define btAssert assert #else - #define btAssert(x) + #define btAssert(x) (void)(x) #endif //btFullAssert is optional, slows down a lot #define btFullAssert(x) @@ -267,7 +267,7 @@ inline int btIsDoublePrecision() #define btAssert assert #endif//defined (__i386__) || defined (__x86_64__) #else//defined(DEBUG) || defined (_DEBUG) - #define btAssert(x) + #define btAssert(x) (void)(x) #endif//defined(DEBUG) || defined (_DEBUG) //btFullAssert is optional, slows down a lot @@ -292,7 +292,7 @@ inline int btIsDoublePrecision() #if defined(DEBUG) || defined (_DEBUG) #define btAssert assert #else - #define btAssert(x) + #define btAssert(x) (void)(x) #endif //btFullAssert is optional, slows down a lot diff --git a/src/LinearMath/btThreads.cpp b/src/LinearMath/btThreads.cpp index 69a86799fa..68d1c55603 100644 --- a/src/LinearMath/btThreads.cpp +++ b/src/LinearMath/btThreads.cpp @@ -428,7 +428,7 @@ void btParallelFor(int iBegin, int iEnd, int grainSize, const btIParallelForBody gBtTaskScheduler->parallelFor(iBegin, iEnd, grainSize, body); #else // #if BT_THREADSAFE - + (void)grainSize; // non-parallel version of btParallelFor btAssert(!"called btParallelFor in non-threadsafe build. enable BT_THREADSAFE"); body.forLoop(iBegin, iEnd); @@ -455,7 +455,7 @@ btScalar btParallelSum(int iBegin, int iEnd, int grainSize, const btIParallelSum return gBtTaskScheduler->parallelSum(iBegin, iEnd, grainSize, body); #else // #if BT_THREADSAFE - + (void)grainSize; // non-parallel version of btParallelSum btAssert(!"called btParallelFor in non-threadsafe build. enable BT_THREADSAFE"); return body.sumLoop(iBegin, iEnd); @@ -473,13 +473,13 @@ class btTaskSchedulerSequential : public btITaskScheduler btTaskSchedulerSequential() : btITaskScheduler("Sequential") {} virtual int getMaxNumThreads() const BT_OVERRIDE { return 1; } virtual int getNumThreads() const BT_OVERRIDE { return 1; } - virtual void setNumThreads(int numThreads) BT_OVERRIDE {} - virtual void parallelFor(int iBegin, int iEnd, int grainSize, const btIParallelForBody& body) BT_OVERRIDE + virtual void setNumThreads(int /*numThreads*/) BT_OVERRIDE {} + virtual void parallelFor(int iBegin, int iEnd, int /*grainSize*/, const btIParallelForBody& body) BT_OVERRIDE { BT_PROFILE("parallelFor_sequential"); body.forLoop(iBegin, iEnd); } - virtual btScalar parallelSum(int iBegin, int iEnd, int grainSize, const btIParallelSumBody& body) BT_OVERRIDE + virtual btScalar parallelSum(int iBegin, int iEnd, int /*grainSize*/, const btIParallelSumBody& body) BT_OVERRIDE { BT_PROFILE("parallelSum_sequential"); return body.sumLoop(iBegin, iEnd); diff --git a/test/InverseDynamics/test_invdyn_kinematics.cpp b/test/InverseDynamics/test_invdyn_kinematics.cpp index 2fab4d048d..cfb0d07672 100644 --- a/test/InverseDynamics/test_invdyn_kinematics.cpp +++ b/test/InverseDynamics/test_invdyn_kinematics.cpp @@ -36,7 +36,7 @@ DiffType toDiffType(ValueType& fd, ValueType& val); // vector case: just return finite difference approximation template <> -vec3 toDiffType(vec3& fd, vec3& val) +vec3 toDiffType(vec3& fd, vec3& /*val*/) { return fd; } diff --git a/test/SharedMemory/gtestwrap.cpp b/test/SharedMemory/gtestwrap.cpp index ba315dac6c..b5680983ff 100644 --- a/test/SharedMemory/gtestwrap.cpp +++ b/test/SharedMemory/gtestwrap.cpp @@ -2,7 +2,7 @@ #include "test.c" #include "Bullet3Common/b3Logging.h" -void myprintf(const char* bla) +void myprintf(const char* /*bla*/) { } diff --git a/test/SharedMemory/test.c b/test/SharedMemory/test.c index 11360caf6a..e5bf5629dc 100644 --- a/test/SharedMemory/test.c +++ b/test/SharedMemory/test.c @@ -59,6 +59,7 @@ void testSharedMemory(b3PhysicsClientHandle sm) ret = b3PhysicsParamSetTimeStep(command, timeStep); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED); + (void)ret; } { @@ -254,6 +255,7 @@ void testSharedMemory(b3PhysicsClientHandle sm) b3RequestCameraImageSetPixelResolution(command, width, height); b3RequestCameraImageSelectRenderer(command, ER_BULLET_HARDWARE_OPENGL); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + (void)statusHandle; } if (b3CanSubmitCommand(sm)) diff --git a/test/collision/main.cpp b/test/collision/main.cpp index 5be7a91f71..fb116a1da2 100644 --- a/test/collision/main.cpp +++ b/test/collision/main.cpp @@ -35,21 +35,21 @@ subject to the following restrictions: namespace { -btVector3 MyBulletShapeSupportFunc(const void* shapeAptr, const btVector3& dir, bool includeMargin) -{ - btConvexShape* shape = (btConvexShape*)shapeAptr; - if (includeMargin) - { - return shape->localGetSupportingVertex(dir); - } - - return shape->localGetSupportingVertexWithoutMargin(dir); -} - -btVector3 MyBulletShapeCenterFunc(const void* shapeAptr) -{ - return btVector3(0, 0, 0); -} +// btVector3 MyBulletShapeSupportFunc(const void* shapeAptr, const btVector3& dir, bool includeMargin) +// { +// btConvexShape* shape = (btConvexShape*)shapeAptr; +// if (includeMargin) +// { +// return shape->localGetSupportingVertex(dir); +// } + +// return shape->localGetSupportingVertexWithoutMargin(dir); +// } + +// btVector3 MyBulletShapeCenterFunc(const void* /*shapeAptr*/) +// { +// return btVector3(0, 0, 0); +// } enum SphereSphereTestMethod { @@ -262,7 +262,7 @@ class TriangleCollector : public btTriangleCallback explicit TriangleCollector(std::vector* triangles) : triangles(triangles) {} virtual ~TriangleCollector() {} - virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex) + virtual void processTriangle(btVector3* triangle, int /*partId*/, int /*triangleIndex*/) { triangles->push_back(*triangle); } From c1bcea7b959c0a4c236b9e21608ccd941b9765ae Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 14:36:28 +0100 Subject: [PATCH 02/57] Compiler warnings - initialization order --- examples/BulletRobotics/FixJointBoxes.cpp | 6 +++--- examples/SharedMemory/Win32SharedMemory.cpp | 6 +++--- .../StandaloneMain/hellovr_opengl_main.cpp | 5 +++-- .../BroadphaseCollision/btBroadphaseProxy.h | 3 ++- .../ConstraintSolver/btJacobianEntry.h | 16 ++++++++-------- .../Featherstone/btMultiBody.cpp | 6 +++--- .../details/IDLinearMathInterface.hpp | 3 +-- .../btReducedDeformableContactConstraint.cpp | 8 ++++---- .../btDeformableContactConstraint.cpp | 18 +++++++++--------- .../btDeformableContactConstraint.h | 10 +++++----- src/LinearMath/btImplicitQRSVD.h | 2 +- src/LinearMath/btReducedVector.h | 2 +- 12 files changed, 43 insertions(+), 42 deletions(-) diff --git a/examples/BulletRobotics/FixJointBoxes.cpp b/examples/BulletRobotics/FixJointBoxes.cpp index 565ddb36f0..d71b92f500 100644 --- a/examples/BulletRobotics/FixJointBoxes.cpp +++ b/examples/BulletRobotics/FixJointBoxes.cpp @@ -31,9 +31,9 @@ class FixJointBoxes : public CommonExampleInterface FixJointBoxes(GUIHelperInterface* helper, int options) : m_guiHelper(helper), m_options(options), - numCubes(30), - cubeIds(numCubes, 0), - solver(solverId) + solver(solverId), + numCubes(30), + cubeIds(numCubes, 0) { (void)m_options; } diff --git a/examples/SharedMemory/Win32SharedMemory.cpp b/examples/SharedMemory/Win32SharedMemory.cpp index 766ce1f9bf..90a7be4c05 100644 --- a/examples/SharedMemory/Win32SharedMemory.cpp +++ b/examples/SharedMemory/Win32SharedMemory.cpp @@ -16,9 +16,9 @@ struct Win32SharedMemorySegment TCHAR m_szName[1024]; Win32SharedMemorySegment() - : m_hMapFile(0), - m_buf(0), - m_key(-1) + : m_key(-1), + m_hMapFile(0), + m_buf(0) { m_szName[0] = 0; } diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index c8a3844754..31b3d4c188 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -49,7 +49,7 @@ CommonExampleInterface *sExample; int sPrevPacketNum = 0; OpenGLGuiHelper *sGuiPtr = 0; -static vr::VRControllerState_t sPrevStates[vr::k_unMaxTrackedDeviceCount] = {0}; +static vr::VRControllerState_t sPrevStates[vr::k_unMaxTrackedDeviceCount] = {}; #if defined(POSIX) #include "unistd.h" @@ -258,7 +258,8 @@ class CMainApplication // Purpose: Constructor //----------------------------------------------------------------------------- CMainApplication::CMainApplication(int argc, char *argv[]) - : m_app(NULL), m_hasContext(false), m_nWindowWidth(1280), m_nWindowHeight(720), m_unSceneProgramID(0), m_unLensProgramID(0), m_unControllerTransformProgramID(0), m_unRenderModelProgramID(0), m_pHMD(NULL), m_pRenderModels(NULL), m_bDebugOpenGL(false), m_bVerbose(false), m_bPerf(false), m_bVblank(false), m_bGlFinishHack(true), m_glControllerVertBuffer(0), m_unControllerVAO(0), m_unLensVAO(0), m_unSceneVAO(0), m_nSceneMatrixLocation(-1), m_nControllerMatrixLocation(-1), m_nRenderModelMatrixLocation(-1), m_iTrackedControllerCount(0), m_iTrackedControllerCount_Last(-1), m_iValidPoseCount(0), m_iValidPoseCount_Last(-1), m_iSceneVolumeInit(20), m_strPoseClasses(""), m_bShowCubes(false) + : m_bDebugOpenGL(false), m_bVerbose(false), m_bPerf(false), m_bVblank(false), m_bGlFinishHack(true), m_pHMD(NULL), m_pRenderModels(NULL), m_app(NULL), m_nWindowWidth(1280), m_nWindowHeight(720), m_hasContext(false), + m_iTrackedControllerCount(0), m_iTrackedControllerCount_Last(-1), m_iValidPoseCount(0), m_iValidPoseCount_Last(-1), m_bShowCubes(false),m_strPoseClasses(""), m_iSceneVolumeInit(20), m_unSceneVAO(0), m_unLensVAO(0), m_glControllerVertBuffer(0), m_unControllerVAO(0), m_unSceneProgramID(0), m_unLensProgramID(0), m_unControllerTransformProgramID(0), m_unRenderModelProgramID(0), m_nSceneMatrixLocation(-1), m_nControllerMatrixLocation(-1), m_nRenderModelMatrixLocation(-1) { (void)m_bPerf; diff --git a/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h b/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h index fb23281aad..5d8304a207 100644 --- a/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h +++ b/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h @@ -114,7 +114,7 @@ btBroadphaseProxy } //used for memory pools - btBroadphaseProxy() : m_clientObject(0) + btBroadphaseProxy() : m_clientObject(0), m_collisionFilterGroup(0), m_collisionFilterMask(0), m_uniqueId(0) { } @@ -122,6 +122,7 @@ btBroadphaseProxy : m_clientObject(userPtr), m_collisionFilterGroup(collisionFilterGroup), m_collisionFilterMask(collisionFilterMask), + m_uniqueId(0), m_aabbMin(aabbMin), m_aabbMax(aabbMax) { diff --git a/src/BulletDynamics/ConstraintSolver/btJacobianEntry.h b/src/BulletDynamics/ConstraintSolver/btJacobianEntry.h index a251073ead..b4165855e8 100644 --- a/src/BulletDynamics/ConstraintSolver/btJacobianEntry.h +++ b/src/BulletDynamics/ConstraintSolver/btJacobianEntry.h @@ -58,10 +58,8 @@ btJacobianEntry const btMatrix3x3& world2B, const btVector3& inertiaInvA, const btVector3& inertiaInvB) - : m_linearJointAxis(btVector3(btScalar(0.), btScalar(0.), btScalar(0.))) + : m_linearJointAxis(btVector3(btScalar(0.), btScalar(0.), btScalar(0.))), m_aJ(world2A * jointAxis), m_bJ(world2B * -jointAxis) { - m_aJ = world2A * jointAxis; - m_bJ = world2B * -jointAxis; m_0MinvJt = inertiaInvA * m_aJ; m_1MinvJt = inertiaInvB * m_bJ; m_Adiag = m_0MinvJt.dot(m_aJ) + m_1MinvJt.dot(m_bJ); @@ -90,12 +88,14 @@ btJacobianEntry const btVector3& jointAxis, const btVector3& inertiaInvA, const btScalar massInvA) - : m_linearJointAxis(jointAxis) + : m_linearJointAxis(jointAxis), + m_aJ(world2A * (rel_pos1.cross(jointAxis))), + m_bJ(world2A * (rel_pos2.cross(-jointAxis))), + m_0MinvJt(inertiaInvA * m_aJ), + m_1MinvJt(btVector3(btScalar(0.), + btScalar(0.), + btScalar(0.))) { - m_aJ = world2A * (rel_pos1.cross(jointAxis)); - m_bJ = world2A * (rel_pos2.cross(-jointAxis)); - m_0MinvJt = inertiaInvA * m_aJ; - m_1MinvJt = btVector3(btScalar(0.), btScalar(0.), btScalar(0.)); m_Adiag = massInvA + m_0MinvJt.dot(m_aJ); btAssert(m_Adiag > btScalar(0.0)); diff --git a/src/BulletDynamics/Featherstone/btMultiBody.cpp b/src/BulletDynamics/Featherstone/btMultiBody.cpp index 5ac73abe0d..ba0f0ea2a8 100644 --- a/src/BulletDynamics/Featherstone/btMultiBody.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBody.cpp @@ -99,9 +99,9 @@ btMultiBody::btMultiBody(int n_links, : m_baseCollider(0), m_baseName(0), m_basePos(0, 0, 0), - m_baseQuat(0, 0, 0, 1), - m_basePos_interpolate(0, 0, 0), - m_baseQuat_interpolate(0, 0, 0, 1), + m_basePos_interpolate(0, 0, 0), + m_baseQuat(0, 0, 0, 1), + m_baseQuat_interpolate(0, 0, 0, 1), m_baseMass(mass), m_baseInertia(inertia), diff --git a/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp b/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp index f8793629c4..9e4eb1515e 100644 --- a/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp +++ b/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp @@ -131,9 +131,8 @@ class mat3x : public matxx { public: mat3x() {} - mat3x(const mat3x& rhs) + mat3x(const mat3x& rhs) : matxx(rhs.rows(), rhs.cols()) { - matxx::resize(rhs.rows(), rhs.cols()); *this = rhs; } mat3x(int /*rows*/, int cols) : matxx(3, cols) diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp index 2835be26c9..e94ff4c3b1 100644 --- a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp @@ -10,7 +10,7 @@ btReducedDeformableStaticConstraint::btReducedDeformableStaticConstraint( const btVector3& dir, const btContactSolverInfo& infoGlobal, btScalar dt) - : m_rsb(rsb), m_ri(ri), m_targetPos(x0), m_impulseDirection(dir), m_dt(dt), btDeformableStaticConstraint(node, infoGlobal) + : btDeformableStaticConstraint(node, infoGlobal), m_rsb(rsb), m_dt(dt), m_ri(ri), m_targetPos(x0), m_impulseDirection(dir) { m_erp = 0.2; m_appliedImpulse = 0; @@ -61,7 +61,7 @@ btReducedDeformableRigidContactConstraint::btReducedDeformableRigidContactConstr const btSoftBody::DeformableRigidContact& c, const btContactSolverInfo& infoGlobal, btScalar dt) - : m_rsb(rsb), m_dt(dt), btDeformableRigidContactConstraint(c, infoGlobal) + : btDeformableRigidContactConstraint(c, infoGlobal), m_rsb(rsb), m_dt(dt) { m_nodeQueryIndex = 0; m_appliedNormalImpulse = 0; @@ -323,7 +323,7 @@ btReducedDeformableNodeRigidContactConstraint::btReducedDeformableNodeRigidConta const btSoftBody::DeformableNodeRigidContact& contact, const btContactSolverInfo& infoGlobal, btScalar dt) - : m_node(contact.m_node), btReducedDeformableRigidContactConstraint(rsb, contact, infoGlobal, dt) + : btReducedDeformableRigidContactConstraint(rsb, contact, infoGlobal, dt), m_node(contact.m_node) { m_contactNormalA = contact.m_cti.m_normal; m_contactNormalB = -contact.m_cti.m_normal; @@ -540,7 +540,7 @@ btReducedDeformableFaceRigidContactConstraint::btReducedDeformableFaceRigidConta const btContactSolverInfo& infoGlobal, btScalar dt, bool useStrainLimiting) - : m_face(contact.m_face), m_useStrainLimiting(useStrainLimiting), btReducedDeformableRigidContactConstraint(rsb, contact, infoGlobal, dt) + : btReducedDeformableRigidContactConstraint(rsb, contact, infoGlobal, dt), m_face(contact.m_face), m_useStrainLimiting(useStrainLimiting) {} btVector3 btReducedDeformableFaceRigidContactConstraint::getVb() const diff --git a/src/BulletSoftBody/btDeformableContactConstraint.cpp b/src/BulletSoftBody/btDeformableContactConstraint.cpp index cb71f0af45..81b5870954 100644 --- a/src/BulletSoftBody/btDeformableContactConstraint.cpp +++ b/src/BulletSoftBody/btDeformableContactConstraint.cpp @@ -16,12 +16,12 @@ #include "btDeformableContactConstraint.h" /* ================ Deformable Node Anchor =================== */ btDeformableNodeAnchorConstraint::btDeformableNodeAnchorConstraint(const btSoftBody::DeformableNodeRigidAnchor& a, const btContactSolverInfo& infoGlobal) - : m_anchor(&a), btDeformableContactConstraint(a.m_cti.m_normal, infoGlobal) + : btDeformableContactConstraint(a.m_cti.m_normal, infoGlobal), m_anchor(&a) { } btDeformableNodeAnchorConstraint::btDeformableNodeAnchorConstraint(const btDeformableNodeAnchorConstraint& other) - : m_anchor(other.m_anchor), btDeformableContactConstraint(other) + : btDeformableContactConstraint(other), m_anchor(other.m_anchor) { } @@ -133,7 +133,7 @@ void btDeformableNodeAnchorConstraint::applyImpulse(const btVector3& impulse) /* ================ Deformable vs. Rigid =================== */ btDeformableRigidContactConstraint::btDeformableRigidContactConstraint(const btSoftBody::DeformableRigidContact& c, const btContactSolverInfo& infoGlobal) - : m_contact(&c), btDeformableContactConstraint(c.m_cti.m_normal, infoGlobal) + : btDeformableContactConstraint(c.m_cti.m_normal, infoGlobal), m_contact(&c) { m_total_normal_dv.setZero(); m_total_tangent_dv.setZero(); @@ -144,7 +144,7 @@ btDeformableRigidContactConstraint::btDeformableRigidContactConstraint(const btS } btDeformableRigidContactConstraint::btDeformableRigidContactConstraint(const btDeformableRigidContactConstraint& other) - : m_contact(other.m_contact), btDeformableContactConstraint(other), m_penetration(other.m_penetration), m_total_split_impulse(other.m_total_split_impulse), m_binding(other.m_binding) + : btDeformableContactConstraint(other), m_penetration(other.m_penetration), m_total_split_impulse(other.m_total_split_impulse), m_binding(other.m_binding), m_contact(other.m_contact) { m_total_normal_dv = other.m_total_normal_dv; m_total_tangent_dv = other.m_total_tangent_dv; @@ -409,12 +409,12 @@ btScalar btDeformableRigidContactConstraint::solveSplitImpulse(const btContactSo } /* ================ Node vs. Rigid =================== */ btDeformableNodeRigidContactConstraint::btDeformableNodeRigidContactConstraint(const btSoftBody::DeformableNodeRigidContact& contact, const btContactSolverInfo& infoGlobal) - : m_node(contact.m_node), btDeformableRigidContactConstraint(contact, infoGlobal) + : btDeformableRigidContactConstraint(contact, infoGlobal), m_node(contact.m_node) { } btDeformableNodeRigidContactConstraint::btDeformableNodeRigidContactConstraint(const btDeformableNodeRigidContactConstraint& other) - : m_node(other.m_node), btDeformableRigidContactConstraint(other) + : btDeformableRigidContactConstraint(other), m_node(other.m_node) { } @@ -449,12 +449,12 @@ void btDeformableNodeRigidContactConstraint::applySplitImpulse(const btVector3& /* ================ Face vs. Rigid =================== */ btDeformableFaceRigidContactConstraint::btDeformableFaceRigidContactConstraint(const btSoftBody::DeformableFaceRigidContact& contact, const btContactSolverInfo& infoGlobal, bool useStrainLimiting) - : m_face(contact.m_face), m_useStrainLimiting(useStrainLimiting), btDeformableRigidContactConstraint(contact, infoGlobal) + : btDeformableRigidContactConstraint(contact, infoGlobal), m_face(contact.m_face), m_useStrainLimiting(useStrainLimiting) { } btDeformableFaceRigidContactConstraint::btDeformableFaceRigidContactConstraint(const btDeformableFaceRigidContactConstraint& other) - : m_face(other.m_face), m_useStrainLimiting(other.m_useStrainLimiting), btDeformableRigidContactConstraint(other) + : btDeformableRigidContactConstraint(other), m_face(other.m_face), m_useStrainLimiting(other.m_useStrainLimiting) { } @@ -594,7 +594,7 @@ void btDeformableFaceRigidContactConstraint::applySplitImpulse(const btVector3& /* ================ Face vs. Node =================== */ btDeformableFaceNodeContactConstraint::btDeformableFaceNodeContactConstraint(const btSoftBody::DeformableFaceNodeContact& contact, const btContactSolverInfo& infoGlobal) - : m_node(contact.m_node), m_face(contact.m_face), m_contact(&contact), btDeformableContactConstraint(contact.m_normal, infoGlobal) + : btDeformableContactConstraint(contact.m_normal, infoGlobal), m_node(contact.m_node), m_face(contact.m_face), m_contact(&contact) { m_total_normal_dv.setZero(); m_total_tangent_dv.setZero(); diff --git a/src/BulletSoftBody/btDeformableContactConstraint.h b/src/BulletSoftBody/btDeformableContactConstraint.h index ceae9c2fe8..d7c9a1ba62 100644 --- a/src/BulletSoftBody/btDeformableContactConstraint.h +++ b/src/BulletSoftBody/btDeformableContactConstraint.h @@ -29,18 +29,18 @@ class btDeformableContactConstraint // normal of the contact btVector3 m_normal; - btDeformableContactConstraint(const btVector3& normal, const btContactSolverInfo& infoGlobal) : m_static(false), m_normal(normal), m_infoGlobal(&infoGlobal) + btDeformableContactConstraint(const btVector3& normal, const btContactSolverInfo& infoGlobal) : m_static(false), m_infoGlobal(&infoGlobal), m_normal(normal) { } - btDeformableContactConstraint(bool isStatic, const btVector3& normal, const btContactSolverInfo& infoGlobal) : m_static(isStatic), m_normal(normal), m_infoGlobal(&infoGlobal) + btDeformableContactConstraint(bool isStatic, const btVector3& normal, const btContactSolverInfo& infoGlobal) : m_static(isStatic), m_infoGlobal(&infoGlobal), m_normal(normal) { } btDeformableContactConstraint() : m_static(false) {} btDeformableContactConstraint(const btDeformableContactConstraint& other) - : m_static(other.m_static), m_normal(other.m_normal), m_infoGlobal(other.m_infoGlobal) + : m_static(other.m_static), m_infoGlobal(other.m_infoGlobal), m_normal(other.m_normal) { } @@ -73,12 +73,12 @@ class btDeformableStaticConstraint : public btDeformableContactConstraint public: btSoftBody::Node* m_node; - btDeformableStaticConstraint(btSoftBody::Node* node, const btContactSolverInfo& infoGlobal) : m_node(node), btDeformableContactConstraint(false, btVector3(0, 0, 0), infoGlobal) + btDeformableStaticConstraint(btSoftBody::Node* node, const btContactSolverInfo& infoGlobal) : btDeformableContactConstraint(false, btVector3(0, 0, 0), infoGlobal), m_node(node) { } btDeformableStaticConstraint() {} btDeformableStaticConstraint(const btDeformableStaticConstraint& other) - : m_node(other.m_node), btDeformableContactConstraint(other) + : btDeformableContactConstraint(other), m_node(other.m_node) { } diff --git a/src/LinearMath/btImplicitQRSVD.h b/src/LinearMath/btImplicitQRSVD.h index 011a47cfbf..48e24cf515 100644 --- a/src/LinearMath/btImplicitQRSVD.h +++ b/src/LinearMath/btImplicitQRSVD.h @@ -47,7 +47,7 @@ class btMatrix2x2 { public: btScalar m_00, m_01, m_10, m_11; - btMatrix2x2(): m_00(0), m_10(0), m_01(0), m_11(0) + btMatrix2x2(): m_00(0), m_01(0), m_10(0), m_11(0) { } btMatrix2x2(const btMatrix2x2& other): m_00(other.m_00),m_01(other.m_01),m_10(other.m_10),m_11(other.m_11) diff --git a/src/LinearMath/btReducedVector.h b/src/LinearMath/btReducedVector.h index 313a4271f0..c1cd08ebf2 100644 --- a/src/LinearMath/btReducedVector.h +++ b/src/LinearMath/btReducedVector.h @@ -46,7 +46,7 @@ class btReducedVector m_vecs.clear(); } - btReducedVector(int sz, const btAlignedObjectArray& indices, const btAlignedObjectArray& vecs): m_sz(sz), m_indices(indices), m_vecs(vecs) + btReducedVector(int sz, const btAlignedObjectArray& indices, const btAlignedObjectArray& vecs): m_indices(indices), m_vecs(vecs), m_sz(sz) { } From ce7b0feac2e5969546bfb8b529324dd3e709aa9e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 14:36:55 +0100 Subject: [PATCH 03/57] Compiler warnings - type conversion --- .../BulletFileLoader/btBulletFile.cpp | 2 +- .../BulletWorldImporter/btWorldImporter.cpp | 4 ++-- Extras/VHACD/src/vhacdMesh.cpp | 4 ++-- examples/BulletRobotics/FixJointBoxes.cpp | 4 ++-- examples/Evolution/NN3DWalkersTimeWarpBase.h | 4 ++-- examples/ExampleBrowser/main.cpp | 2 +- .../ImportMeshUtility/b3ImportMeshUtility.cpp | 2 +- .../Wavefront2GLInstanceGraphicsShape.cpp | 6 ++--- .../ImportURDFDemo/BulletUrdfImporter.cpp | 2 +- .../InverseDynamicsExample.cpp | 4 ++-- .../OpenGLWindow/GLInstancingRenderer.cpp | 10 ++++----- examples/OpenGLWindow/SimpleOpenGL3App.cpp | 4 ++-- .../SharedMemory/GraphicsServerExample.cpp | 2 +- examples/SharedMemory/PhysicsClientC_API.cpp | 5 ++--- examples/SharedMemory/PhysicsClientUDP.cpp | 6 ++--- .../PhysicsServerCommandProcessor.cpp | 22 +++++++++---------- .../SharedMemory/PhysicsServerExample.cpp | 2 +- examples/SharedMemory/main.cpp | 2 +- .../StandaloneMain/hellovr_opengl_main.cpp | 2 +- .../ThirdPartyLibs/stb_image/stb_image.cpp | 2 +- examples/Utils/ChromeTraceUtil.cpp | 6 ++--- examples/Utils/RobotLoggingUtil.cpp | 8 +++---- .../b3GpuGridBroadphase.cpp | 4 ++-- .../b3GpuSapBroadphase.cpp | 8 +++---- .../Initialize/b3OpenCLUtils.cpp | 4 ++-- .../b3ConvexHullContact.cpp | 2 +- .../ParallelPrimitives/b3BoundSearchCL.cpp | 8 +++---- .../ParallelPrimitives/b3PrefixScanCL.cpp | 2 +- .../b3PrefixScanFloat4CL.cpp | 2 +- src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp | 2 +- .../CollisionShapes/btMiniSDF.cpp | 8 +++---- .../btMultiBodyInplaceSolverIslandCallback.h | 2 +- .../btReducedDeformableBodyHelpers.cpp | 8 +++---- .../btDeformableBackwardEulerObjective.h | 3 ++- src/BulletSoftBody/btSoftBody.cpp | 2 +- src/BulletSoftBody/btSoftBody.h | 8 +++---- src/BulletSoftBody/btSoftBodyHelpers.cpp | 6 ++--- test/InverseDynamics/test_invdyn_bullet.cpp | 2 +- .../test_invdyn_kinematics.cpp | 8 +++---- 39 files changed, 92 insertions(+), 92 deletions(-) diff --git a/Extras/Serialize/BulletFileLoader/btBulletFile.cpp b/Extras/Serialize/BulletFileLoader/btBulletFile.cpp index 2b931438cc..01baa427c9 100644 --- a/Extras/Serialize/BulletFileLoader/btBulletFile.cpp +++ b/Extras/Serialize/BulletFileLoader/btBulletFile.cpp @@ -117,7 +117,7 @@ void btBulletFile::parseData() remain -= 12; //invalid/empty file? - if (remain < sizeof(bChunkInd)) + if (remain < (int)sizeof(bChunkInd)) return; char* dataPtr = mFileBuffer + mDataStart; diff --git a/Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp b/Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp index b531de443c..0213ebd7b4 100644 --- a/Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp +++ b/Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp @@ -986,7 +986,7 @@ void btWorldImporter::convertConstraintFloat(btTypedConstraintFloatData* constra dof->setStiffness(i + 3, dofData->m_angularSpringStiffness.m_floats[i], (dofData->m_angularSpringStiffnessLimited[i] != 0)); dof->setEquilibriumPoint(i + 3, dofData->m_angularEquilibriumPoint.m_floats[i]); dof->enableSpring(i + 3, dofData->m_angularEnableSpring[i] != 0); - dof->setDamping(i + 3, dofData->m_angularSpringDamping.m_floats[i], dofData->m_angularSpringDampingLimited[i]); + dof->setDamping(i + 3, dofData->m_angularSpringDamping.m_floats[i], dofData->m_angularSpringDampingLimited[i] != 0); } } } @@ -1304,7 +1304,7 @@ void btWorldImporter::convertConstraintDouble(btTypedConstraintDoubleData* const //6-dof: 3 linear followed by 3 angular for (i = 0; i < 3; i++) { - dof->setStiffness(i, dofData->m_linearSpringStiffness.m_floats[i], dofData->m_linearSpringStiffnessLimited[i]); + dof->setStiffness(i, dofData->m_linearSpringStiffness.m_floats[i], dofData->m_linearSpringStiffnessLimited[i] != 0); dof->setEquilibriumPoint(i, dofData->m_linearEquilibriumPoint.m_floats[i]); dof->enableSpring(i, dofData->m_linearEnableSpring[i] != 0); dof->setDamping(i, dofData->m_linearSpringDamping.m_floats[i], (dofData->m_linearSpringDampingLimited[i] != 0)); diff --git a/Extras/VHACD/src/vhacdMesh.cpp b/Extras/VHACD/src/vhacdMesh.cpp index 113b5c4fdd..90833ac570 100644 --- a/Extras/VHACD/src/vhacdMesh.cpp +++ b/Extras/VHACD/src/vhacdMesh.cpp @@ -50,7 +50,7 @@ double Mesh::ComputeVolume() const Vec3 ver0, ver1, ver2; double totalVolume = 0.0; - for (int t = 0; t < nT; t++) + for (unsigned int t = 0; t < nT; t++) { const Vec3& tri = GetTriangle(t); ver0 = GetPoint(tri[0]); @@ -128,7 +128,7 @@ bool Mesh::IsInside(const Vec3& pt) const } Vec3 ver0, ver1, ver2; double volume; - for (int t = 0; t < nT; t++) + for (unsigned int t = 0; t < nT; t++) { const Vec3& tri = GetTriangle(t); ver0 = GetPoint(tri[0]); diff --git a/examples/BulletRobotics/FixJointBoxes.cpp b/examples/BulletRobotics/FixJointBoxes.cpp index d71b92f500..fae2c8cde0 100644 --- a/examples/BulletRobotics/FixJointBoxes.cpp +++ b/examples/BulletRobotics/FixJointBoxes.cpp @@ -62,7 +62,7 @@ class FixJointBoxes : public CommonExampleInterface b3RobotSimulatorLoadUrdfFileArgs args; b3RobotSimulatorChangeDynamicsArgs dynamicsArgs; - for (int i = 0; i < numCubes; i++) + for (unsigned int i = 0; i < numCubes; i++) { args.m_forceOverrideFixedBase = (i == 0); args.m_startPosition.setValue(0, i * 0.05, 1); @@ -110,7 +110,7 @@ class FixJointBoxes : public CommonExampleInterface void resetCubePosition() { - for (int i = 0; i < numCubes; i++) + for (unsigned int i = 0; i < numCubes; i++) { btVector3 pos(0, i * (btScalar)0.05, 1); btQuaternion quar(0, 0, 0, 1); diff --git a/examples/Evolution/NN3DWalkersTimeWarpBase.h b/examples/Evolution/NN3DWalkersTimeWarpBase.h index 55d2c7da95..20665c5b39 100644 --- a/examples/Evolution/NN3DWalkersTimeWarpBase.h +++ b/examples/Evolution/NN3DWalkersTimeWarpBase.h @@ -829,7 +829,7 @@ struct NN3DWalkersTimeWarpBase : public CommonRigidBodyBase mPhysicsStepStart = mLoopTimer.getTimeMilliseconds(); /**!< The physics updates start (in Milliseconds)*/ mPhysicsStepEnd = mPhysicsStepStart; - while (mPhysicsTick > mPhysicsStepEnd - mPhysicsStepStart) + while (mPhysicsTick > (long)(mPhysicsStepEnd - mPhysicsStepStart)) { /**!< Update the physics until we run out of time (in Milliseconds) */ // b3Printf("Physics passed: %u", mPhysicsStepEnd - mPhysicsStepStart); double timeStep = fixedPhysicsStepSizeSec; /**!< update the world (in Seconds) */ @@ -850,7 +850,7 @@ struct NN3DWalkersTimeWarpBase : public CommonRigidBodyBase void performSpeedStep() { // force-perform the number of steps needed to achieve a certain speed (safe to too high speeds, meaning the application will lose time, not the physics) - if (mFrameTime > gApplicationTick) + if ((int)mFrameTime > gApplicationTick) { /** cap frametime to make the application lose time, not the physics (in Milliseconds) */ mFrameTime = gApplicationTick; // This prevents the physics time accumulator to sum up too much time } // The simulation therefore gets slower, but still performs all requested physics steps diff --git a/examples/ExampleBrowser/main.cpp b/examples/ExampleBrowser/main.cpp index f306c3f029..3a2e8bc055 100644 --- a/examples/ExampleBrowser/main.cpp +++ b/examples/ExampleBrowser/main.cpp @@ -53,7 +53,7 @@ int main(int argc, char* argv[]) memset(&action, 0x0, sizeof(action)); action.sa_handler = cleanup; static const int signos[] = {SIGHUP, SIGINT, SIGQUIT, SIGABRT, SIGSEGV, SIGPIPE, SIGTERM}; - for (int ii(0); ii < sizeof(signos) / sizeof(*signos); ++ii) + for (int ii(0); ii < (int)(sizeof(signos) / sizeof(*signos)); ++ii) { if (0 != sigaction(signos[ii], &action, NULL)) { diff --git a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp index 954f0bb06e..1764bca10a 100644 --- a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp +++ b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp @@ -77,7 +77,7 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string& B3_PROFILE("Load Texture"); //int textureIndex = -1; //try to load some texture - for (int i = 0; meshData.m_textureImage1 == 0 && i < shapes.size(); i++) + for (unsigned int i = 0; meshData.m_textureImage1 == 0 && i < shapes.size(); i++) { const bt_tinyobj::shape_t& shape = shapes[i]; meshData.m_rgbaColor[0] = shape.material.diffuse[0]; diff --git a/examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp b/examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp index aa3a23817b..5f028f0211 100644 --- a/examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp +++ b/examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp @@ -46,7 +46,7 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(const bt_tinyobj { int uv0Index = 2 * v_0.texcoord_index; int uv1Index = 2 * v_0.texcoord_index + 1; - if (uv0Index >= 0 && uv1Index >= 0 && (uv0Index < int(attribute.texcoords.size()) && (uv1Index < attribute.texcoords.size()))) + if (uv0Index >= 0 && uv1Index >= 0 && (uv0Index < int(attribute.texcoords.size()) && (uv1Index < (int)attribute.texcoords.size()))) { vtx0.uv[0] = attribute.texcoords[uv0Index]; vtx0.uv[1] = attribute.texcoords[uv1Index]; @@ -75,7 +75,7 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(const bt_tinyobj { int uv0Index = 2 * v_1.texcoord_index; int uv1Index = 2 * v_1.texcoord_index + 1; - if (uv0Index >= 0 && uv1Index >= 0 && (uv0Index < attribute.texcoords.size()) && (uv1Index < attribute.texcoords.size())) + if (uv0Index >= 0 && uv1Index >= 0 && (uv0Index < (int)attribute.texcoords.size()) && (uv1Index < (int)attribute.texcoords.size())) { vtx1.uv[0] = attribute.texcoords[uv0Index]; vtx1.uv[1] = attribute.texcoords[uv1Index]; @@ -104,7 +104,7 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(const bt_tinyobj int uv0Index = 2 * v_2.texcoord_index; int uv1Index = 2 * v_2.texcoord_index + 1; - if (uv0Index >= 0 && uv1Index >= 0 && (uv0Index < attribute.texcoords.size()) && (uv1Index < attribute.texcoords.size())) + if (uv0Index >= 0 && uv1Index >= 0 && (uv0Index < (int)attribute.texcoords.size()) && (uv1Index < (int)attribute.texcoords.size())) { vtx2.uv[0] = attribute.texcoords[uv0Index]; vtx2.uv[1] = attribute.texcoords[uv1Index]; diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index 5155f2f5b5..65d1c2fe03 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -193,7 +193,7 @@ bool BulletURDFImporter::loadURDF(const char* fileName, bool forceFixedBase) if (xml_string.length()) { - result = m_data->m_urdfParser.loadUrdf(xml_string.c_str(), &loggie, forceFixedBase, (m_data->m_flags & CUF_PARSE_SENSORS)); + result = m_data->m_urdfParser.loadUrdf(xml_string.c_str(), &loggie, forceFixedBase, (m_data->m_flags & CUF_PARSE_SENSORS) != 0); if (m_data->m_flags & CUF_IGNORE_VISUAL_SHAPES) { diff --git a/examples/InverseDynamics/InverseDynamicsExample.cpp b/examples/InverseDynamics/InverseDynamicsExample.cpp index d94b9e2b44..95ad3dbf7f 100644 --- a/examples/InverseDynamics/InverseDynamicsExample.cpp +++ b/examples/InverseDynamics/InverseDynamicsExample.cpp @@ -224,13 +224,13 @@ void InverseDynamicsExample::initPhysics() { qd[dof] = 0; char tmp[25]; - sprintf(tmp, "q_desired[%lu]", dof); + sprintf(tmp, "q_desired[%zu]", dof); qd_name[dof] = tmp; SliderParams slider(qd_name[dof].c_str(), &qd[dof]); slider.m_minVal = -3.14; slider.m_maxVal = 3.14; - sprintf(tmp, "q[%lu]", dof); + sprintf(tmp, "q[%lu]", (unsigned long)dof); q_name[dof] = tmp; m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); btVector4 color = sJointCurveColors[dof & 7]; diff --git a/examples/OpenGLWindow/GLInstancingRenderer.cpp b/examples/OpenGLWindow/GLInstancingRenderer.cpp index a9c20b3875..910e3d73f1 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.cpp +++ b/examples/OpenGLWindow/GLInstancingRenderer.cpp @@ -162,9 +162,9 @@ struct b3GraphicsInstance int m_flags; //transparency etc b3GraphicsInstance() - : m_cube_vao(-1), - m_index_vbo(-1), - m_textureIndex(-1), + : m_cube_vao((GLuint)-1), + m_index_vbo((GLuint)-1), + m_textureIndex((GLuint)-1), m_numIndices(-1), m_numVertices(-1), m_numGraphicsInstances(0), @@ -1070,11 +1070,11 @@ void GLInstancingRenderer::replaceTexture(int shapeIndex, int textureId) b3GraphicsInstance* gfxObj = m_graphicsInstances[shapeIndex]; if (textureId >= 0 && textureId < m_data->m_textureHandles.size()) { - gfxObj->m_textureIndex = textureId; + gfxObj->m_textureIndex = (GLuint)textureId; gfxObj->m_flags |= B3_INSTANCE_TEXTURE; } else { - gfxObj->m_textureIndex = -1; + gfxObj->m_textureIndex = (GLuint)-1; gfxObj->m_flags &= ~B3_INSTANCE_TEXTURE; } } diff --git a/examples/OpenGLWindow/SimpleOpenGL3App.cpp b/examples/OpenGLWindow/SimpleOpenGL3App.cpp index 39a880fe05..fe0a3017bb 100644 --- a/examples/OpenGLWindow/SimpleOpenGL3App.cpp +++ b/examples/OpenGLWindow/SimpleOpenGL3App.cpp @@ -1002,8 +1002,8 @@ void SimpleOpenGL3App::getScreenPixels(unsigned char* rgbaBuffer, int bufferSize glstat = glGetError(); b3Assert(glstat == GL_NO_ERROR); } - b3Assert((width * height * sizeof(float)) == depthBufferSizeInBytes); - if ((width * height * sizeof(float)) == depthBufferSizeInBytes) + b3Assert((int)(width * height * sizeof(float)) == depthBufferSizeInBytes); + if ((int)(width * height * sizeof(float)) == depthBufferSizeInBytes) { glReadPixels(0, 0, width, height, GL_DEPTH_COMPONENT, GL_FLOAT, depthBuffer); int glstat; diff --git a/examples/SharedMemory/GraphicsServerExample.cpp b/examples/SharedMemory/GraphicsServerExample.cpp index 0ce0832787..539508c689 100644 --- a/examples/SharedMemory/GraphicsServerExample.cpp +++ b/examples/SharedMemory/GraphicsServerExample.cpp @@ -58,7 +58,7 @@ void submitStatus(CActiveSocket* pClient, GraphicsSharedMemoryStatus& serverStat MySerializeInt(sz, &packetData[curPos]); curPos += 4; - for (int i = 0; i < sizeof(GraphicsSharedMemoryStatus); i++) + for (int i = 0; i < (int)sizeof(GraphicsSharedMemoryStatus); i++) { packetData[i + curPos] = statBytes[i]; } diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index e4642969ed..ca68efb43e 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -1835,9 +1835,8 @@ B3_SHARED_API int b3CreateCollisionShapeAddConvexMesh(b3PhysicsClientHandle phys int shapeIndex = command->m_createUserShapeArgs.m_numUserShapes; if (shapeIndex < MAX_COMPOUND_COLLISION_SHAPES && numVertices >= 0) { - int i=0; - if (numVertices>B3_MAX_NUM_VERTICES) - numVertices=B3_MAX_NUM_VERTICES; + if (numVertices>(int)B3_MAX_NUM_VERTICES) + numVertices=(int)B3_MAX_NUM_VERTICES; command->m_createUserShapeArgs.m_shapes[shapeIndex].m_type = GEOM_MESH; command->m_createUserShapeArgs.m_shapes[shapeIndex].m_collisionFlags = 0; command->m_createUserShapeArgs.m_shapes[shapeIndex].m_visualFlags = 0; diff --git a/examples/SharedMemory/PhysicsClientUDP.cpp b/examples/SharedMemory/PhysicsClientUDP.cpp index 7a67f5a7bc..886e61b893 100644 --- a/examples/SharedMemory/PhysicsClientUDP.cpp +++ b/examples/SharedMemory/PhysicsClientUDP.cpp @@ -166,7 +166,7 @@ struct UdpNetworkedInternalData printf( "A packet of length %lu containing '%s' was " "received from %s on channel %u.\n", - m_event.packet->dataLength, + (unsigned long)m_event.packet->dataLength, (char*)m_event.packet->data, (char*)m_event.peer->data, m_event.channelID); @@ -222,7 +222,7 @@ struct UdpNetworkedInternalData printf( "A packet of length %lu containing '%s' was " "received from %s on channel %u.\n", - m_event.packet->dataLength, + (unsigned long)m_event.packet->dataLength, (char*)m_event.packet->data, (char*)m_event.peer->data, m_event.channelID); @@ -230,7 +230,7 @@ struct UdpNetworkedInternalData int packetSizeInBytes = b3DeserializeInt(m_event.packet->data); - if (packetSizeInBytes == m_event.packet->dataLength) + if (packetSizeInBytes == (int)m_event.packet->dataLength) { SharedMemoryStatus* statPtr = (SharedMemoryStatus*)&m_event.packet->data[4]; if (statPtr->m_type == CMD_STEP_FORWARD_SIMULATION_COMPLETED) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 7b5068b5b3..dcecb886eb 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -832,7 +832,7 @@ struct MyOverlapFilterCallback : public btOverlapFilterCallback return collisionInterface->needsBroadphaseCollision(objectUniqueIdA, linkIndexA, collisionFilterGroupA, collisionFilterMaskA, - objectUniqueIdB, linkIndexB, collisionFilterGroupB, collisionFilterMaskB, m_filterMode); + objectUniqueIdB, linkIndexB, collisionFilterGroupB, collisionFilterMaskB, m_filterMode) != 0; } else { @@ -3668,7 +3668,7 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto if (!(u2b.getDeformableModel().m_visualFileName.empty())) { bool use_self_collision = false; - use_self_collision = (flags & CUF_USE_SELF_COLLISION); + use_self_collision = (flags & CUF_USE_SELF_COLLISION) != 0; bool ok = processDeformable(u2b.getDeformableModel(), pos, orn, bodyUniqueIdPtr, bufferServerToClient, bufferSizeInBytes, globalScaling, use_self_collision); if (ok) { @@ -4736,10 +4736,10 @@ static unsigned char* MyGetRawHeightfieldData(CommonFileIOInterface& fileIO, PHY rows = 0; std::string line(lineChar); int pos = 0; - while (pos < line.length()) + while (pos < (int)line.length()) { int nextPos = pos + 1; - while (nextPos < line.length()) + while (nextPos < (int)line.length()) { if (line[nextPos - 1] == ',') { @@ -5681,7 +5681,7 @@ bool PhysicsServerCommandProcessor::processRequestMeshDataCommand(const struct S { separateRenderMesh = (psb->m_renderNodes.size() != 0); } - bool requestVelocity = clientCmd.m_updateFlags & B3_MESH_DATA_SIMULATION_MESH_VELOCITY; + bool requestVelocity = (clientCmd.m_updateFlags & B3_MESH_DATA_SIMULATION_MESH_VELOCITY) != 0; int numVertices = separateRenderMesh ? psb->m_renderNodes.size() : psb->m_nodes.size(); @@ -6983,7 +6983,7 @@ bool PhysicsServerCommandProcessor::processCollisionFilterCommand(const struct S clientCmd.m_collisionFilterArgs.m_bodyUniqueIdB, clientCmd.m_collisionFilterArgs.m_linkIndexA, clientCmd.m_collisionFilterArgs.m_linkIndexB, - clientCmd.m_collisionFilterArgs.m_enableCollision); + clientCmd.m_collisionFilterArgs.m_enableCollision != 0); btAlignedObjectArray bodies; @@ -7909,8 +7909,8 @@ bool PhysicsServerCommandProcessor::processRequestActualStateCommand(const struc SendActualStateSharedMemoryStorage* stateDetails = (SendActualStateSharedMemoryStorage*)bufferServerToClient; //make sure the storage fits, otherwise - btAssert(sizeof(SendActualStateSharedMemoryStorage) < bufferSizeInBytes); - if (sizeof(SendActualStateSharedMemoryStorage) > bufferSizeInBytes) + btAssert((int)sizeof(SendActualStateSharedMemoryStorage) < bufferSizeInBytes); + if ((int)sizeof(SendActualStateSharedMemoryStorage) > bufferSizeInBytes) { //this forces an error report body = 0; @@ -9347,11 +9347,11 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo const bt_tinyobj::shape_t& shape = shapes[0]; btAlignedObjectArray vertices; btAlignedObjectArray indices; - for (int i = 0; i < attribute.vertices.size(); i++) + for (unsigned int i = 0; i < attribute.vertices.size(); i++) { vertices.push_back(attribute.vertices[i]); } - for (int i = 0; i < shape.mesh.indices.size(); i++) + for (unsigned int i = 0; i < shape.mesh.indices.size(); i++) { indices.push_back(shape.mesh.indices[i].vertex_index); } @@ -10312,7 +10312,7 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar bool use_self_collision = false; if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_USE_SELF_COLLISION) { - use_self_collision = clientCmd.m_loadSoftBodyArguments.m_useSelfCollision; + use_self_collision = clientCmd.m_loadSoftBodyArguments.m_useSelfCollision != 0; } int bodyUniqueId = -1; diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index cfe91314da..342fa25929 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -778,7 +778,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface m_shapeIndex(-1), m_textureId(-1), m_instanceId(-1), - m_skipGraphicsUpdate(skipGraphicsUpdate) + m_skipGraphicsUpdate(skipGraphicsUpdate != 0) { m_cameraUpdated = 0; m_childGuiHelper = guiHelper; diff --git a/examples/SharedMemory/main.cpp b/examples/SharedMemory/main.cpp index 4cafee102b..cc4e1e7e86 100644 --- a/examples/SharedMemory/main.cpp +++ b/examples/SharedMemory/main.cpp @@ -56,7 +56,7 @@ int main(int argc, char* argv[]) memset(&action, 0x0, sizeof(action)); action.sa_handler = cleanup; static const int signos[] = {SIGHUP, SIGINT, SIGQUIT, SIGABRT, SIGSEGV, SIGPIPE, SIGTERM}; - for (int ii(0); ii < sizeof(signos) / sizeof(*signos); ++ii) + for (int ii(0); ii < (int)(sizeof(signos) / sizeof(*signos)); ++ii) { if (0 != sigaction(signos[ii], &action, NULL)) { diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index 31b3d4c188..39376ad636 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -1971,7 +1971,7 @@ void CMainApplication::UpdateHMDMatrixPose() { B3_PROFILE("for loop"); - for (int nDevice = 0; nDevice < vr::k_unMaxTrackedDeviceCount; ++nDevice) + for (unsigned int nDevice = 0; nDevice < vr::k_unMaxTrackedDeviceCount; ++nDevice) { if (m_rTrackedDevicePose[nDevice].bPoseIsValid) { diff --git a/examples/ThirdPartyLibs/stb_image/stb_image.cpp b/examples/ThirdPartyLibs/stb_image/stb_image.cpp index 9f140db8fb..5f9d6a86d5 100644 --- a/examples/ThirdPartyLibs/stb_image/stb_image.cpp +++ b/examples/ThirdPartyLibs/stb_image/stb_image.cpp @@ -877,7 +877,7 @@ stbi_inline static int extend_receive(jpeg *j, int n) // predict well. I tried to table accelerate it but failed. // maybe it's compiling as a conditional move? if (k < m) - return (-1 << n) + k + 1; + return (int)((unsigned int)-1 << n) + k + 1; else return k; } diff --git a/examples/Utils/ChromeTraceUtil.cpp b/examples/Utils/ChromeTraceUtil.cpp index fbb030c3a8..c2b7ee4236 100644 --- a/examples/Utils/ChromeTraceUtil.cpp +++ b/examples/Utils/ChromeTraceUtil.cpp @@ -178,7 +178,7 @@ void MyEnterProfileZoneFunc(const char* msg) return; int threadId = btQuickprofGetCurrentThreadIndex2(); - if (threadId < 0 || threadId >= BT_QUICKPROF_MAX_THREAD_COUNT) + if (threadId < 0 || threadId >= (int)BT_QUICKPROF_MAX_THREAD_COUNT) return; if (gStackDepths[threadId] >= MAX_NESTING) @@ -201,7 +201,7 @@ void MyLeaveProfileZoneFunc() return; int threadId = btQuickprofGetCurrentThreadIndex2(); - if (threadId < 0 || threadId >= BT_QUICKPROF_MAX_THREAD_COUNT) + if (threadId < 0 || threadId >= (int)BT_QUICKPROF_MAX_THREAD_COUNT) return; if (gStackDepths[threadId] <= 0) @@ -246,7 +246,7 @@ void b3ChromeUtilsStopTimingsAndWriteJsonFile(const char* fileNamePrefix) { fprintf(gTimingFile, "{\"traceEvents\":[\n"); //dump the content to file - for (int i = 0; i < BT_QUICKPROF_MAX_THREAD_COUNT; i++) + for (int i = 0; i < (int)BT_QUICKPROF_MAX_THREAD_COUNT; i++) { if (gTimings[i].m_numTimings) { diff --git a/examples/Utils/RobotLoggingUtil.cpp b/examples/Utils/RobotLoggingUtil.cpp index 221be830e4..c3c8a4aae2 100644 --- a/examples/Utils/RobotLoggingUtil.cpp +++ b/examples/Utils/RobotLoggingUtil.cpp @@ -41,14 +41,14 @@ int readMinitaurLogFile(const char* fileName, btAlignedObjectArray& { printf("Num Fields = %d\n", structNames.size()); } - btAssert(structTypes.size() == structNames.size()); - if (structTypes.size() != structNames.size()) + btAssert((int)structTypes.size() == structNames.size()); + if ((int)structTypes.size() != structNames.size()) { retVal = eCorruptHeader; } int numStructsRead = 0; - if (structTypes.size() == structNames.size()) + if ((int)structTypes.size() == structNames.size()) { while (!eof) { @@ -223,7 +223,7 @@ void appendMinitaurLogData(FILE* f, std::string& structTypes, const MinitaurLogR { unsigned char buf[2] = {0xaa, 0xbb}; fwrite(buf, 2, 1, f); - if (structTypes.length() == logData.m_values.size()) + if ((int)structTypes.length() == logData.m_values.size()) { for (int i = 0; i < logData.m_values.size(); i++) { diff --git a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.cpp b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.cpp index 5b4bd486a1..618cae5c25 100644 --- a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.cpp +++ b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.cpp @@ -245,9 +245,9 @@ void b3GpuGridBroadphase::calculateOverlappingPairs(int maxPairs) int sz = m_gpuPairs.size(); printf("m_gpuPairs.size()=%d\n", sz); - for (int i = 0; i < m_gpuPairs.size(); i++) + for (size_t i = 0; i < m_gpuPairs.size(); i++) { - printf("pair %d = %d,%d\n", i, pairsCpu[i].x, pairsCpu[i].y); + printf("pair %zu = %d,%d\n", i, pairsCpu[i].x, pairsCpu[i].y); } printf("?!?\n"); diff --git a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.cpp b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.cpp index d63b139a38..be1d12cfe7 100644 --- a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.cpp +++ b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.cpp @@ -580,7 +580,7 @@ void b3GpuSapBroadphase::calculateOverlappingPairsHostIncremental3Sap() if (dmin != 0) { int stepMin = dmin < 0 ? -1 : 1; - for (int j = prevMinIndex; j != curMinIndex; j += stepMin) + for (int j = prevMinIndex; j != (int)curMinIndex; j += stepMin) { int otherIndex2 = m_sortedAxisCPU[axis][otherbuffer][j].y; int otherIndex = otherIndex2 / 2; @@ -661,7 +661,7 @@ void b3GpuSapBroadphase::calculateOverlappingPairsHostIncremental3Sap() if (dmax != 0) { int stepMax = dmax < 0 ? -1 : 1; - for (int j = prevMaxIndex; j != curMaxIndex; j += stepMax) + for (int j = prevMaxIndex; j != (int)curMaxIndex; j += stepMax) { int otherIndex2 = m_sortedAxisCPU[axis][otherbuffer][j].y; int otherIndex = otherIndex2 / 2; @@ -865,7 +865,7 @@ void b3GpuSapBroadphase::calculateOverlappingPairsHost(int maxPairs) // if (m_currentBuffer>=0) // return calculateOverlappingPairsHostIncremental3Sap(); - b3Assert(m_allAabbsCPU.size() == m_allAabbsGPU.size()); + b3Assert(m_allAabbsCPU.size() == (int)m_allAabbsGPU.size()); m_allAabbsGPU.copyToHost(m_allAabbsCPU); int axis = 0; @@ -1014,7 +1014,7 @@ void b3GpuSapBroadphase::calculateOverlappingPairs(int maxPairs) { //bool syncOnHost = false; - int numSmallAabbs = m_smallAabbsMappingCPU.size(); + size_t numSmallAabbs = m_smallAabbsMappingCPU.size(); if (m_prefixScanFloat4 && numSmallAabbs) { B3_PROFILE("GPU compute best variance axis"); diff --git a/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp b/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp index df06177a7e..37cf0f1621 100644 --- a/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp +++ b/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp @@ -237,7 +237,7 @@ cl_context b3OpenCLUtils_createContextFromPlatform(cl_platform_id platform, cl_d #endif //_WIN32 num_entries = B3_MAX_CL_DEVICES; - num_devices = -1; + num_devices = (cl_uint)-1; ciErrNum = clGetDeviceIDs( platform, @@ -336,7 +336,7 @@ cl_context b3OpenCLUtils_createContextFromType(cl_device_type deviceType, cl_int return NULL; } - if (preferredPlatformIndex >= 0 && i == preferredPlatformIndex) + if (preferredPlatformIndex >= 0 && (int)i == preferredPlatformIndex) { cl_platform_id tmpPlatform = platforms[0]; platforms[0] = platforms[i]; diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexHullContact.cpp b/src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexHullContact.cpp index 66e3f35f91..c20931a8e3 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexHullContact.cpp +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexHullContact.cpp @@ -379,7 +379,7 @@ inline bool IsPointInPolygon(const float4& p, float4 v0 = baseVertex[convexIndices[face->m_indexOffset + face->m_numIndices - 1]]; b = v0; - for (unsigned i = 0; i != face->m_numIndices; ++i) + for (unsigned i = 0; (int)i != face->m_numIndices; ++i) { a = b; float4 vi = baseVertex[convexIndices[face->m_indexOffset + i]]; diff --git a/src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.cpp b/src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.cpp index afb0ecb059..7aaba54881 100644 --- a/src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.cpp +++ b/src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.cpp @@ -103,8 +103,8 @@ void b3BoundSearchCL::execute(b3OpenCLArray& src, int nSrc, b3OpenCL { b3Assert(m_lower); b3Assert(m_upper); - b3Assert(m_lower->capacity() <= (int)nDst); - b3Assert(m_upper->capacity() <= (int)nDst); + b3Assert((int)m_lower->capacity() <= nDst); + b3Assert((int)m_upper->capacity() <= nDst); int zero = 0; m_filler->execute(*m_lower, zero, nDst); @@ -137,8 +137,8 @@ void b3BoundSearchCL::executeHost(b3AlignedObjectArray& src, int nSr b3Assert(src[i].m_key <= src[i + 1].m_key); b3SortData minData, /*zeroData,*/ maxData; - minData.m_key = -1; - minData.m_value = -1; + minData.m_key = (unsigned int)-1; + minData.m_value = (unsigned int)-1; // zeroData.m_key = 0; // zeroData.m_value = 0; maxData.m_key = nDst; diff --git a/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.cpp b/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.cpp index 822b511633..5663768fa3 100644 --- a/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.cpp +++ b/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.cpp @@ -37,7 +37,7 @@ template T b3NextPowerOf2(T n) { n -= 1; - for (int i = 0; i < sizeof(T) * 8; i++) + for (unsigned int i = 0; i < sizeof(T) * 8; i++) n = n | (n >> i); return n + 1; } diff --git a/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanFloat4CL.cpp b/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanFloat4CL.cpp index 1cac97c988..9cd31a989b 100644 --- a/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanFloat4CL.cpp +++ b/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanFloat4CL.cpp @@ -37,7 +37,7 @@ template T b3NextPowerOf2(T n) { n -= 1; - for (int i = 0; i < sizeof(T) * 8; i++) + for (unsigned int i = 0; i < sizeof(T) * 8; i++) n = n | (n >> i); return n + 1; } diff --git a/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp b/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp index 0b73e1d273..9a35b571aa 100644 --- a/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp +++ b/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp @@ -299,7 +299,7 @@ void b3GpuRaycast::castRays(const b3AlignedObjectArray& rays, b3Align int numRayRigidPairs = -1; m_data->m_gpuNumRayRigidPairs->copyToHostPointer(&numRayRigidPairs, 1); - if (numRayRigidPairs > m_data->m_gpuRayRigidPairs->size()) + if (numRayRigidPairs > (int)m_data->m_gpuRayRigidPairs->size()) { numRayRigidPairs = m_data->m_gpuRayRigidPairs->size(); m_data->m_gpuNumRayRigidPairs->copyFromHostPointer(&numRayRigidPairs, 1); diff --git a/src/BulletCollision/CollisionShapes/btMiniSDF.cpp b/src/BulletCollision/CollisionShapes/btMiniSDF.cpp index 9f654bf4a7..f79325abaf 100644 --- a/src/BulletCollision/CollisionShapes/btMiniSDF.cpp +++ b/src/BulletCollision/CollisionShapes/btMiniSDF.cpp @@ -114,13 +114,13 @@ bool btMiniSDF::load(const char* data, int size) unsigned long long int n_cells0; ds.read(n_cells0); m_cells.resize(n_cells0); - for (int i = 0; i < n_cells0; i++) + for (unsigned long long i = 0; i < n_cells0; i++) { unsigned long long int n_cells1; btAlignedObjectArray& cells = m_cells[i]; ds.read(n_cells1); cells.resize(n_cells1); - for (int j = 0; j < n_cells1; j++) + for (unsigned long long j = 0; j < n_cells1; j++) { btCell32& cell = cells[j]; ds.read(cell); @@ -132,13 +132,13 @@ bool btMiniSDF::load(const char* data, int size) ds.read(n_cell_maps0); m_cell_map.resize(n_cell_maps0); - for (int i = 0; i < n_cell_maps0; i++) + for (unsigned long long i = 0; i < n_cell_maps0; i++) { unsigned long long int n_cell_maps1; btAlignedObjectArray& cell_maps = m_cell_map[i]; ds.read(n_cell_maps1); cell_maps.resize(n_cell_maps1); - for (int j = 0; j < n_cell_maps1; j++) + for (unsigned long long j = 0; j < n_cell_maps1; j++) { unsigned int& cell_map = cell_maps[j]; ds.read(cell_map); diff --git a/src/BulletDynamics/Featherstone/btMultiBodyInplaceSolverIslandCallback.h b/src/BulletDynamics/Featherstone/btMultiBodyInplaceSolverIslandCallback.h index 3169b86e61..d01a343b9f 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyInplaceSolverIslandCallback.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyInplaceSolverIslandCallback.h @@ -190,7 +190,7 @@ struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager:: { for (i = 0; i < numBodies; i++) { - bool isSoftBodyType = (bodies[i]->getInternalType() & btCollisionObject::CO_SOFT_BODY); + bool isSoftBodyType = (bodies[i]->getInternalType() & btCollisionObject::CO_SOFT_BODY) != 0; if (!isSoftBodyType) { m_bodies.push_back(bodies[i]); diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.cpp b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.cpp index 92dae314c0..c3ca696701 100644 --- a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.cpp +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.cpp @@ -96,7 +96,7 @@ btReducedDeformableBody* btReducedDeformableBodyHelpers::createFromVtkFile(btSof } btReducedDeformableBody* rsb = new btReducedDeformableBody(&worldInfo, n_points, &X[0], 0); - for (int i = 0; i < n_tets; ++i) + for (unsigned int i = 0; i < n_tets; ++i) { const Index& ni = indices[i]; rsb->appendTetra(ni[0], ni[1], ni[2], ni[3]); @@ -188,14 +188,14 @@ void btReducedDeformableBodyHelpers::readBinaryMat(btReducedDeformableBody::tDen // read data mat.resize(n_modes); - for (int i = 0; i < n_modes; ++i) + for (unsigned int i = 0; i < n_modes; ++i) { - for (int j = 0; j < n_full; ++j) + for (unsigned int j = 0; j < n_full; ++j) { double temp; f_in.read((char*)&temp, sizeof(double)); - if (mat[i].size() != n_modes) + if (mat[i].size() != (int)n_modes) mat[i].resize(n_full); mat[i][j] = btScalar(temp); } diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h index 60b6fe3882..a6627ec343 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h @@ -194,7 +194,8 @@ class btDeformableBackwardEulerObjective m_lf[i]->addScaledDampingForceDifferential(-m_dt, dv, f); } counter = 0; - for (; counter < f.size(); ++counter) + const size_t stackSize = f.size() >= 0 ? (size_t)f.size() : 0; + for (; counter < stackSize; ++counter) { f[counter] = rhs[counter] - f[counter]; } diff --git a/src/BulletSoftBody/btSoftBody.cpp b/src/BulletSoftBody/btSoftBody.cpp index 9c9e3bd5c6..dd155f20f7 100644 --- a/src/BulletSoftBody/btSoftBody.cpp +++ b/src/BulletSoftBody/btSoftBody.cpp @@ -2417,7 +2417,7 @@ void btSoftBody::pointersToIndices() { #define PTR2IDX(_p_, _b_) reinterpret_cast((_p_) - (_b_)) btSoftBody::Node* base = m_nodes.size() ? &m_nodes[0] : 0; - int i, ni; + size_t i, ni; for (i = 0, ni = m_nodes.size(); i < ni; ++i) { diff --git a/src/BulletSoftBody/btSoftBody.h b/src/BulletSoftBody/btSoftBody.h index 5aad271ae7..8a83f6498e 100644 --- a/src/BulletSoftBody/btSoftBody.h +++ b/src/BulletSoftBody/btSoftBody.h @@ -278,7 +278,7 @@ class btSoftBody : public btCollisionObject btScalar m_area; // Area btDbvtNode* m_leaf; // Leaf data int m_constrained; // depth of penetration - int m_battach : 1; // Attached + unsigned int m_battach : 1; // Attached int index; btVector3 m_splitv; // velocity associated with split impulse btMatrix3x3 m_effectiveMass; // effective mass in contact @@ -291,7 +291,7 @@ class btSoftBody : public btCollisionObject btVector3 m_c3; // gradient Node* m_n[2]; // Node pointers btScalar m_rl; // Rest length - int m_bbending : 1; // Bending link + unsigned int m_bbending : 1; // Bending link btScalar m_c0; // (ima+imb)*kLST btScalar m_c1; // rl^2 btScalar m_c2; // |gradient|^2/c0 @@ -493,8 +493,8 @@ class btSoftBody : public btCollisionObject { btVector3 m_velocity; btVector3 m_drift; - int m_asVelocity : 1; - int m_asDrift : 1; + unsigned int m_asVelocity : 1; + unsigned int m_asDrift : 1; Impulse() : m_velocity(0, 0, 0), m_drift(0, 0, 0), m_asVelocity(0), m_asDrift(0) {} Impulse operator-() const { diff --git a/src/BulletSoftBody/btSoftBodyHelpers.cpp b/src/BulletSoftBody/btSoftBodyHelpers.cpp index d596e3e3f3..5abbd44bfd 100644 --- a/src/BulletSoftBody/btSoftBodyHelpers.cpp +++ b/src/BulletSoftBody/btSoftBodyHelpers.cpp @@ -748,11 +748,11 @@ btSoftBody* btSoftBodyHelpers::CreatePatch(btSoftBodyWorldInfo& worldInfo, const for (int ix = 0; ix < rx; ++ix) { const btScalar tx = ix / (btScalar)(rx - 1); - btScalar pert = perturbation * btScalar(rand()) / RAND_MAX; + btScalar pert = perturbation * btScalar(rand()) / btScalar(RAND_MAX); btVector3 temp1 = py1; temp1.setY(py1.getY() + pert); btVector3 temp = py0; - pert = perturbation * btScalar(rand()) / RAND_MAX; + pert = perturbation * btScalar(rand()) / btScalar(RAND_MAX); temp.setY(py0.getY() + pert); x[IDX(ix, iy)] = lerp(temp, temp1, tx); m[IDX(ix, iy)] = 1; @@ -1325,7 +1325,7 @@ btSoftBody* btSoftBodyHelpers::CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, } btSoftBody* psb = new btSoftBody(&worldInfo, n_points, &X[0], 0); - for (int i = 0; i < n_tets; ++i) + for (unsigned int i = 0; i < n_tets; ++i) { const Index& ni = indices[i]; psb->appendTetra(ni[0], ni[1], ni[2], ni[3]); diff --git a/test/InverseDynamics/test_invdyn_bullet.cpp b/test/InverseDynamics/test_invdyn_bullet.cpp index 51a7e1482b..50807c7aa9 100644 --- a/test/InverseDynamics/test_invdyn_bullet.cpp +++ b/test/InverseDynamics/test_invdyn_bullet.cpp @@ -47,7 +47,7 @@ TEST(InvDynCompare, bulletUrdfR2D2) char relativeFileName[1024]; - ASSERT_TRUE(b3ResourcePath::findResourcePath(kUrdfFile, relativeFileName, 1024,0)); + ASSERT_TRUE(b3ResourcePath::findResourcePath(kUrdfFile, relativeFileName, 1024,0) != 0); mb_load.setFileName(relativeFileName); mb_load.init(); diff --git a/test/InverseDynamics/test_invdyn_kinematics.cpp b/test/InverseDynamics/test_invdyn_kinematics.cpp index cfb0d07672..cf52ec65a9 100644 --- a/test/InverseDynamics/test_invdyn_kinematics.cpp +++ b/test/InverseDynamics/test_invdyn_kinematics.cpp @@ -148,7 +148,7 @@ class VecDiffFD public: VecDiffFD(std::string name, int dim, idScalar dt) : m_name(name), m_fd(dim), m_dt(dt) { - for (int i = 0; i < m_fd.size(); i++) + for (unsigned int i = 0; i < m_fd.size(); i++) { char buf[256]; BT_ID_SNPRINTF(buf, 256, "%s-%.2d", name.c_str(), i); @@ -159,7 +159,7 @@ class VecDiffFD idScalar getMaxError() const { idScalar max_error = 0; - for (int i = 0; i < m_fd.size(); i++) + for (unsigned int i = 0; i < m_fd.size(); i++) { const idScalar error = m_fd[i].getMaxError(); if (error > max_error) @@ -172,7 +172,7 @@ class VecDiffFD idScalar getMaxValue() const { idScalar max_value = 0; - for (int i = 0; i < m_fd.size(); i++) + for (unsigned int i = 0; i < m_fd.size(); i++) { const idScalar value = m_fd[i].getMaxValue(); if (value > max_value) @@ -189,7 +189,7 @@ class VecDiffFD void printCurrent() { - for (int i = 0; i < m_fd.size(); i++) + for (unsigned int i = 0; i < m_fd.size(); i++) { m_fd[i].printCurrent(); } From 95103284d7583991cc5c342401572ccd4454ed24 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 16:06:47 +0100 Subject: [PATCH 04/57] Compiler warnings - implicit conversion --- src/BulletCollision/BroadphaseCollision/btDbvt.h | 2 +- src/LinearMath/btQuaternion.h | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/BulletCollision/BroadphaseCollision/btDbvt.h b/src/BulletCollision/BroadphaseCollision/btDbvt.h index 430f5771cf..1e731258c4 100644 --- a/src/BulletCollision/BroadphaseCollision/btDbvt.h +++ b/src/BulletCollision/BroadphaseCollision/btDbvt.h @@ -1289,7 +1289,7 @@ inline void btDbvt::rayTest(const btDbvtNode* root, rayDirectionInverse[0] = rayDir[0] == btScalar(0.0) ? btScalar(BT_LARGE_FLOAT) : btScalar(1.0) / rayDir[0]; rayDirectionInverse[1] = rayDir[1] == btScalar(0.0) ? btScalar(BT_LARGE_FLOAT) : btScalar(1.0) / rayDir[1]; rayDirectionInverse[2] = rayDir[2] == btScalar(0.0) ? btScalar(BT_LARGE_FLOAT) : btScalar(1.0) / rayDir[2]; - unsigned int signs[3] = {rayDirectionInverse[0] < 0.0, rayDirectionInverse[1] < 0.0, rayDirectionInverse[2] < 0.0}; + unsigned int signs[3] = {rayDirectionInverse[0] < btScalar(0.0), rayDirectionInverse[1] < btScalar(0.0), rayDirectionInverse[2] < btScalar(0.0)}; btScalar lambda_max = rayDir.dot(rayTo - rayFrom); diff --git a/src/LinearMath/btQuaternion.h b/src/LinearMath/btQuaternion.h index 40d6e145c5..9f891062fb 100644 --- a/src/LinearMath/btQuaternion.h +++ b/src/LinearMath/btQuaternion.h @@ -582,7 +582,7 @@ class btQuaternion : public btQuadWord const btScalar product = dot(q) / magnitude; const btScalar absproduct = btFabs(product); - if (absproduct < btScalar(1.0 - SIMD_EPSILON)) + if (absproduct < (btScalar(1.0) - SIMD_EPSILON)) { // Take care of long angle case see http://en.wikipedia.org/wiki/Slerp const btScalar theta = btAcos(absproduct); @@ -942,7 +942,7 @@ shortestArcQuat(const btVector3& v0, const btVector3& v1) // Game Programming G btVector3 c = v0.cross(v1); btScalar d = v0.dot(v1); - if (d < -1.0 + SIMD_EPSILON) + if (d < (btScalar(-1.0) + SIMD_EPSILON)) { btVector3 n, unused; btPlaneSpace1(v0, n, unused); From f8c1b06fadcc207fb9c5016cfacdbe3723ed0600 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 14:37:12 +0100 Subject: [PATCH 05/57] Compiler warnings - maybe uninitialized --- Extras/ConvexDecomposition/cd_hull.cpp | 2 +- Extras/VHACD/inc/vhacdVolume.h | 4 +- .../Collision/CollisionTutorialBullet2.cpp | 2 +- .../CollisionShape2TriangleMesh.cpp | 2 +- .../ImportMJCFDemo/BulletMJCFImporter.cpp | 2 +- .../ImportMeshUtility/b3ImportMeshUtility.cpp | 2 +- examples/OpenGLWindow/SimpleOpenGL3App.cpp | 2 +- .../PhysicsServerCommandProcessor.cpp | 4 +- examples/SharedMemory/b3PluginManager.cpp | 18 +++---- .../TinyRendererVisualShapeConverter.cpp | 2 +- .../StandaloneMain/hellovr_opengl_main.cpp | 4 +- .../ThirdPartyLibs/stb_image/stb_truetype.h | 2 +- examples/Tutorial/Tutorial.cpp | 2 +- examples/Utils/b3Clock.cpp | 2 +- .../shared/b3ContactConvexConvexSAT.h | 2 +- src/Bullet3Common/b3Vector3.cpp | 4 +- .../Initialize/b3OpenCLUtils.cpp | 4 +- .../NarrowphaseCollision/b3OptimizedBvh.cpp | 2 +- src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp | 4 ++ .../btInternalEdgeUtility.cpp | 2 +- .../btBvhTriangleMeshShape.cpp | 4 +- .../CollisionShapes/btMiniSDF.cpp | 48 +++++++++++++------ .../CollisionShapes/btOptimizedBvh.cpp | 2 +- .../NarrowPhaseCollision/btMprPenetration.h | 1 + .../btKinematicCharacterController.cpp | 3 ++ src/BulletDynamics/Vehicle/btWheelInfo.h | 3 ++ .../btDeformableBackwardEulerObjective.cpp | 2 +- src/BulletSoftBody/btSoftBody.cpp | 3 ++ src/BulletSoftBody/btSoftBodyInternals.h | 2 +- .../TaskScheduler/btTaskScheduler.cpp | 4 +- src/LinearMath/btHashMap.h | 2 +- src/LinearMath/btVector3.cpp | 4 +- 32 files changed, 91 insertions(+), 55 deletions(-) diff --git a/Extras/ConvexDecomposition/cd_hull.cpp b/Extras/ConvexDecomposition/cd_hull.cpp index b26bfa9838..bd2680642d 100644 --- a/Extras/ConvexDecomposition/cd_hull.cpp +++ b/Extras/ConvexDecomposition/cd_hull.cpp @@ -3103,7 +3103,7 @@ bool HullLibrary::CleanupVertices(unsigned int svcount, vcount = 0; - float recip[3]; + float recip[3] = {}; if (scale) { diff --git a/Extras/VHACD/inc/vhacdVolume.h b/Extras/VHACD/inc/vhacdVolume.h index d3ec16c1ef..5254ca2616 100644 --- a/Extras/VHACD/inc/vhacdVolume.h +++ b/Extras/VHACD/inc/vhacdVolume.h @@ -354,8 +354,8 @@ void Volume::Voxelize(const T* const points, const unsigned int stridePoints, co Vec3 p[3]; size_t i, j, k; - size_t i0, j0, k0; - size_t i1, j1, k1; + size_t i0 = 0, j0 = 0, k0 = 0; + size_t i1 = 0, j1 = 0, k1 = 0; Vec3 boxcenter; Vec3 pt; const Vec3 boxhalfsize(0.5, 0.5, 0.5); diff --git a/examples/Collision/CollisionTutorialBullet2.cpp b/examples/Collision/CollisionTutorialBullet2.cpp index 1edbf8bc1b..3b9ae5055a 100644 --- a/examples/Collision/CollisionTutorialBullet2.cpp +++ b/examples/Collision/CollisionTutorialBullet2.cpp @@ -203,7 +203,7 @@ class CollisionTutorialBullet2 : public CommonExampleInterface if (1) { - int width, height, n; + int width=0, height=0, n; const char* filename = "data/cube.png"; const unsigned char* image = 0; diff --git a/examples/ExampleBrowser/CollisionShape2TriangleMesh.cpp b/examples/ExampleBrowser/CollisionShape2TriangleMesh.cpp index 7ba53d62eb..efaa690bc8 100644 --- a/examples/ExampleBrowser/CollisionShape2TriangleMesh.cpp +++ b/examples/ExampleBrowser/CollisionShape2TriangleMesh.cpp @@ -82,7 +82,7 @@ void CollisionShape2TriangleMesh(btCollisionShape* collisionShape, const btTrans for (int j = 2; j >= 0; j--) { - int graphicsindex; + int graphicsindex=0; switch (indicestype) { case PHY_INTEGER: graphicsindex = gfxbase[j]; break; case PHY_SHORT: graphicsindex = ((unsigned short*)gfxbase)[j]; break; diff --git a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp index e6a697f292..c21fc698e8 100644 --- a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp +++ b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp @@ -519,7 +519,7 @@ struct BulletMJCFImporterInternalData } bool isLimited = lim == "true"; - UrdfJointTypes ejtype; + UrdfJointTypes ejtype = (UrdfJointTypes)0; if (jType) { std::string jointType = jType; diff --git a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp index 1764bca10a..9a43aa45d1 100644 --- a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp +++ b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp @@ -94,7 +94,7 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string& if (shape.material.diffuse_texname.length() > 0) { - int width, height, n; + int width=0, height=0, n; const char* filename = shape.material.diffuse_texname.c_str(); unsigned char* image = 0; diff --git a/examples/OpenGLWindow/SimpleOpenGL3App.cpp b/examples/OpenGLWindow/SimpleOpenGL3App.cpp index fe0a3017bb..e3ea466140 100644 --- a/examples/OpenGLWindow/SimpleOpenGL3App.cpp +++ b/examples/OpenGLWindow/SimpleOpenGL3App.cpp @@ -495,7 +495,7 @@ void SimpleOpenGL3App::drawText3D(const char* txt, float position[3], float orie float posX = position[0]; float posY = position[1]; float posZ = position[2]; (void)posZ; - float winx, winy, winz; + float winx = 0, winy = 0, winz = 0; if (optionFlag & CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera) { diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index dcecb886eb..f832bfc248 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -4969,7 +4969,7 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str { int width; int height; - btScalar minHeight, maxHeight; + btScalar minHeight=0, maxHeight=0; PHY_ScalarType scalarType = PHY_FLOAT; CommonFileIOInterface* fileIO = m_data->m_pluginManager.getFileIOInterface(); const unsigned char* heightfieldData = 0; @@ -14741,7 +14741,7 @@ bool PhysicsServerCommandProcessor::processLoadTextureCommand(const struct Share } { - int width, height, n; + int width = 0, height = 0, n; unsigned char* imageData = 0; CommonFileIOInterface* fileIO = m_data->m_pluginManager.getFileIOInterface(); diff --git a/examples/SharedMemory/b3PluginManager.cpp b/examples/SharedMemory/b3PluginManager.cpp index f6f90a57be..d09eeee20d 100644 --- a/examples/SharedMemory/b3PluginManager.cpp +++ b/examples/SharedMemory/b3PluginManager.cpp @@ -208,7 +208,7 @@ int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr) b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId); if (!plugin->m_isInitialized) { - b3PluginContext context = {0}; + b3PluginContext context = {}; context.m_userPointer = 0; context.m_physClient = (b3PhysicsClientHandle)m_data->m_physicsDirect; context.m_rpcCommandProcessorInterface = m_data->m_rpcCommandProcessorInterface; @@ -348,7 +348,7 @@ void b3PluginManager::unloadPlugin(int pluginUniqueId) { m_data->m_numNotificationPlugins--; } - b3PluginContext context = {0}; + b3PluginContext context = {}; context.m_userPointer = plugin->m_userPointer; context.m_physClient = (b3PhysicsClientHandle)m_data->m_physicsDirect; @@ -406,7 +406,7 @@ void b3PluginManager::tickPlugins(double /*timeStep*/, b3PluginManagerTickMode t if (tick) { - b3PluginContext context = {0}; + b3PluginContext context = {}; context.m_userPointer = plugin->m_userPointer; context.m_physClient = (b3PhysicsClientHandle)m_data->m_physicsDirect; context.m_numMouseEvents = m_data->m_mouseEvents.size(); @@ -454,7 +454,7 @@ void b3PluginManager::reportNotifications() if (plugin->m_processNotificationsFunc) { - b3PluginContext context = {0}; + b3PluginContext context = {}; context.m_userPointer = plugin->m_userPointer; context.m_physClient = (b3PhysicsClientHandle)m_data->m_physicsDirect; context.m_numNotifications = notifications.size(); @@ -472,7 +472,7 @@ int b3PluginManager::executePluginCommand(int pluginUniqueId, const b3PluginArgu b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId); if (plugin) { - b3PluginContext context = {0}; + b3PluginContext context = {}; context.m_userPointer = plugin->m_userPointer; context.m_physClient = (b3PhysicsClientHandle)m_data->m_physicsDirect; context.m_rpcCommandProcessorInterface = m_data->m_rpcCommandProcessorInterface; @@ -518,7 +518,7 @@ int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, b3Plugi if (initPlugin) { - b3PluginContext context = {0}; + b3PluginContext context = {}; context.m_userPointer = 0; context.m_returnData = 0; context.m_physClient = (b3PhysicsClientHandle)m_data->m_physicsDirect; @@ -546,7 +546,7 @@ UrdfRenderingInterface* b3PluginManager::getRenderInterface() b3PluginHandle* plugin = m_data->m_plugins.getHandle(m_data->m_activeRendererPluginUid); if (plugin && plugin->m_getRendererFunc) { - b3PluginContext context = {0}; + b3PluginContext context = {}; context.m_userPointer = plugin->m_userPointer; context.m_physClient = (b3PhysicsClientHandle)m_data->m_physicsDirect; renderer = plugin->m_getRendererFunc(&context); @@ -568,7 +568,7 @@ struct CommonFileIOInterface* b3PluginManager::getFileIOInterface() b3PluginHandle* plugin = m_data->m_plugins.getHandle(m_data->m_activeFileIOPluginUid); if (plugin && plugin->m_getFileIOFunc) { - b3PluginContext context = {0}; + b3PluginContext context = {}; context.m_userPointer = plugin->m_userPointer; context.m_physClient = (b3PhysicsClientHandle)m_data->m_physicsDirect; fileIOInterface = plugin->m_getFileIOFunc(&context); @@ -594,7 +594,7 @@ struct b3PluginCollisionInterface* b3PluginManager::getCollisionInterface() b3PluginHandle* plugin = m_data->m_plugins.getHandle(m_data->m_activeCollisionPluginUid); if (plugin && plugin->m_getCollisionFunc) { - b3PluginContext context = {0}; + b3PluginContext context = {}; context.m_userPointer = plugin->m_userPointer; context.m_physClient = (b3PhysicsClientHandle)m_data->m_physicsDirect; collisionInterface = plugin->m_getCollisionFunc(&context); diff --git a/examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp index 8d534c43f0..fc229cbb10 100644 --- a/examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp @@ -1554,7 +1554,7 @@ int TinyRendererVisualShapeConverter::registerTexture(unsigned char* texels, int int TinyRendererVisualShapeConverter::loadTextureFile(const char* filename, struct CommonFileIOInterface* fileIO) { B3_PROFILE("loadTextureFile"); - int width, height, n; + int width=0, height=0, n; unsigned char* image = 0; if (fileIO) { diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index 39376ad636..f9bde93bf6 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -725,7 +725,7 @@ bool CMainApplication::HandleInput() //if (sPrevStates[unDevice].unPacketNum != state.unPacketNum) if (m_pHMD->GetTrackedDeviceClass(unDevice) == vr::TrackedDeviceClass_HMD) { - Matrix4 rotYtoZ = rotYtoZ.identity(); + Matrix4 rotYtoZ = Matrix4(); //some Bullet apps (especially robotics related) require Z as up-axis) if (m_app->getUpAxis() == 2) { @@ -1683,7 +1683,7 @@ void CMainApplication::RenderStereoTargets() m_app->m_instancingRenderer->init(); - Matrix4 rotYtoZ = rotYtoZ.identity(); + Matrix4 rotYtoZ = Matrix4(); //some Bullet apps (especially robotics related) require Z as up-axis) if (m_app->getUpAxis() == 2) diff --git a/examples/ThirdPartyLibs/stb_image/stb_truetype.h b/examples/ThirdPartyLibs/stb_image/stb_truetype.h index 4d84eb1722..22fe6e45dd 100644 --- a/examples/ThirdPartyLibs/stb_image/stb_truetype.h +++ b/examples/ThirdPartyLibs/stb_image/stb_truetype.h @@ -2203,7 +2203,7 @@ static void stbtt__fill_active_edges_new(float *scanline, float *scanline_fill, // directly AA rasterize edges w/o supersampling static void stbtt__rasterize_sorted_edges(stbtt__bitmap *result, stbtt__edge *e, int n, int vsubsample, int off_x, int off_y, void *userdata) { - stbtt__hheap hh = {0}; + stbtt__hheap hh = {}; stbtt__active_edge *active = NULL; int y, j = 0, i; float scanline_data[129], *scanline, *scanline2; diff --git a/examples/Tutorial/Tutorial.cpp b/examples/Tutorial/Tutorial.cpp index 85f14f6dc8..7fd3ecd733 100644 --- a/examples/Tutorial/Tutorial.cpp +++ b/examples/Tutorial/Tutorial.cpp @@ -388,7 +388,7 @@ class Tutorial : public CommonExampleInterface if (1) { - int width, height, n; + int width=0, height=0, n; const char* filename = "data/checker_huge.gif"; const unsigned char* image = 0; diff --git a/examples/Utils/b3Clock.cpp b/examples/Utils/b3Clock.cpp index 6d738a8cac..a405817ccf 100644 --- a/examples/Utils/b3Clock.cpp +++ b/examples/Utils/b3Clock.cpp @@ -89,7 +89,7 @@ void b3Clock::reset(bool zeroReference) #ifdef __CELLOS_LV2__ m_data->mStartTime = 0; #else - m_data->mStartTime = (struct timeval){0}; + m_data->mStartTime = timeval(); #endif #endif } diff --git a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3ContactConvexConvexSAT.h b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3ContactConvexConvexSAT.h index d7167bfa34..27675015d8 100644 --- a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3ContactConvexConvexSAT.h +++ b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3ContactConvexConvexSAT.h @@ -428,7 +428,7 @@ inline int b3ContactConvexConvexSAT( b3ConvexPolyhedronData hullA, hullB; - b3Float4 sepNormalWorldSpace; + b3Float4 sepNormalWorldSpace = {}; b3Collidable colA = collidables[collidableIndexA]; hullA = convexShapes[colA.m_shapeIndex]; diff --git a/src/Bullet3Common/b3Vector3.cpp b/src/Bullet3Common/b3Vector3.cpp index 100fb774c1..4123604a17 100644 --- a/src/Bullet3Common/b3Vector3.cpp +++ b/src/Bullet3Common/b3Vector3.cpp @@ -351,7 +351,7 @@ long b3_maxdot_large(const float *vv, const float *vec, unsigned long count, flo // process the last few points if (count & 3) { - float4 v0, v1, v2, x, y, z; + float4 v0, v1, v2, x = {}, y = {}, z = {}; switch (count & 3) { case 3: @@ -746,7 +746,7 @@ long b3_mindot_large(const float *vv, const float *vec, unsigned long count, flo // process the last few points if (count & 3) { - float4 v0, v1, v2, x, y, z; + float4 v0, v1, v2, x = {}, y = {}, z = {}; switch (count & 3) { case 3: diff --git a/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp b/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp index 37cf0f1621..b16e8a97de 100644 --- a/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp +++ b/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp @@ -615,7 +615,7 @@ cl_program b3OpenCLUtils_compileCLProgramFromString(cl_context clContext, cl_dev #ifdef _WIN32 //printf("searching for %s\n", binaryFileName); - FILETIME modtimeBinary; + FILETIME modtimeBinary = {}; CreateDirectoryA(sCachedBinaryPath, 0); { HANDLE binaryFileHandle = CreateFileA(binaryFileName, GENERIC_READ, 0, 0, OPEN_EXISTING, FILE_ATTRIBUTE_NORMAL, 0); @@ -673,7 +673,7 @@ cl_program b3OpenCLUtils_compileCLProgramFromString(cl_context clContext, cl_dev if (srcFileHandle != INVALID_HANDLE_VALUE) { - FILETIME modtimeSrc; + FILETIME modtimeSrc = {}; if (GetFileTime(srcFileHandle, NULL, NULL, &modtimeSrc) == 0) { DWORD errorCode; diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3OptimizedBvh.cpp b/src/Bullet3OpenCL/NarrowphaseCollision/b3OptimizedBvh.cpp index 4938fa17af..8a9223dd25 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3OptimizedBvh.cpp +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3OptimizedBvh.cpp @@ -292,7 +292,7 @@ void b3OptimizedBvh::updateBvhNodes(b3StridingMeshInterface* meshInterface, int for (int j = 2; j >= 0; j--) { - int graphicsindex; + int graphicsindex=0; switch (indicestype) { case PHY_INTEGER: graphicsindex = gfxbase[j]; break; case PHY_SHORT: graphicsindex = ((unsigned short*)gfxbase)[j]; break; diff --git a/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp b/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp index 9a35b571aa..858e54825b 100644 --- a/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp +++ b/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp @@ -186,6 +186,10 @@ void b3GpuRaycast::castRaysHost(const b3AlignedObjectArray& rays, b3A int hitBodyIndex = -1; b3Vector3 hitNormal; + hitNormal.m_floats[0] = 0.0f; + hitNormal.m_floats[1] = 0.0f; + hitNormal.m_floats[2] = 0.0f; + hitNormal.m_floats[3] = 0.0f; for (int b = 0; b < numBodies; b++) { diff --git a/src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.cpp b/src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.cpp index ac2e319beb..3364285620 100644 --- a/src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.cpp +++ b/src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.cpp @@ -361,7 +361,7 @@ void btGenerateInternalEdgeInfo(btBvhTriangleMeshShape* trimeshShape, btTriangle for (int j = 2; j >= 0; j--) { - int graphicsindex; + int graphicsindex = 0; switch (indicestype) { case PHY_INTEGER: graphicsindex = gfxbase[j]; break; case PHY_SHORT: graphicsindex = ((unsigned short*)gfxbase)[j]; break; diff --git a/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp b/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp index c66ce58e3e..4f001c5a5e 100644 --- a/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp +++ b/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp @@ -128,7 +128,7 @@ void btBvhTriangleMeshShape::performRaycast(btTriangleCallback* callback, const const btVector3& meshScaling = m_meshInterface->getScaling(); for (int j = 2; j >= 0; j--) { - int graphicsindex; + int graphicsindex=0; switch (indicestype) { case PHY_INTEGER: graphicsindex = gfxbase[j]; break; case PHY_SHORT: graphicsindex = ((unsigned short*)gfxbase)[j]; break; @@ -202,7 +202,7 @@ void btBvhTriangleMeshShape::performConvexcast(btTriangleCallback* callback, con const btVector3& meshScaling = m_meshInterface->getScaling(); for (int j = 2; j >= 0; j--) { - int graphicsindex; + int graphicsindex=0; switch (indicestype) { case PHY_INTEGER: graphicsindex = gfxbase[j]; break; case PHY_SHORT: graphicsindex = ((unsigned short*)gfxbase)[j]; break; diff --git a/src/BulletCollision/CollisionShapes/btMiniSDF.cpp b/src/BulletCollision/CollisionShapes/btMiniSDF.cpp index f79325abaf..e3377a61fc 100644 --- a/src/BulletCollision/CollisionShapes/btMiniSDF.cpp +++ b/src/BulletCollision/CollisionShapes/btMiniSDF.cpp @@ -47,7 +47,8 @@ bool btMiniSDF::load(const char* data, int size) btSdfDataStream ds(data, size); { double buf[6]; - ds.read(buf); + if(ds.read(buf)) + { m_domain.m_min[0] = buf[0]; m_domain.m_min[1] = buf[1]; m_domain.m_min[2] = buf[2]; @@ -56,42 +57,50 @@ bool btMiniSDF::load(const char* data, int size) m_domain.m_max[1] = buf[4]; m_domain.m_max[2] = buf[5]; m_domain.m_max[3] = 0; + } } { unsigned int buf2[3]; - ds.read(buf2); + if(ds.read(buf2)) + { m_resolution[0] = buf2[0]; m_resolution[1] = buf2[1]; m_resolution[2] = buf2[2]; + } } { double buf[3]; - ds.read(buf); + if(ds.read(buf)) + { m_cell_size[0] = buf[0]; m_cell_size[1] = buf[1]; m_cell_size[2] = buf[2]; + } } { double buf[3]; - ds.read(buf); + if(ds.read(buf)) + { m_inv_cell_size[0] = buf[0]; m_inv_cell_size[1] = buf[1]; m_inv_cell_size[2] = buf[2]; + } } { unsigned long long int cells; - ds.read(cells); - m_n_cells = cells; + if(ds.read(cells)) + m_n_cells = cells; } { unsigned long long int fields; - ds.read(fields); - m_n_fields = fields; + if(ds.read(fields)) + m_n_fields = fields; } unsigned long long int nodes0; std::size_t n_nodes0; - ds.read(nodes0); + if(ds.read(nodes0)) + { n_nodes0 = nodes0; if (n_nodes0 > 1024 * 1024 * 1024) { @@ -101,7 +110,8 @@ bool btMiniSDF::load(const char* data, int size) for (unsigned int i = 0; i < n_nodes0; i++) { unsigned long long int n_nodes1; - ds.read(n_nodes1); + if(ds.read(n_nodes1)) + { btAlignedObjectArray& nodes = m_nodes[i]; nodes.resize(n_nodes1); for (int j = 0; j < nodes.size(); j++) @@ -109,40 +119,50 @@ bool btMiniSDF::load(const char* data, int size) double& node = nodes[j]; ds.read(node); } + } + } } unsigned long long int n_cells0; - ds.read(n_cells0); + if(ds.read(n_cells0)) + { m_cells.resize(n_cells0); for (unsigned long long i = 0; i < n_cells0; i++) { unsigned long long int n_cells1; btAlignedObjectArray& cells = m_cells[i]; - ds.read(n_cells1); + if(ds.read(n_cells1)) + { cells.resize(n_cells1); for (unsigned long long j = 0; j < n_cells1; j++) { btCell32& cell = cells[j]; ds.read(cell); } + } + } } { unsigned long long int n_cell_maps0; - ds.read(n_cell_maps0); + if(ds.read(n_cell_maps0)) + { m_cell_map.resize(n_cell_maps0); for (unsigned long long i = 0; i < n_cell_maps0; i++) { unsigned long long int n_cell_maps1; btAlignedObjectArray& cell_maps = m_cell_map[i]; - ds.read(n_cell_maps1); + if(ds.read(n_cell_maps1)) + { cell_maps.resize(n_cell_maps1); for (unsigned long long j = 0; j < n_cell_maps1; j++) { unsigned int& cell_map = cell_maps[j]; ds.read(cell_map); } + } + } } } diff --git a/src/BulletCollision/CollisionShapes/btOptimizedBvh.cpp b/src/BulletCollision/CollisionShapes/btOptimizedBvh.cpp index 863ea6d6ac..3ff92781a7 100644 --- a/src/BulletCollision/CollisionShapes/btOptimizedBvh.cpp +++ b/src/BulletCollision/CollisionShapes/btOptimizedBvh.cpp @@ -293,7 +293,7 @@ void btOptimizedBvh::updateBvhNodes(btStridingMeshInterface* meshInterface, int for (int j = 2; j >= 0; j--) { - int graphicsindex; + int graphicsindex=0; switch (indicestype) { case PHY_INTEGER: graphicsindex = gfxbase[j]; break; case PHY_SHORT: graphicsindex = ((unsigned short*)gfxbase)[j]; break; diff --git a/src/BulletCollision/NarrowPhaseCollision/btMprPenetration.h b/src/BulletCollision/NarrowPhaseCollision/btMprPenetration.h index f5c9ae0b37..6c14ad43f1 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btMprPenetration.h +++ b/src/BulletCollision/NarrowPhaseCollision/btMprPenetration.h @@ -673,6 +673,7 @@ inline float btMprVec3PointTriDist2(const btVector3 *P, if (btMprIsZero(div)) { s = -1; + t = 0; } else { diff --git a/src/BulletDynamics/Character/btKinematicCharacterController.cpp b/src/BulletDynamics/Character/btKinematicCharacterController.cpp index 1a6991d8a5..8ff000d999 100644 --- a/src/BulletDynamics/Character/btKinematicCharacterController.cpp +++ b/src/BulletDynamics/Character/btKinematicCharacterController.cpp @@ -159,6 +159,9 @@ btKinematicCharacterController::btKinematicCharacterController(btPairCachingGhos bounce_fix = false; m_linearDamping = btScalar(0.0); m_angularDamping = btScalar(0.0); + m_halfHeight = 0.0; + m_maxJumpHeight = 0.0; + m_touchingContact = false; setUp(up); setStepHeight(stepHeight); diff --git a/src/BulletDynamics/Vehicle/btWheelInfo.h b/src/BulletDynamics/Vehicle/btWheelInfo.h index 68f61423de..e88b896760 100644 --- a/src/BulletDynamics/Vehicle/btWheelInfo.h +++ b/src/BulletDynamics/Vehicle/btWheelInfo.h @@ -102,6 +102,9 @@ struct btWheelInfo m_rollInfluence = btScalar(0.1); m_bIsFrontWheel = ci.m_bIsFrontWheel; m_maxSuspensionForce = ci.m_maxSuspensionForce; + + m_worldTransform.setIdentity(); + m_raycastInfo = RaycastInfo(); } void updateWheel(const btRigidBody& chassis, RaycastInfo& raycastInfo); diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp index 2455ed2138..0eb50f799e 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp @@ -219,7 +219,7 @@ void btDeformableBackwardEulerObjective::applyExplicitForce(TVStack& force) if (m_implicit) { // apply forces except gravity force - btVector3 gravity; + btVector3 gravity(btScalar(0),btScalar(0),btScalar(0)); for (int i = 0; i < m_lf.size(); ++i) { if (m_lf[i]->getForceType() == BT_GRAVITY_FORCE) diff --git a/src/BulletSoftBody/btSoftBody.cpp b/src/BulletSoftBody/btSoftBody.cpp index dd155f20f7..800a4fa51e 100644 --- a/src/BulletSoftBody/btSoftBody.cpp +++ b/src/BulletSoftBody/btSoftBody.cpp @@ -524,6 +524,9 @@ void btSoftBody::appendAnchor(int node, btRigidBody* body, const btVector3& loca a.m_local = localPivot; a.m_node->m_battach = 1; a.m_influence = influence; + a.m_c0.setZero(); + a.m_c1 = btVector3(btScalar(0),btScalar(0),btScalar(0)); + a.m_c2 = btScalar(0); m_anchors.push_back(a); } diff --git a/src/BulletSoftBody/btSoftBodyInternals.h b/src/BulletSoftBody/btSoftBodyInternals.h index d0de7952d2..e9d320d418 100644 --- a/src/BulletSoftBody/btSoftBodyInternals.h +++ b/src/BulletSoftBody/btSoftBodyInternals.h @@ -1882,7 +1882,7 @@ struct btSoftColliders } btVector3 o = node->m_x; - btVector3 p; + btVector3 p(btScalar(0),btScalar(0),btScalar(0)); btScalar d = SIMD_INFINITY; ProjectOrigin(face->m_n[0]->m_x - o, face->m_n[1]->m_x - o, diff --git a/src/LinearMath/TaskScheduler/btTaskScheduler.cpp b/src/LinearMath/TaskScheduler/btTaskScheduler.cpp index 2ef4ca0657..bfb674c3cb 100644 --- a/src/LinearMath/TaskScheduler/btTaskScheduler.cpp +++ b/src/LinearMath/TaskScheduler/btTaskScheduler.cpp @@ -5,6 +5,7 @@ #include "LinearMath/btQuickprof.h" #include #include +#include #if BT_THREADSAFE @@ -195,12 +196,13 @@ JobQueue { m_jobMem = NULL; m_jobMemSize = 0; + m_queueIsEmpty = true; m_threadSupport = NULL; m_queueLock = NULL; m_headIndex = 0; m_tailIndex = 0; m_useSpinMutex = false; - (void)m_cachePadding; + memset(&m_cachePadding,0,sizeof(m_cachePadding)); } ~JobQueue() { diff --git a/src/LinearMath/btHashMap.h b/src/LinearMath/btHashMap.h index 1fca0fb73a..528b12527f 100644 --- a/src/LinearMath/btHashMap.h +++ b/src/LinearMath/btHashMap.h @@ -66,7 +66,7 @@ class btHashInt int m_uid; public: - btHashInt() + btHashInt() : m_uid(0) { } diff --git a/src/LinearMath/btVector3.cpp b/src/LinearMath/btVector3.cpp index 55796c41e9..6c9fe077eb 100644 --- a/src/LinearMath/btVector3.cpp +++ b/src/LinearMath/btVector3.cpp @@ -356,7 +356,7 @@ long _maxdot_large(const float *vv, const float *vec, unsigned long count, float // process the last few points if (count & 3) { - float4 v0, v1, v2, x, y, z; + float4 v0, v1, v2, x = {}, y = {}, z = {}; switch (count & 3) { case 3: @@ -750,7 +750,7 @@ long _mindot_large(const float *vv, const float *vec, unsigned long count, float // process the last few points if (count & 3) { - float4 v0, v1, v2, x, y, z; + float4 v0, v1, v2, x = {}, y = {}, z = {}; switch (count & 3) { case 3: From 2f7f87463c0f77bd97606388a5bbad56f91f359a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 15:07:10 +0100 Subject: [PATCH 06/57] Compiler warnings - compare unsigned to negative --- Extras/ConvexDecomposition/cd_hull.cpp | 4 ++-- Extras/VHACD/inc/vhacdVolume.h | 14 +++++++------- Extras/VHACD/src/VHACD.cpp | 4 ---- examples/MultiThreading/b3PosixThreadSupport.cpp | 2 +- .../ParallelPrimitives/b3OpenCLArray.h | 1 - .../TaskScheduler/btThreadSupportPosix.cpp | 2 +- src/LinearMath/btConvexHull.cpp | 4 ++-- 7 files changed, 13 insertions(+), 18 deletions(-) diff --git a/Extras/ConvexDecomposition/cd_hull.cpp b/Extras/ConvexDecomposition/cd_hull.cpp index bd2680642d..2e4d5a525a 100644 --- a/Extras/ConvexDecomposition/cd_hull.cpp +++ b/Extras/ConvexDecomposition/cd_hull.cpp @@ -3346,7 +3346,7 @@ void HullLibrary::BringOutYourDead(const float *verts, unsigned int vcount, floa { unsigned int v = indices[i]; // original array index - assert(v >= 0 && v < vcount); + assert(v < vcount); if (used[v]) // if already remapped { @@ -3362,7 +3362,7 @@ void HullLibrary::BringOutYourDead(const float *verts, unsigned int vcount, floa ocount++; // increment output vert count - assert(ocount >= 0 && ocount <= vcount); + assert(ocount <= vcount); used[v] = ocount; // assign new index remapping } diff --git a/Extras/VHACD/inc/vhacdVolume.h b/Extras/VHACD/inc/vhacdVolume.h index 5254ca2616..11d28da4c9 100644 --- a/Extras/VHACD/inc/vhacdVolume.h +++ b/Extras/VHACD/inc/vhacdVolume.h @@ -226,16 +226,16 @@ class Volume const size_t dim, const Vec3& barycenter, const double (&rot)[3][3]); unsigned char& GetVoxel(const size_t i, const size_t j, const size_t k) { - assert(i < m_dim[0] || i >= 0); - assert(j < m_dim[0] || j >= 0); - assert(k < m_dim[0] || k >= 0); + assert(i < m_dim[0]); + assert(j < m_dim[0]); + assert(k < m_dim[0]); return m_data[i + j * m_dim[0] + k * m_dim[0] * m_dim[1]]; } const unsigned char& GetVoxel(const size_t i, const size_t j, const size_t k) const { - assert(i < m_dim[0] || i >= 0); - assert(j < m_dim[0] || j >= 0); - assert(k < m_dim[0] || k >= 0); + assert(i < m_dim[0]); + assert(j < m_dim[0]); + assert(k < m_dim[0]); return m_data[i + j * m_dim[0] + k * m_dim[0] * m_dim[1]]; } const size_t GetNPrimitivesOnSurf() const { return m_numVoxelsOnSurface; } @@ -373,7 +373,7 @@ void Volume::Voxelize(const T* const points, const unsigned int stridePoints, co i = static_cast(p[c][0] + 0.5); j = static_cast(p[c][1] + 0.5); k = static_cast(p[c][2] + 0.5); - assert(i < m_dim[0] && i >= 0 && j < m_dim[1] && j >= 0 && k < m_dim[2] && k >= 0); + assert(i < m_dim[0] && j < m_dim[1] && k < m_dim[2]); if (c == 0) { diff --git a/Extras/VHACD/src/VHACD.cpp b/Extras/VHACD/src/VHACD.cpp index 80644c7229..d5fc57134e 100644 --- a/Extras/VHACD/src/VHACD.cpp +++ b/Extras/VHACD/src/VHACD.cpp @@ -1460,8 +1460,6 @@ void VHACD::MergeConvexHulls(const Parameters& params) const size_t addrI = (static_cast(sqrt(nr)) - 1) >> 1; const size_t p1 = addrI + 1; const size_t p2 = addr - ((addrI * (addrI + 1)) >> 1); - assert(p1 >= 0); - assert(p2 >= 0); assert(p1 < costSize); assert(p2 < costSize); @@ -1500,7 +1498,6 @@ void VHACD::MergeConvexHulls(const Parameters& params) ComputeConvexHull(m_convexHulls[p2], m_convexHulls[i], pts, &combinedCH); costMatrix[rowIdx] = ComputeConcavity(volume1 + m_convexHulls[i]->ComputeVolume(), combinedCH.ComputeVolume(), m_volumeCH0); rowIdx += i; - assert(rowIdx >= 0); } // Move the top column in to replace its space @@ -1525,7 +1522,6 @@ void VHACD::MergeConvexHulls(const Parameters& params) { costMatrix[rowIdx] = costMatrix[top_row++]; rowIdx += i; - assert(rowIdx >= 0); } } costMatrix.Resize(erase_idx); diff --git a/examples/MultiThreading/b3PosixThreadSupport.cpp b/examples/MultiThreading/b3PosixThreadSupport.cpp index 0a66ac5ba1..54b22ef64a 100644 --- a/examples/MultiThreading/b3PosixThreadSupport.cpp +++ b/examples/MultiThreading/b3PosixThreadSupport.cpp @@ -210,7 +210,7 @@ void b3PosixThreadSupport::waitForResponse(int* puiArgument0, int* puiArgument1) spuStatus.m_status = 0; // need to find an active spu - b3Assert(last >= 0); + b3Assert(last != size_t(-1)); *puiArgument0 = spuStatus.m_taskId; *puiArgument1 = spuStatus.m_status; diff --git a/src/Bullet3OpenCL/ParallelPrimitives/b3OpenCLArray.h b/src/Bullet3OpenCL/ParallelPrimitives/b3OpenCLArray.h index e837cceb66..eb00a44c25 100644 --- a/src/Bullet3OpenCL/ParallelPrimitives/b3OpenCLArray.h +++ b/src/Bullet3OpenCL/ParallelPrimitives/b3OpenCLArray.h @@ -100,7 +100,6 @@ class b3OpenCLArray B3_FORCE_INLINE T at(size_t n) const { - b3Assert(n >= 0); b3Assert(n < size()); T elem; copyToHostPointer(&elem, 1, n, true); diff --git a/src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp b/src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp index d906fdcc45..e871570301 100644 --- a/src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp +++ b/src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp @@ -253,7 +253,7 @@ int btThreadSupportPosix::waitForResponse() threadStatus.m_status = 0; // need to find an active spu - btAssert(last >= 0); + btAssert(last != size_t(-1)); m_startedThreadsMask &= ~(UINT64(1) << last); return last; diff --git a/src/LinearMath/btConvexHull.cpp b/src/LinearMath/btConvexHull.cpp index 94b68baf54..58caa2bc52 100644 --- a/src/LinearMath/btConvexHull.cpp +++ b/src/LinearMath/btConvexHull.cpp @@ -1092,7 +1092,7 @@ void HullLibrary::BringOutYourDead(const btVector3 *verts, unsigned int vcount, { unsigned int v = indices[i]; // original array index - btAssert(v >= 0 && v < vcount); + btAssert(v < vcount); if (usedIndices[static_cast(v)]) // if already remapped { @@ -1114,7 +1114,7 @@ void HullLibrary::BringOutYourDead(const btVector3 *verts, unsigned int vcount, ocount++; // increment output vert count - btAssert(ocount >= 0 && ocount <= vcount); + btAssert(ocount <= vcount); usedIndices[static_cast(v)] = ocount; // assign new index remapping } From 4f19894d3805f5b6f0bc31cf327ceccbd388d473 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 15:08:35 +0100 Subject: [PATCH 07/57] Compiler warnings - memset non-trivial type --- Extras/HACD/hacdHACD.cpp | 2 +- Extras/Serialize/BulletFileLoader/bFile.cpp | 8 ++++---- Extras/VHACD/inc/vhacdSArray.h | 6 +++--- examples/OpenGLWindow/fontstash.cpp | 4 ++-- .../plugins/stablePDPlugin/BulletConversion.cpp | 2 +- src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.cpp | 2 +- src/Bullet3Serialize/Bullet2FileLoader/b3File.cpp | 8 ++++---- .../btSequentialImpulseConstraintSolver.cpp | 2 +- src/BulletSoftBody/btSoftBodyInternals.h | 2 +- 9 files changed, 18 insertions(+), 18 deletions(-) diff --git a/Extras/HACD/hacdHACD.cpp b/Extras/HACD/hacdHACD.cpp index d9347e0c2c..cd38a7018a 100644 --- a/Extras/HACD/hacdHACD.cpp +++ b/Extras/HACD/hacdHACD.cpp @@ -190,7 +190,7 @@ void HACD::InitializeDualGraph() m_facePoints = new Vec3[m_nTriangles]; m_faceNormals = new Vec3[m_nTriangles]; } - memset(m_normals, 0, sizeof(Vec3) * m_nPoints); + memset((void*)m_normals, 0, sizeof(Vec3) * m_nPoints); for (unsigned long f = 0; f < m_nTriangles; f++) { if (m_callBack) (*m_callBack)("+ InitializeDualGraph\n", f, m_nTriangles, 0); diff --git a/Extras/Serialize/BulletFileLoader/bFile.cpp b/Extras/Serialize/BulletFileLoader/bFile.cpp index 982a7b9b8f..98a418029f 100644 --- a/Extras/Serialize/BulletFileLoader/bFile.cpp +++ b/Extras/Serialize/BulletFileLoader/bFile.cpp @@ -1596,7 +1596,7 @@ int bFile::getNextBlock(bChunkInd *dataChunk, const char *dataPtr, const int fla SWITCH_INT(chunk.nr); } - memcpy(dataChunk, &chunk, sizeof(bChunkInd)); + memcpy((void*)dataChunk, &chunk, sizeof(bChunkInd)); } else { @@ -1613,7 +1613,7 @@ int bFile::getNextBlock(bChunkInd *dataChunk, const char *dataPtr, const int fla SWITCH_INT(c.nr); } - memcpy(dataChunk, &c, sizeof(bChunkInd)); + memcpy((void*)dataChunk, &c, sizeof(bChunkInd)); } } else @@ -1653,7 +1653,7 @@ int bFile::getNextBlock(bChunkInd *dataChunk, const char *dataPtr, const int fla SWITCH_INT(chunk.nr); } - memcpy(dataChunk, &chunk, sizeof(bChunkInd)); + memcpy((void*)dataChunk, &chunk, sizeof(bChunkInd)); } else { @@ -1669,7 +1669,7 @@ int bFile::getNextBlock(bChunkInd *dataChunk, const char *dataPtr, const int fla SWITCH_INT(c.dna_nr); SWITCH_INT(c.nr); } - memcpy(dataChunk, &c, sizeof(bChunkInd)); + memcpy((void*)dataChunk, &c, sizeof(bChunkInd)); } } diff --git a/Extras/VHACD/inc/vhacdSArray.h b/Extras/VHACD/inc/vhacdSArray.h index 22a6a9dadc..431f4da4f2 100644 --- a/Extras/VHACD/inc/vhacdSArray.h +++ b/Extras/VHACD/inc/vhacdSArray.h @@ -66,7 +66,7 @@ class SArray if (size > m_maxSize) { T* temp = new T[size]; - memcpy(temp, Data(), m_size * sizeof(T)); + memcpy((void*)temp, Data(), m_size * sizeof(T)); delete[] m_data; m_data = temp; m_maxSize = size; @@ -84,7 +84,7 @@ class SArray { size_t maxSize = (m_maxSize << 1); T* temp = new T[maxSize]; - memcpy(temp, Data(), m_maxSize * sizeof(T)); + memcpy((void*)temp, Data(), m_maxSize * sizeof(T)); delete[] m_data; m_data = temp; m_maxSize = maxSize; @@ -130,7 +130,7 @@ class SArray m_data = new T[m_maxSize]; } m_size = rhs.m_size; - memcpy(Data(), rhs.Data(), m_size * sizeof(T)); + memcpy((void*)Data(), rhs.Data(), m_size * sizeof(T)); } void Initialize() { diff --git a/examples/OpenGLWindow/fontstash.cpp b/examples/OpenGLWindow/fontstash.cpp index 7b1f6cde60..0881f02a0a 100644 --- a/examples/OpenGLWindow/fontstash.cpp +++ b/examples/OpenGLWindow/fontstash.cpp @@ -137,7 +137,7 @@ struct sth_stash* sth_create(int cachew, int cacheh, RenderCallbacks* renderCall assert(0); free(stash); } - memset(texture, 0, sizeof(struct sth_texture)); + memset((void*)texture, 0, sizeof(struct sth_texture)); // Create first texture for the cache. stash->tw = cachew; @@ -405,7 +405,7 @@ static struct sth_glyph* get_glyph(struct sth_stash* stash, struct sth_font* fnt texture->next = (struct sth_texture*)malloc(sizeof(struct sth_texture)); texture = texture->next; if (texture == NULL) goto error; - memset(texture, 0, sizeof(struct sth_texture)); + memset((void*)texture, 0, sizeof(struct sth_texture)); stash->m_renderCallbacks->updateTexture(texture, 0, stash->tw, stash->th); } diff --git a/examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp b/examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp index dd763e3bad..5438c1417d 100644 --- a/examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp +++ b/examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp @@ -301,7 +301,7 @@ void btExtractJointBodyFromBullet(const btMultiBody* bulletMB, Eigen::MatrixXd& links.resize(bulletMB->getNumLinks() + baseLink); for (int i = 0; i < links.size(); i++) { - memset(&links[i], 0xffffffff, sizeof(TempLink)); + memset((void*)&links[i], 0xffffffff, sizeof(TempLink)); } int totalDofs = 0; diff --git a/src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.cpp b/src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.cpp index 3316491536..3ab919bf95 100644 --- a/src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.cpp +++ b/src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.cpp @@ -21,7 +21,7 @@ b3GpuNarrowPhase::b3GpuNarrowPhase(cl_context ctx, cl_device_id device, cl_comma m_data = new b3GpuNarrowPhaseInternalData(); m_data->m_currentContactBuffer = 0; - memset(m_data, 0, sizeof(b3GpuNarrowPhaseInternalData)); + memset((void*)m_data, 0, sizeof(b3GpuNarrowPhaseInternalData)); m_data->m_config = config; diff --git a/src/Bullet3Serialize/Bullet2FileLoader/b3File.cpp b/src/Bullet3Serialize/Bullet2FileLoader/b3File.cpp index 2e0f5a32f7..f3d22cac11 100644 --- a/src/Bullet3Serialize/Bullet2FileLoader/b3File.cpp +++ b/src/Bullet3Serialize/Bullet2FileLoader/b3File.cpp @@ -1562,7 +1562,7 @@ int bFile::getNextBlock(bChunkInd *dataChunk, const char *dataPtr, const int fla B3_SWITCH_INT(chunk.nr); } - memcpy(dataChunk, &chunk, sizeof(bChunkInd)); + memcpy((void*)dataChunk, &chunk, sizeof(bChunkInd)); } else { @@ -1579,7 +1579,7 @@ int bFile::getNextBlock(bChunkInd *dataChunk, const char *dataPtr, const int fla B3_SWITCH_INT(c.nr); } - memcpy(dataChunk, &c, sizeof(bChunkInd)); + memcpy((void*)dataChunk, &c, sizeof(bChunkInd)); } } else @@ -1619,7 +1619,7 @@ int bFile::getNextBlock(bChunkInd *dataChunk, const char *dataPtr, const int fla B3_SWITCH_INT(chunk.nr); } - memcpy(dataChunk, &chunk, sizeof(bChunkInd)); + memcpy((void*)dataChunk, &chunk, sizeof(bChunkInd)); } else { @@ -1635,7 +1635,7 @@ int bFile::getNextBlock(bChunkInd *dataChunk, const char *dataPtr, const int fla B3_SWITCH_INT(c.dna_nr); B3_SWITCH_INT(c.nr); } - memcpy(dataChunk, &c, sizeof(bChunkInd)); + memcpy((void*)dataChunk, &c, sizeof(bChunkInd)); } } diff --git a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp index c24feeeca4..21b59c3d75 100644 --- a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp +++ b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp @@ -1176,7 +1176,7 @@ void btSequentialImpulseConstraintSolver::convertJoint(btSolverConstraint* curre for (int j = 0; j < info1.m_numConstraintRows; j++) { - memset(¤tConstraintRow[j], 0, sizeof(btSolverConstraint)); + memset((void*)¤tConstraintRow[j], 0, sizeof(btSolverConstraint)); currentConstraintRow[j].m_lowerLimit = -SIMD_INFINITY; currentConstraintRow[j].m_upperLimit = SIMD_INFINITY; currentConstraintRow[j].m_appliedImpulse = 0.f; diff --git a/src/BulletSoftBody/btSoftBodyInternals.h b/src/BulletSoftBody/btSoftBodyInternals.h index e9d320d418..74cf977c96 100644 --- a/src/BulletSoftBody/btSoftBodyInternals.h +++ b/src/BulletSoftBody/btSoftBodyInternals.h @@ -788,7 +788,7 @@ class btSoftClusterCollisionShape : public btConvexInternalShape template static inline void ZeroInitialize(T& value) { - memset(&value, 0, sizeof(T)); + memset((void*)&value, 0, sizeof(T)); } // template From 76318baac828c4e05b461781b642bc3a48881598 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 15:09:00 +0100 Subject: [PATCH 08/57] Compiler warnings - unreachable code --- .../Internal/RealTimeBullet3CollisionSdk.cpp | 4 +--- examples/OpenGLWindow/LoadShader.cpp | 12 ++++++------ .../ConstraintSolver/btHingeConstraint.cpp | 2 -- .../details/MultiBodyTreeImpl.cpp | 2 +- src/BulletSoftBody/btSoftBodyInternals.h | 18 +++++++++--------- .../InverseDynamics/test_invdyn_kinematics.cpp | 2 +- 6 files changed, 18 insertions(+), 22 deletions(-) diff --git a/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp b/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp index 44cd49ca7e..4d69ff2d7d 100644 --- a/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp +++ b/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp @@ -446,10 +446,8 @@ int RealTimeBullet3CollisionSdk::collide(plCollisionWorldHandle worldHandle, plC // [world->m_childShapes[colB.m_shapeIndex+j].m_shapeType](world,colAIndex,colA.m_shapeIndex+i,colBIndex,colB.m_shapeIndex+j,&contactCache); } } - return contactCache.numAddedPoints; } - - return 0; + return contactCache.numAddedPoints; } void RealTimeBullet3CollisionSdk::collideWorld(plCollisionWorldHandle worldHandle, diff --git a/examples/OpenGLWindow/LoadShader.cpp b/examples/OpenGLWindow/LoadShader.cpp index 4766d13830..f1bdc87784 100644 --- a/examples/OpenGLWindow/LoadShader.cpp +++ b/examples/OpenGLWindow/LoadShader.cpp @@ -42,9 +42,9 @@ GLuint gltLoadShaderPair(const char *szVertexProg, const char *szFragmentProg) fprintf(stderr, "Compile failed:\n%s\n", temp); assert(0); return 0; - glDeleteShader(hVertexShader); - glDeleteShader(hFragmentShader); - return (GLuint)0; + // glDeleteShader(hVertexShader); + // glDeleteShader(hFragmentShader); + // return (GLuint)0; } assert(glGetError() == GL_NO_ERROR); @@ -60,9 +60,9 @@ GLuint gltLoadShaderPair(const char *szVertexProg, const char *szFragmentProg) fprintf(stderr, "Compile failed:\n%s\n", temp); assert(0); exit(EXIT_FAILURE); - glDeleteShader(hVertexShader); - glDeleteShader(hFragmentShader); - return (GLuint)0; + // glDeleteShader(hVertexShader); + // glDeleteShader(hFragmentShader); + // return (GLuint)0; } assert(glGetError() == GL_NO_ERROR); diff --git a/src/BulletDynamics/ConstraintSolver/btHingeConstraint.cpp b/src/BulletDynamics/ConstraintSolver/btHingeConstraint.cpp index cb59e5a5b5..2fc986c751 100644 --- a/src/BulletDynamics/ConstraintSolver/btHingeConstraint.cpp +++ b/src/BulletDynamics/ConstraintSolver/btHingeConstraint.cpp @@ -308,8 +308,6 @@ static btScalar btShortestAngleUpdate(btScalar accAngle, btScalar curAngle) return curAngle; else return accAngle + result; - - return curAngle; } btScalar btHingeAccumulatedAngleConstraint::getAccumulatedHingeAngle() diff --git a/src/BulletInverseDynamics/details/MultiBodyTreeImpl.cpp b/src/BulletInverseDynamics/details/MultiBodyTreeImpl.cpp index ec9a562295..97aecc3f82 100644 --- a/src/BulletInverseDynamics/details/MultiBodyTreeImpl.cpp +++ b/src/BulletInverseDynamics/details/MultiBodyTreeImpl.cpp @@ -766,7 +766,7 @@ static inline int jointNumDoFs(const JointType &type) bt_id_error_message("invalid joint type\n"); // TODO add configurable abort/crash function abort(); - return 0; + // return 0; } int MultiBodyTree::MultiBodyImpl::calculateMassMatrix(const vecx &q, const bool update_kinematics, diff --git a/src/BulletSoftBody/btSoftBodyInternals.h b/src/BulletSoftBody/btSoftBodyInternals.h index 74cf977c96..99e5c436f4 100644 --- a/src/BulletSoftBody/btSoftBodyInternals.h +++ b/src/BulletSoftBody/btSoftBodyInternals.h @@ -496,7 +496,7 @@ static SIMD_FORCE_INLINE bool coplanarAndInsideTest(const btScalar& k0, const bt // inside test return signDetermination1(k0, k1, k2, k3, face, node, dt); } - return false; + // return false; } static SIMD_FORCE_INLINE bool conservativeCulling(const btScalar& k0, const btScalar& k1, const btScalar& k2, const btScalar& k3, const btScalar& mrg) { @@ -530,14 +530,14 @@ static SIMD_FORCE_INLINE bool bernsteinVFTest(const btSoftBody::Face* face, cons if (conservativeCulling(k0, k1, k2, k3, mrg)) return false; return true; - if (diffSign(k2 - 2.0 * k1 + k0, k3 - 2.0 * k2 + k1)) - { - btScalar k10, k20, k30, k21, k12; - btScalar t0 = (k2 - 2.0 * k1 + k0) / (k0 - 3.0 * k1 + 3.0 * k2 - k3); - deCasteljau(k0, k1, k2, k3, t0, k10, k20, k30, k21, k12); - return bernsteinVFTest(k0, k10, k20, k30, mrg, face, node, dt) || bernsteinVFTest(k30, k21, k12, k3, mrg, face, node, dt); - } - return coplanarAndInsideTest(k0, k1, k2, k3, face, node, dt); + // if (diffSign(k2 - 2.0 * k1 + k0, k3 - 2.0 * k2 + k1)) + // { + // btScalar k10, k20, k30, k21, k12; + // btScalar t0 = (k2 - 2.0 * k1 + k0) / (k0 - 3.0 * k1 + 3.0 * k2 - k3); + // deCasteljau(k0, k1, k2, k3, t0, k10, k20, k30, k21, k12); + // return bernsteinVFTest(k0, k10, k20, k30, mrg, face, node, dt) || bernsteinVFTest(k30, k21, k12, k3, mrg, face, node, dt); + // } + // return coplanarAndInsideTest(k0, k1, k2, k3, face, node, dt); } static SIMD_FORCE_INLINE bool continuousCollisionDetection(const btSoftBody::Face* face, const btSoftBody::Node* node, const btScalar& dt, const btScalar& mrg, btVector3& bary) diff --git a/test/InverseDynamics/test_invdyn_kinematics.cpp b/test/InverseDynamics/test_invdyn_kinematics.cpp index cf52ec65a9..a6eb36217d 100644 --- a/test/InverseDynamics/test_invdyn_kinematics.cpp +++ b/test/InverseDynamics/test_invdyn_kinematics.cpp @@ -400,5 +400,5 @@ int main(int argc, char** argv) ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); - return EXIT_SUCCESS; + // return EXIT_SUCCESS; } From 1e38009927e6b4d8137d9e950a029072b62ed9c3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 22:31:54 +0100 Subject: [PATCH 09/57] Compiler warnings - unreachable code (bugfix) --- examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp index c21fc698e8..25c3a0d9a1 100644 --- a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp +++ b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp @@ -1595,8 +1595,8 @@ bool BulletMJCFImporter::getLinkColor2(int linkIndex, struct UrdfMaterialColor& { matCol = link->m_collisionArray[0].m_geometry.m_localMaterial.m_matColor; hasLinkColor = true; + break; } - break; } } } From 1c8b39e40c6ca63a6bb02e49463d20529394cbb4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 15:09:42 +0100 Subject: [PATCH 10/57] Compiler warnings - compare instead of assignment in asserts (bugfix) --- examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp | 2 +- examples/SharedMemory/PhysicsClientC_API.cpp | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp b/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp index 20cd94d15a..5d2bee2a94 100644 --- a/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp +++ b/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp @@ -644,7 +644,7 @@ void SimpleOpenGL2Renderer::updateShape(int shapeIndex, const float* vertices, i { SimpleGL2Shape* shape = m_data->m_shapes[shapeIndex]; int numvertices = shape->m_vertices.size(); - b3Assert(numVertices = numvertices); + b3Assert(numVertices == numvertices); if (numVertices != numvertices) return; diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index ca68efb43e..631a2e4c33 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -6042,7 +6042,7 @@ B3_SHARED_API int b3StateLoggingSetLinkIndexA(b3SharedMemoryCommandHandle comman { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; b3Assert(command); - b3Assert(command->m_type = CMD_STATE_LOGGING); + b3Assert(command->m_type == CMD_STATE_LOGGING); if (command->m_type == CMD_STATE_LOGGING) { command->m_updateFlags |= STATE_LOGGING_FILTER_LINK_INDEX_A; @@ -6055,7 +6055,7 @@ B3_SHARED_API int b3StateLoggingSetLinkIndexB(b3SharedMemoryCommandHandle comman { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; b3Assert(command); - b3Assert(command->m_type = CMD_STATE_LOGGING); + b3Assert(command->m_type == CMD_STATE_LOGGING); if (command->m_type == CMD_STATE_LOGGING) { command->m_updateFlags |= STATE_LOGGING_FILTER_LINK_INDEX_B; @@ -6068,7 +6068,7 @@ B3_SHARED_API int b3StateLoggingSetBodyAUniqueId(b3SharedMemoryCommandHandle com { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; b3Assert(command); - b3Assert(command->m_type = CMD_STATE_LOGGING); + b3Assert(command->m_type == CMD_STATE_LOGGING); if (command->m_type == CMD_STATE_LOGGING) { command->m_updateFlags |= STATE_LOGGING_FILTER_BODY_UNIQUE_ID_A; @@ -6081,7 +6081,7 @@ B3_SHARED_API int b3StateLoggingSetBodyBUniqueId(b3SharedMemoryCommandHandle com { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; b3Assert(command); - b3Assert(command->m_type = CMD_STATE_LOGGING); + b3Assert(command->m_type == CMD_STATE_LOGGING); if (command->m_type == CMD_STATE_LOGGING) { command->m_updateFlags |= STATE_LOGGING_FILTER_BODY_UNIQUE_ID_B; From eadc0fc711fa254285183b038ce07cbf1e85de58 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Thu, 11 Apr 2024 20:03:11 +0200 Subject: [PATCH 11/57] Compiler warnings - scoped variables hides other (bugfix) --- .../ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp index fafa28ab78..06f1d39923 100644 --- a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp +++ b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp @@ -905,7 +905,6 @@ void btSequentialImpulseConstraintSolverMt::solveGroupCacheFriendlySplitImpulseI { const btBatchedConstraints& batchedCons = m_batchedContactConstraints; ContactSplitPenetrationImpulseSolverLoop loop(this, &batchedCons); - btScalar leastSquaresResidual = 0.f; for (int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase) { int iPhase = batchedCons.m_phaseOrder[iiPhase]; @@ -1408,7 +1407,6 @@ btScalar btSequentialImpulseConstraintSolverMt::resolveAllRollingFrictionConstra // use batching if there are many rolling friction constraints const btBatchedConstraints& batchedCons = m_batchedContactConstraints; ContactRollingFrictionSolverLoop loop(this, &batchedCons); - btScalar leastSquaresResidual = 0.f; for (int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase) { int iPhase = batchedCons.m_phaseOrder[iiPhase]; From dd60def61c5d5ec3a88fe5563c8017643d3d35d3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 15:16:26 +0100 Subject: [PATCH 12/57] Compiler warnings - MinGW MSVC and macro redefinition --- Extras/ConvexDecomposition/cd_vector.h | 2 ++ Extras/ConvexDecomposition/float_math.h | 2 +- Extras/ConvexDecomposition/vlookup.cpp | 2 ++ Extras/VHACD/inc/vhacdMutex.h | 2 +- Extras/VHACD/src/VHACD.cpp | 2 ++ Extras/VHACD/src/vhacdMesh.cpp | 2 ++ Extras/VHACD/src/vhacdVolume.cpp | 2 ++ Extras/VHACD/test/src/main_vhacd.cpp | 2 ++ examples/SharedMemory/PhysicsClientTCP.cpp | 3 +-- examples/SharedMemory/RemoteGUIHelperTCP.cpp | 3 ++- examples/StandaloneMain/hellovr_opengl_main.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Platforms/Windows.cpp | 2 ++ src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp | 2 +- src/Bullet3OpenCL/ParallelPrimitives/b3LauncherCL.h | 2 +- src/LinearMath/btThreads.h | 8 ++++---- 15 files changed, 26 insertions(+), 12 deletions(-) diff --git a/Extras/ConvexDecomposition/cd_vector.h b/Extras/ConvexDecomposition/cd_vector.h index 6d46b2f3ec..b1d4b4ea90 100644 --- a/Extras/ConvexDecomposition/cd_vector.h +++ b/Extras/ConvexDecomposition/cd_vector.h @@ -36,7 +36,9 @@ // http://www.amillionpixels.us // +#if _MSC_VER #pragma warning(disable : 4786) +#endif #include #include diff --git a/Extras/ConvexDecomposition/float_math.h b/Extras/ConvexDecomposition/float_math.h index b23280011a..241cee81e4 100644 --- a/Extras/ConvexDecomposition/float_math.h +++ b/Extras/ConvexDecomposition/float_math.h @@ -2,7 +2,7 @@ #define FLOAT_MATH_H -#ifdef _WIN32 +#ifdef _MSC_VER #pragma warning(disable : 4324) // disable padding warning #pragma warning(disable : 4244) // disable padding warning #pragma warning(disable : 4267) // possible loss of data diff --git a/Extras/ConvexDecomposition/vlookup.cpp b/Extras/ConvexDecomposition/vlookup.cpp index ee181342e5..4e25ab4460 100644 --- a/Extras/ConvexDecomposition/vlookup.cpp +++ b/Extras/ConvexDecomposition/vlookup.cpp @@ -4,7 +4,9 @@ #include #include +#if _MSC_VER #pragma warning(disable : 4786) +#endif #include #include diff --git a/Extras/VHACD/inc/vhacdMutex.h b/Extras/VHACD/inc/vhacdMutex.h index bfd5720256..41bf139788 100644 --- a/Extras/VHACD/inc/vhacdMutex.h +++ b/Extras/VHACD/inc/vhacdMutex.h @@ -50,7 +50,7 @@ #ifndef VHACD_MUTEX_H #define VHACD_MUTEX_H -#if defined(WIN32) +#if defined(_MSC_VER) //#define _WIN32_WINNT 0x400 #include diff --git a/Extras/VHACD/src/VHACD.cpp b/Extras/VHACD/src/VHACD.cpp index d5fc57134e..37dca26383 100644 --- a/Extras/VHACD/src/VHACD.cpp +++ b/Extras/VHACD/src/VHACD.cpp @@ -13,7 +13,9 @@ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ +#ifndef _CRT_SECURE_NO_WARNINGS #define _CRT_SECURE_NO_WARNINGS +#endif #include #include diff --git a/Extras/VHACD/src/vhacdMesh.cpp b/Extras/VHACD/src/vhacdMesh.cpp index 90833ac570..4f5816f527 100644 --- a/Extras/VHACD/src/vhacdMesh.cpp +++ b/Extras/VHACD/src/vhacdMesh.cpp @@ -12,7 +12,9 @@ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ +#ifndef _CRT_SECURE_NO_WARNINGS #define _CRT_SECURE_NO_WARNINGS +#endif #include "LinearMath/btConvexHullComputer.h" #include "vhacdMesh.h" diff --git a/Extras/VHACD/src/vhacdVolume.cpp b/Extras/VHACD/src/vhacdVolume.cpp index 23627c225e..da6f8a9afc 100644 --- a/Extras/VHACD/src/vhacdVolume.cpp +++ b/Extras/VHACD/src/vhacdVolume.cpp @@ -12,7 +12,9 @@ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ +#ifndef _CRT_SECURE_NO_WARNINGS #define _CRT_SECURE_NO_WARNINGS +#endif #include "LinearMath/btConvexHullComputer.h" #include "vhacdVolume.h" #include diff --git a/Extras/VHACD/test/src/main_vhacd.cpp b/Extras/VHACD/test/src/main_vhacd.cpp index ad37a79395..59e0de43c9 100644 --- a/Extras/VHACD/test/src/main_vhacd.cpp +++ b/Extras/VHACD/test/src/main_vhacd.cpp @@ -13,7 +13,9 @@ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ +#ifndef _CRT_SECURE_NO_WARNINGS #define _CRT_SECURE_NO_WARNINGS +#endif #include #include #include diff --git a/examples/SharedMemory/PhysicsClientTCP.cpp b/examples/SharedMemory/PhysicsClientTCP.cpp index 416a962280..b9c2893711 100644 --- a/examples/SharedMemory/PhysicsClientTCP.cpp +++ b/examples/SharedMemory/PhysicsClientTCP.cpp @@ -1,7 +1,5 @@ #include "PhysicsClientTCP.h" -#include "ActiveSocket.h" - #include #include #include "../Utils/b3Clock.h" @@ -11,6 +9,7 @@ #include #include "Bullet3Common/b3Logging.h" #include "Bullet3Common/b3AlignedObjectArray.h" +#include "ActiveSocket.h" unsigned int b3DeserializeInt2(const unsigned char* input) { diff --git a/examples/SharedMemory/RemoteGUIHelperTCP.cpp b/examples/SharedMemory/RemoteGUIHelperTCP.cpp index 09bca39bbe..8ec84f9ca1 100644 --- a/examples/SharedMemory/RemoteGUIHelperTCP.cpp +++ b/examples/SharedMemory/RemoteGUIHelperTCP.cpp @@ -14,8 +14,9 @@ #include "Bullet3Common/b3AlignedObjectArray.h" #include "BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h" -#include "ActiveSocket.h" #include +#include "ActiveSocket.h" + static unsigned int b3DeserializeInt3(const unsigned char* input) { unsigned int tmp = (input[3] << 24) + (input[2] << 16) + (input[1] << 8) + input[0]; diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index f9bde93bf6..e5744ef538 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -38,8 +38,8 @@ static int maxShapeCapacityInBytes = 128 * 1024 * 1024; #include #include -#include "strtools.h" #include "compat.h" +#include "strtools.h" #include "lodepng.h" #include "Matrices.h" #include "pathtools.h" diff --git a/examples/ThirdPartyLibs/Gwen/Platforms/Windows.cpp b/examples/ThirdPartyLibs/Gwen/Platforms/Windows.cpp index b5aa34946e..9510bc49e2 100644 --- a/examples/ThirdPartyLibs/Gwen/Platforms/Windows.cpp +++ b/examples/ThirdPartyLibs/Gwen/Platforms/Windows.cpp @@ -12,7 +12,9 @@ #include #include +#if _MSC_VER #pragma comment(lib, "winmm.lib") +#endif using namespace Gwen; using namespace Gwen::Platform; diff --git a/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp b/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp index b16e8a97de..c9613ef012 100644 --- a/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp +++ b/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp @@ -23,7 +23,7 @@ bool gDebugSkipLoadingBinary = false; #include -#ifdef _WIN32 +#ifdef _MSC_VER #pragma warning(disable : 4996) #endif #include "b3OpenCLUtils.h" diff --git a/src/Bullet3OpenCL/ParallelPrimitives/b3LauncherCL.h b/src/Bullet3OpenCL/ParallelPrimitives/b3LauncherCL.h index 18e9c1db2b..2690576a94 100644 --- a/src/Bullet3OpenCL/ParallelPrimitives/b3LauncherCL.h +++ b/src/Bullet3OpenCL/ParallelPrimitives/b3LauncherCL.h @@ -9,7 +9,7 @@ #define B3_DEBUG_SERIALIZE_CL -#ifdef _WIN32 +#ifdef _MSC_VER #pragma warning(disable : 4996) #endif #define B3_CL_MAX_ARG_SIZE 16 diff --git a/src/LinearMath/btThreads.h b/src/LinearMath/btThreads.h index b2227e1724..d83eb51b1f 100644 --- a/src/LinearMath/btThreads.h +++ b/src/LinearMath/btThreads.h @@ -17,7 +17,7 @@ subject to the following restrictions: #include "btScalar.h" // has definitions like SIMD_FORCE_INLINE -#if defined(_MSC_VER) && _MSC_VER >= 1600 +#if (defined(_MSC_VER) && _MSC_VER >= 1600) || defined(__clang__) // give us a compile error if any signatures of overriden methods is changed #define BT_OVERRIDE override #endif @@ -69,7 +69,7 @@ class btSpinMutex // SIMD_FORCE_INLINE void btMutexLock(btSpinMutex* mutex) { -#if BT_THREADSAFE +#if defined(BT_THREADSAFE) && BT_THREADSAFE!=0 mutex->lock(); #else (void)mutex; @@ -78,7 +78,7 @@ SIMD_FORCE_INLINE void btMutexLock(btSpinMutex* mutex) SIMD_FORCE_INLINE void btMutexUnlock(btSpinMutex* mutex) { -#if BT_THREADSAFE +#if defined(BT_THREADSAFE) && BT_THREADSAFE!=0 mutex->unlock(); #else (void)mutex; @@ -87,7 +87,7 @@ SIMD_FORCE_INLINE void btMutexUnlock(btSpinMutex* mutex) SIMD_FORCE_INLINE bool btMutexTryLock(btSpinMutex* mutex) { -#if BT_THREADSAFE +#if defined(BT_THREADSAFE) && BT_THREADSAFE!=0 return mutex->tryLock(); #else (void)mutex; From 516800b2f5b13b89b29e9385f2347789a7915b44 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 16:05:56 +0100 Subject: [PATCH 13/57] Compiler warnings - constant expression in conditional statement --- examples/SharedMemory/PhysicsServerCommandProcessor.cpp | 3 ++- src/Bullet3Serialize/Bullet2FileLoader/b3Serializer.h | 3 ++- src/LinearMath/btImplicitQRSVD.h | 3 ++- src/LinearMath/btSerializer.h | 3 ++- 4 files changed, 8 insertions(+), 4 deletions(-) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index f832bfc248..2d614eebe8 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -410,7 +410,8 @@ struct CommandLogger int littleEndian = 1; littleEndian = ((char*)&littleEndian)[0]; - if (sizeof(void*) == 8) + const bool is64bitSystem = sizeof(void*) == 8; + if (is64bitSystem) { buffer[7] = '-'; } diff --git a/src/Bullet3Serialize/Bullet2FileLoader/b3Serializer.h b/src/Bullet3Serialize/Bullet2FileLoader/b3Serializer.h index 448e4e07f4..8edf1e2439 100644 --- a/src/Bullet3Serialize/Bullet2FileLoader/b3Serializer.h +++ b/src/Bullet3Serialize/Bullet2FileLoader/b3Serializer.h @@ -393,7 +393,8 @@ class b3DefaultSerializer : public b3Serializer int littleEndian = 1; littleEndian = ((char*)&littleEndian)[0]; - if (sizeof(void*) == 8) + const bool is64bitSystem = sizeof(void*) == 8; + if (is64bitSystem) { buffer[7] = '-'; } diff --git a/src/LinearMath/btImplicitQRSVD.h b/src/LinearMath/btImplicitQRSVD.h index 48e24cf515..16200123fe 100644 --- a/src/LinearMath/btImplicitQRSVD.h +++ b/src/LinearMath/btImplicitQRSVD.h @@ -599,7 +599,8 @@ inline void process(btMatrix3x3& B, btMatrix3x3& U, btVector3& sigma, btMatrix3x sigma[other] = B[other][other]; btMatrix2x2 B_sub, sigma_sub; - if (t == 0) + const bool isZero = t == 0; + if (isZero) { B_sub.m_00 = B[0][0]; B_sub.m_10 = B[1][0]; diff --git a/src/LinearMath/btSerializer.h b/src/LinearMath/btSerializer.h index e0cdbd7d14..ed5e320eca 100644 --- a/src/LinearMath/btSerializer.h +++ b/src/LinearMath/btSerializer.h @@ -461,7 +461,8 @@ class btDefaultSerializer : public btSerializer int littleEndian = 1; littleEndian = ((char*)&littleEndian)[0]; - if (sizeof(void*) == 8) + const bool is64BitSystem = ((sizeof(void*) == 8)); + if (is64BitSystem) { buffer[7] = '-'; } From 74d576ced95a023a24ac528e8c7596fd52c94436 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 15:19:31 +0100 Subject: [PATCH 14/57] Compiler warnings - assign in conditional statement --- Extras/HACD/hacdICHull.cpp | 3 ++- examples/Heightfield/HeightfieldExample.cpp | 4 ++-- examples/SharedMemory/PhysicsServerCommandProcessor.cpp | 2 +- 3 files changed, 5 insertions(+), 4 deletions(-) diff --git a/Extras/HACD/hacdICHull.cpp b/Extras/HACD/hacdICHull.cpp index 16796296e9..5181997ab1 100644 --- a/Extras/HACD/hacdICHull.cpp +++ b/Extras/HACD/hacdICHull.cpp @@ -491,7 +491,8 @@ CircularListElement *ICHull::MakeConeFace(CircularListElement *newEdges[2]; for (int i = 0; i < 2; ++i) { - if (!(newEdges[i] = e->GetData().m_vertices[i]->GetData().m_duplicate)) + newEdges[i] = e->GetData().m_vertices[i]->GetData().m_duplicate; + if (!newEdges[i]) { // if the edge doesn't exits add it and mark the vertex as duplicated newEdges[i] = m_mesh.AddEdge(); newEdges[i]->GetData().m_vertices[0] = e->GetData().m_vertices[i]; diff --git a/examples/Heightfield/HeightfieldExample.cpp b/examples/Heightfield/HeightfieldExample.cpp index a2f75aaa0b..ac9cbcac3d 100644 --- a/examples/Heightfield/HeightfieldExample.cpp +++ b/examples/Heightfield/HeightfieldExample.cpp @@ -541,7 +541,7 @@ getRawHeightfieldData if (slot>=0) { char* lineChar; - while (lineChar = fileIO.readLine(slot, lineBuffer, MYLINELENGTH)) + while ((lineChar = fileIO.readLine(slot, lineBuffer, MYLINELENGTH))) { rows=0; char** values = urdfStrSplit(lineChar, ","); @@ -549,7 +549,7 @@ getRawHeightfieldData { int index = 0; char* value; - while (value = values[index++]) + while ((value = values[index++])) { std::string strval(value); double v; diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 2d614eebe8..ad89ddddc5 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -4732,7 +4732,7 @@ static unsigned char* MyGetRawHeightfieldData(CommonFileIOInterface& fileIO, PHY if (slot >= 0) { char* lineChar; - while (lineChar = fileIO.readLine(slot, &lineBuffer[0], MYLINELENGTH)) + while ((lineChar = fileIO.readLine(slot, &lineBuffer[0], MYLINELENGTH))) { rows = 0; std::string line(lineChar); From 6a715937a3dfe5c4ce5e9104f3a3db4f5480f936 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 15:22:57 +0100 Subject: [PATCH 15/57] Compiler warnings - suggest paranthesis --- examples/FractureDemo/btFractureDynamicsWorld.cpp | 2 +- examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/FractureDemo/btFractureDynamicsWorld.cpp b/examples/FractureDemo/btFractureDynamicsWorld.cpp index 2012788d06..ef555cf0f8 100644 --- a/examples/FractureDemo/btFractureDynamicsWorld.cpp +++ b/examples/FractureDemo/btFractureDynamicsWorld.cpp @@ -481,7 +481,7 @@ void btFractureDynamicsWorld::fractureCallback() int f0 = m_fractureBodies.findLinearSearch((btFractureBody*)manifold->getBody0()); int f1 = m_fractureBodies.findLinearSearch((btFractureBody*)manifold->getBody1()); - if (f0 == f1 == m_fractureBodies.size()) + if ((f0 == f1) && (f1 == m_fractureBodies.size())) continue; if (f0 < m_fractureBodies.size()) diff --git a/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp b/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp index 0bc0adb956..b6ba420723 100644 --- a/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp +++ b/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp @@ -640,7 +640,7 @@ bool Path_WriteBinaryFile(const std::string &strFilename, unsigned char *pData, fclose(f); } - return written = nSize ? true : false; + return (written = nSize ? true : false); } std::string Path_ReadTextFile(const std::string &strFilename) From 1f104ca25fc61df3bb5dbc85cb81735aef15490b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 15:24:37 +0100 Subject: [PATCH 16/57] Compiler warnings - implicit fallthrough --- examples/OpenGLWindow/X11OpenGLWindow.cpp | 1 + .../NarrowPhaseCollision/shared/b3NewContactReduction.h | 3 +++ src/Bullet3Geometry/b3ConvexHullComputer.cpp | 2 +- src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp | 1 + 4 files changed, 6 insertions(+), 1 deletion(-) diff --git a/examples/OpenGLWindow/X11OpenGLWindow.cpp b/examples/OpenGLWindow/X11OpenGLWindow.cpp index 6a0d7f4716..d42402f96c 100644 --- a/examples/OpenGLWindow/X11OpenGLWindow.cpp +++ b/examples/OpenGLWindow/X11OpenGLWindow.cpp @@ -954,6 +954,7 @@ void X11OpenGLWindow::pumpMessage() case ButtonRelease: buttonState = 0; //continue with ButtonPress code + // fallthrough case ButtonPress: { // printf("!"); diff --git a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3NewContactReduction.h b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3NewContactReduction.h index 6e991e14b0..0297ffd80c 100644 --- a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3NewContactReduction.h +++ b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3NewContactReduction.h @@ -152,10 +152,13 @@ __kernel void b3NewContactReductionKernel(__global b3Int4* pairs, { case 4: c->m_worldPosB[3] = pointsIn[contactIdx.w]; + // fallthrough case 3: c->m_worldPosB[2] = pointsIn[contactIdx.z]; + // fallthrough case 2: c->m_worldPosB[1] = pointsIn[contactIdx.y]; + // fallthrough case 1: c->m_worldPosB[0] = pointsIn[contactIdx.x]; default: diff --git a/src/Bullet3Geometry/b3ConvexHullComputer.cpp b/src/Bullet3Geometry/b3ConvexHullComputer.cpp index b37652456e..6f8e2eb262 100644 --- a/src/Bullet3Geometry/b3ConvexHullComputer.cpp +++ b/src/Bullet3Geometry/b3ConvexHullComputer.cpp @@ -1283,7 +1283,7 @@ void b3ConvexHullInternal::computeInternal(int start, int end, IntermediateHull& return; } } - // lint -fallthrough + // fallthrough case 1: { Vertex* v = originalVertices[start]; diff --git a/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp b/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp index 858e54825b..70b7674b31 100644 --- a/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp +++ b/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp @@ -209,6 +209,7 @@ void b3GpuRaycast::castRaysHost(const b3AlignedObjectArray& rays, b3A hitNormal = (hitPoint - bodies[b].m_pos).normalize(); } } + // fallthrough case SHAPE_CONVEX_HULL: { b3Transform convexWorldTransform; From eb97b50a39c1f435befad13dd19ec8c6dd33edff Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 15:25:06 +0100 Subject: [PATCH 17/57] Compiler warnings - unused return value --- Extras/VHACD/src/vhacdMesh.cpp | 25 +++++++++++++------------ Extras/VHACD/test/src/main_vhacd.cpp | 21 +++++++++++---------- 2 files changed, 24 insertions(+), 22 deletions(-) diff --git a/Extras/VHACD/src/vhacdMesh.cpp b/Extras/VHACD/src/vhacdMesh.cpp index 4f5816f527..dc5ae1ab8b 100644 --- a/Extras/VHACD/src/vhacdMesh.cpp +++ b/Extras/VHACD/src/vhacdMesh.cpp @@ -293,7 +293,8 @@ bool Mesh::LoadOFF(const std::string& fileName, bool invert) { const std::string strOFF("OFF"); char temp[1024]; - fscanf(fid, "%s", temp); + int len = fscanf(fid, "%s", temp); + (void)len; if (std::string(temp) != strOFF) { fclose(fid); @@ -304,18 +305,18 @@ bool Mesh::LoadOFF(const std::string& fileName, bool invert) int nv = 0; int nf = 0; int ne = 0; - fscanf(fid, "%i", &nv); - fscanf(fid, "%i", &nf); - fscanf(fid, "%i", &ne); + len = fscanf(fid, "%i", &nv); + len = fscanf(fid, "%i", &nf); + len = fscanf(fid, "%i", &ne); m_points.Resize(nv); m_triangles.Resize(nf); Vec3 coord; float x, y, z; for (int p = 0; p < nv; p++) { - fscanf(fid, "%f", &x); - fscanf(fid, "%f", &y); - fscanf(fid, "%f", &z); + len = fscanf(fid, "%f", &x); + len = fscanf(fid, "%f", &y); + len = fscanf(fid, "%f", &z); m_points[p][0] = x; m_points[p][1] = y; m_points[p][2] = z; @@ -323,12 +324,12 @@ bool Mesh::LoadOFF(const std::string& fileName, bool invert) int i, j, k, s; for (int t = 0; t < nf; ++t) { - fscanf(fid, "%i", &s); + len = fscanf(fid, "%i", &s); if (s == 3) { - fscanf(fid, "%i", &i); - fscanf(fid, "%i", &j); - fscanf(fid, "%i", &k); + len = fscanf(fid, "%i", &i); + len = fscanf(fid, "%i", &j); + len = fscanf(fid, "%i", &k); m_triangles[t][0] = i; if (invert) { @@ -344,7 +345,7 @@ bool Mesh::LoadOFF(const std::string& fileName, bool invert) else // Fix me: support only triangular meshes { for (int h = 0; h < s; ++h) - fscanf(fid, "%i", &s); + len = fscanf(fid, "%i", &s); } } fclose(fid); diff --git a/Extras/VHACD/test/src/main_vhacd.cpp b/Extras/VHACD/test/src/main_vhacd.cpp index 59e0de43c9..7649e7dfd0 100644 --- a/Extras/VHACD/test/src/main_vhacd.cpp +++ b/Extras/VHACD/test/src/main_vhacd.cpp @@ -478,7 +478,8 @@ bool LoadOFF(const string& fileName, vector& points, vector& triangl { const string strOFF("OFF"); char temp[1024]; - fscanf(fid, "%s", temp); + int len = fscanf(fid, "%s", temp); + (void)len; if (string(temp) != strOFF) { logger.Log("Loading error: format not recognized \n"); @@ -490,30 +491,30 @@ bool LoadOFF(const string& fileName, vector& points, vector& triangl int nv = 0; int nf = 0; int ne = 0; - fscanf(fid, "%i", &nv); - fscanf(fid, "%i", &nf); - fscanf(fid, "%i", &ne); + len = fscanf(fid, "%i", &nv); + len = fscanf(fid, "%i", &nf); + len = fscanf(fid, "%i", &ne); points.resize(nv * 3); triangles.resize(nf * 3); const int np = nv * 3; for (int p = 0; p < np; p++) { - fscanf(fid, "%f", &(points[p])); + len = fscanf(fid, "%f", &(points[p])); } int s; for (int t = 0, r = 0; t < nf; ++t) { - fscanf(fid, "%i", &s); + len = fscanf(fid, "%i", &s); if (s == 3) { - fscanf(fid, "%i", &(triangles[r++])); - fscanf(fid, "%i", &(triangles[r++])); - fscanf(fid, "%i", &(triangles[r++])); + len = fscanf(fid, "%i", &(triangles[r++])); + len = fscanf(fid, "%i", &(triangles[r++])); + len = fscanf(fid, "%i", &(triangles[r++])); } else // Fix me: support only triangular meshes { for (int h = 0; h < s; ++h) - fscanf(fid, "%i", &s); + len = fscanf(fid, "%i", &s); } } fclose(fid); From ecadad637aece9f83ad35dc0b766f4ff82c658fa Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 15:26:23 +0100 Subject: [PATCH 18/57] Compiler warnings - useless const --- Extras/VHACD/inc/vhacdMesh.h | 12 ++--- Extras/VHACD/inc/vhacdSArray.h | 4 +- Extras/VHACD/inc/vhacdVector.h | 2 +- Extras/VHACD/inc/vhacdVector.inl | 4 +- Extras/VHACD/inc/vhacdVolume.h | 46 +++++++++---------- Extras/VHACD/src/vhacdVolume.cpp | 6 +-- .../ParallelPrimitives/b3PrefixScanCL.cpp | 2 +- .../b3PrefixScanFloat4CL.cpp | 2 +- 8 files changed, 39 insertions(+), 39 deletions(-) diff --git a/Extras/VHACD/inc/vhacdMesh.h b/Extras/VHACD/inc/vhacdMesh.h index a617fc8ca1..e43da355b8 100644 --- a/Extras/VHACD/inc/vhacdMesh.h +++ b/Extras/VHACD/inc/vhacdMesh.h @@ -74,18 +74,18 @@ class Mesh Vec3& GetPoint(size_t index) { return m_points[index]; }; size_t GetNPoints() const { return m_points.Size(); }; double* GetPoints() { return (double*)m_points.Data(); } // ugly - const double* const GetPoints() const { return (double*)m_points.Data(); } // ugly - const Vec3* const GetPointsBuffer() const { return m_points.Data(); } // - Vec3* const GetPointsBuffer() { return m_points.Data(); } // + const double* GetPoints() const { return (double*)m_points.Data(); } // ugly + const Vec3* GetPointsBuffer() const { return m_points.Data(); } // + Vec3* GetPointsBuffer() { return m_points.Data(); } // void AddTriangle(const Vec3& tri) { m_triangles.PushBack(tri); }; void SetTriangle(size_t index, const Vec3& tri) { m_triangles[index] = tri; }; const Vec3& GetTriangle(size_t index) const { return m_triangles[index]; }; Vec3& GetTriangle(size_t index) { return m_triangles[index]; }; size_t GetNTriangles() const { return m_triangles.Size(); }; int* GetTriangles() { return (int*)m_triangles.Data(); } // ugly - const int* const GetTriangles() const { return (int*)m_triangles.Data(); } // ugly - const Vec3* const GetTrianglesBuffer() const { return m_triangles.Data(); } - Vec3* const GetTrianglesBuffer() { return m_triangles.Data(); } + const int* GetTriangles() const { return (int*)m_triangles.Data(); } // ugly + const Vec3* GetTrianglesBuffer() const { return m_triangles.Data(); } + Vec3* GetTrianglesBuffer() { return m_triangles.Data(); } const Vec3& GetCenter() const { return m_center; } const Vec3& GetMinBB() const { return m_minBB; } const Vec3& GetMaxBB() const { return m_maxBB; } diff --git a/Extras/VHACD/inc/vhacdSArray.h b/Extras/VHACD/inc/vhacdSArray.h index 431f4da4f2..353bb8dc81 100644 --- a/Extras/VHACD/inc/vhacdSArray.h +++ b/Extras/VHACD/inc/vhacdSArray.h @@ -42,11 +42,11 @@ class SArray { return m_size; } - T* const Data() + T* Data() { return (m_maxSize == N) ? m_data0 : m_data; } - const T* const Data() const + const T* Data() const { return (m_maxSize == N) ? m_data0 : m_data; } diff --git a/Extras/VHACD/inc/vhacdVector.h b/Extras/VHACD/inc/vhacdVector.h index 0e724cc6ae..5abbef0faa 100644 --- a/Extras/VHACD/inc/vhacdVector.h +++ b/Extras/VHACD/inc/vhacdVector.h @@ -98,7 +98,7 @@ class Vec2 }; template -const bool Colinear(const Vec3& a, const Vec3& b, const Vec3& c); +bool Colinear(const Vec3& a, const Vec3& b, const Vec3& c); template const T ComputeVolume4(const Vec3& a, const Vec3& b, const Vec3& c, const Vec3& d); } // namespace VHACD diff --git a/Extras/VHACD/inc/vhacdVector.inl b/Extras/VHACD/inc/vhacdVector.inl index 223c2ef173..7e87c602f6 100644 --- a/Extras/VHACD/inc/vhacdVector.inl +++ b/Extras/VHACD/inc/vhacdVector.inl @@ -162,7 +162,7 @@ namespace VHACD inline Vec3::Vec3() {} template - inline const bool Colinear(const Vec3 & a, const Vec3 & b, const Vec3 & c) + inline bool Colinear(const Vec3 & a, const Vec3 & b, const Vec3 & c) { return ((c.Z() - a.Z()) * (b.Y() - a.Y()) - (b.Z() - a.Z()) * (c.Y() - a.Y()) == 0.0 /*EPS*/) && ((b.Z() - a.Z()) * (c.X() - a.X()) - (b.X() - a.X()) * (c.Z() - a.Z()) == 0.0 /*EPS*/) && @@ -343,7 +343,7 @@ namespace VHACD defined by A, B, C. */ template - inline const bool InsideTriangle(const Vec2 & a, const Vec2 & b, const Vec2 & c, const Vec2 & p) + inline bool InsideTriangle(const Vec2 & a, const Vec2 & b, const Vec2 & c, const Vec2 & p) { T ax, ay, bx, by, cx, cy, apx, apy, bpx, bpy, cpx, cpy; T cCROSSap, bCROSScp, aCROSSbp; diff --git a/Extras/VHACD/inc/vhacdVolume.h b/Extras/VHACD/inc/vhacdVolume.h index 11d28da4c9..1362833497 100644 --- a/Extras/VHACD/inc/vhacdVolume.h +++ b/Extras/VHACD/inc/vhacdVolume.h @@ -41,12 +41,12 @@ class PrimitiveSet public: virtual ~PrimitiveSet(){}; virtual PrimitiveSet* Create() const = 0; - virtual const size_t GetNPrimitives() const = 0; - virtual const size_t GetNPrimitivesOnSurf() const = 0; - virtual const size_t GetNPrimitivesInsideSurf() const = 0; - virtual const double GetEigenValue(AXIS axis) const = 0; - virtual const double ComputeMaxVolumeError() const = 0; - virtual const double ComputeVolume() const = 0; + virtual size_t GetNPrimitives() const = 0; + virtual size_t GetNPrimitivesOnSurf() const = 0; + virtual size_t GetNPrimitivesInsideSurf() const = 0; + virtual double GetEigenValue(AXIS axis) const = 0; + virtual double ComputeMaxVolumeError() const = 0; + virtual double ComputeVolume() const = 0; virtual void Clip(const Plane& plane, PrimitiveSet* const positivePart, PrimitiveSet* const negativePart) const = 0; virtual void Intersect(const Plane& plane, SArray >* const positivePts, @@ -80,12 +80,12 @@ class VoxelSet : public PrimitiveSet //! Constructor. VoxelSet(); - const size_t GetNPrimitives() const { return m_voxels.Size(); } - const size_t GetNPrimitivesOnSurf() const { return m_numVoxelsOnSurface; } - const size_t GetNPrimitivesInsideSurf() const { return m_numVoxelsInsideSurface; } - const double GetEigenValue(AXIS axis) const { return m_D[axis][axis]; } - const double ComputeVolume() const { return m_unitVolume * m_voxels.Size(); } - const double ComputeMaxVolumeError() const { return m_unitVolume * m_numVoxelsOnSurface; } + size_t GetNPrimitives() const { return m_voxels.Size(); } + size_t GetNPrimitivesOnSurf() const { return m_numVoxelsOnSurface; } + size_t GetNPrimitivesInsideSurf() const { return m_numVoxelsInsideSurface; } + double GetEigenValue(AXIS axis) const { return m_D[axis][axis]; } + double ComputeVolume() const { return m_unitVolume * m_voxels.Size(); } + double ComputeMaxVolumeError() const { return m_unitVolume * m_numVoxelsOnSurface; } const Vec3& GetMinBBVoxels() const { return m_minBBVoxels; } const Vec3& GetMaxBBVoxels() const { return m_maxBBVoxels; } const Vec3& GetMinBB() const { return m_minBB; } @@ -127,8 +127,8 @@ class VoxelSet : public PrimitiveSet } void AlignToPrincipalAxes(){}; void RevertAlignToPrincipalAxes(){}; - Voxel* const GetVoxels() { return m_voxels.Data(); } - const Voxel* const GetVoxels() const { return m_voxels.Data(); } + Voxel* GetVoxels() { return m_voxels.Data(); } + const Voxel* GetVoxels() const { return m_voxels.Data(); } private: size_t m_numVoxelsOnSurface; @@ -165,16 +165,16 @@ class TetrahedronSet : public PrimitiveSet //! Constructor. TetrahedronSet(); - const size_t GetNPrimitives() const { return m_tetrahedra.Size(); } - const size_t GetNPrimitivesOnSurf() const { return m_numTetrahedraOnSurface; } - const size_t GetNPrimitivesInsideSurf() const { return m_numTetrahedraInsideSurface; } + size_t GetNPrimitives() const { return m_tetrahedra.Size(); } + size_t GetNPrimitivesOnSurf() const { return m_numTetrahedraOnSurface; } + size_t GetNPrimitivesInsideSurf() const { return m_numTetrahedraInsideSurface; } const Vec3& GetMinBB() const { return m_minBB; } const Vec3& GetMaxBB() const { return m_maxBB; } const Vec3& GetBarycenter() const { return m_barycenter; } - const double GetEigenValue(AXIS axis) const { return m_D[axis][axis]; } - const double GetSacle() const { return m_scale; } - const double ComputeVolume() const; - const double ComputeMaxVolumeError() const; + double GetEigenValue(AXIS axis) const { return m_D[axis][axis]; } + double GetSacle() const { return m_scale; } + double ComputeVolume() const; + double ComputeMaxVolumeError() const; void ComputeConvexHull(Mesh& meshCH, const size_t sampling = 1) const; void ComputePrincipalAxes(); void AlignToPrincipalAxes(); @@ -238,8 +238,8 @@ class Volume assert(k < m_dim[0]); return m_data[i + j * m_dim[0] + k * m_dim[0] * m_dim[1]]; } - const size_t GetNPrimitivesOnSurf() const { return m_numVoxelsOnSurface; } - const size_t GetNPrimitivesInsideSurf() const { return m_numVoxelsInsideSurface; } + size_t GetNPrimitivesOnSurf() const { return m_numVoxelsOnSurface; } + size_t GetNPrimitivesInsideSurf() const { return m_numVoxelsInsideSurface; } void Convert(Mesh& mesh, const VOXEL_VALUE value) const; void Convert(VoxelSet& vset) const; void Convert(TetrahedronSet& tset) const; diff --git a/Extras/VHACD/src/vhacdVolume.cpp b/Extras/VHACD/src/vhacdVolume.cpp index da6f8a9afc..8f45440710 100644 --- a/Extras/VHACD/src/vhacdVolume.cpp +++ b/Extras/VHACD/src/vhacdVolume.cpp @@ -1687,9 +1687,9 @@ void TetrahedronSet::Convert(Mesh& mesh, const VOXEL_VALUE value) const } } } -const double TetrahedronSet::ComputeVolume() const +double TetrahedronSet::ComputeVolume() const { - const size_t nTetrahedra = m_tetrahedra.Size(); + size_t nTetrahedra = m_tetrahedra.Size(); if (nTetrahedra == 0) return 0.0; double volume = 0.0; @@ -1700,7 +1700,7 @@ const double TetrahedronSet::ComputeVolume() const } return volume / 6.0; } -const double TetrahedronSet::ComputeMaxVolumeError() const +double TetrahedronSet::ComputeMaxVolumeError() const { const size_t nTetrahedra = m_tetrahedra.Size(); if (nTetrahedra == 0) diff --git a/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.cpp b/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.cpp index 5663768fa3..3490cafdee 100644 --- a/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.cpp +++ b/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.cpp @@ -45,7 +45,7 @@ T b3NextPowerOf2(T n) void b3PrefixScanCL::execute(b3OpenCLArray& src, b3OpenCLArray& dst, int n, unsigned int* sum) { // b3Assert( data->m_option == EXCLUSIVE ); - const unsigned int numBlocks = (const unsigned int)((n + BLOCK_SIZE * 2 - 1) / (BLOCK_SIZE * 2)); + const unsigned int numBlocks = (unsigned int)((n + BLOCK_SIZE * 2 - 1) / (BLOCK_SIZE * 2)); dst.resize(src.size()); m_workBuffer->resize(src.size()); diff --git a/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanFloat4CL.cpp b/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanFloat4CL.cpp index 9cd31a989b..3b497c300d 100644 --- a/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanFloat4CL.cpp +++ b/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanFloat4CL.cpp @@ -45,7 +45,7 @@ T b3NextPowerOf2(T n) void b3PrefixScanFloat4CL::execute(b3OpenCLArray& src, b3OpenCLArray& dst, int n, b3Vector3* sum) { // b3Assert( data->m_option == EXCLUSIVE ); - const unsigned int numBlocks = (const unsigned int)((n + BLOCK_SIZE * 2 - 1) / (BLOCK_SIZE * 2)); + const unsigned int numBlocks = (unsigned int)((n + BLOCK_SIZE * 2 - 1) / (BLOCK_SIZE * 2)); dst.resize(src.size()); m_workBuffer->resize(src.size()); From 0ece71fe896867862cc53663302b3c3a2f5052af Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 15:27:25 +0100 Subject: [PATCH 19/57] Compiler warnings - anonymous struct --- src/Bullet3Common/b3QuadWord.h | 2 +- src/Bullet3Common/b3Scalar.h | 14 ++++++++++++++ src/Bullet3Common/b3Vector3.h | 2 +- src/Bullet3Common/shared/b3Int2.h | 22 ++++++++++++++++++---- src/Bullet3Common/shared/b3Int4.h | 8 ++++---- src/clew/clew.h | 3 ++- 6 files changed, 40 insertions(+), 11 deletions(-) diff --git a/src/Bullet3Common/b3QuadWord.h b/src/Bullet3Common/b3QuadWord.h index 0def305fac..4183957f32 100644 --- a/src/Bullet3Common/b3QuadWord.h +++ b/src/Bullet3Common/b3QuadWord.h @@ -71,7 +71,7 @@ class b3QuadWord public: union { b3Scalar m_floats[4]; - struct + ANONYMOUS_STRUCTS struct { b3Scalar x, y, z, w; }; diff --git a/src/Bullet3Common/b3Scalar.h b/src/Bullet3Common/b3Scalar.h index 54ae4e1f7e..9df2b8618f 100644 --- a/src/Bullet3Common/b3Scalar.h +++ b/src/Bullet3Common/b3Scalar.h @@ -24,6 +24,20 @@ subject to the following restrictions: #include //size_t for MSVC 6.0 #include +#ifndef ANONYMOUS_STRUCTS +#if defined(__GNUC__) +#define ANONYMOUS_STRUCTS __extension__ +#if defined(__clang__) +#pragma clang diagnostic ignored "-Wnested-anon-types" +#endif +#else // __GNUC__ +#if defined(_MSC_VER) +#pragma warning(disable : 4201) // nonstandard extension used: nameless struct/union +#endif // _MSC_VER +#define ANONYMOUS_STRUCTS +#endif // __GNUC__ +#endif // ANONYMOUS_STRUCTS + //Original repository is at http://github.com/erwincoumans/bullet3 #define B3_BULLET_VERSION 300 diff --git a/src/Bullet3Common/b3Vector3.h b/src/Bullet3Common/b3Vector3.h index a70d68d6e1..62f7910b49 100644 --- a/src/Bullet3Common/b3Vector3.h +++ b/src/Bullet3Common/b3Vector3.h @@ -99,7 +99,7 @@ b3Vector3 #else union { float m_floats[4]; - struct + ANONYMOUS_STRUCTS struct { float x, y, z, w; }; diff --git a/src/Bullet3Common/shared/b3Int2.h b/src/Bullet3Common/shared/b3Int2.h index 7b84de4436..013c40db33 100644 --- a/src/Bullet3Common/shared/b3Int2.h +++ b/src/Bullet3Common/shared/b3Int2.h @@ -18,14 +18,28 @@ subject to the following restrictions: #ifdef __cplusplus +#ifndef ANONYMOUS_STRUCTS +#if defined(__GNUC__) +#define ANONYMOUS_STRUCTS __extension__ +#if defined(__clang__) +#pragma clang diagnostic ignored "-Wnested-anon-types" +#endif +#else // __GNUC__ +#if defined(_MSC_VER) +#pragma warning(disable : 4201) // nonstandard extension used: nameless struct/union +#endif // _MSC_VER +#define ANONYMOUS_STRUCTS +#endif // __GNUC__ +#endif // ANONYMOUS_STRUCTS + struct b3UnsignedInt2 { union { - struct + ANONYMOUS_STRUCTS struct { unsigned int x, y; }; - struct + ANONYMOUS_STRUCTS struct { unsigned int s[2]; }; @@ -35,11 +49,11 @@ struct b3UnsignedInt2 struct b3Int2 { union { - struct + ANONYMOUS_STRUCTS struct { int x, y; }; - struct + ANONYMOUS_STRUCTS struct { int s[2]; }; diff --git a/src/Bullet3Common/shared/b3Int4.h b/src/Bullet3Common/shared/b3Int4.h index f6a1754245..f654b8ef95 100644 --- a/src/Bullet3Common/shared/b3Int4.h +++ b/src/Bullet3Common/shared/b3Int4.h @@ -11,11 +11,11 @@ b3UnsignedInt4 B3_DECLARE_ALIGNED_ALLOCATOR(); union { - struct + ANONYMOUS_STRUCTS struct { unsigned int x, y, z, w; }; - struct + ANONYMOUS_STRUCTS struct { unsigned int s[4]; }; @@ -28,11 +28,11 @@ b3Int4 B3_DECLARE_ALIGNED_ALLOCATOR(); union { - struct + ANONYMOUS_STRUCTS struct { int x, y, z, w; }; - struct + ANONYMOUS_STRUCTS struct { int s[4]; }; diff --git a/src/clew/clew.h b/src/clew/clew.h index cba8585233..a4ab1b416d 100644 --- a/src/clew/clew.h +++ b/src/clew/clew.h @@ -464,7 +464,8 @@ float nanf(const char *); #endif #if defined(CL_NAMED_STRUCT_SUPPORTED) && defined(_MSC_VER) -#define __extension__ __pragma(warning(suppress : 4201)) +#pragma warning(disable: 4201) +#define __extension__ #endif /* Define cl_vector types */ From f185dc5b849d8b4b2aa7e8ccbf031cdd191e21c7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 15:30:17 +0100 Subject: [PATCH 20/57] Compiler warnings - printf possible OOB write --- Extras/obj2sdf/obj2sdf.cpp | 8 +++++--- .../GwenGUISupport/GwenParameterInterface.cpp | 2 +- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/Extras/obj2sdf/obj2sdf.cpp b/Extras/obj2sdf/obj2sdf.cpp index 60881d50e3..4fd2fa0942 100644 --- a/Extras/obj2sdf/obj2sdf.cpp +++ b/Extras/obj2sdf/obj2sdf.cpp @@ -47,6 +47,7 @@ struct ShapeContainer b3HashMap gMaterialNames; #define MAX_PATH_LEN 1024 +#define APPEND_SIZE 20 std::string StripExtension(const std::string& sPath) { @@ -86,10 +87,11 @@ int main(int argc, char* argv[]) } bool mergeMaterials = args.CheckCmdLineFlag("mergeMaterials"); - char fileNameWithPath[MAX_PATH_LEN]; + char fileNameWithPath[MAX_PATH_LEN-APPEND_SIZE]; bool fileFound = (b3ResourcePath::findResourcePath(fileName, fileNameWithPath, MAX_PATH_LEN,0)) > 0; - char materialPrefixPath[MAX_PATH_LEN]; - b3FileUtils::extractPath(fileNameWithPath, materialPrefixPath, MAX_PATH_LEN); + (void)fileFound; + char materialPrefixPath[MAX_PATH_LEN-APPEND_SIZE]; + b3FileUtils::extractPath(fileNameWithPath, materialPrefixPath, MAX_PATH_LEN-APPEND_SIZE); std::vector shapes; bt_tinyobj::attrib_t attribute; diff --git a/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp b/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp index 61108c55a9..965d897d1e 100644 --- a/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp +++ b/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp @@ -88,7 +88,7 @@ struct MySliderEventHandler : public Gwen::Event::Handler float val = float(v); //todo: specialize on template type if (m_showValue) { - char txt[1024]; + char txt[1033]; safe_printf(txt, sizeof(txt), "%s : %.3f", m_variableName, val); m_label->SetText(txt); } From 39c2af754567eea341020c6c80b63220a44e61a6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 15:40:22 +0100 Subject: [PATCH 21/57] Compiler warnings - virtual functions not marked override --- .../btBroadphaseInterface.h | 2 +- .../BroadphaseCollision/btDbvtBroadphase.h | 28 ++--- .../btOverlappingPairCache.h | 110 +++++++++--------- .../BroadphaseCollision/btSimpleBroadphase.h | 26 ++--- .../CollisionDispatch/btCollisionDispatcher.h | 30 ++--- .../CollisionDispatch/btCollisionWorld.h | 6 +- .../btDefaultCollisionConfiguration.h | 10 +- .../CollisionDispatch/btGhostObject.h | 16 +-- .../CollisionDispatch/btManifoldResult.h | 8 +- .../CollisionShapes/btBoxShape.h | 34 +++--- .../CollisionShapes/btBvhTriangleMeshShape.h | 12 +- .../CollisionShapes/btCapsuleShape.h | 24 ++-- .../CollisionShapes/btConcaveShape.h | 6 +- .../CollisionShapes/btConeShape.h | 26 ++--- .../CollisionShapes/btConvexInternalShape.h | 28 ++--- .../CollisionShapes/btConvexShape.h | 12 +- .../btMultimaterialTriangleMeshShape.h | 4 +- .../CollisionShapes/btOptimizedBvh.h | 2 +- .../CollisionShapes/btPolyhedralConvexShape.h | 12 +- .../btTriangleIndexVertexArray.h | 22 ++-- .../CollisionShapes/btTriangleMesh.h | 4 +- .../CollisionShapes/btTriangleMeshShape.h | 14 +-- .../btDiscreteCollisionDetectorInterface.h | 4 +- .../NarrowPhaseCollision/btRaycastCallback.h | 4 +- .../btSequentialImpulseConstraintSolver.h | 8 +- .../Dynamics/btDiscreteDynamicsWorld.h | 54 ++++----- src/BulletDynamics/Dynamics/btDynamicsWorld.h | 4 +- src/BulletDynamics/Dynamics/btRigidBody.h | 8 +- .../Dynamics/btSimpleDynamicsWorld.h | 34 +++--- .../btMultiBodyMLCPConstraintSolver.h | 4 +- src/LinearMath/btDefaultMotionState.h | 4 +- src/LinearMath/btSerializer.h | 32 ++--- 32 files changed, 296 insertions(+), 296 deletions(-) diff --git a/src/BulletCollision/BroadphaseCollision/btBroadphaseInterface.h b/src/BulletCollision/BroadphaseCollision/btBroadphaseInterface.h index 4176256f3c..2b184bb87e 100644 --- a/src/BulletCollision/BroadphaseCollision/btBroadphaseInterface.h +++ b/src/BulletCollision/BroadphaseCollision/btBroadphaseInterface.h @@ -35,7 +35,7 @@ struct btBroadphaseRayCallback : public btBroadphaseAabbCallback unsigned int m_signs[3]; btScalar m_lambda_max; - virtual ~btBroadphaseRayCallback() {} + virtual ~btBroadphaseRayCallback() override {} protected: btBroadphaseRayCallback() {} diff --git a/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.h b/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.h index a71feef53b..d11a6a7b6b 100644 --- a/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.h +++ b/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.h @@ -102,26 +102,26 @@ struct btDbvtBroadphase : btBroadphaseInterface #endif /* Methods */ btDbvtBroadphase(btOverlappingPairCache* paircache = 0); - ~btDbvtBroadphase(); + ~btDbvtBroadphase() override; void collide(btDispatcher* dispatcher); void optimize(); /* btBroadphaseInterface Implementation */ - btBroadphaseProxy* createProxy(const btVector3& aabbMin, const btVector3& aabbMax, int shapeType, void* userPtr, int collisionFilterGroup, int collisionFilterMask, btDispatcher* dispatcher); - virtual void destroyProxy(btBroadphaseProxy* proxy, btDispatcher* dispatcher); - virtual void setAabb(btBroadphaseProxy* proxy, const btVector3& aabbMin, const btVector3& aabbMax, btDispatcher* dispatcher); - virtual void rayTest(const btVector3& rayFrom, const btVector3& rayTo, btBroadphaseRayCallback& rayCallback, const btVector3& aabbMin = btVector3(0, 0, 0), const btVector3& aabbMax = btVector3(0, 0, 0)); - virtual void aabbTest(const btVector3& aabbMin, const btVector3& aabbMax, btBroadphaseAabbCallback& callback); - - virtual void getAabb(btBroadphaseProxy* proxy, btVector3& aabbMin, btVector3& aabbMax) const; - virtual void calculateOverlappingPairs(btDispatcher* dispatcher); - virtual btOverlappingPairCache* getOverlappingPairCache(); - virtual const btOverlappingPairCache* getOverlappingPairCache() const; - virtual void getBroadphaseAabb(btVector3& aabbMin, btVector3& aabbMax) const; - virtual void printStats(); + btBroadphaseProxy* createProxy(const btVector3& aabbMin, const btVector3& aabbMax, int shapeType, void* userPtr, int collisionFilterGroup, int collisionFilterMask, btDispatcher* dispatcher) override; + virtual void destroyProxy(btBroadphaseProxy* proxy, btDispatcher* dispatcher) override; + virtual void setAabb(btBroadphaseProxy* proxy, const btVector3& aabbMin, const btVector3& aabbMax, btDispatcher* dispatcher) override; + virtual void rayTest(const btVector3& rayFrom, const btVector3& rayTo, btBroadphaseRayCallback& rayCallback, const btVector3& aabbMin = btVector3(0, 0, 0), const btVector3& aabbMax = btVector3(0, 0, 0)) override; + virtual void aabbTest(const btVector3& aabbMin, const btVector3& aabbMax, btBroadphaseAabbCallback& callback) override; + + virtual void getAabb(btBroadphaseProxy* proxy, btVector3& aabbMin, btVector3& aabbMax) const override; + virtual void calculateOverlappingPairs(btDispatcher* dispatcher) override; + virtual btOverlappingPairCache* getOverlappingPairCache() override; + virtual const btOverlappingPairCache* getOverlappingPairCache() const override; + virtual void getBroadphaseAabb(btVector3& aabbMin, btVector3& aabbMax) const override; + virtual void printStats() override; ///reset broadphase internal structures, to ensure determinism/reproducability - virtual void resetPool(btDispatcher* dispatcher); + virtual void resetPool(btDispatcher* dispatcher) override; void performDeferredRemoval(btDispatcher* dispatcher); diff --git a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h index 1d82726475..fc99b11a51 100644 --- a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h +++ b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h @@ -50,7 +50,7 @@ const int BT_NULL_PAIR = 0xffffffff; class btOverlappingPairCache : public btOverlappingPairCallback { public: - virtual ~btOverlappingPairCache() {} // this is needed so we can get to the derived class destructor + virtual ~btOverlappingPairCache() override {} // this is needed so we can get to the derived class destructor virtual btBroadphasePair* getOverlappingPairArrayPtr() = 0; @@ -99,13 +99,13 @@ btHashedOverlappingPairCache : public btOverlappingPairCache BT_DECLARE_ALIGNED_ALLOCATOR(); btHashedOverlappingPairCache(); - virtual ~btHashedOverlappingPairCache(); + virtual ~btHashedOverlappingPairCache() override; - void removeOverlappingPairsContainingProxy(btBroadphaseProxy * proxy, btDispatcher * dispatcher); + void removeOverlappingPairsContainingProxy(btBroadphaseProxy * proxy, btDispatcher * dispatcher) override; - virtual void* removeOverlappingPair(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1, btDispatcher * dispatcher); + virtual void* removeOverlappingPair(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1, btDispatcher * dispatcher) override; - SIMD_FORCE_INLINE bool needsBroadphaseCollision(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1) const + SIMD_FORCE_INLINE bool needsBroadphaseCollision(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1) const override { if (m_overlapFilterCallback) return m_overlapFilterCallback->needBroadphaseCollision(proxy0, proxy1); @@ -118,7 +118,7 @@ btHashedOverlappingPairCache : public btOverlappingPairCache // Add a pair and return the new pair. If the pair already exists, // no new pair is created and the old one is returned. - virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1) + virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1) override { if (!needsBroadphaseCollision(proxy0, proxy1)) return 0; @@ -126,23 +126,23 @@ btHashedOverlappingPairCache : public btOverlappingPairCache return internalAddPair(proxy0, proxy1); } - void cleanProxyFromPairs(btBroadphaseProxy * proxy, btDispatcher * dispatcher); + void cleanProxyFromPairs(btBroadphaseProxy * proxy, btDispatcher * dispatcher) override; - virtual void processAllOverlappingPairs(btOverlapCallback*, btDispatcher * dispatcher); + virtual void processAllOverlappingPairs(btOverlapCallback*, btDispatcher * dispatcher) override; - virtual void processAllOverlappingPairs(btOverlapCallback * callback, btDispatcher * dispatcher, const struct btDispatcherInfo& dispatchInfo); + virtual void processAllOverlappingPairs(btOverlapCallback * callback, btDispatcher * dispatcher, const struct btDispatcherInfo& dispatchInfo) override; - virtual btBroadphasePair* getOverlappingPairArrayPtr() + virtual btBroadphasePair* getOverlappingPairArrayPtr() override { return &m_overlappingPairArray[0]; } - const btBroadphasePair* getOverlappingPairArrayPtr() const + const btBroadphasePair* getOverlappingPairArrayPtr() const override { return &m_overlappingPairArray[0]; } - btBroadphasePairArray& getOverlappingPairArray() + btBroadphasePairArray& getOverlappingPairArray() override { return m_overlappingPairArray; } @@ -152,24 +152,24 @@ btHashedOverlappingPairCache : public btOverlappingPairCache return m_overlappingPairArray; } - void cleanOverlappingPair(btBroadphasePair & pair, btDispatcher * dispatcher); + void cleanOverlappingPair(btBroadphasePair & pair, btDispatcher * dispatcher) override; - btBroadphasePair* findPair(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1); + btBroadphasePair* findPair(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1) override; int GetCount() const { return m_overlappingPairArray.size(); } // btBroadphasePair* GetPairs() { return m_pairs; } - btOverlapFilterCallback* getOverlapFilterCallback() + btOverlapFilterCallback* getOverlapFilterCallback() override { return m_overlapFilterCallback; } - void setOverlapFilterCallback(btOverlapFilterCallback * callback) + void setOverlapFilterCallback(btOverlapFilterCallback * callback) override { m_overlapFilterCallback = callback; } - int getNumOverlappingPairs() const + int getNumOverlappingPairs() const override { return m_overlappingPairArray.size(); } @@ -240,17 +240,17 @@ btHashedOverlappingPairCache : public btOverlappingPairCache return &m_overlappingPairArray[index]; } - virtual bool hasDeferredRemoval() + virtual bool hasDeferredRemoval() override { return false; } - virtual void setInternalGhostPairCallback(btOverlappingPairCallback * ghostPairCallback) + virtual void setInternalGhostPairCallback(btOverlappingPairCallback * ghostPairCallback) override { m_ghostPairCallback = ghostPairCallback; } - virtual void sortOverlappingPairs(btDispatcher * dispatcher); + virtual void sortOverlappingPairs(btDispatcher * dispatcher) override; }; ///btSortedOverlappingPairCache maintains the objects with overlapping AABB @@ -274,23 +274,23 @@ class btSortedOverlappingPairCache : public btOverlappingPairCache public: btSortedOverlappingPairCache(); - virtual ~btSortedOverlappingPairCache(); + virtual ~btSortedOverlappingPairCache() override; - virtual void processAllOverlappingPairs(btOverlapCallback*, btDispatcher* dispatcher); + virtual void processAllOverlappingPairs(btOverlapCallback*, btDispatcher* dispatcher) override; - void* removeOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1, btDispatcher* dispatcher); + void* removeOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1, btDispatcher* dispatcher) override; - void cleanOverlappingPair(btBroadphasePair& pair, btDispatcher* dispatcher); + void cleanOverlappingPair(btBroadphasePair& pair, btDispatcher* dispatcher) override; - btBroadphasePair* addOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1); + btBroadphasePair* addOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) override; - btBroadphasePair* findPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1); + btBroadphasePair* findPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) override; - void cleanProxyFromPairs(btBroadphaseProxy* proxy, btDispatcher* dispatcher); + void cleanProxyFromPairs(btBroadphaseProxy* proxy, btDispatcher* dispatcher) override; - void removeOverlappingPairsContainingProxy(btBroadphaseProxy* proxy, btDispatcher* dispatcher); + void removeOverlappingPairsContainingProxy(btBroadphaseProxy* proxy, btDispatcher* dispatcher) override; - inline bool needsBroadphaseCollision(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) const + inline bool needsBroadphaseCollision(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) const override { if (m_overlapFilterCallback) return m_overlapFilterCallback->needBroadphaseCollision(proxy0, proxy1); @@ -301,7 +301,7 @@ class btSortedOverlappingPairCache : public btOverlappingPairCache return collides; } - btBroadphasePairArray& getOverlappingPairArray() + btBroadphasePairArray& getOverlappingPairArray() override { return m_overlappingPairArray; } @@ -311,42 +311,42 @@ class btSortedOverlappingPairCache : public btOverlappingPairCache return m_overlappingPairArray; } - btBroadphasePair* getOverlappingPairArrayPtr() + btBroadphasePair* getOverlappingPairArrayPtr() override { return &m_overlappingPairArray[0]; } - const btBroadphasePair* getOverlappingPairArrayPtr() const + const btBroadphasePair* getOverlappingPairArrayPtr() const override { return &m_overlappingPairArray[0]; } - int getNumOverlappingPairs() const + int getNumOverlappingPairs() const override { return m_overlappingPairArray.size(); } - btOverlapFilterCallback* getOverlapFilterCallback() + btOverlapFilterCallback* getOverlapFilterCallback() override { return m_overlapFilterCallback; } - void setOverlapFilterCallback(btOverlapFilterCallback* callback) + void setOverlapFilterCallback(btOverlapFilterCallback* callback) override { m_overlapFilterCallback = callback; } - virtual bool hasDeferredRemoval() + virtual bool hasDeferredRemoval() override { return m_hasDeferredRemoval; } - virtual void setInternalGhostPairCallback(btOverlappingPairCallback* ghostPairCallback) + virtual void setInternalGhostPairCallback(btOverlappingPairCallback* ghostPairCallback) override { m_ghostPairCallback = ghostPairCallback; } - virtual void sortOverlappingPairs(btDispatcher* dispatcher); + virtual void sortOverlappingPairs(btDispatcher* dispatcher) override; }; ///btNullPairCache skips add/removal of overlapping pairs. Userful for benchmarking and unit testing. @@ -355,77 +355,77 @@ class btNullPairCache : public btOverlappingPairCache btBroadphasePairArray m_overlappingPairArray; public: - virtual btBroadphasePair* getOverlappingPairArrayPtr() + virtual btBroadphasePair* getOverlappingPairArrayPtr() override { return &m_overlappingPairArray[0]; } - const btBroadphasePair* getOverlappingPairArrayPtr() const + const btBroadphasePair* getOverlappingPairArrayPtr() const override { return &m_overlappingPairArray[0]; } - btBroadphasePairArray& getOverlappingPairArray() + btBroadphasePairArray& getOverlappingPairArray() override { return m_overlappingPairArray; } - virtual void cleanOverlappingPair(btBroadphasePair& /*pair*/, btDispatcher* /*dispatcher*/) + virtual void cleanOverlappingPair(btBroadphasePair& /*pair*/, btDispatcher* /*dispatcher*/) override { } - virtual int getNumOverlappingPairs() const + virtual int getNumOverlappingPairs() const override { return 0; } - virtual void cleanProxyFromPairs(btBroadphaseProxy* /*proxy*/, btDispatcher* /*dispatcher*/) + virtual void cleanProxyFromPairs(btBroadphaseProxy* /*proxy*/, btDispatcher* /*dispatcher*/) override { } - bool needsBroadphaseCollision(btBroadphaseProxy*, btBroadphaseProxy*) const + bool needsBroadphaseCollision(btBroadphaseProxy*, btBroadphaseProxy*) const override { return true; } - btOverlapFilterCallback* getOverlapFilterCallback() + btOverlapFilterCallback* getOverlapFilterCallback() override { return 0; } - virtual void setOverlapFilterCallback(btOverlapFilterCallback* /*callback*/) + virtual void setOverlapFilterCallback(btOverlapFilterCallback* /*callback*/) override { } - virtual void processAllOverlappingPairs(btOverlapCallback*, btDispatcher* /*dispatcher*/) + virtual void processAllOverlappingPairs(btOverlapCallback*, btDispatcher* /*dispatcher*/) override { } - virtual btBroadphasePair* findPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/) + virtual btBroadphasePair* findPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/) override { return 0; } - virtual bool hasDeferredRemoval() + virtual bool hasDeferredRemoval() override { return true; } - virtual void setInternalGhostPairCallback(btOverlappingPairCallback* /* ghostPairCallback */) + virtual void setInternalGhostPairCallback(btOverlappingPairCallback* /* ghostPairCallback */) override { } - virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/) + virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/) override { return 0; } - virtual void* removeOverlappingPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/, btDispatcher* /*dispatcher*/) + virtual void* removeOverlappingPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/, btDispatcher* /*dispatcher*/) override { return 0; } - virtual void removeOverlappingPairsContainingProxy(btBroadphaseProxy* /*proxy0*/, btDispatcher* /*dispatcher*/) + virtual void removeOverlappingPairsContainingProxy(btBroadphaseProxy* /*proxy0*/, btDispatcher* /*dispatcher*/) override { } - virtual void sortOverlappingPairs(btDispatcher* dispatcher) + virtual void sortOverlappingPairs(btDispatcher* dispatcher) override { (void)dispatcher; } diff --git a/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h b/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h index f97073c588..983a2a3b7a 100644 --- a/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h +++ b/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h @@ -97,33 +97,33 @@ class btSimpleBroadphase : public btBroadphaseInterface } ///reset broadphase internal structures, to ensure determinism/reproducability - virtual void resetPool(btDispatcher* dispatcher); + virtual void resetPool(btDispatcher* dispatcher) override; void validate(); protected: public: btSimpleBroadphase(int maxProxies = 16384, btOverlappingPairCache* overlappingPairCache = 0); - virtual ~btSimpleBroadphase(); + virtual ~btSimpleBroadphase() override; static bool aabbOverlap(btSimpleBroadphaseProxy* proxy0, btSimpleBroadphaseProxy* proxy1); - virtual btBroadphaseProxy* createProxy(const btVector3& aabbMin, const btVector3& aabbMax, int shapeType, void* userPtr, int collisionFilterGroup, int collisionFilterMask, btDispatcher* dispatcher); + virtual btBroadphaseProxy* createProxy(const btVector3& aabbMin, const btVector3& aabbMax, int shapeType, void* userPtr, int collisionFilterGroup, int collisionFilterMask, btDispatcher* dispatcher) override; - virtual void calculateOverlappingPairs(btDispatcher* dispatcher); + virtual void calculateOverlappingPairs(btDispatcher* dispatcher) override; - virtual void destroyProxy(btBroadphaseProxy* proxy, btDispatcher* dispatcher); - virtual void setAabb(btBroadphaseProxy* proxy, const btVector3& aabbMin, const btVector3& aabbMax, btDispatcher* dispatcher); - virtual void getAabb(btBroadphaseProxy* proxy, btVector3& aabbMin, btVector3& aabbMax) const; + virtual void destroyProxy(btBroadphaseProxy* proxy, btDispatcher* dispatcher) override; + virtual void setAabb(btBroadphaseProxy* proxy, const btVector3& aabbMin, const btVector3& aabbMax, btDispatcher* dispatcher) override; + virtual void getAabb(btBroadphaseProxy* proxy, btVector3& aabbMin, btVector3& aabbMax) const override; - virtual void rayTest(const btVector3& rayFrom, const btVector3& rayTo, btBroadphaseRayCallback& rayCallback, const btVector3& aabbMin = btVector3(0, 0, 0), const btVector3& aabbMax = btVector3(0, 0, 0)); - virtual void aabbTest(const btVector3& aabbMin, const btVector3& aabbMax, btBroadphaseAabbCallback& callback); + virtual void rayTest(const btVector3& rayFrom, const btVector3& rayTo, btBroadphaseRayCallback& rayCallback, const btVector3& aabbMin = btVector3(0, 0, 0), const btVector3& aabbMax = btVector3(0, 0, 0)) override; + virtual void aabbTest(const btVector3& aabbMin, const btVector3& aabbMax, btBroadphaseAabbCallback& callback) override; - btOverlappingPairCache* getOverlappingPairCache() + btOverlappingPairCache* getOverlappingPairCache() override { return m_pairCache; } - const btOverlappingPairCache* getOverlappingPairCache() const + const btOverlappingPairCache* getOverlappingPairCache() const override { return m_pairCache; } @@ -132,13 +132,13 @@ class btSimpleBroadphase : public btBroadphaseInterface ///getAabb returns the axis aligned bounding box in the 'global' coordinate frame ///will add some transform later - virtual void getBroadphaseAabb(btVector3& aabbMin, btVector3& aabbMax) const + virtual void getBroadphaseAabb(btVector3& aabbMin, btVector3& aabbMax) const override { aabbMin.setValue(-BT_LARGE_FLOAT, -BT_LARGE_FLOAT, -BT_LARGE_FLOAT); aabbMax.setValue(BT_LARGE_FLOAT, BT_LARGE_FLOAT, BT_LARGE_FLOAT); } - virtual void printStats() + virtual void printStats() override { // printf("btSimpleBroadphase.h\n"); // printf("numHandles = %d, maxHandles = %d\n",m_numHandles,m_maxHandles); diff --git a/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h b/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h index 1399148fa2..4b1115df42 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h @@ -81,17 +81,17 @@ class btCollisionDispatcher : public btDispatcher void registerClosestPointsCreateFunc(int proxyType0, int proxyType1, btCollisionAlgorithmCreateFunc* createFunc); - int getNumManifolds() const + int getNumManifolds() const override { return int(m_manifoldsPtr.size()); } - btPersistentManifold** getInternalManifoldPointer() + btPersistentManifold** getInternalManifoldPointer() override { return m_manifoldsPtr.size() ? &m_manifoldsPtr[0] : 0; } - btPersistentManifold* getManifoldByIndexInternal(int index) + btPersistentManifold* getManifoldByIndexInternal(int index) override { btAssert(index>=0); btAssert(index m_hitPointWorld; btAlignedObjectArray m_hitFractions; - virtual btScalar addSingleResult(LocalRayResult& rayResult, bool normalInWorldSpace) + virtual btScalar addSingleResult(LocalRayResult& rayResult, bool normalInWorldSpace) override { m_collisionObject = rayResult.m_collisionObject; m_collisionObjects.push_back(rayResult.m_collisionObject); @@ -375,7 +375,7 @@ class btCollisionWorld btVector3 m_hitPointWorld; const btCollisionObject* m_hitCollisionObject; - virtual btScalar addSingleResult(LocalConvexResult& convexResult, bool normalInWorldSpace) + virtual btScalar addSingleResult(LocalConvexResult& convexResult, bool normalInWorldSpace) override { //caller already does the filter on the m_closestHitFraction btAssert(convexResult.m_hitFraction <= m_closestHitFraction); diff --git a/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h b/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h index adab540c05..dce933d14b 100644 --- a/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h +++ b/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h @@ -79,22 +79,22 @@ class btDefaultCollisionConfiguration : public btCollisionConfiguration public: btDefaultCollisionConfiguration(const btDefaultCollisionConstructionInfo& constructionInfo = btDefaultCollisionConstructionInfo()); - virtual ~btDefaultCollisionConfiguration(); + virtual ~btDefaultCollisionConfiguration() override; ///memory pools - virtual btPoolAllocator* getPersistentManifoldPool() + virtual btPoolAllocator* getPersistentManifoldPool() override { return m_persistentManifoldPool; } - virtual btPoolAllocator* getCollisionAlgorithmPool() + virtual btPoolAllocator* getCollisionAlgorithmPool() override { return m_collisionAlgorithmPool; } - virtual btCollisionAlgorithmCreateFunc* getCollisionAlgorithmCreateFunc(int proxyType0, int proxyType1); + virtual btCollisionAlgorithmCreateFunc* getCollisionAlgorithmCreateFunc(int proxyType0, int proxyType1) override; - virtual btCollisionAlgorithmCreateFunc* getClosestPointsAlgorithmCreateFunc(int proxyType0, int proxyType1); + virtual btCollisionAlgorithmCreateFunc* getClosestPointsAlgorithmCreateFunc(int proxyType0, int proxyType1) override; ///Use this method to allow to generate multiple contact points between at once, between two objects using the generic convex-convex algorithm. ///By default, this feature is disabled for best performance. diff --git a/src/BulletCollision/CollisionDispatch/btGhostObject.h b/src/BulletCollision/CollisionDispatch/btGhostObject.h index aa7f48d5cb..e3b6d8cd45 100644 --- a/src/BulletCollision/CollisionDispatch/btGhostObject.h +++ b/src/BulletCollision/CollisionDispatch/btGhostObject.h @@ -39,7 +39,7 @@ btGhostObject : public btCollisionObject public: btGhostObject(); - virtual ~btGhostObject(); + virtual ~btGhostObject() override; void convexSweepTest(const class btConvexShape* castShape, const btTransform& convexFromWorld, const btTransform& convexToWorld, btCollisionWorld::ConvexResultCallback& resultCallback, btScalar allowedCcdPenetration = 0.f) const; @@ -100,12 +100,12 @@ class btPairCachingGhostObject : public btGhostObject public: btPairCachingGhostObject(); - virtual ~btPairCachingGhostObject(); + virtual ~btPairCachingGhostObject() override; ///this method is mainly for expert/internal use only. - virtual void addOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btBroadphaseProxy* thisProxy = 0); + virtual void addOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btBroadphaseProxy* thisProxy = 0) override; - virtual void removeOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btDispatcher* dispatcher, btBroadphaseProxy* thisProxy = 0); + virtual void removeOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btDispatcher* dispatcher, btBroadphaseProxy* thisProxy = 0) override; btHashedOverlappingPairCache* getOverlappingPairCache() { @@ -121,11 +121,11 @@ class btGhostPairCallback : public btOverlappingPairCallback { } - virtual ~btGhostPairCallback() + virtual ~btGhostPairCallback() override { } - virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) + virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) override { btCollisionObject* colObj0 = (btCollisionObject*)proxy0->m_clientObject; btCollisionObject* colObj1 = (btCollisionObject*)proxy1->m_clientObject; @@ -138,7 +138,7 @@ class btGhostPairCallback : public btOverlappingPairCallback return 0; } - virtual void* removeOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1, btDispatcher* dispatcher) + virtual void* removeOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1, btDispatcher* dispatcher) override { btCollisionObject* colObj0 = (btCollisionObject*)proxy0->m_clientObject; btCollisionObject* colObj1 = (btCollisionObject*)proxy1->m_clientObject; @@ -151,7 +151,7 @@ class btGhostPairCallback : public btOverlappingPairCallback return 0; } - virtual void removeOverlappingPairsContainingProxy(btBroadphaseProxy* /*proxy0*/, btDispatcher* /*dispatcher*/) + virtual void removeOverlappingPairsContainingProxy(btBroadphaseProxy* /*proxy0*/, btDispatcher* /*dispatcher*/) override { btAssert(0); //need to keep track of all ghost objects and call them here diff --git a/src/BulletCollision/CollisionDispatch/btManifoldResult.h b/src/BulletCollision/CollisionDispatch/btManifoldResult.h index 1a8f46f2bd..9cd79b8a9d 100644 --- a/src/BulletCollision/CollisionDispatch/btManifoldResult.h +++ b/src/BulletCollision/CollisionDispatch/btManifoldResult.h @@ -72,7 +72,7 @@ class btManifoldResult : public btDiscreteCollisionDetectorInterface::Result btManifoldResult(const btCollisionObjectWrapper* body0Wrap, const btCollisionObjectWrapper* body1Wrap); - virtual ~btManifoldResult(){}; + virtual ~btManifoldResult() override {}; void setPersistentManifold(btPersistentManifold* manifoldPtr) { @@ -88,19 +88,19 @@ class btManifoldResult : public btDiscreteCollisionDetectorInterface::Result return m_manifoldPtr; } - virtual void setShapeIdentifiersA(int partId0, int index0) + virtual void setShapeIdentifiersA(int partId0, int index0) override { m_partId0 = partId0; m_index0 = index0; } - virtual void setShapeIdentifiersB(int partId1, int index1) + virtual void setShapeIdentifiersB(int partId1, int index1) override { m_partId1 = partId1; m_index1 = index1; } - virtual void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorld, btScalar depth); + virtual void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorld, btScalar depth) override; SIMD_FORCE_INLINE void refreshContactPoints() { diff --git a/src/BulletCollision/CollisionShapes/btBoxShape.h b/src/BulletCollision/CollisionShapes/btBoxShape.h index 00c6583622..b3a54b5d69 100644 --- a/src/BulletCollision/CollisionShapes/btBoxShape.h +++ b/src/BulletCollision/CollisionShapes/btBoxShape.h @@ -44,7 +44,7 @@ btBoxShape : public btPolyhedralConvexShape return m_implicitShapeDimensions; //scaling is included, margin is not } - virtual btVector3 localGetSupportingVertex(const btVector3& vec) const + virtual btVector3 localGetSupportingVertex(const btVector3& vec) const override { btVector3 halfExtents = getHalfExtentsWithoutMargin(); btVector3 margin(getMargin(), getMargin(), getMargin()); @@ -55,7 +55,7 @@ btBoxShape : public btPolyhedralConvexShape btFsels(vec.z(), halfExtents.z(), -halfExtents.z())); } - SIMD_FORCE_INLINE btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const + SIMD_FORCE_INLINE btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const override { const btVector3& halfExtents = getHalfExtentsWithoutMargin(); @@ -64,7 +64,7 @@ btBoxShape : public btPolyhedralConvexShape btFsels(vec.z(), halfExtents.z(), -halfExtents.z())); } - virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const + virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const override { const btVector3& halfExtents = getHalfExtentsWithoutMargin(); @@ -79,7 +79,7 @@ btBoxShape : public btPolyhedralConvexShape btBoxShape(const btVector3& boxHalfExtents); - virtual void setMargin(btScalar collisionMargin) + virtual void setMargin(btScalar collisionMargin) override { //correct the m_implicitShapeDimensions for the margin btVector3 oldMargin(getMargin(), getMargin(), getMargin()); @@ -89,7 +89,7 @@ btBoxShape : public btPolyhedralConvexShape btVector3 newMargin(getMargin(), getMargin(), getMargin()); m_implicitShapeDimensions = implicitShapeDimensionsWithMargin - newMargin; } - virtual void setLocalScaling(const btVector3& scaling) + virtual void setLocalScaling(const btVector3& scaling) override { btVector3 oldMargin(getMargin(), getMargin(), getMargin()); btVector3 implicitShapeDimensionsWithMargin = m_implicitShapeDimensions + oldMargin; @@ -100,11 +100,11 @@ btBoxShape : public btPolyhedralConvexShape m_implicitShapeDimensions = (unScaledImplicitShapeDimensionsWithMargin * m_localScaling) - oldMargin; } - virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const; + virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override; - virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const; + virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const override; - virtual void getPlane(btVector3 & planeNormal, btVector3 & planeSupport, int i) const + virtual void getPlane(btVector3 & planeNormal, btVector3 & planeSupport, int i) const override { //this plane might not be aligned... // btVector4 plane; @@ -114,22 +114,22 @@ btBoxShape : public btPolyhedralConvexShape (void)planeNormal; (void)planeSupport; (void)i; } - virtual int getNumPlanes() const + virtual int getNumPlanes() const override { return 6; } - virtual int getNumVertices() const + virtual int getNumVertices() const override { return 8; } - virtual int getNumEdges() const + virtual int getNumEdges() const override { return 12; } - virtual void getVertex(int i, btVector3& vtx) const + virtual void getVertex(int i, btVector3& vtx) const override { btVector3 halfExtents = getHalfExtentsWithMargin(); @@ -168,7 +168,7 @@ btBoxShape : public btPolyhedralConvexShape } } - virtual void getEdge(int i, btVector3& pa, btVector3& pb) const + virtual void getEdge(int i, btVector3& pa, btVector3& pb) const override //virtual void getEdge(int i,Edge& edge) const { int edgeVert0 = 0; @@ -234,7 +234,7 @@ btBoxShape : public btPolyhedralConvexShape getVertex(edgeVert1, pb); } - virtual bool isInside(const btVector3& pt, btScalar tolerance) const + virtual bool isInside(const btVector3& pt, btScalar tolerance) const override { btVector3 halfExtents = getHalfExtentsWithoutMargin(); @@ -251,17 +251,17 @@ btBoxShape : public btPolyhedralConvexShape } //debugging - virtual const char* getName() const + virtual const char* getName() const override { return "Box"; } - virtual int getNumPreferredPenetrationDirections() const + virtual int getNumPreferredPenetrationDirections() const override { return 6; } - virtual void getPreferredPenetrationDirection(int index, btVector3& penetrationVector) const + virtual void getPreferredPenetrationDirection(int index, btVector3& penetrationVector) const override { switch (index) { diff --git a/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h b/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h index 8b2f2ee85e..e1542cb484 100644 --- a/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h +++ b/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h @@ -53,7 +53,7 @@ btBvhTriangleMeshShape : public btTriangleMeshShape ///optionally pass in a larger bvh aabb, used for quantization. This allows for deformations within this aabb btBvhTriangleMeshShape(btStridingMeshInterface * meshInterface, bool useQuantizedAabbCompression, const btVector3& bvhAabbMin, const btVector3& bvhAabbMax, bool buildBvh = true); - virtual ~btBvhTriangleMeshShape(); + virtual ~btBvhTriangleMeshShape() override; bool getOwnsBvh() const { @@ -63,7 +63,7 @@ btBvhTriangleMeshShape : public btTriangleMeshShape void performRaycast(btTriangleCallback * callback, const btVector3& raySource, const btVector3& rayTarget); void performConvexcast(btTriangleCallback * callback, const btVector3& boxSource, const btVector3& boxTarget, const btVector3& boxMin, const btVector3& boxMax); - virtual void processAllTriangles(btTriangleCallback * callback, const btVector3& aabbMin, const btVector3& aabbMax) const; + virtual void processAllTriangles(btTriangleCallback * callback, const btVector3& aabbMin, const btVector3& aabbMax) const override; void refitTree(const btVector3& aabbMin, const btVector3& aabbMax); @@ -71,9 +71,9 @@ btBvhTriangleMeshShape : public btTriangleMeshShape void partialRefitTree(const btVector3& aabbMin, const btVector3& aabbMax); //debugging - virtual const char* getName() const { return "BVHTRIANGLEMESH"; } + virtual const char* getName() const override{ return "BVHTRIANGLEMESH"; } - virtual void setLocalScaling(const btVector3& scaling); + virtual void setLocalScaling(const btVector3& scaling) override; btOptimizedBvh* getOptimizedBvh() { @@ -104,10 +104,10 @@ btBvhTriangleMeshShape : public btTriangleMeshShape return m_triangleInfoMap; } - virtual int calculateSerializeBufferSize() const; + virtual int calculateSerializeBufferSize() const override; ///fills the dataBuffer and returns the struct name (and 0 on failure) - virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const; + virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const override; virtual void serializeSingleBvh(btSerializer * serializer) const; diff --git a/src/BulletCollision/CollisionShapes/btCapsuleShape.h b/src/BulletCollision/CollisionShapes/btCapsuleShape.h index 138d0c0f7c..67707a8933 100644 --- a/src/BulletCollision/CollisionShapes/btCapsuleShape.h +++ b/src/BulletCollision/CollisionShapes/btCapsuleShape.h @@ -38,20 +38,20 @@ btCapsuleShape : public btConvexInternalShape btCapsuleShape(btScalar radius, btScalar height); ///CollisionShape Interface - virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const; + virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const override; /// btConvexShape Interface - virtual btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const; + virtual btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const override; - virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const; + virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const override; - virtual void setMargin(btScalar collisionMargin) + virtual void setMargin(btScalar collisionMargin) override { //don't override the margin for capsules, their entire radius == margin (void)collisionMargin; } - virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const + virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override { btVector3 halfExtents(getRadius(), getRadius(), getRadius()); halfExtents[m_upAxis] = getRadius() + getHalfHeight(); @@ -63,7 +63,7 @@ btCapsuleShape : public btConvexInternalShape aabbMax = center + extent; } - virtual const char* getName() const + virtual const char* getName() const override { return "CapsuleShape"; } @@ -84,7 +84,7 @@ btCapsuleShape : public btConvexInternalShape return m_implicitShapeDimensions[m_upAxis]; } - virtual void setLocalScaling(const btVector3& scaling) + virtual void setLocalScaling(const btVector3& scaling) override { btVector3 unScaledImplicitShapeDimensions = m_implicitShapeDimensions / m_localScaling; btConvexInternalShape::setLocalScaling(scaling); @@ -94,17 +94,17 @@ btCapsuleShape : public btConvexInternalShape m_collisionMargin = m_implicitShapeDimensions[radiusAxis]; } - virtual btVector3 getAnisotropicRollingFrictionDirection() const + virtual btVector3 getAnisotropicRollingFrictionDirection() const override { btVector3 aniDir(0, 0, 0); aniDir[getUpAxis()] = 1; return aniDir; } - virtual int calculateSerializeBufferSize() const; + virtual int calculateSerializeBufferSize() const override; ///fills the dataBuffer and returns the struct name (and 0 on failure) - virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const; + virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const override; SIMD_FORCE_INLINE void deSerializeFloat(struct btCapsuleShapeData * dataBuffer); }; @@ -117,7 +117,7 @@ class btCapsuleShapeX : public btCapsuleShape btCapsuleShapeX(btScalar radius, btScalar height); //debugging - virtual const char* getName() const + virtual const char* getName() const override { return "CapsuleX"; } @@ -131,7 +131,7 @@ class btCapsuleShapeZ : public btCapsuleShape btCapsuleShapeZ(btScalar radius, btScalar height); //debugging - virtual const char* getName() const + virtual const char* getName() const override { return "CapsuleZ"; } diff --git a/src/BulletCollision/CollisionShapes/btConcaveShape.h b/src/BulletCollision/CollisionShapes/btConcaveShape.h index 716624e182..ad8c678d52 100644 --- a/src/BulletCollision/CollisionShapes/btConcaveShape.h +++ b/src/BulletCollision/CollisionShapes/btConcaveShape.h @@ -45,15 +45,15 @@ btConcaveShape : public btCollisionShape btConcaveShape(); - virtual ~btConcaveShape(); + virtual ~btConcaveShape() override; virtual void processAllTriangles(btTriangleCallback * callback, const btVector3& aabbMin, const btVector3& aabbMax) const = 0; - virtual btScalar getMargin() const + virtual btScalar getMargin() const override { return m_collisionMargin; } - virtual void setMargin(btScalar collisionMargin) + virtual void setMargin(btScalar collisionMargin) override { m_collisionMargin = collisionMargin; } diff --git a/src/BulletCollision/CollisionShapes/btConeShape.h b/src/BulletCollision/CollisionShapes/btConeShape.h index 49f26bc4e5..4d4605e4de 100644 --- a/src/BulletCollision/CollisionShapes/btConeShape.h +++ b/src/BulletCollision/CollisionShapes/btConeShape.h @@ -35,9 +35,9 @@ btConeShape : public btConvexInternalShape btConeShape(btScalar radius, btScalar height); - virtual btVector3 localGetSupportingVertex(const btVector3& vec) const; - virtual btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const; - virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const; + virtual btVector3 localGetSupportingVertex(const btVector3& vec) const override; + virtual btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const override; + virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const override; btScalar getRadius() const { return m_radius; } btScalar getHeight() const { return m_height; } @@ -51,7 +51,7 @@ btConeShape : public btConvexInternalShape m_height = height; } - virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const + virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const override { btTransform identity; identity.setIdentity(); @@ -77,7 +77,7 @@ btConeShape : public btConvexInternalShape // inertia.z() = scaledmass * (x2+y2); } - virtual const char* getName() const + virtual const char* getName() const override { return "Cone"; } @@ -90,17 +90,17 @@ btConeShape : public btConvexInternalShape return m_coneIndices[1]; } - virtual btVector3 getAnisotropicRollingFrictionDirection() const + virtual btVector3 getAnisotropicRollingFrictionDirection() const override { return btVector3(0, 1, 0); } - virtual void setLocalScaling(const btVector3& scaling); + virtual void setLocalScaling(const btVector3& scaling) override; - virtual int calculateSerializeBufferSize() const; + virtual int calculateSerializeBufferSize() const override; ///fills the dataBuffer and returns the struct name (and 0 on failure) - virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const; + virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const override; }; ///btConeShape implements a Cone shape, around the X axis @@ -109,13 +109,13 @@ class btConeShapeX : public btConeShape public: btConeShapeX(btScalar radius, btScalar height); - virtual btVector3 getAnisotropicRollingFrictionDirection() const + virtual btVector3 getAnisotropicRollingFrictionDirection() const override { return btVector3(1, 0, 0); } //debugging - virtual const char* getName() const + virtual const char* getName() const override { return "ConeX"; } @@ -127,13 +127,13 @@ class btConeShapeZ : public btConeShape public: btConeShapeZ(btScalar radius, btScalar height); - virtual btVector3 getAnisotropicRollingFrictionDirection() const + virtual btVector3 getAnisotropicRollingFrictionDirection() const override { return btVector3(0, 0, 1); } //debugging - virtual const char* getName() const + virtual const char* getName() const override { return "ConeZ"; } diff --git a/src/BulletCollision/CollisionShapes/btConvexInternalShape.h b/src/BulletCollision/CollisionShapes/btConvexInternalShape.h index a28c57de4b..9f093d6208 100644 --- a/src/BulletCollision/CollisionShapes/btConvexInternalShape.h +++ b/src/BulletCollision/CollisionShapes/btConvexInternalShape.h @@ -43,11 +43,11 @@ btConvexInternalShape : public btConvexShape public: BT_DECLARE_ALIGNED_ALLOCATOR(); - virtual ~btConvexInternalShape() + virtual ~btConvexInternalShape() override { } - virtual btVector3 localGetSupportingVertex(const btVector3& vec) const; + virtual btVector3 localGetSupportingVertex(const btVector3& vec) const override; const btVector3& getImplicitShapeDimensions() const { @@ -81,15 +81,15 @@ btConvexInternalShape : public btConvexShape } ///getAabb's default implementation is brute force, expected derived classes to implement a fast dedicated version - void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const + void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override { getAabbSlow(t, aabbMin, aabbMax); } - virtual void getAabbSlow(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const; + virtual void getAabbSlow(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override; - virtual void setLocalScaling(const btVector3& scaling); - virtual const btVector3& getLocalScaling() const + virtual void setLocalScaling(const btVector3& scaling) override; + virtual const btVector3& getLocalScaling() const override { return m_localScaling; } @@ -99,11 +99,11 @@ btConvexInternalShape : public btConvexShape return m_localScaling; } - virtual void setMargin(btScalar margin) + virtual void setMargin(btScalar margin) override { m_collisionMargin = margin; } - virtual btScalar getMargin() const + virtual btScalar getMargin() const override { return m_collisionMargin; } @@ -113,22 +113,22 @@ btConvexInternalShape : public btConvexShape return m_collisionMargin; } - virtual int getNumPreferredPenetrationDirections() const + virtual int getNumPreferredPenetrationDirections() const override { return 0; } - virtual void getPreferredPenetrationDirection(int index, btVector3& penetrationVector) const + virtual void getPreferredPenetrationDirection(int index, btVector3& penetrationVector) const override { (void)penetrationVector; (void)index; btAssert(0); } - virtual int calculateSerializeBufferSize() const; + virtual int calculateSerializeBufferSize() const override; ///fills the dataBuffer and returns the struct name (and 0 on failure) - virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const; + virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const override; }; ///do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64 @@ -198,9 +198,9 @@ class btConvexInternalAabbCachingShape : public btConvexInternalShape } public: - virtual void setLocalScaling(const btVector3& scaling); + virtual void setLocalScaling(const btVector3& scaling) override; - virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const; + virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override; void recalcLocalAabb(); }; diff --git a/src/BulletCollision/CollisionShapes/btConvexShape.h b/src/BulletCollision/CollisionShapes/btConvexShape.h index d3b3ed816e..ee54450bd3 100644 --- a/src/BulletCollision/CollisionShapes/btConvexShape.h +++ b/src/BulletCollision/CollisionShapes/btConvexShape.h @@ -36,7 +36,7 @@ btConvexShape : public btCollisionShape btConvexShape(); - virtual ~btConvexShape(); + virtual ~btConvexShape() override; virtual btVector3 localGetSupportingVertex(const btVector3& vec) const = 0; @@ -56,16 +56,16 @@ btConvexShape : public btCollisionShape virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const = 0; ///getAabb's default implementation is brute force, expected derived classes to implement a fast dedicated version - void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const = 0; + void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override = 0; virtual void getAabbSlow(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const = 0; - virtual void setLocalScaling(const btVector3& scaling) = 0; - virtual const btVector3& getLocalScaling() const = 0; + virtual void setLocalScaling(const btVector3& scaling) override = 0; + virtual const btVector3& getLocalScaling() const override = 0; - virtual void setMargin(btScalar margin) = 0; + virtual void setMargin(btScalar margin) override = 0; - virtual btScalar getMargin() const = 0; + virtual btScalar getMargin() const override = 0; virtual int getNumPreferredPenetrationDirections() const = 0; diff --git a/src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.h b/src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.h index d1d42f8e04..184af027ce 100644 --- a/src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.h +++ b/src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.h @@ -93,7 +93,7 @@ btMultimaterialTriangleMeshShape : public btBvhTriangleMeshShape } } - virtual ~btMultimaterialTriangleMeshShape() + virtual ~btMultimaterialTriangleMeshShape() override { /* for(int i = 0; i < m_meshInterface->getNumSubParts(); i++) @@ -106,7 +106,7 @@ btMultimaterialTriangleMeshShape : public btBvhTriangleMeshShape */ } //debugging - virtual const char *getName() const { return "MULTIMATERIALTRIANGLEMESH"; } + virtual const char *getName() const override{ return "MULTIMATERIALTRIANGLEMESH"; } ///Obtains the material for a specific triangle const btMaterial *getMaterialProperties(int partID, int triIndex); diff --git a/src/BulletCollision/CollisionShapes/btOptimizedBvh.h b/src/BulletCollision/CollisionShapes/btOptimizedBvh.h index 22f131c8b2..0b9cad629c 100644 --- a/src/BulletCollision/CollisionShapes/btOptimizedBvh.h +++ b/src/BulletCollision/CollisionShapes/btOptimizedBvh.h @@ -33,7 +33,7 @@ btOptimizedBvh : public btQuantizedBvh public: btOptimizedBvh(); - virtual ~btOptimizedBvh(); + virtual ~btOptimizedBvh() override; void build(btStridingMeshInterface * triangles, bool useQuantizedAabbCompression, const btVector3& bvhAabbMin, const btVector3& bvhAabbMax); diff --git a/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h b/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h index b3ffab7a23..5c5dbbc362 100644 --- a/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h +++ b/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h @@ -32,7 +32,7 @@ btPolyhedralConvexShape : public btConvexInternalShape btPolyhedralConvexShape(); - virtual ~btPolyhedralConvexShape(); + virtual ~btPolyhedralConvexShape() override; ///optional method mainly used to generate multiple contact points by clipping polyhedral features (faces/edges) ///experimental/work-in-progress @@ -47,10 +47,10 @@ btPolyhedralConvexShape : public btConvexInternalShape //brute force implementations - virtual btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const; - virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const; + virtual btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const override; + virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const override; - virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const; + virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const override; virtual int getNumVertices() const = 0; virtual int getNumEdges() const = 0; @@ -96,9 +96,9 @@ class btPolyhedralConvexAabbCachingShape : public btPolyhedralConvexShape btTransformAabb(m_localAabbMin, m_localAabbMax, margin, trans, aabbMin, aabbMax); } - virtual void setLocalScaling(const btVector3& scaling); + virtual void setLocalScaling(const btVector3& scaling) override; - virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const; + virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override; void recalcLocalAabb(); }; diff --git a/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h b/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h index 556aa3fef4..084af648fc 100644 --- a/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h +++ b/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h @@ -79,7 +79,7 @@ btTriangleIndexVertexArray : public btStridingMeshInterface { } - virtual ~btTriangleIndexVertexArray(); + virtual ~btTriangleIndexVertexArray() override; //just to be backwards compatible btTriangleIndexVertexArray(int numTriangles, int* triangleIndexBase, int triangleIndexStride, int numVertices, btScalar* vertexBase, int vertexStride); @@ -90,19 +90,19 @@ btTriangleIndexVertexArray : public btStridingMeshInterface m_indexedMeshes[m_indexedMeshes.size() - 1].m_indexType = indexType; } - virtual void getLockedVertexIndexBase(unsigned char** vertexbase, int& numverts, PHY_ScalarType& type, int& vertexStride, unsigned char** indexbase, int& indexstride, int& numfaces, PHY_ScalarType& indicestype, int subpart = 0); + virtual void getLockedVertexIndexBase(unsigned char** vertexbase, int& numverts, PHY_ScalarType& type, int& vertexStride, unsigned char** indexbase, int& indexstride, int& numfaces, PHY_ScalarType& indicestype, int subpart = 0) override; - virtual void getLockedReadOnlyVertexIndexBase(const unsigned char** vertexbase, int& numverts, PHY_ScalarType& type, int& vertexStride, const unsigned char** indexbase, int& indexstride, int& numfaces, PHY_ScalarType& indicestype, int subpart = 0) const; + virtual void getLockedReadOnlyVertexIndexBase(const unsigned char** vertexbase, int& numverts, PHY_ScalarType& type, int& vertexStride, const unsigned char** indexbase, int& indexstride, int& numfaces, PHY_ScalarType& indicestype, int subpart = 0) const override; /// unLockVertexBase finishes the access to a subpart of the triangle mesh /// make a call to unLockVertexBase when the read and write access (using getLockedVertexIndexBase) is finished - virtual void unLockVertexBase(int subpart) { (void)subpart; } + virtual void unLockVertexBase(int subpart) override { (void)subpart; } - virtual void unLockReadOnlyVertexBase(int subpart) const { (void)subpart; } + virtual void unLockReadOnlyVertexBase(int subpart) const override { (void)subpart; } /// getNumSubParts returns the number of separate subparts /// each subpart has a continuous array of vertices and indices - virtual int getNumSubParts() const + virtual int getNumSubParts() const override { return (int)m_indexedMeshes.size(); } @@ -117,12 +117,12 @@ btTriangleIndexVertexArray : public btStridingMeshInterface return m_indexedMeshes; } - virtual void preallocateVertices(int numverts) { (void)numverts; } - virtual void preallocateIndices(int numindices) { (void)numindices; } + virtual void preallocateVertices(int numverts) override { (void)numverts; } + virtual void preallocateIndices(int numindices) override { (void)numindices; } - virtual bool hasPremadeAabb() const; - virtual void setPremadeAabb(const btVector3& aabbMin, const btVector3& aabbMax) const; - virtual void getPremadeAabb(btVector3 * aabbMin, btVector3 * aabbMax) const; + virtual bool hasPremadeAabb() const override; + virtual void setPremadeAabb(const btVector3& aabbMin, const btVector3& aabbMax) const override; + virtual void getPremadeAabb(btVector3 * aabbMin, btVector3 * aabbMax) const override; }; #endif //BT_TRIANGLE_INDEX_VERTEX_ARRAY_H diff --git a/src/BulletCollision/CollisionShapes/btTriangleMesh.h b/src/BulletCollision/CollisionShapes/btTriangleMesh.h index a8a362355c..3afcfdb902 100644 --- a/src/BulletCollision/CollisionShapes/btTriangleMesh.h +++ b/src/BulletCollision/CollisionShapes/btTriangleMesh.h @@ -57,8 +57,8 @@ class btTriangleMesh : public btTriangleIndexVertexArray int getNumTriangles() const; - virtual void preallocateVertices(int numverts); - virtual void preallocateIndices(int numindices); + virtual void preallocateVertices(int numverts) override; + virtual void preallocateIndices(int numindices) override; ///findOrAddVertex is an internal method, use addTriangle instead int findOrAddVertex(const btVector3& vertex, bool removeDuplicateVertices); diff --git a/src/BulletCollision/CollisionShapes/btTriangleMeshShape.h b/src/BulletCollision/CollisionShapes/btTriangleMeshShape.h index 4a70e283fa..2438a2abaa 100644 --- a/src/BulletCollision/CollisionShapes/btTriangleMeshShape.h +++ b/src/BulletCollision/CollisionShapes/btTriangleMeshShape.h @@ -35,7 +35,7 @@ btTriangleMeshShape : public btConcaveShape public: BT_DECLARE_ALIGNED_ALLOCATOR(); - virtual ~btTriangleMeshShape(); + virtual ~btTriangleMeshShape() override; virtual btVector3 localGetSupportingVertex(const btVector3& vec) const; @@ -47,14 +47,14 @@ btTriangleMeshShape : public btConcaveShape void recalcLocalAabb(); - virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const; + virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override; - virtual void processAllTriangles(btTriangleCallback * callback, const btVector3& aabbMin, const btVector3& aabbMax) const; + virtual void processAllTriangles(btTriangleCallback * callback, const btVector3& aabbMin, const btVector3& aabbMax) const override; - virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const; + virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const override; - virtual void setLocalScaling(const btVector3& scaling); - virtual const btVector3& getLocalScaling() const; + virtual void setLocalScaling(const btVector3& scaling) override; + virtual const btVector3& getLocalScaling() const override; btStridingMeshInterface* getMeshInterface() { @@ -76,7 +76,7 @@ btTriangleMeshShape : public btConcaveShape } //debugging - virtual const char* getName() const { return "TRIANGLEMESH"; } + virtual const char* getName() const override { return "TRIANGLEMESH"; } }; #endif //BT_TRIANGLE_MESH_SHAPE_H diff --git a/src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h b/src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h index 973975f3cd..deef70749f 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h +++ b/src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h @@ -69,9 +69,9 @@ struct btStorageResult : public btDiscreteCollisionDetectorInterface::Result } public: - virtual ~btStorageResult(){}; + virtual ~btStorageResult() override {}; - virtual void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorld, btScalar depth) + virtual void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorld, btScalar depth) override { if (depth < m_distance) { diff --git a/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h b/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h index 58a48c7a77..49956654d0 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h +++ b/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h @@ -46,7 +46,7 @@ class btTriangleRaycastCallback : public btTriangleCallback btTriangleRaycastCallback(const btVector3& from, const btVector3& to, unsigned int flags = 0); - virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex); + virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex) override; virtual btScalar reportHit(const btVector3& hitNormalLocal, btScalar hitFraction, int partId, int triangleIndex) = 0; }; @@ -64,7 +64,7 @@ class btTriangleConvexcastCallback : public btTriangleCallback btTriangleConvexcastCallback(const btConvexShape* convexShape, const btTransform& convexShapeFrom, const btTransform& convexShapeTo, const btTransform& triangleToWorld, const btScalar triangleCollisionMargin); - virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex); + virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex) override; virtual btScalar reportHit(const btVector3& hitNormalLocal, const btVector3& hitPointLocal, btScalar hitFraction, int partId, int triangleIndex) = 0; }; diff --git a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h index cd00967d08..b4555fb129 100644 --- a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h +++ b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h @@ -156,12 +156,12 @@ btSequentialImpulseConstraintSolver : public btConstraintSolver BT_DECLARE_ALIGNED_ALLOCATOR(); btSequentialImpulseConstraintSolver(); - virtual ~btSequentialImpulseConstraintSolver(); + virtual ~btSequentialImpulseConstraintSolver() override; - virtual btScalar solveGroup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifold, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* dispatcher); + virtual btScalar solveGroup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifold, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* dispatcher) override; ///clear internal cached data and reset random seed - virtual void reset(); + virtual void reset() override; unsigned long btRand2(); @@ -176,7 +176,7 @@ btSequentialImpulseConstraintSolver : public btConstraintSolver return m_btSeed2; } - virtual btConstraintSolverType getSolverType() const + virtual btConstraintSolverType getSolverType() const override { return BT_SEQUENTIAL_IMPULSE_SOLVER; } diff --git a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h index 73607c61fd..601d105d96 100644 --- a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h +++ b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h @@ -102,25 +102,25 @@ btDiscreteDynamicsWorld : public btDynamicsWorld ///this btDiscreteDynamicsWorld constructor gets created objects from the user, and will not delete those btDiscreteDynamicsWorld(btDispatcher * dispatcher, btBroadphaseInterface * pairCache, btConstraintSolver * constraintSolver, btCollisionConfiguration * collisionConfiguration); - virtual ~btDiscreteDynamicsWorld(); + virtual ~btDiscreteDynamicsWorld() override; ///if maxSubSteps > 0, it will interpolate motion between fixedTimeStep's - virtual int stepSimulation(btScalar timeStep, int maxSubSteps = 1, btScalar fixedTimeStep = btScalar(1.) / btScalar(60.)); + virtual int stepSimulation(btScalar timeStep, int maxSubSteps = 1, btScalar fixedTimeStep = btScalar(1.) / btScalar(60.)) override; virtual void solveConstraints(btContactSolverInfo & solverInfo); - virtual void synchronizeMotionStates(); + virtual void synchronizeMotionStates() override; ///this can be useful to synchronize a single rigid body -> graphics object void synchronizeSingleMotionState(btRigidBody * body); - virtual void addConstraint(btTypedConstraint * constraint, bool disableCollisionsBetweenLinkedBodies = false); + virtual void addConstraint(btTypedConstraint * constraint, bool disableCollisionsBetweenLinkedBodies = false) override; - virtual void removeConstraint(btTypedConstraint * constraint); + virtual void removeConstraint(btTypedConstraint * constraint) override; - virtual void addAction(btActionInterface*); + virtual void addAction(btActionInterface*) override; - virtual void removeAction(btActionInterface*); + virtual void removeAction(btActionInterface*) override; btSimulationIslandManager* getSimulationIslandManager() { @@ -137,42 +137,42 @@ btDiscreteDynamicsWorld : public btDynamicsWorld return this; } - virtual void setGravity(const btVector3& gravity); + virtual void setGravity(const btVector3& gravity) override; - virtual btVector3 getGravity() const; + virtual btVector3 getGravity() const override; - virtual void addCollisionObject(btCollisionObject * collisionObject, int collisionFilterGroup = btBroadphaseProxy::StaticFilter, int collisionFilterMask = btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter); + virtual void addCollisionObject(btCollisionObject * collisionObject, int collisionFilterGroup = btBroadphaseProxy::StaticFilter, int collisionFilterMask = btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter) override; - virtual void addRigidBody(btRigidBody * body); + virtual void addRigidBody(btRigidBody * body) override; - virtual void addRigidBody(btRigidBody * body, int group, int mask); + virtual void addRigidBody(btRigidBody * body, int group, int mask) override; - virtual void removeRigidBody(btRigidBody * body); + virtual void removeRigidBody(btRigidBody * body) override; ///removeCollisionObject will first check if it is a rigid body, if so call removeRigidBody otherwise call btCollisionWorld::removeCollisionObject - virtual void removeCollisionObject(btCollisionObject * collisionObject); + virtual void removeCollisionObject(btCollisionObject * collisionObject) override; virtual void debugDrawConstraint(btTypedConstraint * constraint); - virtual void debugDrawWorld(); + virtual void debugDrawWorld() override; - virtual void setConstraintSolver(btConstraintSolver * solver); + virtual void setConstraintSolver(btConstraintSolver * solver) override; - virtual btConstraintSolver* getConstraintSolver(); + virtual btConstraintSolver* getConstraintSolver() override; - virtual int getNumConstraints() const; + virtual int getNumConstraints() const override; - virtual btTypedConstraint* getConstraint(int index); + virtual btTypedConstraint* getConstraint(int index) override; - virtual const btTypedConstraint* getConstraint(int index) const; + virtual const btTypedConstraint* getConstraint(int index) const override; - virtual btDynamicsWorldType getWorldType() const + virtual btDynamicsWorldType getWorldType() const override { return BT_DISCRETE_DYNAMICS_WORLD; } ///the forces on each rigidbody is accumulating together with gravity. clear this after each timestep. - virtual void clearForces(); + virtual void clearForces() override; ///apply gravity, call this once per timestep virtual void applyGravity(); @@ -189,13 +189,13 @@ btDiscreteDynamicsWorld : public btDynamicsWorld } ///obsolete, use addAction instead - virtual void addVehicle(btActionInterface * vehicle); + virtual void addVehicle(btActionInterface * vehicle) override; ///obsolete, use removeAction instead - virtual void removeVehicle(btActionInterface * vehicle); + virtual void removeVehicle(btActionInterface * vehicle) override; ///obsolete, use addAction instead - virtual void addCharacter(btActionInterface * character); + virtual void addCharacter(btActionInterface * character) override; ///obsolete, use removeAction instead - virtual void removeCharacter(btActionInterface * character); + virtual void removeCharacter(btActionInterface * character) override; void setSynchronizeAllMotionStates(bool synchronizeAll) { @@ -217,7 +217,7 @@ btDiscreteDynamicsWorld : public btDynamicsWorld } ///Preliminary serialization test for Bullet 2.76. Loading those files requires a separate parser (see Bullet/Demos/SerializeDemo) - virtual void serialize(btSerializer * serializer); + virtual void serialize(btSerializer * serializer) override; ///Interpolate motion state between previous and current transform, instead of current and next transform. ///This can relieve discontinuities in the rendering, due to penetrations diff --git a/src/BulletDynamics/Dynamics/btDynamicsWorld.h b/src/BulletDynamics/Dynamics/btDynamicsWorld.h index a5a4411ade..0f63caef7c 100644 --- a/src/BulletDynamics/Dynamics/btDynamicsWorld.h +++ b/src/BulletDynamics/Dynamics/btDynamicsWorld.h @@ -54,7 +54,7 @@ class btDynamicsWorld : public btCollisionWorld { } - virtual ~btDynamicsWorld() + virtual ~btDynamicsWorld() override { } @@ -64,7 +64,7 @@ class btDynamicsWorld : public btCollisionWorld ///You can disable subdividing the timestep/substepping by passing maxSubSteps=0 as second argument to stepSimulation, but in that case you have to keep the timeStep constant. virtual int stepSimulation(btScalar timeStep, int maxSubSteps = 1, btScalar fixedTimeStep = btScalar(1.) / btScalar(60.)) = 0; - virtual void debugDrawWorld() = 0; + virtual void debugDrawWorld() override {}; virtual void addConstraint(btTypedConstraint* constraint, bool disableCollisionsBetweenLinkedBodies = false) { diff --git a/src/BulletDynamics/Dynamics/btRigidBody.h b/src/BulletDynamics/Dynamics/btRigidBody.h index 00143ef4e1..1dc761240e 100644 --- a/src/BulletDynamics/Dynamics/btRigidBody.h +++ b/src/BulletDynamics/Dynamics/btRigidBody.h @@ -170,7 +170,7 @@ class btRigidBody : public btCollisionObject ///To specify friction (etc) during rigid body construction, please use the other constructor (using btRigidBodyConstructionInfo) btRigidBody(btScalar mass, btMotionState* motionState, btCollisionShape* collisionShape, const btVector3& localInertia = btVector3(0, 0, 0)); - virtual ~btRigidBody() + virtual ~btRigidBody() override { //No constraints should point to this rigidbody //Remove constraints from the dynamics world before you delete the related rigidbodies. @@ -622,12 +622,12 @@ class btRigidBody : public btCollisionObject /////////////////////////////////////////////// - virtual int calculateSerializeBufferSize() const; + virtual int calculateSerializeBufferSize() const override; ///fills the dataBuffer and returns the struct name (and 0 on failure) - virtual const char* serialize(void* dataBuffer, class btSerializer* serializer) const; + virtual const char* serialize(void* dataBuffer, class btSerializer* serializer) const override; - virtual void serializeSingleObject(class btSerializer* serializer) const; + virtual void serializeSingleObject(class btSerializer* serializer) const override; }; //@todo add m_optionalMotionState and m_constraintRefs to btRigidBodyData diff --git a/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h b/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h index 46bd535f65..8f9d0b7bdc 100644 --- a/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h +++ b/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h @@ -41,44 +41,44 @@ class btSimpleDynamicsWorld : public btDynamicsWorld ///this btSimpleDynamicsWorld constructor creates dispatcher, broadphase pairCache and constraintSolver btSimpleDynamicsWorld(btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btConstraintSolver* constraintSolver, btCollisionConfiguration* collisionConfiguration); - virtual ~btSimpleDynamicsWorld(); + virtual ~btSimpleDynamicsWorld() override; ///maxSubSteps/fixedTimeStep for interpolation is currently ignored for btSimpleDynamicsWorld, use btDiscreteDynamicsWorld instead - virtual int stepSimulation(btScalar timeStep, int maxSubSteps = 1, btScalar fixedTimeStep = btScalar(1.) / btScalar(60.)); + virtual int stepSimulation(btScalar timeStep, int maxSubSteps = 1, btScalar fixedTimeStep = btScalar(1.) / btScalar(60.)) override; - virtual void setGravity(const btVector3& gravity); + virtual void setGravity(const btVector3& gravity) override; - virtual btVector3 getGravity() const; + virtual btVector3 getGravity() const override; - virtual void addRigidBody(btRigidBody* body); + virtual void addRigidBody(btRigidBody* body) override; - virtual void addRigidBody(btRigidBody* body, int group, int mask); + virtual void addRigidBody(btRigidBody* body, int group, int mask) override; - virtual void removeRigidBody(btRigidBody* body); + virtual void removeRigidBody(btRigidBody* body) override; - virtual void debugDrawWorld(); + virtual void debugDrawWorld() override; - virtual void addAction(btActionInterface* action); + virtual void addAction(btActionInterface* action) override; - virtual void removeAction(btActionInterface* action); + virtual void removeAction(btActionInterface* action) override; ///removeCollisionObject will first check if it is a rigid body, if so call removeRigidBody otherwise call btCollisionWorld::removeCollisionObject - virtual void removeCollisionObject(btCollisionObject* collisionObject); + virtual void removeCollisionObject(btCollisionObject* collisionObject) override; - virtual void updateAabbs(); + virtual void updateAabbs() override; - virtual void synchronizeMotionStates(); + virtual void synchronizeMotionStates() override; - virtual void setConstraintSolver(btConstraintSolver* solver); + virtual void setConstraintSolver(btConstraintSolver* solver) override; - virtual btConstraintSolver* getConstraintSolver(); + virtual btConstraintSolver* getConstraintSolver() override; - virtual btDynamicsWorldType getWorldType() const + virtual btDynamicsWorldType getWorldType() const override { return BT_SIMPLE_DYNAMICS_WORLD; } - virtual void clearForces(); + virtual void clearForces() override; }; #endif //BT_SIMPLE_DYNAMICS_WORLD_H diff --git a/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h b/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h index 77fdb86bb9..dbcb388807 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h @@ -156,7 +156,7 @@ class btMultiBodyMLCPConstraintSolver : public btMultiBodyConstraintSolver btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, - btIDebugDraw* debugDrawer) ; + btIDebugDraw* debugDrawer) override; public: BT_DECLARE_ALIGNED_ALLOCATOR() @@ -181,7 +181,7 @@ class btMultiBodyMLCPConstraintSolver : public btMultiBodyConstraintSolver void setNumFallbacks(int num); /// Returns the constraint solver type. - virtual btConstraintSolverType getSolverType() const; + virtual btConstraintSolverType getSolverType() const override; }; #endif // BT_MULTIBODY_MLCP_CONSTRAINT_SOLVER_H diff --git a/src/LinearMath/btDefaultMotionState.h b/src/LinearMath/btDefaultMotionState.h index 14c40d36b0..18b6ae47f2 100644 --- a/src/LinearMath/btDefaultMotionState.h +++ b/src/LinearMath/btDefaultMotionState.h @@ -24,14 +24,14 @@ btDefaultMotionState : public btMotionState } ///synchronizes world transform from user to physics - virtual void getWorldTransform(btTransform & centerOfMassWorldTrans) const + virtual void getWorldTransform(btTransform & centerOfMassWorldTrans) const override { centerOfMassWorldTrans = m_graphicsWorldTrans * m_centerOfMassOffset.inverse(); } ///synchronizes world transform from physics to user ///Bullet only calls the update of worldtransform for active objects - virtual void setWorldTransform(const btTransform& centerOfMassWorldTrans) + virtual void setWorldTransform(const btTransform& centerOfMassWorldTrans) override { m_graphicsWorldTrans = centerOfMassWorldTrans * m_centerOfMassOffset; } diff --git a/src/LinearMath/btSerializer.h b/src/LinearMath/btSerializer.h index ed5e320eca..200651107c 100644 --- a/src/LinearMath/btSerializer.h +++ b/src/LinearMath/btSerializer.h @@ -181,7 +181,7 @@ class btDefaultSerializer : public btSerializer btAlignedObjectArray m_chunkPtrs; protected: - virtual void* findPointer(void* oldPtr) + virtual void* findPointer(void* oldPtr) override { void** ptr = m_chunkP.find(oldPtr); if (ptr && *ptr) @@ -416,7 +416,7 @@ class btDefaultSerializer : public btSerializer #endif //BT_INTERNAL_UPDATE_SERIALIZATION_STRUCTURES } - virtual ~btDefaultSerializer() + virtual ~btDefaultSerializer() override { if (m_buffer && m_ownsBuffer) btAlignedFree(m_buffer); @@ -485,7 +485,7 @@ class btDefaultSerializer : public btSerializer buffer[11] = '6'; } - virtual void startSerialization() + virtual void startSerialization() override { m_uniqueIdGenerator = 1; if (m_totalSize) @@ -495,7 +495,7 @@ class btDefaultSerializer : public btSerializer } } - virtual void finishSerialization() + virtual void finishSerialization() override { writeDNA(); @@ -532,7 +532,7 @@ class btDefaultSerializer : public btSerializer m_chunkPtrs.clear(); } - virtual void* getUniquePointer(void* oldPtr) + virtual void* getUniquePointer(void* oldPtr) override { btAssert(m_uniqueIdGenerator >= 0); if (!oldPtr) @@ -559,17 +559,17 @@ class btDefaultSerializer : public btSerializer return uid.m_ptr; } - virtual const unsigned char* getBufferPointer() const + virtual const unsigned char* getBufferPointer() const override { return m_buffer; } - virtual int getCurrentBufferSize() const + virtual int getCurrentBufferSize() const override { return m_currentSize; } - virtual void finalizeChunk(btChunk* chunk, const char* structType, int chunkCode, void* oldPtr) + virtual void finalizeChunk(btChunk* chunk, const char* structType, int chunkCode, void* oldPtr) override { if (!(m_serializationFlags & BT_SERIALIZE_NO_DUPLICATE_ASSERT)) { @@ -604,7 +604,7 @@ class btDefaultSerializer : public btSerializer return ptr; } - virtual btChunk* allocate(size_t size, int numElements) + virtual btChunk* allocate(size_t size, int numElements) override { unsigned char* ptr = internalAlloc(int(size) * numElements + sizeof(btChunk)); @@ -621,7 +621,7 @@ class btDefaultSerializer : public btSerializer return chunk; } - virtual const char* findNameForPointer(const void* ptr) const + virtual const char* findNameForPointer(const void* ptr) const override { const char* const* namePtr = m_nameMap.find(ptr); if (namePtr && *namePtr) @@ -629,12 +629,12 @@ class btDefaultSerializer : public btSerializer return 0; } - virtual void registerNameForPointer(const void* ptr, const char* name) + virtual void registerNameForPointer(const void* ptr, const char* name) override { m_nameMap.insert(ptr, name); } - virtual void serializeName(const char* name) + virtual void serializeName(const char* name) override { if (name) { @@ -662,21 +662,21 @@ class btDefaultSerializer : public btSerializer } } - virtual int getSerializationFlags() const + virtual int getSerializationFlags() const override { return m_serializationFlags; } - virtual void setSerializationFlags(int flags) + virtual void setSerializationFlags(int flags) override { m_serializationFlags = flags; } - int getNumChunks() const + int getNumChunks() const override { return m_chunkPtrs.size(); } - const btChunk* getChunk(int chunkIndex) const + const btChunk* getChunk(int chunkIndex) const override { return m_chunkPtrs[chunkIndex]; } From 81fe91489c66a0988070c3684749cc47a809a6ab Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 04:11:10 +0100 Subject: [PATCH 22/57] override to BT_OVERRIDE --- .../btBroadphaseInterface.h | 3 +- .../BroadphaseCollision/btDbvtBroadphase.h | 28 ++--- .../btOverlappingPairCache.h | 110 +++++++++--------- .../BroadphaseCollision/btSimpleBroadphase.h | 26 ++--- .../CollisionDispatch/btCollisionDispatcher.h | 31 ++--- .../CollisionDispatch/btCollisionWorld.h | 6 +- .../btDefaultCollisionConfiguration.h | 11 +- .../CollisionDispatch/btGhostObject.h | 16 +-- .../CollisionDispatch/btManifoldResult.h | 9 +- .../CollisionShapes/btBoxShape.h | 35 +++--- .../CollisionShapes/btBvhTriangleMeshShape.h | 12 +- .../CollisionShapes/btCapsuleShape.h | 24 ++-- .../CollisionShapes/btConcaveShape.h | 7 +- .../CollisionShapes/btConeShape.h | 26 ++--- .../CollisionShapes/btConvexInternalShape.h | 28 ++--- .../CollisionShapes/btConvexShape.h | 13 ++- .../btMultimaterialTriangleMeshShape.h | 4 +- .../CollisionShapes/btOptimizedBvh.h | 3 +- .../CollisionShapes/btPolyhedralConvexShape.h | 13 ++- .../btTriangleIndexVertexArray.h | 22 ++-- .../CollisionShapes/btTriangleMesh.h | 4 +- .../CollisionShapes/btTriangleMeshShape.h | 14 +-- .../btDiscreteCollisionDetectorInterface.h | 5 +- .../NarrowPhaseCollision/btRaycastCallback.h | 4 +- .../ConstraintSolver/btBatchedConstraints.cpp | 1 + .../btSequentialImpulseConstraintSolver.h | 8 +- .../Dynamics/btDiscreteDynamicsWorld.h | 54 ++++----- src/BulletDynamics/Dynamics/btDynamicsWorld.h | 4 +- src/BulletDynamics/Dynamics/btRigidBody.h | 9 +- .../Dynamics/btSimpleDynamicsWorld.h | 34 +++--- .../btMultiBodyMLCPConstraintSolver.h | 4 +- .../TaskScheduler/btTaskScheduler.cpp | 1 + .../TaskScheduler/btThreadSupportPosix.cpp | 1 + .../TaskScheduler/btThreadSupportWin32.cpp | 1 + src/LinearMath/btDefaultMotionState.h | 4 +- src/LinearMath/btOverride.h | 12 ++ src/LinearMath/btSerializer.h | 33 +++--- src/LinearMath/btThreads.cpp | 1 + src/LinearMath/btThreads.h | 9 -- 39 files changed, 325 insertions(+), 305 deletions(-) create mode 100644 src/LinearMath/btOverride.h diff --git a/src/BulletCollision/BroadphaseCollision/btBroadphaseInterface.h b/src/BulletCollision/BroadphaseCollision/btBroadphaseInterface.h index 2b184bb87e..1ff072aa4e 100644 --- a/src/BulletCollision/BroadphaseCollision/btBroadphaseInterface.h +++ b/src/BulletCollision/BroadphaseCollision/btBroadphaseInterface.h @@ -19,6 +19,7 @@ subject to the following restrictions: struct btDispatcherInfo; class btDispatcher; #include "btBroadphaseProxy.h" +#include "LinearMath/btOverride.h" class btOverlappingPairCache; @@ -35,7 +36,7 @@ struct btBroadphaseRayCallback : public btBroadphaseAabbCallback unsigned int m_signs[3]; btScalar m_lambda_max; - virtual ~btBroadphaseRayCallback() override {} + virtual ~btBroadphaseRayCallback() BT_OVERRIDE {} protected: btBroadphaseRayCallback() {} diff --git a/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.h b/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.h index d11a6a7b6b..f35775d07d 100644 --- a/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.h +++ b/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.h @@ -102,26 +102,26 @@ struct btDbvtBroadphase : btBroadphaseInterface #endif /* Methods */ btDbvtBroadphase(btOverlappingPairCache* paircache = 0); - ~btDbvtBroadphase() override; + ~btDbvtBroadphase() BT_OVERRIDE; void collide(btDispatcher* dispatcher); void optimize(); /* btBroadphaseInterface Implementation */ - btBroadphaseProxy* createProxy(const btVector3& aabbMin, const btVector3& aabbMax, int shapeType, void* userPtr, int collisionFilterGroup, int collisionFilterMask, btDispatcher* dispatcher) override; - virtual void destroyProxy(btBroadphaseProxy* proxy, btDispatcher* dispatcher) override; - virtual void setAabb(btBroadphaseProxy* proxy, const btVector3& aabbMin, const btVector3& aabbMax, btDispatcher* dispatcher) override; - virtual void rayTest(const btVector3& rayFrom, const btVector3& rayTo, btBroadphaseRayCallback& rayCallback, const btVector3& aabbMin = btVector3(0, 0, 0), const btVector3& aabbMax = btVector3(0, 0, 0)) override; - virtual void aabbTest(const btVector3& aabbMin, const btVector3& aabbMax, btBroadphaseAabbCallback& callback) override; - - virtual void getAabb(btBroadphaseProxy* proxy, btVector3& aabbMin, btVector3& aabbMax) const override; - virtual void calculateOverlappingPairs(btDispatcher* dispatcher) override; - virtual btOverlappingPairCache* getOverlappingPairCache() override; - virtual const btOverlappingPairCache* getOverlappingPairCache() const override; - virtual void getBroadphaseAabb(btVector3& aabbMin, btVector3& aabbMax) const override; - virtual void printStats() override; + btBroadphaseProxy* createProxy(const btVector3& aabbMin, const btVector3& aabbMax, int shapeType, void* userPtr, int collisionFilterGroup, int collisionFilterMask, btDispatcher* dispatcher) BT_OVERRIDE; + virtual void destroyProxy(btBroadphaseProxy* proxy, btDispatcher* dispatcher) BT_OVERRIDE; + virtual void setAabb(btBroadphaseProxy* proxy, const btVector3& aabbMin, const btVector3& aabbMax, btDispatcher* dispatcher) BT_OVERRIDE; + virtual void rayTest(const btVector3& rayFrom, const btVector3& rayTo, btBroadphaseRayCallback& rayCallback, const btVector3& aabbMin = btVector3(0, 0, 0), const btVector3& aabbMax = btVector3(0, 0, 0)) BT_OVERRIDE; + virtual void aabbTest(const btVector3& aabbMin, const btVector3& aabbMax, btBroadphaseAabbCallback& callback) BT_OVERRIDE; + + virtual void getAabb(btBroadphaseProxy* proxy, btVector3& aabbMin, btVector3& aabbMax) const BT_OVERRIDE; + virtual void calculateOverlappingPairs(btDispatcher* dispatcher) BT_OVERRIDE; + virtual btOverlappingPairCache* getOverlappingPairCache() BT_OVERRIDE; + virtual const btOverlappingPairCache* getOverlappingPairCache() const BT_OVERRIDE; + virtual void getBroadphaseAabb(btVector3& aabbMin, btVector3& aabbMax) const BT_OVERRIDE; + virtual void printStats() BT_OVERRIDE; ///reset broadphase internal structures, to ensure determinism/reproducability - virtual void resetPool(btDispatcher* dispatcher) override; + virtual void resetPool(btDispatcher* dispatcher) BT_OVERRIDE; void performDeferredRemoval(btDispatcher* dispatcher); diff --git a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h index fc99b11a51..0fc6665c67 100644 --- a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h +++ b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h @@ -50,7 +50,7 @@ const int BT_NULL_PAIR = 0xffffffff; class btOverlappingPairCache : public btOverlappingPairCallback { public: - virtual ~btOverlappingPairCache() override {} // this is needed so we can get to the derived class destructor + virtual ~btOverlappingPairCache() BT_OVERRIDE {} // this is needed so we can get to the derived class destructor virtual btBroadphasePair* getOverlappingPairArrayPtr() = 0; @@ -99,13 +99,13 @@ btHashedOverlappingPairCache : public btOverlappingPairCache BT_DECLARE_ALIGNED_ALLOCATOR(); btHashedOverlappingPairCache(); - virtual ~btHashedOverlappingPairCache() override; + virtual ~btHashedOverlappingPairCache() BT_OVERRIDE; - void removeOverlappingPairsContainingProxy(btBroadphaseProxy * proxy, btDispatcher * dispatcher) override; + void removeOverlappingPairsContainingProxy(btBroadphaseProxy * proxy, btDispatcher * dispatcher) BT_OVERRIDE; - virtual void* removeOverlappingPair(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1, btDispatcher * dispatcher) override; + virtual void* removeOverlappingPair(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1, btDispatcher * dispatcher) BT_OVERRIDE; - SIMD_FORCE_INLINE bool needsBroadphaseCollision(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1) const override + SIMD_FORCE_INLINE bool needsBroadphaseCollision(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1) const BT_OVERRIDE { if (m_overlapFilterCallback) return m_overlapFilterCallback->needBroadphaseCollision(proxy0, proxy1); @@ -118,7 +118,7 @@ btHashedOverlappingPairCache : public btOverlappingPairCache // Add a pair and return the new pair. If the pair already exists, // no new pair is created and the old one is returned. - virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1) override + virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1) BT_OVERRIDE { if (!needsBroadphaseCollision(proxy0, proxy1)) return 0; @@ -126,23 +126,23 @@ btHashedOverlappingPairCache : public btOverlappingPairCache return internalAddPair(proxy0, proxy1); } - void cleanProxyFromPairs(btBroadphaseProxy * proxy, btDispatcher * dispatcher) override; + void cleanProxyFromPairs(btBroadphaseProxy * proxy, btDispatcher * dispatcher) BT_OVERRIDE; - virtual void processAllOverlappingPairs(btOverlapCallback*, btDispatcher * dispatcher) override; + virtual void processAllOverlappingPairs(btOverlapCallback*, btDispatcher * dispatcher) BT_OVERRIDE; - virtual void processAllOverlappingPairs(btOverlapCallback * callback, btDispatcher * dispatcher, const struct btDispatcherInfo& dispatchInfo) override; + virtual void processAllOverlappingPairs(btOverlapCallback * callback, btDispatcher * dispatcher, const struct btDispatcherInfo& dispatchInfo) BT_OVERRIDE; - virtual btBroadphasePair* getOverlappingPairArrayPtr() override + virtual btBroadphasePair* getOverlappingPairArrayPtr() BT_OVERRIDE { return &m_overlappingPairArray[0]; } - const btBroadphasePair* getOverlappingPairArrayPtr() const override + const btBroadphasePair* getOverlappingPairArrayPtr() const BT_OVERRIDE { return &m_overlappingPairArray[0]; } - btBroadphasePairArray& getOverlappingPairArray() override + btBroadphasePairArray& getOverlappingPairArray() BT_OVERRIDE { return m_overlappingPairArray; } @@ -152,24 +152,24 @@ btHashedOverlappingPairCache : public btOverlappingPairCache return m_overlappingPairArray; } - void cleanOverlappingPair(btBroadphasePair & pair, btDispatcher * dispatcher) override; + void cleanOverlappingPair(btBroadphasePair & pair, btDispatcher * dispatcher) BT_OVERRIDE; - btBroadphasePair* findPair(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1) override; + btBroadphasePair* findPair(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1) BT_OVERRIDE; int GetCount() const { return m_overlappingPairArray.size(); } // btBroadphasePair* GetPairs() { return m_pairs; } - btOverlapFilterCallback* getOverlapFilterCallback() override + btOverlapFilterCallback* getOverlapFilterCallback() BT_OVERRIDE { return m_overlapFilterCallback; } - void setOverlapFilterCallback(btOverlapFilterCallback * callback) override + void setOverlapFilterCallback(btOverlapFilterCallback * callback) BT_OVERRIDE { m_overlapFilterCallback = callback; } - int getNumOverlappingPairs() const override + int getNumOverlappingPairs() const BT_OVERRIDE { return m_overlappingPairArray.size(); } @@ -240,17 +240,17 @@ btHashedOverlappingPairCache : public btOverlappingPairCache return &m_overlappingPairArray[index]; } - virtual bool hasDeferredRemoval() override + virtual bool hasDeferredRemoval() BT_OVERRIDE { return false; } - virtual void setInternalGhostPairCallback(btOverlappingPairCallback * ghostPairCallback) override + virtual void setInternalGhostPairCallback(btOverlappingPairCallback * ghostPairCallback) BT_OVERRIDE { m_ghostPairCallback = ghostPairCallback; } - virtual void sortOverlappingPairs(btDispatcher * dispatcher) override; + virtual void sortOverlappingPairs(btDispatcher * dispatcher) BT_OVERRIDE; }; ///btSortedOverlappingPairCache maintains the objects with overlapping AABB @@ -274,23 +274,23 @@ class btSortedOverlappingPairCache : public btOverlappingPairCache public: btSortedOverlappingPairCache(); - virtual ~btSortedOverlappingPairCache() override; + virtual ~btSortedOverlappingPairCache() BT_OVERRIDE; - virtual void processAllOverlappingPairs(btOverlapCallback*, btDispatcher* dispatcher) override; + virtual void processAllOverlappingPairs(btOverlapCallback*, btDispatcher* dispatcher) BT_OVERRIDE; - void* removeOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1, btDispatcher* dispatcher) override; + void* removeOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1, btDispatcher* dispatcher) BT_OVERRIDE; - void cleanOverlappingPair(btBroadphasePair& pair, btDispatcher* dispatcher) override; + void cleanOverlappingPair(btBroadphasePair& pair, btDispatcher* dispatcher) BT_OVERRIDE; - btBroadphasePair* addOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) override; + btBroadphasePair* addOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) BT_OVERRIDE; - btBroadphasePair* findPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) override; + btBroadphasePair* findPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) BT_OVERRIDE; - void cleanProxyFromPairs(btBroadphaseProxy* proxy, btDispatcher* dispatcher) override; + void cleanProxyFromPairs(btBroadphaseProxy* proxy, btDispatcher* dispatcher) BT_OVERRIDE; - void removeOverlappingPairsContainingProxy(btBroadphaseProxy* proxy, btDispatcher* dispatcher) override; + void removeOverlappingPairsContainingProxy(btBroadphaseProxy* proxy, btDispatcher* dispatcher) BT_OVERRIDE; - inline bool needsBroadphaseCollision(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) const override + inline bool needsBroadphaseCollision(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) const BT_OVERRIDE { if (m_overlapFilterCallback) return m_overlapFilterCallback->needBroadphaseCollision(proxy0, proxy1); @@ -301,7 +301,7 @@ class btSortedOverlappingPairCache : public btOverlappingPairCache return collides; } - btBroadphasePairArray& getOverlappingPairArray() override + btBroadphasePairArray& getOverlappingPairArray() BT_OVERRIDE { return m_overlappingPairArray; } @@ -311,42 +311,42 @@ class btSortedOverlappingPairCache : public btOverlappingPairCache return m_overlappingPairArray; } - btBroadphasePair* getOverlappingPairArrayPtr() override + btBroadphasePair* getOverlappingPairArrayPtr() BT_OVERRIDE { return &m_overlappingPairArray[0]; } - const btBroadphasePair* getOverlappingPairArrayPtr() const override + const btBroadphasePair* getOverlappingPairArrayPtr() const BT_OVERRIDE { return &m_overlappingPairArray[0]; } - int getNumOverlappingPairs() const override + int getNumOverlappingPairs() const BT_OVERRIDE { return m_overlappingPairArray.size(); } - btOverlapFilterCallback* getOverlapFilterCallback() override + btOverlapFilterCallback* getOverlapFilterCallback() BT_OVERRIDE { return m_overlapFilterCallback; } - void setOverlapFilterCallback(btOverlapFilterCallback* callback) override + void setOverlapFilterCallback(btOverlapFilterCallback* callback) BT_OVERRIDE { m_overlapFilterCallback = callback; } - virtual bool hasDeferredRemoval() override + virtual bool hasDeferredRemoval() BT_OVERRIDE { return m_hasDeferredRemoval; } - virtual void setInternalGhostPairCallback(btOverlappingPairCallback* ghostPairCallback) override + virtual void setInternalGhostPairCallback(btOverlappingPairCallback* ghostPairCallback) BT_OVERRIDE { m_ghostPairCallback = ghostPairCallback; } - virtual void sortOverlappingPairs(btDispatcher* dispatcher) override; + virtual void sortOverlappingPairs(btDispatcher* dispatcher) BT_OVERRIDE; }; ///btNullPairCache skips add/removal of overlapping pairs. Userful for benchmarking and unit testing. @@ -355,77 +355,77 @@ class btNullPairCache : public btOverlappingPairCache btBroadphasePairArray m_overlappingPairArray; public: - virtual btBroadphasePair* getOverlappingPairArrayPtr() override + virtual btBroadphasePair* getOverlappingPairArrayPtr() BT_OVERRIDE { return &m_overlappingPairArray[0]; } - const btBroadphasePair* getOverlappingPairArrayPtr() const override + const btBroadphasePair* getOverlappingPairArrayPtr() const BT_OVERRIDE { return &m_overlappingPairArray[0]; } - btBroadphasePairArray& getOverlappingPairArray() override + btBroadphasePairArray& getOverlappingPairArray() BT_OVERRIDE { return m_overlappingPairArray; } - virtual void cleanOverlappingPair(btBroadphasePair& /*pair*/, btDispatcher* /*dispatcher*/) override + virtual void cleanOverlappingPair(btBroadphasePair& /*pair*/, btDispatcher* /*dispatcher*/) BT_OVERRIDE { } - virtual int getNumOverlappingPairs() const override + virtual int getNumOverlappingPairs() const BT_OVERRIDE { return 0; } - virtual void cleanProxyFromPairs(btBroadphaseProxy* /*proxy*/, btDispatcher* /*dispatcher*/) override + virtual void cleanProxyFromPairs(btBroadphaseProxy* /*proxy*/, btDispatcher* /*dispatcher*/) BT_OVERRIDE { } - bool needsBroadphaseCollision(btBroadphaseProxy*, btBroadphaseProxy*) const override + bool needsBroadphaseCollision(btBroadphaseProxy*, btBroadphaseProxy*) const BT_OVERRIDE { return true; } - btOverlapFilterCallback* getOverlapFilterCallback() override + btOverlapFilterCallback* getOverlapFilterCallback() BT_OVERRIDE { return 0; } - virtual void setOverlapFilterCallback(btOverlapFilterCallback* /*callback*/) override + virtual void setOverlapFilterCallback(btOverlapFilterCallback* /*callback*/) BT_OVERRIDE { } - virtual void processAllOverlappingPairs(btOverlapCallback*, btDispatcher* /*dispatcher*/) override + virtual void processAllOverlappingPairs(btOverlapCallback*, btDispatcher* /*dispatcher*/) BT_OVERRIDE { } - virtual btBroadphasePair* findPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/) override + virtual btBroadphasePair* findPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/) BT_OVERRIDE { return 0; } - virtual bool hasDeferredRemoval() override + virtual bool hasDeferredRemoval() BT_OVERRIDE { return true; } - virtual void setInternalGhostPairCallback(btOverlappingPairCallback* /* ghostPairCallback */) override + virtual void setInternalGhostPairCallback(btOverlappingPairCallback* /* ghostPairCallback */) BT_OVERRIDE { } - virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/) override + virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/) BT_OVERRIDE { return 0; } - virtual void* removeOverlappingPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/, btDispatcher* /*dispatcher*/) override + virtual void* removeOverlappingPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/, btDispatcher* /*dispatcher*/) BT_OVERRIDE { return 0; } - virtual void removeOverlappingPairsContainingProxy(btBroadphaseProxy* /*proxy0*/, btDispatcher* /*dispatcher*/) override + virtual void removeOverlappingPairsContainingProxy(btBroadphaseProxy* /*proxy0*/, btDispatcher* /*dispatcher*/) BT_OVERRIDE { } - virtual void sortOverlappingPairs(btDispatcher* dispatcher) override + virtual void sortOverlappingPairs(btDispatcher* dispatcher) BT_OVERRIDE { (void)dispatcher; } diff --git a/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h b/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h index 983a2a3b7a..9b8c4ada60 100644 --- a/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h +++ b/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h @@ -97,33 +97,33 @@ class btSimpleBroadphase : public btBroadphaseInterface } ///reset broadphase internal structures, to ensure determinism/reproducability - virtual void resetPool(btDispatcher* dispatcher) override; + virtual void resetPool(btDispatcher* dispatcher) BT_OVERRIDE; void validate(); protected: public: btSimpleBroadphase(int maxProxies = 16384, btOverlappingPairCache* overlappingPairCache = 0); - virtual ~btSimpleBroadphase() override; + virtual ~btSimpleBroadphase() BT_OVERRIDE; static bool aabbOverlap(btSimpleBroadphaseProxy* proxy0, btSimpleBroadphaseProxy* proxy1); - virtual btBroadphaseProxy* createProxy(const btVector3& aabbMin, const btVector3& aabbMax, int shapeType, void* userPtr, int collisionFilterGroup, int collisionFilterMask, btDispatcher* dispatcher) override; + virtual btBroadphaseProxy* createProxy(const btVector3& aabbMin, const btVector3& aabbMax, int shapeType, void* userPtr, int collisionFilterGroup, int collisionFilterMask, btDispatcher* dispatcher) BT_OVERRIDE; - virtual void calculateOverlappingPairs(btDispatcher* dispatcher) override; + virtual void calculateOverlappingPairs(btDispatcher* dispatcher) BT_OVERRIDE; - virtual void destroyProxy(btBroadphaseProxy* proxy, btDispatcher* dispatcher) override; - virtual void setAabb(btBroadphaseProxy* proxy, const btVector3& aabbMin, const btVector3& aabbMax, btDispatcher* dispatcher) override; - virtual void getAabb(btBroadphaseProxy* proxy, btVector3& aabbMin, btVector3& aabbMax) const override; + virtual void destroyProxy(btBroadphaseProxy* proxy, btDispatcher* dispatcher) BT_OVERRIDE; + virtual void setAabb(btBroadphaseProxy* proxy, const btVector3& aabbMin, const btVector3& aabbMax, btDispatcher* dispatcher) BT_OVERRIDE; + virtual void getAabb(btBroadphaseProxy* proxy, btVector3& aabbMin, btVector3& aabbMax) const BT_OVERRIDE; - virtual void rayTest(const btVector3& rayFrom, const btVector3& rayTo, btBroadphaseRayCallback& rayCallback, const btVector3& aabbMin = btVector3(0, 0, 0), const btVector3& aabbMax = btVector3(0, 0, 0)) override; - virtual void aabbTest(const btVector3& aabbMin, const btVector3& aabbMax, btBroadphaseAabbCallback& callback) override; + virtual void rayTest(const btVector3& rayFrom, const btVector3& rayTo, btBroadphaseRayCallback& rayCallback, const btVector3& aabbMin = btVector3(0, 0, 0), const btVector3& aabbMax = btVector3(0, 0, 0)) BT_OVERRIDE; + virtual void aabbTest(const btVector3& aabbMin, const btVector3& aabbMax, btBroadphaseAabbCallback& callback) BT_OVERRIDE; - btOverlappingPairCache* getOverlappingPairCache() override + btOverlappingPairCache* getOverlappingPairCache() BT_OVERRIDE { return m_pairCache; } - const btOverlappingPairCache* getOverlappingPairCache() const override + const btOverlappingPairCache* getOverlappingPairCache() const BT_OVERRIDE { return m_pairCache; } @@ -132,13 +132,13 @@ class btSimpleBroadphase : public btBroadphaseInterface ///getAabb returns the axis aligned bounding box in the 'global' coordinate frame ///will add some transform later - virtual void getBroadphaseAabb(btVector3& aabbMin, btVector3& aabbMax) const override + virtual void getBroadphaseAabb(btVector3& aabbMin, btVector3& aabbMax) const BT_OVERRIDE { aabbMin.setValue(-BT_LARGE_FLOAT, -BT_LARGE_FLOAT, -BT_LARGE_FLOAT); aabbMax.setValue(BT_LARGE_FLOAT, BT_LARGE_FLOAT, BT_LARGE_FLOAT); } - virtual void printStats() override + virtual void printStats() BT_OVERRIDE { // printf("btSimpleBroadphase.h\n"); // printf("numHandles = %d, maxHandles = %d\n",m_numHandles,m_maxHandles); diff --git a/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h b/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h index 4b1115df42..dd6ec79349 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h @@ -23,6 +23,7 @@ subject to the following restrictions: #include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h" #include "LinearMath/btAlignedObjectArray.h" +#include "LinearMath/btOverride.h" class btIDebugDraw; class btOverlappingPairCache; @@ -81,17 +82,17 @@ class btCollisionDispatcher : public btDispatcher void registerClosestPointsCreateFunc(int proxyType0, int proxyType1, btCollisionAlgorithmCreateFunc* createFunc); - int getNumManifolds() const override + int getNumManifolds() const BT_OVERRIDE { return int(m_manifoldsPtr.size()); } - btPersistentManifold** getInternalManifoldPointer() override + btPersistentManifold** getInternalManifoldPointer() BT_OVERRIDE { return m_manifoldsPtr.size() ? &m_manifoldsPtr[0] : 0; } - btPersistentManifold* getManifoldByIndexInternal(int index) override + btPersistentManifold* getManifoldByIndexInternal(int index) BT_OVERRIDE { btAssert(index>=0); btAssert(index m_hitPointWorld; btAlignedObjectArray m_hitFractions; - virtual btScalar addSingleResult(LocalRayResult& rayResult, bool normalInWorldSpace) override + virtual btScalar addSingleResult(LocalRayResult& rayResult, bool normalInWorldSpace) BT_OVERRIDE { m_collisionObject = rayResult.m_collisionObject; m_collisionObjects.push_back(rayResult.m_collisionObject); @@ -375,7 +375,7 @@ class btCollisionWorld btVector3 m_hitPointWorld; const btCollisionObject* m_hitCollisionObject; - virtual btScalar addSingleResult(LocalConvexResult& convexResult, bool normalInWorldSpace) override + virtual btScalar addSingleResult(LocalConvexResult& convexResult, bool normalInWorldSpace) BT_OVERRIDE { //caller already does the filter on the m_closestHitFraction btAssert(convexResult.m_hitFraction <= m_closestHitFraction); diff --git a/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h b/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h index dce933d14b..fd52c575e9 100644 --- a/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h +++ b/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h @@ -17,6 +17,7 @@ subject to the following restrictions: #define BT_DEFAULT_COLLISION_CONFIGURATION #include "btCollisionConfiguration.h" +#include "LinearMath/btOverride.h" class btVoronoiSimplexSolver; class btConvexPenetrationDepthSolver; @@ -79,22 +80,22 @@ class btDefaultCollisionConfiguration : public btCollisionConfiguration public: btDefaultCollisionConfiguration(const btDefaultCollisionConstructionInfo& constructionInfo = btDefaultCollisionConstructionInfo()); - virtual ~btDefaultCollisionConfiguration() override; + virtual ~btDefaultCollisionConfiguration() BT_OVERRIDE; ///memory pools - virtual btPoolAllocator* getPersistentManifoldPool() override + virtual btPoolAllocator* getPersistentManifoldPool() BT_OVERRIDE { return m_persistentManifoldPool; } - virtual btPoolAllocator* getCollisionAlgorithmPool() override + virtual btPoolAllocator* getCollisionAlgorithmPool() BT_OVERRIDE { return m_collisionAlgorithmPool; } - virtual btCollisionAlgorithmCreateFunc* getCollisionAlgorithmCreateFunc(int proxyType0, int proxyType1) override; + virtual btCollisionAlgorithmCreateFunc* getCollisionAlgorithmCreateFunc(int proxyType0, int proxyType1) BT_OVERRIDE; - virtual btCollisionAlgorithmCreateFunc* getClosestPointsAlgorithmCreateFunc(int proxyType0, int proxyType1) override; + virtual btCollisionAlgorithmCreateFunc* getClosestPointsAlgorithmCreateFunc(int proxyType0, int proxyType1) BT_OVERRIDE; ///Use this method to allow to generate multiple contact points between at once, between two objects using the generic convex-convex algorithm. ///By default, this feature is disabled for best performance. diff --git a/src/BulletCollision/CollisionDispatch/btGhostObject.h b/src/BulletCollision/CollisionDispatch/btGhostObject.h index e3b6d8cd45..69e9332b76 100644 --- a/src/BulletCollision/CollisionDispatch/btGhostObject.h +++ b/src/BulletCollision/CollisionDispatch/btGhostObject.h @@ -39,7 +39,7 @@ btGhostObject : public btCollisionObject public: btGhostObject(); - virtual ~btGhostObject() override; + virtual ~btGhostObject() BT_OVERRIDE; void convexSweepTest(const class btConvexShape* castShape, const btTransform& convexFromWorld, const btTransform& convexToWorld, btCollisionWorld::ConvexResultCallback& resultCallback, btScalar allowedCcdPenetration = 0.f) const; @@ -100,12 +100,12 @@ class btPairCachingGhostObject : public btGhostObject public: btPairCachingGhostObject(); - virtual ~btPairCachingGhostObject() override; + virtual ~btPairCachingGhostObject() BT_OVERRIDE; ///this method is mainly for expert/internal use only. - virtual void addOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btBroadphaseProxy* thisProxy = 0) override; + virtual void addOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btBroadphaseProxy* thisProxy = 0) BT_OVERRIDE; - virtual void removeOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btDispatcher* dispatcher, btBroadphaseProxy* thisProxy = 0) override; + virtual void removeOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btDispatcher* dispatcher, btBroadphaseProxy* thisProxy = 0) BT_OVERRIDE; btHashedOverlappingPairCache* getOverlappingPairCache() { @@ -121,11 +121,11 @@ class btGhostPairCallback : public btOverlappingPairCallback { } - virtual ~btGhostPairCallback() override + virtual ~btGhostPairCallback() BT_OVERRIDE { } - virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) override + virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) BT_OVERRIDE { btCollisionObject* colObj0 = (btCollisionObject*)proxy0->m_clientObject; btCollisionObject* colObj1 = (btCollisionObject*)proxy1->m_clientObject; @@ -138,7 +138,7 @@ class btGhostPairCallback : public btOverlappingPairCallback return 0; } - virtual void* removeOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1, btDispatcher* dispatcher) override + virtual void* removeOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1, btDispatcher* dispatcher) BT_OVERRIDE { btCollisionObject* colObj0 = (btCollisionObject*)proxy0->m_clientObject; btCollisionObject* colObj1 = (btCollisionObject*)proxy1->m_clientObject; @@ -151,7 +151,7 @@ class btGhostPairCallback : public btOverlappingPairCallback return 0; } - virtual void removeOverlappingPairsContainingProxy(btBroadphaseProxy* /*proxy0*/, btDispatcher* /*dispatcher*/) override + virtual void removeOverlappingPairsContainingProxy(btBroadphaseProxy* /*proxy0*/, btDispatcher* /*dispatcher*/) BT_OVERRIDE { btAssert(0); //need to keep track of all ghost objects and call them here diff --git a/src/BulletCollision/CollisionDispatch/btManifoldResult.h b/src/BulletCollision/CollisionDispatch/btManifoldResult.h index 9cd79b8a9d..fc6e5a963d 100644 --- a/src/BulletCollision/CollisionDispatch/btManifoldResult.h +++ b/src/BulletCollision/CollisionDispatch/btManifoldResult.h @@ -25,6 +25,7 @@ class btManifoldPoint; #include "BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h" #include "LinearMath/btTransform.h" +#include "LinearMath/btOverride.h" #include "BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h" #include "BulletCollision/CollisionDispatch/btCollisionObject.h" @@ -72,7 +73,7 @@ class btManifoldResult : public btDiscreteCollisionDetectorInterface::Result btManifoldResult(const btCollisionObjectWrapper* body0Wrap, const btCollisionObjectWrapper* body1Wrap); - virtual ~btManifoldResult() override {}; + virtual ~btManifoldResult() BT_OVERRIDE {}; void setPersistentManifold(btPersistentManifold* manifoldPtr) { @@ -88,19 +89,19 @@ class btManifoldResult : public btDiscreteCollisionDetectorInterface::Result return m_manifoldPtr; } - virtual void setShapeIdentifiersA(int partId0, int index0) override + virtual void setShapeIdentifiersA(int partId0, int index0) BT_OVERRIDE { m_partId0 = partId0; m_index0 = index0; } - virtual void setShapeIdentifiersB(int partId1, int index1) override + virtual void setShapeIdentifiersB(int partId1, int index1) BT_OVERRIDE { m_partId1 = partId1; m_index1 = index1; } - virtual void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorld, btScalar depth) override; + virtual void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorld, btScalar depth) BT_OVERRIDE; SIMD_FORCE_INLINE void refreshContactPoints() { diff --git a/src/BulletCollision/CollisionShapes/btBoxShape.h b/src/BulletCollision/CollisionShapes/btBoxShape.h index b3a54b5d69..373443a259 100644 --- a/src/BulletCollision/CollisionShapes/btBoxShape.h +++ b/src/BulletCollision/CollisionShapes/btBoxShape.h @@ -21,6 +21,7 @@ subject to the following restrictions: #include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h" #include "LinearMath/btVector3.h" #include "LinearMath/btMinMax.h" +#include "LinearMath/btOverride.h" ///The btBoxShape is a box primitive around the origin, its sides axis aligned with length specified by half extents, in local shape coordinates. When used as part of a btCollisionObject or btRigidBody it will be an oriented box in world space. ATTRIBUTE_ALIGNED16(class) @@ -44,7 +45,7 @@ btBoxShape : public btPolyhedralConvexShape return m_implicitShapeDimensions; //scaling is included, margin is not } - virtual btVector3 localGetSupportingVertex(const btVector3& vec) const override + virtual btVector3 localGetSupportingVertex(const btVector3& vec) const BT_OVERRIDE { btVector3 halfExtents = getHalfExtentsWithoutMargin(); btVector3 margin(getMargin(), getMargin(), getMargin()); @@ -55,7 +56,7 @@ btBoxShape : public btPolyhedralConvexShape btFsels(vec.z(), halfExtents.z(), -halfExtents.z())); } - SIMD_FORCE_INLINE btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const override + SIMD_FORCE_INLINE btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const BT_OVERRIDE { const btVector3& halfExtents = getHalfExtentsWithoutMargin(); @@ -64,7 +65,7 @@ btBoxShape : public btPolyhedralConvexShape btFsels(vec.z(), halfExtents.z(), -halfExtents.z())); } - virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const override + virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const BT_OVERRIDE { const btVector3& halfExtents = getHalfExtentsWithoutMargin(); @@ -79,7 +80,7 @@ btBoxShape : public btPolyhedralConvexShape btBoxShape(const btVector3& boxHalfExtents); - virtual void setMargin(btScalar collisionMargin) override + virtual void setMargin(btScalar collisionMargin) BT_OVERRIDE { //correct the m_implicitShapeDimensions for the margin btVector3 oldMargin(getMargin(), getMargin(), getMargin()); @@ -89,7 +90,7 @@ btBoxShape : public btPolyhedralConvexShape btVector3 newMargin(getMargin(), getMargin(), getMargin()); m_implicitShapeDimensions = implicitShapeDimensionsWithMargin - newMargin; } - virtual void setLocalScaling(const btVector3& scaling) override + virtual void setLocalScaling(const btVector3& scaling) BT_OVERRIDE { btVector3 oldMargin(getMargin(), getMargin(), getMargin()); btVector3 implicitShapeDimensionsWithMargin = m_implicitShapeDimensions + oldMargin; @@ -100,11 +101,11 @@ btBoxShape : public btPolyhedralConvexShape m_implicitShapeDimensions = (unScaledImplicitShapeDimensionsWithMargin * m_localScaling) - oldMargin; } - virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override; + virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const BT_OVERRIDE; - virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const override; + virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const BT_OVERRIDE; - virtual void getPlane(btVector3 & planeNormal, btVector3 & planeSupport, int i) const override + virtual void getPlane(btVector3 & planeNormal, btVector3 & planeSupport, int i) const BT_OVERRIDE { //this plane might not be aligned... // btVector4 plane; @@ -114,22 +115,22 @@ btBoxShape : public btPolyhedralConvexShape (void)planeNormal; (void)planeSupport; (void)i; } - virtual int getNumPlanes() const override + virtual int getNumPlanes() const BT_OVERRIDE { return 6; } - virtual int getNumVertices() const override + virtual int getNumVertices() const BT_OVERRIDE { return 8; } - virtual int getNumEdges() const override + virtual int getNumEdges() const BT_OVERRIDE { return 12; } - virtual void getVertex(int i, btVector3& vtx) const override + virtual void getVertex(int i, btVector3& vtx) const BT_OVERRIDE { btVector3 halfExtents = getHalfExtentsWithMargin(); @@ -168,7 +169,7 @@ btBoxShape : public btPolyhedralConvexShape } } - virtual void getEdge(int i, btVector3& pa, btVector3& pb) const override + virtual void getEdge(int i, btVector3& pa, btVector3& pb) const BT_OVERRIDE //virtual void getEdge(int i,Edge& edge) const { int edgeVert0 = 0; @@ -234,7 +235,7 @@ btBoxShape : public btPolyhedralConvexShape getVertex(edgeVert1, pb); } - virtual bool isInside(const btVector3& pt, btScalar tolerance) const override + virtual bool isInside(const btVector3& pt, btScalar tolerance) const BT_OVERRIDE { btVector3 halfExtents = getHalfExtentsWithoutMargin(); @@ -251,17 +252,17 @@ btBoxShape : public btPolyhedralConvexShape } //debugging - virtual const char* getName() const override + virtual const char* getName() const BT_OVERRIDE { return "Box"; } - virtual int getNumPreferredPenetrationDirections() const override + virtual int getNumPreferredPenetrationDirections() const BT_OVERRIDE { return 6; } - virtual void getPreferredPenetrationDirection(int index, btVector3& penetrationVector) const override + virtual void getPreferredPenetrationDirection(int index, btVector3& penetrationVector) const BT_OVERRIDE { switch (index) { diff --git a/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h b/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h index e1542cb484..3668cabcdc 100644 --- a/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h +++ b/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h @@ -53,7 +53,7 @@ btBvhTriangleMeshShape : public btTriangleMeshShape ///optionally pass in a larger bvh aabb, used for quantization. This allows for deformations within this aabb btBvhTriangleMeshShape(btStridingMeshInterface * meshInterface, bool useQuantizedAabbCompression, const btVector3& bvhAabbMin, const btVector3& bvhAabbMax, bool buildBvh = true); - virtual ~btBvhTriangleMeshShape() override; + virtual ~btBvhTriangleMeshShape() BT_OVERRIDE; bool getOwnsBvh() const { @@ -63,7 +63,7 @@ btBvhTriangleMeshShape : public btTriangleMeshShape void performRaycast(btTriangleCallback * callback, const btVector3& raySource, const btVector3& rayTarget); void performConvexcast(btTriangleCallback * callback, const btVector3& boxSource, const btVector3& boxTarget, const btVector3& boxMin, const btVector3& boxMax); - virtual void processAllTriangles(btTriangleCallback * callback, const btVector3& aabbMin, const btVector3& aabbMax) const override; + virtual void processAllTriangles(btTriangleCallback * callback, const btVector3& aabbMin, const btVector3& aabbMax) const BT_OVERRIDE; void refitTree(const btVector3& aabbMin, const btVector3& aabbMax); @@ -71,9 +71,9 @@ btBvhTriangleMeshShape : public btTriangleMeshShape void partialRefitTree(const btVector3& aabbMin, const btVector3& aabbMax); //debugging - virtual const char* getName() const override{ return "BVHTRIANGLEMESH"; } + virtual const char* getName() const BT_OVERRIDE{ return "BVHTRIANGLEMESH"; } - virtual void setLocalScaling(const btVector3& scaling) override; + virtual void setLocalScaling(const btVector3& scaling) BT_OVERRIDE; btOptimizedBvh* getOptimizedBvh() { @@ -104,10 +104,10 @@ btBvhTriangleMeshShape : public btTriangleMeshShape return m_triangleInfoMap; } - virtual int calculateSerializeBufferSize() const override; + virtual int calculateSerializeBufferSize() const BT_OVERRIDE; ///fills the dataBuffer and returns the struct name (and 0 on failure) - virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const override; + virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const BT_OVERRIDE; virtual void serializeSingleBvh(btSerializer * serializer) const; diff --git a/src/BulletCollision/CollisionShapes/btCapsuleShape.h b/src/BulletCollision/CollisionShapes/btCapsuleShape.h index 67707a8933..6fd33e3199 100644 --- a/src/BulletCollision/CollisionShapes/btCapsuleShape.h +++ b/src/BulletCollision/CollisionShapes/btCapsuleShape.h @@ -38,20 +38,20 @@ btCapsuleShape : public btConvexInternalShape btCapsuleShape(btScalar radius, btScalar height); ///CollisionShape Interface - virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const override; + virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const BT_OVERRIDE; /// btConvexShape Interface - virtual btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const override; + virtual btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const BT_OVERRIDE; - virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const override; + virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const BT_OVERRIDE; - virtual void setMargin(btScalar collisionMargin) override + virtual void setMargin(btScalar collisionMargin) BT_OVERRIDE { //don't override the margin for capsules, their entire radius == margin (void)collisionMargin; } - virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override + virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const BT_OVERRIDE { btVector3 halfExtents(getRadius(), getRadius(), getRadius()); halfExtents[m_upAxis] = getRadius() + getHalfHeight(); @@ -63,7 +63,7 @@ btCapsuleShape : public btConvexInternalShape aabbMax = center + extent; } - virtual const char* getName() const override + virtual const char* getName() const BT_OVERRIDE { return "CapsuleShape"; } @@ -84,7 +84,7 @@ btCapsuleShape : public btConvexInternalShape return m_implicitShapeDimensions[m_upAxis]; } - virtual void setLocalScaling(const btVector3& scaling) override + virtual void setLocalScaling(const btVector3& scaling) BT_OVERRIDE { btVector3 unScaledImplicitShapeDimensions = m_implicitShapeDimensions / m_localScaling; btConvexInternalShape::setLocalScaling(scaling); @@ -94,17 +94,17 @@ btCapsuleShape : public btConvexInternalShape m_collisionMargin = m_implicitShapeDimensions[radiusAxis]; } - virtual btVector3 getAnisotropicRollingFrictionDirection() const override + virtual btVector3 getAnisotropicRollingFrictionDirection() const BT_OVERRIDE { btVector3 aniDir(0, 0, 0); aniDir[getUpAxis()] = 1; return aniDir; } - virtual int calculateSerializeBufferSize() const override; + virtual int calculateSerializeBufferSize() const BT_OVERRIDE; ///fills the dataBuffer and returns the struct name (and 0 on failure) - virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const override; + virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const BT_OVERRIDE; SIMD_FORCE_INLINE void deSerializeFloat(struct btCapsuleShapeData * dataBuffer); }; @@ -117,7 +117,7 @@ class btCapsuleShapeX : public btCapsuleShape btCapsuleShapeX(btScalar radius, btScalar height); //debugging - virtual const char* getName() const override + virtual const char* getName() const BT_OVERRIDE { return "CapsuleX"; } @@ -131,7 +131,7 @@ class btCapsuleShapeZ : public btCapsuleShape btCapsuleShapeZ(btScalar radius, btScalar height); //debugging - virtual const char* getName() const override + virtual const char* getName() const BT_OVERRIDE { return "CapsuleZ"; } diff --git a/src/BulletCollision/CollisionShapes/btConcaveShape.h b/src/BulletCollision/CollisionShapes/btConcaveShape.h index ad8c678d52..c27d87c1b4 100644 --- a/src/BulletCollision/CollisionShapes/btConcaveShape.h +++ b/src/BulletCollision/CollisionShapes/btConcaveShape.h @@ -19,6 +19,7 @@ subject to the following restrictions: #include "btCollisionShape.h" #include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h" // for the types #include "btTriangleCallback.h" +#include "LinearMath/btOverride.h" /// PHY_ScalarType enumerates possible scalar types. /// See the btStridingMeshInterface or btHeightfieldTerrainShape for its use @@ -45,15 +46,15 @@ btConcaveShape : public btCollisionShape btConcaveShape(); - virtual ~btConcaveShape() override; + virtual ~btConcaveShape() BT_OVERRIDE; virtual void processAllTriangles(btTriangleCallback * callback, const btVector3& aabbMin, const btVector3& aabbMax) const = 0; - virtual btScalar getMargin() const override + virtual btScalar getMargin() const BT_OVERRIDE { return m_collisionMargin; } - virtual void setMargin(btScalar collisionMargin) override + virtual void setMargin(btScalar collisionMargin) BT_OVERRIDE { m_collisionMargin = collisionMargin; } diff --git a/src/BulletCollision/CollisionShapes/btConeShape.h b/src/BulletCollision/CollisionShapes/btConeShape.h index 4d4605e4de..0d836a3d16 100644 --- a/src/BulletCollision/CollisionShapes/btConeShape.h +++ b/src/BulletCollision/CollisionShapes/btConeShape.h @@ -35,9 +35,9 @@ btConeShape : public btConvexInternalShape btConeShape(btScalar radius, btScalar height); - virtual btVector3 localGetSupportingVertex(const btVector3& vec) const override; - virtual btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const override; - virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const override; + virtual btVector3 localGetSupportingVertex(const btVector3& vec) const BT_OVERRIDE; + virtual btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const BT_OVERRIDE; + virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const BT_OVERRIDE; btScalar getRadius() const { return m_radius; } btScalar getHeight() const { return m_height; } @@ -51,7 +51,7 @@ btConeShape : public btConvexInternalShape m_height = height; } - virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const override + virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const BT_OVERRIDE { btTransform identity; identity.setIdentity(); @@ -77,7 +77,7 @@ btConeShape : public btConvexInternalShape // inertia.z() = scaledmass * (x2+y2); } - virtual const char* getName() const override + virtual const char* getName() const BT_OVERRIDE { return "Cone"; } @@ -90,17 +90,17 @@ btConeShape : public btConvexInternalShape return m_coneIndices[1]; } - virtual btVector3 getAnisotropicRollingFrictionDirection() const override + virtual btVector3 getAnisotropicRollingFrictionDirection() const BT_OVERRIDE { return btVector3(0, 1, 0); } - virtual void setLocalScaling(const btVector3& scaling) override; + virtual void setLocalScaling(const btVector3& scaling) BT_OVERRIDE; - virtual int calculateSerializeBufferSize() const override; + virtual int calculateSerializeBufferSize() const BT_OVERRIDE; ///fills the dataBuffer and returns the struct name (and 0 on failure) - virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const override; + virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const BT_OVERRIDE; }; ///btConeShape implements a Cone shape, around the X axis @@ -109,13 +109,13 @@ class btConeShapeX : public btConeShape public: btConeShapeX(btScalar radius, btScalar height); - virtual btVector3 getAnisotropicRollingFrictionDirection() const override + virtual btVector3 getAnisotropicRollingFrictionDirection() const BT_OVERRIDE { return btVector3(1, 0, 0); } //debugging - virtual const char* getName() const override + virtual const char* getName() const BT_OVERRIDE { return "ConeX"; } @@ -127,13 +127,13 @@ class btConeShapeZ : public btConeShape public: btConeShapeZ(btScalar radius, btScalar height); - virtual btVector3 getAnisotropicRollingFrictionDirection() const override + virtual btVector3 getAnisotropicRollingFrictionDirection() const BT_OVERRIDE { return btVector3(0, 0, 1); } //debugging - virtual const char* getName() const override + virtual const char* getName() const BT_OVERRIDE { return "ConeZ"; } diff --git a/src/BulletCollision/CollisionShapes/btConvexInternalShape.h b/src/BulletCollision/CollisionShapes/btConvexInternalShape.h index 9f093d6208..9643a6fac3 100644 --- a/src/BulletCollision/CollisionShapes/btConvexInternalShape.h +++ b/src/BulletCollision/CollisionShapes/btConvexInternalShape.h @@ -43,11 +43,11 @@ btConvexInternalShape : public btConvexShape public: BT_DECLARE_ALIGNED_ALLOCATOR(); - virtual ~btConvexInternalShape() override + virtual ~btConvexInternalShape() BT_OVERRIDE { } - virtual btVector3 localGetSupportingVertex(const btVector3& vec) const override; + virtual btVector3 localGetSupportingVertex(const btVector3& vec) const BT_OVERRIDE; const btVector3& getImplicitShapeDimensions() const { @@ -81,15 +81,15 @@ btConvexInternalShape : public btConvexShape } ///getAabb's default implementation is brute force, expected derived classes to implement a fast dedicated version - void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override + void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const BT_OVERRIDE { getAabbSlow(t, aabbMin, aabbMax); } - virtual void getAabbSlow(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override; + virtual void getAabbSlow(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const BT_OVERRIDE; - virtual void setLocalScaling(const btVector3& scaling) override; - virtual const btVector3& getLocalScaling() const override + virtual void setLocalScaling(const btVector3& scaling) BT_OVERRIDE; + virtual const btVector3& getLocalScaling() const BT_OVERRIDE { return m_localScaling; } @@ -99,11 +99,11 @@ btConvexInternalShape : public btConvexShape return m_localScaling; } - virtual void setMargin(btScalar margin) override + virtual void setMargin(btScalar margin) BT_OVERRIDE { m_collisionMargin = margin; } - virtual btScalar getMargin() const override + virtual btScalar getMargin() const BT_OVERRIDE { return m_collisionMargin; } @@ -113,22 +113,22 @@ btConvexInternalShape : public btConvexShape return m_collisionMargin; } - virtual int getNumPreferredPenetrationDirections() const override + virtual int getNumPreferredPenetrationDirections() const BT_OVERRIDE { return 0; } - virtual void getPreferredPenetrationDirection(int index, btVector3& penetrationVector) const override + virtual void getPreferredPenetrationDirection(int index, btVector3& penetrationVector) const BT_OVERRIDE { (void)penetrationVector; (void)index; btAssert(0); } - virtual int calculateSerializeBufferSize() const override; + virtual int calculateSerializeBufferSize() const BT_OVERRIDE; ///fills the dataBuffer and returns the struct name (and 0 on failure) - virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const override; + virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const BT_OVERRIDE; }; ///do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64 @@ -198,9 +198,9 @@ class btConvexInternalAabbCachingShape : public btConvexInternalShape } public: - virtual void setLocalScaling(const btVector3& scaling) override; + virtual void setLocalScaling(const btVector3& scaling) BT_OVERRIDE; - virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override; + virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const BT_OVERRIDE; void recalcLocalAabb(); }; diff --git a/src/BulletCollision/CollisionShapes/btConvexShape.h b/src/BulletCollision/CollisionShapes/btConvexShape.h index ee54450bd3..5c14d4b168 100644 --- a/src/BulletCollision/CollisionShapes/btConvexShape.h +++ b/src/BulletCollision/CollisionShapes/btConvexShape.h @@ -23,6 +23,7 @@ subject to the following restrictions: #include "LinearMath/btMatrix3x3.h" #include "btCollisionMargin.h" #include "LinearMath/btAlignedAllocator.h" +#include "LinearMath/btOverride.h" #define MAX_PREFERRED_PENETRATION_DIRECTIONS 10 @@ -36,7 +37,7 @@ btConvexShape : public btCollisionShape btConvexShape(); - virtual ~btConvexShape() override; + virtual ~btConvexShape() BT_OVERRIDE; virtual btVector3 localGetSupportingVertex(const btVector3& vec) const = 0; @@ -56,16 +57,16 @@ btConvexShape : public btCollisionShape virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const = 0; ///getAabb's default implementation is brute force, expected derived classes to implement a fast dedicated version - void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override = 0; + void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const BT_OVERRIDE = 0; virtual void getAabbSlow(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const = 0; - virtual void setLocalScaling(const btVector3& scaling) override = 0; - virtual const btVector3& getLocalScaling() const override = 0; + virtual void setLocalScaling(const btVector3& scaling) BT_OVERRIDE = 0; + virtual const btVector3& getLocalScaling() const BT_OVERRIDE = 0; - virtual void setMargin(btScalar margin) override = 0; + virtual void setMargin(btScalar margin) BT_OVERRIDE = 0; - virtual btScalar getMargin() const override = 0; + virtual btScalar getMargin() const BT_OVERRIDE = 0; virtual int getNumPreferredPenetrationDirections() const = 0; diff --git a/src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.h b/src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.h index 184af027ce..c40e809376 100644 --- a/src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.h +++ b/src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.h @@ -93,7 +93,7 @@ btMultimaterialTriangleMeshShape : public btBvhTriangleMeshShape } } - virtual ~btMultimaterialTriangleMeshShape() override + virtual ~btMultimaterialTriangleMeshShape() BT_OVERRIDE { /* for(int i = 0; i < m_meshInterface->getNumSubParts(); i++) @@ -106,7 +106,7 @@ btMultimaterialTriangleMeshShape : public btBvhTriangleMeshShape */ } //debugging - virtual const char *getName() const override{ return "MULTIMATERIALTRIANGLEMESH"; } + virtual const char *getName() const BT_OVERRIDE{ return "MULTIMATERIALTRIANGLEMESH"; } ///Obtains the material for a specific triangle const btMaterial *getMaterialProperties(int partID, int triIndex); diff --git a/src/BulletCollision/CollisionShapes/btOptimizedBvh.h b/src/BulletCollision/CollisionShapes/btOptimizedBvh.h index 0b9cad629c..4fac000e31 100644 --- a/src/BulletCollision/CollisionShapes/btOptimizedBvh.h +++ b/src/BulletCollision/CollisionShapes/btOptimizedBvh.h @@ -19,6 +19,7 @@ subject to the following restrictions: #define BT_OPTIMIZED_BVH_H #include "BulletCollision/BroadphaseCollision/btQuantizedBvh.h" +#include "LinearMath/btOverride.h" class btStridingMeshInterface; @@ -33,7 +34,7 @@ btOptimizedBvh : public btQuantizedBvh public: btOptimizedBvh(); - virtual ~btOptimizedBvh() override; + virtual ~btOptimizedBvh() BT_OVERRIDE; void build(btStridingMeshInterface * triangles, bool useQuantizedAabbCompression, const btVector3& bvhAabbMin, const btVector3& bvhAabbMax); diff --git a/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h b/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h index 5c5dbbc362..703fe4f0cf 100644 --- a/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h +++ b/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h @@ -17,6 +17,7 @@ subject to the following restrictions: #define BT_POLYHEDRAL_CONVEX_SHAPE_H #include "LinearMath/btMatrix3x3.h" +#include "LinearMath/btOverride.h" #include "btConvexInternalShape.h" class btConvexPolyhedron; @@ -32,7 +33,7 @@ btPolyhedralConvexShape : public btConvexInternalShape btPolyhedralConvexShape(); - virtual ~btPolyhedralConvexShape() override; + virtual ~btPolyhedralConvexShape() BT_OVERRIDE; ///optional method mainly used to generate multiple contact points by clipping polyhedral features (faces/edges) ///experimental/work-in-progress @@ -47,10 +48,10 @@ btPolyhedralConvexShape : public btConvexInternalShape //brute force implementations - virtual btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const override; - virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const override; + virtual btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const BT_OVERRIDE; + virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const BT_OVERRIDE; - virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const override; + virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const BT_OVERRIDE; virtual int getNumVertices() const = 0; virtual int getNumEdges() const = 0; @@ -96,9 +97,9 @@ class btPolyhedralConvexAabbCachingShape : public btPolyhedralConvexShape btTransformAabb(m_localAabbMin, m_localAabbMax, margin, trans, aabbMin, aabbMax); } - virtual void setLocalScaling(const btVector3& scaling) override; + virtual void setLocalScaling(const btVector3& scaling) BT_OVERRIDE; - virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override; + virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const BT_OVERRIDE; void recalcLocalAabb(); }; diff --git a/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h b/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h index 084af648fc..8104f7f7b1 100644 --- a/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h +++ b/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h @@ -79,7 +79,7 @@ btTriangleIndexVertexArray : public btStridingMeshInterface { } - virtual ~btTriangleIndexVertexArray() override; + virtual ~btTriangleIndexVertexArray() BT_OVERRIDE; //just to be backwards compatible btTriangleIndexVertexArray(int numTriangles, int* triangleIndexBase, int triangleIndexStride, int numVertices, btScalar* vertexBase, int vertexStride); @@ -90,19 +90,19 @@ btTriangleIndexVertexArray : public btStridingMeshInterface m_indexedMeshes[m_indexedMeshes.size() - 1].m_indexType = indexType; } - virtual void getLockedVertexIndexBase(unsigned char** vertexbase, int& numverts, PHY_ScalarType& type, int& vertexStride, unsigned char** indexbase, int& indexstride, int& numfaces, PHY_ScalarType& indicestype, int subpart = 0) override; + virtual void getLockedVertexIndexBase(unsigned char** vertexbase, int& numverts, PHY_ScalarType& type, int& vertexStride, unsigned char** indexbase, int& indexstride, int& numfaces, PHY_ScalarType& indicestype, int subpart = 0) BT_OVERRIDE; - virtual void getLockedReadOnlyVertexIndexBase(const unsigned char** vertexbase, int& numverts, PHY_ScalarType& type, int& vertexStride, const unsigned char** indexbase, int& indexstride, int& numfaces, PHY_ScalarType& indicestype, int subpart = 0) const override; + virtual void getLockedReadOnlyVertexIndexBase(const unsigned char** vertexbase, int& numverts, PHY_ScalarType& type, int& vertexStride, const unsigned char** indexbase, int& indexstride, int& numfaces, PHY_ScalarType& indicestype, int subpart = 0) const BT_OVERRIDE; /// unLockVertexBase finishes the access to a subpart of the triangle mesh /// make a call to unLockVertexBase when the read and write access (using getLockedVertexIndexBase) is finished - virtual void unLockVertexBase(int subpart) override { (void)subpart; } + virtual void unLockVertexBase(int subpart) BT_OVERRIDE { (void)subpart; } - virtual void unLockReadOnlyVertexBase(int subpart) const override { (void)subpart; } + virtual void unLockReadOnlyVertexBase(int subpart) const BT_OVERRIDE { (void)subpart; } /// getNumSubParts returns the number of separate subparts /// each subpart has a continuous array of vertices and indices - virtual int getNumSubParts() const override + virtual int getNumSubParts() const BT_OVERRIDE { return (int)m_indexedMeshes.size(); } @@ -117,12 +117,12 @@ btTriangleIndexVertexArray : public btStridingMeshInterface return m_indexedMeshes; } - virtual void preallocateVertices(int numverts) override { (void)numverts; } - virtual void preallocateIndices(int numindices) override { (void)numindices; } + virtual void preallocateVertices(int numverts) BT_OVERRIDE { (void)numverts; } + virtual void preallocateIndices(int numindices) BT_OVERRIDE { (void)numindices; } - virtual bool hasPremadeAabb() const override; - virtual void setPremadeAabb(const btVector3& aabbMin, const btVector3& aabbMax) const override; - virtual void getPremadeAabb(btVector3 * aabbMin, btVector3 * aabbMax) const override; + virtual bool hasPremadeAabb() const BT_OVERRIDE; + virtual void setPremadeAabb(const btVector3& aabbMin, const btVector3& aabbMax) const BT_OVERRIDE; + virtual void getPremadeAabb(btVector3 * aabbMin, btVector3 * aabbMax) const BT_OVERRIDE; }; #endif //BT_TRIANGLE_INDEX_VERTEX_ARRAY_H diff --git a/src/BulletCollision/CollisionShapes/btTriangleMesh.h b/src/BulletCollision/CollisionShapes/btTriangleMesh.h index 3afcfdb902..400e6c9501 100644 --- a/src/BulletCollision/CollisionShapes/btTriangleMesh.h +++ b/src/BulletCollision/CollisionShapes/btTriangleMesh.h @@ -57,8 +57,8 @@ class btTriangleMesh : public btTriangleIndexVertexArray int getNumTriangles() const; - virtual void preallocateVertices(int numverts) override; - virtual void preallocateIndices(int numindices) override; + virtual void preallocateVertices(int numverts) BT_OVERRIDE; + virtual void preallocateIndices(int numindices) BT_OVERRIDE; ///findOrAddVertex is an internal method, use addTriangle instead int findOrAddVertex(const btVector3& vertex, bool removeDuplicateVertices); diff --git a/src/BulletCollision/CollisionShapes/btTriangleMeshShape.h b/src/BulletCollision/CollisionShapes/btTriangleMeshShape.h index 2438a2abaa..6df067552f 100644 --- a/src/BulletCollision/CollisionShapes/btTriangleMeshShape.h +++ b/src/BulletCollision/CollisionShapes/btTriangleMeshShape.h @@ -35,7 +35,7 @@ btTriangleMeshShape : public btConcaveShape public: BT_DECLARE_ALIGNED_ALLOCATOR(); - virtual ~btTriangleMeshShape() override; + virtual ~btTriangleMeshShape() BT_OVERRIDE; virtual btVector3 localGetSupportingVertex(const btVector3& vec) const; @@ -47,14 +47,14 @@ btTriangleMeshShape : public btConcaveShape void recalcLocalAabb(); - virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override; + virtual void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const BT_OVERRIDE; - virtual void processAllTriangles(btTriangleCallback * callback, const btVector3& aabbMin, const btVector3& aabbMax) const override; + virtual void processAllTriangles(btTriangleCallback * callback, const btVector3& aabbMin, const btVector3& aabbMax) const BT_OVERRIDE; - virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const override; + virtual void calculateLocalInertia(btScalar mass, btVector3 & inertia) const BT_OVERRIDE; - virtual void setLocalScaling(const btVector3& scaling) override; - virtual const btVector3& getLocalScaling() const override; + virtual void setLocalScaling(const btVector3& scaling) BT_OVERRIDE; + virtual const btVector3& getLocalScaling() const BT_OVERRIDE; btStridingMeshInterface* getMeshInterface() { @@ -76,7 +76,7 @@ btTriangleMeshShape : public btConcaveShape } //debugging - virtual const char* getName() const override { return "TRIANGLEMESH"; } + virtual const char* getName() const BT_OVERRIDE { return "TRIANGLEMESH"; } }; #endif //BT_TRIANGLE_MESH_SHAPE_H diff --git a/src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h b/src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h index deef70749f..23aef0ea5a 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h +++ b/src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h @@ -18,6 +18,7 @@ subject to the following restrictions: #include "LinearMath/btTransform.h" #include "LinearMath/btVector3.h" +#include "LinearMath/btOverride.h" /// This interface is made to be used by an iterative approach to do TimeOfImpact calculations /// This interface allows to query for closest points and penetration depth between two (convex) objects @@ -69,9 +70,9 @@ struct btStorageResult : public btDiscreteCollisionDetectorInterface::Result } public: - virtual ~btStorageResult() override {}; + virtual ~btStorageResult() BT_OVERRIDE {}; - virtual void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorld, btScalar depth) override + virtual void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorld, btScalar depth) BT_OVERRIDE { if (depth < m_distance) { diff --git a/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h b/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h index 49956654d0..735e364a6f 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h +++ b/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h @@ -46,7 +46,7 @@ class btTriangleRaycastCallback : public btTriangleCallback btTriangleRaycastCallback(const btVector3& from, const btVector3& to, unsigned int flags = 0); - virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex) override; + virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex) BT_OVERRIDE; virtual btScalar reportHit(const btVector3& hitNormalLocal, btScalar hitFraction, int partId, int triangleIndex) = 0; }; @@ -64,7 +64,7 @@ class btTriangleConvexcastCallback : public btTriangleCallback btTriangleConvexcastCallback(const btConvexShape* convexShape, const btTransform& convexShapeFrom, const btTransform& convexShapeTo, const btTransform& triangleToWorld, const btScalar triangleCollisionMargin); - virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex) override; + virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex) BT_OVERRIDE; virtual btScalar reportHit(const btVector3& hitNormalLocal, const btVector3& hitPointLocal, btScalar hitFraction, int partId, int triangleIndex) = 0; }; diff --git a/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp b/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp index 0ecf3aecc3..f37a29d1ac 100644 --- a/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp +++ b/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp @@ -19,6 +19,7 @@ subject to the following restrictions: #include "LinearMath/btMinMax.h" #include "LinearMath/btStackAlloc.h" #include "LinearMath/btQuickprof.h" +#include "LinearMath/btOverride.h" #include //for memset diff --git a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h index b4555fb129..20cac6ec0c 100644 --- a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h +++ b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h @@ -156,12 +156,12 @@ btSequentialImpulseConstraintSolver : public btConstraintSolver BT_DECLARE_ALIGNED_ALLOCATOR(); btSequentialImpulseConstraintSolver(); - virtual ~btSequentialImpulseConstraintSolver() override; + virtual ~btSequentialImpulseConstraintSolver() BT_OVERRIDE; - virtual btScalar solveGroup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifold, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* dispatcher) override; + virtual btScalar solveGroup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifold, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* dispatcher) BT_OVERRIDE; ///clear internal cached data and reset random seed - virtual void reset() override; + virtual void reset() BT_OVERRIDE; unsigned long btRand2(); @@ -176,7 +176,7 @@ btSequentialImpulseConstraintSolver : public btConstraintSolver return m_btSeed2; } - virtual btConstraintSolverType getSolverType() const override + virtual btConstraintSolverType getSolverType() const BT_OVERRIDE { return BT_SEQUENTIAL_IMPULSE_SOLVER; } diff --git a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h index 601d105d96..dc8e862e8d 100644 --- a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h +++ b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h @@ -102,25 +102,25 @@ btDiscreteDynamicsWorld : public btDynamicsWorld ///this btDiscreteDynamicsWorld constructor gets created objects from the user, and will not delete those btDiscreteDynamicsWorld(btDispatcher * dispatcher, btBroadphaseInterface * pairCache, btConstraintSolver * constraintSolver, btCollisionConfiguration * collisionConfiguration); - virtual ~btDiscreteDynamicsWorld() override; + virtual ~btDiscreteDynamicsWorld() BT_OVERRIDE; ///if maxSubSteps > 0, it will interpolate motion between fixedTimeStep's - virtual int stepSimulation(btScalar timeStep, int maxSubSteps = 1, btScalar fixedTimeStep = btScalar(1.) / btScalar(60.)) override; + virtual int stepSimulation(btScalar timeStep, int maxSubSteps = 1, btScalar fixedTimeStep = btScalar(1.) / btScalar(60.)) BT_OVERRIDE; virtual void solveConstraints(btContactSolverInfo & solverInfo); - virtual void synchronizeMotionStates() override; + virtual void synchronizeMotionStates() BT_OVERRIDE; ///this can be useful to synchronize a single rigid body -> graphics object void synchronizeSingleMotionState(btRigidBody * body); - virtual void addConstraint(btTypedConstraint * constraint, bool disableCollisionsBetweenLinkedBodies = false) override; + virtual void addConstraint(btTypedConstraint * constraint, bool disableCollisionsBetweenLinkedBodies = false) BT_OVERRIDE; - virtual void removeConstraint(btTypedConstraint * constraint) override; + virtual void removeConstraint(btTypedConstraint * constraint) BT_OVERRIDE; - virtual void addAction(btActionInterface*) override; + virtual void addAction(btActionInterface*) BT_OVERRIDE; - virtual void removeAction(btActionInterface*) override; + virtual void removeAction(btActionInterface*) BT_OVERRIDE; btSimulationIslandManager* getSimulationIslandManager() { @@ -137,42 +137,42 @@ btDiscreteDynamicsWorld : public btDynamicsWorld return this; } - virtual void setGravity(const btVector3& gravity) override; + virtual void setGravity(const btVector3& gravity) BT_OVERRIDE; - virtual btVector3 getGravity() const override; + virtual btVector3 getGravity() const BT_OVERRIDE; - virtual void addCollisionObject(btCollisionObject * collisionObject, int collisionFilterGroup = btBroadphaseProxy::StaticFilter, int collisionFilterMask = btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter) override; + virtual void addCollisionObject(btCollisionObject * collisionObject, int collisionFilterGroup = btBroadphaseProxy::StaticFilter, int collisionFilterMask = btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter) BT_OVERRIDE; - virtual void addRigidBody(btRigidBody * body) override; + virtual void addRigidBody(btRigidBody * body) BT_OVERRIDE; - virtual void addRigidBody(btRigidBody * body, int group, int mask) override; + virtual void addRigidBody(btRigidBody * body, int group, int mask) BT_OVERRIDE; - virtual void removeRigidBody(btRigidBody * body) override; + virtual void removeRigidBody(btRigidBody * body) BT_OVERRIDE; ///removeCollisionObject will first check if it is a rigid body, if so call removeRigidBody otherwise call btCollisionWorld::removeCollisionObject - virtual void removeCollisionObject(btCollisionObject * collisionObject) override; + virtual void removeCollisionObject(btCollisionObject * collisionObject) BT_OVERRIDE; virtual void debugDrawConstraint(btTypedConstraint * constraint); - virtual void debugDrawWorld() override; + virtual void debugDrawWorld() BT_OVERRIDE; - virtual void setConstraintSolver(btConstraintSolver * solver) override; + virtual void setConstraintSolver(btConstraintSolver * solver) BT_OVERRIDE; - virtual btConstraintSolver* getConstraintSolver() override; + virtual btConstraintSolver* getConstraintSolver() BT_OVERRIDE; - virtual int getNumConstraints() const override; + virtual int getNumConstraints() const BT_OVERRIDE; - virtual btTypedConstraint* getConstraint(int index) override; + virtual btTypedConstraint* getConstraint(int index) BT_OVERRIDE; - virtual const btTypedConstraint* getConstraint(int index) const override; + virtual const btTypedConstraint* getConstraint(int index) const BT_OVERRIDE; - virtual btDynamicsWorldType getWorldType() const override + virtual btDynamicsWorldType getWorldType() const BT_OVERRIDE { return BT_DISCRETE_DYNAMICS_WORLD; } ///the forces on each rigidbody is accumulating together with gravity. clear this after each timestep. - virtual void clearForces() override; + virtual void clearForces() BT_OVERRIDE; ///apply gravity, call this once per timestep virtual void applyGravity(); @@ -189,13 +189,13 @@ btDiscreteDynamicsWorld : public btDynamicsWorld } ///obsolete, use addAction instead - virtual void addVehicle(btActionInterface * vehicle) override; + virtual void addVehicle(btActionInterface * vehicle) BT_OVERRIDE; ///obsolete, use removeAction instead - virtual void removeVehicle(btActionInterface * vehicle) override; + virtual void removeVehicle(btActionInterface * vehicle) BT_OVERRIDE; ///obsolete, use addAction instead - virtual void addCharacter(btActionInterface * character) override; + virtual void addCharacter(btActionInterface * character) BT_OVERRIDE; ///obsolete, use removeAction instead - virtual void removeCharacter(btActionInterface * character) override; + virtual void removeCharacter(btActionInterface * character) BT_OVERRIDE; void setSynchronizeAllMotionStates(bool synchronizeAll) { @@ -217,7 +217,7 @@ btDiscreteDynamicsWorld : public btDynamicsWorld } ///Preliminary serialization test for Bullet 2.76. Loading those files requires a separate parser (see Bullet/Demos/SerializeDemo) - virtual void serialize(btSerializer * serializer) override; + virtual void serialize(btSerializer * serializer) BT_OVERRIDE; ///Interpolate motion state between previous and current transform, instead of current and next transform. ///This can relieve discontinuities in the rendering, due to penetrations diff --git a/src/BulletDynamics/Dynamics/btDynamicsWorld.h b/src/BulletDynamics/Dynamics/btDynamicsWorld.h index 0f63caef7c..8af1782c42 100644 --- a/src/BulletDynamics/Dynamics/btDynamicsWorld.h +++ b/src/BulletDynamics/Dynamics/btDynamicsWorld.h @@ -54,7 +54,7 @@ class btDynamicsWorld : public btCollisionWorld { } - virtual ~btDynamicsWorld() override + virtual ~btDynamicsWorld() BT_OVERRIDE { } @@ -64,7 +64,7 @@ class btDynamicsWorld : public btCollisionWorld ///You can disable subdividing the timestep/substepping by passing maxSubSteps=0 as second argument to stepSimulation, but in that case you have to keep the timeStep constant. virtual int stepSimulation(btScalar timeStep, int maxSubSteps = 1, btScalar fixedTimeStep = btScalar(1.) / btScalar(60.)) = 0; - virtual void debugDrawWorld() override {}; + virtual void debugDrawWorld() BT_OVERRIDE {}; virtual void addConstraint(btTypedConstraint* constraint, bool disableCollisionsBetweenLinkedBodies = false) { diff --git a/src/BulletDynamics/Dynamics/btRigidBody.h b/src/BulletDynamics/Dynamics/btRigidBody.h index 1dc761240e..219000aa72 100644 --- a/src/BulletDynamics/Dynamics/btRigidBody.h +++ b/src/BulletDynamics/Dynamics/btRigidBody.h @@ -18,6 +18,7 @@ subject to the following restrictions: #include "LinearMath/btAlignedObjectArray.h" #include "LinearMath/btTransform.h" +#include "LinearMath/btOverride.h" #include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h" #include "BulletCollision/CollisionDispatch/btCollisionObject.h" @@ -170,7 +171,7 @@ class btRigidBody : public btCollisionObject ///To specify friction (etc) during rigid body construction, please use the other constructor (using btRigidBodyConstructionInfo) btRigidBody(btScalar mass, btMotionState* motionState, btCollisionShape* collisionShape, const btVector3& localInertia = btVector3(0, 0, 0)); - virtual ~btRigidBody() override + virtual ~btRigidBody() BT_OVERRIDE { //No constraints should point to this rigidbody //Remove constraints from the dynamics world before you delete the related rigidbodies. @@ -622,12 +623,12 @@ class btRigidBody : public btCollisionObject /////////////////////////////////////////////// - virtual int calculateSerializeBufferSize() const override; + virtual int calculateSerializeBufferSize() const BT_OVERRIDE; ///fills the dataBuffer and returns the struct name (and 0 on failure) - virtual const char* serialize(void* dataBuffer, class btSerializer* serializer) const override; + virtual const char* serialize(void* dataBuffer, class btSerializer* serializer) const BT_OVERRIDE; - virtual void serializeSingleObject(class btSerializer* serializer) const override; + virtual void serializeSingleObject(class btSerializer* serializer) const BT_OVERRIDE; }; //@todo add m_optionalMotionState and m_constraintRefs to btRigidBodyData diff --git a/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h b/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h index 8f9d0b7bdc..fb7fd05239 100644 --- a/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h +++ b/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h @@ -41,44 +41,44 @@ class btSimpleDynamicsWorld : public btDynamicsWorld ///this btSimpleDynamicsWorld constructor creates dispatcher, broadphase pairCache and constraintSolver btSimpleDynamicsWorld(btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btConstraintSolver* constraintSolver, btCollisionConfiguration* collisionConfiguration); - virtual ~btSimpleDynamicsWorld() override; + virtual ~btSimpleDynamicsWorld() BT_OVERRIDE; ///maxSubSteps/fixedTimeStep for interpolation is currently ignored for btSimpleDynamicsWorld, use btDiscreteDynamicsWorld instead - virtual int stepSimulation(btScalar timeStep, int maxSubSteps = 1, btScalar fixedTimeStep = btScalar(1.) / btScalar(60.)) override; + virtual int stepSimulation(btScalar timeStep, int maxSubSteps = 1, btScalar fixedTimeStep = btScalar(1.) / btScalar(60.)) BT_OVERRIDE; - virtual void setGravity(const btVector3& gravity) override; + virtual void setGravity(const btVector3& gravity) BT_OVERRIDE; - virtual btVector3 getGravity() const override; + virtual btVector3 getGravity() const BT_OVERRIDE; - virtual void addRigidBody(btRigidBody* body) override; + virtual void addRigidBody(btRigidBody* body) BT_OVERRIDE; - virtual void addRigidBody(btRigidBody* body, int group, int mask) override; + virtual void addRigidBody(btRigidBody* body, int group, int mask) BT_OVERRIDE; - virtual void removeRigidBody(btRigidBody* body) override; + virtual void removeRigidBody(btRigidBody* body) BT_OVERRIDE; - virtual void debugDrawWorld() override; + virtual void debugDrawWorld() BT_OVERRIDE; - virtual void addAction(btActionInterface* action) override; + virtual void addAction(btActionInterface* action) BT_OVERRIDE; - virtual void removeAction(btActionInterface* action) override; + virtual void removeAction(btActionInterface* action) BT_OVERRIDE; ///removeCollisionObject will first check if it is a rigid body, if so call removeRigidBody otherwise call btCollisionWorld::removeCollisionObject - virtual void removeCollisionObject(btCollisionObject* collisionObject) override; + virtual void removeCollisionObject(btCollisionObject* collisionObject) BT_OVERRIDE; - virtual void updateAabbs() override; + virtual void updateAabbs() BT_OVERRIDE; - virtual void synchronizeMotionStates() override; + virtual void synchronizeMotionStates() BT_OVERRIDE; - virtual void setConstraintSolver(btConstraintSolver* solver) override; + virtual void setConstraintSolver(btConstraintSolver* solver) BT_OVERRIDE; - virtual btConstraintSolver* getConstraintSolver() override; + virtual btConstraintSolver* getConstraintSolver() BT_OVERRIDE; - virtual btDynamicsWorldType getWorldType() const override + virtual btDynamicsWorldType getWorldType() const BT_OVERRIDE { return BT_SIMPLE_DYNAMICS_WORLD; } - virtual void clearForces() override; + virtual void clearForces() BT_OVERRIDE; }; #endif //BT_SIMPLE_DYNAMICS_WORLD_H diff --git a/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h b/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h index dbcb388807..8178d78ab3 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h @@ -156,7 +156,7 @@ class btMultiBodyMLCPConstraintSolver : public btMultiBodyConstraintSolver btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, - btIDebugDraw* debugDrawer) override; + btIDebugDraw* debugDrawer) BT_OVERRIDE; public: BT_DECLARE_ALIGNED_ALLOCATOR() @@ -181,7 +181,7 @@ class btMultiBodyMLCPConstraintSolver : public btMultiBodyConstraintSolver void setNumFallbacks(int num); /// Returns the constraint solver type. - virtual btConstraintSolverType getSolverType() const override; + virtual btConstraintSolverType getSolverType() const BT_OVERRIDE; }; #endif // BT_MULTIBODY_MLCP_CONSTRAINT_SOLVER_H diff --git a/src/LinearMath/TaskScheduler/btTaskScheduler.cpp b/src/LinearMath/TaskScheduler/btTaskScheduler.cpp index bfb674c3cb..8d92b5ccf8 100644 --- a/src/LinearMath/TaskScheduler/btTaskScheduler.cpp +++ b/src/LinearMath/TaskScheduler/btTaskScheduler.cpp @@ -3,6 +3,7 @@ #include "LinearMath/btAlignedObjectArray.h" #include "LinearMath/btThreads.h" #include "LinearMath/btQuickprof.h" +#include "LinearMath/btOverride.h" #include #include #include diff --git a/src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp b/src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp index e871570301..5c5ac74d0e 100644 --- a/src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp +++ b/src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp @@ -20,6 +20,7 @@ subject to the following restrictions: #include "LinearMath/btAlignedObjectArray.h" #include "LinearMath/btThreads.h" #include "LinearMath/btMinMax.h" +#include "LinearMath/btOverride.h" #include "btThreadSupportInterface.h" #include diff --git a/src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp b/src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp index 5010cca847..6f06447039 100644 --- a/src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp +++ b/src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp @@ -19,6 +19,7 @@ subject to the following restrictions: #include "LinearMath/btMinMax.h" #include "LinearMath/btAlignedObjectArray.h" #include "LinearMath/btThreads.h" +#include "LinearMath/btOverride.h" #include "btThreadSupportInterface.h" #include #include diff --git a/src/LinearMath/btDefaultMotionState.h b/src/LinearMath/btDefaultMotionState.h index 18b6ae47f2..7c9ef81ec5 100644 --- a/src/LinearMath/btDefaultMotionState.h +++ b/src/LinearMath/btDefaultMotionState.h @@ -24,14 +24,14 @@ btDefaultMotionState : public btMotionState } ///synchronizes world transform from user to physics - virtual void getWorldTransform(btTransform & centerOfMassWorldTrans) const override + virtual void getWorldTransform(btTransform & centerOfMassWorldTrans) const BT_OVERRIDE { centerOfMassWorldTrans = m_graphicsWorldTrans * m_centerOfMassOffset.inverse(); } ///synchronizes world transform from physics to user ///Bullet only calls the update of worldtransform for active objects - virtual void setWorldTransform(const btTransform& centerOfMassWorldTrans) override + virtual void setWorldTransform(const btTransform& centerOfMassWorldTrans) BT_OVERRIDE { m_graphicsWorldTrans = centerOfMassWorldTrans * m_centerOfMassOffset; } diff --git a/src/LinearMath/btOverride.h b/src/LinearMath/btOverride.h new file mode 100644 index 0000000000..b426990138 --- /dev/null +++ b/src/LinearMath/btOverride.h @@ -0,0 +1,12 @@ +#ifndef BT_OVERRIDE_H +#define BT_OVERRIDE_H + +#if (defined(__cplusplus) && __cplusplus >= 201103L) || (defined(_MSC_VER) && _MSC_VER >= 1600) // FIXME: msvc may need extra treatment if not /Z:__cplusplus is given as compile flag +// give us a compile error if any signatures of overriden methods is changed +#define BT_OVERRIDE override +#endif +#ifndef BT_OVERRIDE +#define BT_OVERRIDE +#endif + +#endif // BT_OVERRIDE_H diff --git a/src/LinearMath/btSerializer.h b/src/LinearMath/btSerializer.h index 200651107c..c7e23a78f9 100644 --- a/src/LinearMath/btSerializer.h +++ b/src/LinearMath/btSerializer.h @@ -18,6 +18,7 @@ subject to the following restrictions: #include "btScalar.h" // has definitions like SIMD_FORCE_INLINE #include "btHashMap.h" +#include "LinearMath/btOverride.h" #if !defined(__CELLOS_LV2__) && !defined(__MWERKS__) #include @@ -181,7 +182,7 @@ class btDefaultSerializer : public btSerializer btAlignedObjectArray m_chunkPtrs; protected: - virtual void* findPointer(void* oldPtr) override + virtual void* findPointer(void* oldPtr) BT_OVERRIDE { void** ptr = m_chunkP.find(oldPtr); if (ptr && *ptr) @@ -416,7 +417,7 @@ class btDefaultSerializer : public btSerializer #endif //BT_INTERNAL_UPDATE_SERIALIZATION_STRUCTURES } - virtual ~btDefaultSerializer() override + virtual ~btDefaultSerializer() BT_OVERRIDE { if (m_buffer && m_ownsBuffer) btAlignedFree(m_buffer); @@ -485,7 +486,7 @@ class btDefaultSerializer : public btSerializer buffer[11] = '6'; } - virtual void startSerialization() override + virtual void startSerialization() BT_OVERRIDE { m_uniqueIdGenerator = 1; if (m_totalSize) @@ -495,7 +496,7 @@ class btDefaultSerializer : public btSerializer } } - virtual void finishSerialization() override + virtual void finishSerialization() BT_OVERRIDE { writeDNA(); @@ -532,7 +533,7 @@ class btDefaultSerializer : public btSerializer m_chunkPtrs.clear(); } - virtual void* getUniquePointer(void* oldPtr) override + virtual void* getUniquePointer(void* oldPtr) BT_OVERRIDE { btAssert(m_uniqueIdGenerator >= 0); if (!oldPtr) @@ -559,17 +560,17 @@ class btDefaultSerializer : public btSerializer return uid.m_ptr; } - virtual const unsigned char* getBufferPointer() const override + virtual const unsigned char* getBufferPointer() const BT_OVERRIDE { return m_buffer; } - virtual int getCurrentBufferSize() const override + virtual int getCurrentBufferSize() const BT_OVERRIDE { return m_currentSize; } - virtual void finalizeChunk(btChunk* chunk, const char* structType, int chunkCode, void* oldPtr) override + virtual void finalizeChunk(btChunk* chunk, const char* structType, int chunkCode, void* oldPtr) BT_OVERRIDE { if (!(m_serializationFlags & BT_SERIALIZE_NO_DUPLICATE_ASSERT)) { @@ -604,7 +605,7 @@ class btDefaultSerializer : public btSerializer return ptr; } - virtual btChunk* allocate(size_t size, int numElements) override + virtual btChunk* allocate(size_t size, int numElements) BT_OVERRIDE { unsigned char* ptr = internalAlloc(int(size) * numElements + sizeof(btChunk)); @@ -621,7 +622,7 @@ class btDefaultSerializer : public btSerializer return chunk; } - virtual const char* findNameForPointer(const void* ptr) const override + virtual const char* findNameForPointer(const void* ptr) const BT_OVERRIDE { const char* const* namePtr = m_nameMap.find(ptr); if (namePtr && *namePtr) @@ -629,12 +630,12 @@ class btDefaultSerializer : public btSerializer return 0; } - virtual void registerNameForPointer(const void* ptr, const char* name) override + virtual void registerNameForPointer(const void* ptr, const char* name) BT_OVERRIDE { m_nameMap.insert(ptr, name); } - virtual void serializeName(const char* name) override + virtual void serializeName(const char* name) BT_OVERRIDE { if (name) { @@ -662,21 +663,21 @@ class btDefaultSerializer : public btSerializer } } - virtual int getSerializationFlags() const override + virtual int getSerializationFlags() const BT_OVERRIDE { return m_serializationFlags; } - virtual void setSerializationFlags(int flags) override + virtual void setSerializationFlags(int flags) BT_OVERRIDE { m_serializationFlags = flags; } - int getNumChunks() const override + int getNumChunks() const BT_OVERRIDE { return m_chunkPtrs.size(); } - const btChunk* getChunk(int chunkIndex) const override + const btChunk* getChunk(int chunkIndex) const BT_OVERRIDE { return m_chunkPtrs[chunkIndex]; } diff --git a/src/LinearMath/btThreads.cpp b/src/LinearMath/btThreads.cpp index 68d1c55603..a7ec2a36b5 100644 --- a/src/LinearMath/btThreads.cpp +++ b/src/LinearMath/btThreads.cpp @@ -14,6 +14,7 @@ subject to the following restrictions: #include "btThreads.h" #include "btQuickprof.h" +#include "LinearMath/btOverride.h" #include // for min and max #if BT_USE_OPENMP && BT_THREADSAFE diff --git a/src/LinearMath/btThreads.h b/src/LinearMath/btThreads.h index d83eb51b1f..012c6e4ffe 100644 --- a/src/LinearMath/btThreads.h +++ b/src/LinearMath/btThreads.h @@ -17,15 +17,6 @@ subject to the following restrictions: #include "btScalar.h" // has definitions like SIMD_FORCE_INLINE -#if (defined(_MSC_VER) && _MSC_VER >= 1600) || defined(__clang__) -// give us a compile error if any signatures of overriden methods is changed -#define BT_OVERRIDE override -#endif - -#ifndef BT_OVERRIDE -#define BT_OVERRIDE -#endif - // Don't set this to larger than 64, without modifying btThreadSupportPosix // and btThreadSupportWin32. They use UINT64 bit-masks. const unsigned int BT_MAX_THREAD_COUNT = 64; // only if BT_THREADSAFE is 1 From 43176e908c35fff5c94c977c0466709db2c5fa27 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 04:12:41 +0100 Subject: [PATCH 23/57] Compiler warnings - zero as nullptr - NULL --- .../BroadphaseCollision/btBroadphaseProxy.h | 14 +++++------ .../BroadphaseCollision/btDbvt.h | 12 +++++----- .../BroadphaseCollision/btDbvtBroadphase.h | 4 ++-- .../BroadphaseCollision/btDispatcher.h | 2 +- .../btOverlappingPairCache.h | 10 ++++---- .../BroadphaseCollision/btSimpleBroadphase.h | 4 ++-- .../CollisionDispatch/btCollisionCreateFunc.h | 2 +- .../CollisionDispatch/btCollisionDispatcher.h | 2 +- .../CollisionDispatch/btCollisionWorld.h | 6 ++--- .../btDefaultCollisionConfiguration.h | 5 ++-- .../CollisionDispatch/btGhostObject.h | 16 ++++++------- .../CollisionShapes/btCollisionShape.h | 2 +- .../CollisionShapes/btTriangleInfoMap.h | 8 +++---- .../NarrowPhaseCollision/btManifoldPoint.h | 4 ++-- .../btPersistentManifold.h | 4 ++-- src/BulletDynamics/Dynamics/btDynamicsWorld.h | 8 +++---- src/BulletDynamics/Dynamics/btRigidBody.h | 6 ++--- src/LinearMath/btAlignedAllocator.h | 2 +- src/LinearMath/btAlignedObjectArray.h | 6 ++--- src/LinearMath/btDefaultMotionState.h | 2 +- src/LinearMath/btSerializer.h | 24 +++++++++---------- 21 files changed, 72 insertions(+), 71 deletions(-) diff --git a/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h b/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h index 5d8304a207..f1f2f6a4d6 100644 --- a/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h +++ b/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h @@ -114,7 +114,7 @@ btBroadphaseProxy } //used for memory pools - btBroadphaseProxy() : m_clientObject(0), m_collisionFilterGroup(0), m_collisionFilterMask(0), m_uniqueId(0) + btBroadphaseProxy() : m_clientObject(NULL), m_collisionFilterGroup(0), m_collisionFilterMask(0), m_uniqueId(0) { } @@ -179,10 +179,10 @@ ATTRIBUTE_ALIGNED16(struct) btBroadphasePair { btBroadphasePair() - : m_pProxy0(0), - m_pProxy1(0), - m_algorithm(0), - m_internalInfo1(0) + : m_pProxy0(NULL), + m_pProxy1(NULL), + m_algorithm(NULL), + m_internalInfo1(NULL) { } @@ -202,8 +202,8 @@ btBroadphasePair m_pProxy1 = &proxy0; } - m_algorithm = 0; - m_internalInfo1 = 0; + m_algorithm = NULL; + m_internalInfo1 = NULL; } btBroadphaseProxy* m_pProxy0; diff --git a/src/BulletCollision/BroadphaseCollision/btDbvt.h b/src/BulletCollision/BroadphaseCollision/btDbvt.h index 1e731258c4..ae3e635789 100644 --- a/src/BulletCollision/BroadphaseCollision/btDbvt.h +++ b/src/BulletCollision/BroadphaseCollision/btDbvt.h @@ -181,7 +181,7 @@ struct btDbvtNode { btDbvtVolume volume; btDbvtNode* parent; - DBVT_INLINE bool isleaf() const { return (childs[1] == 0); } + DBVT_INLINE bool isleaf() const { return (childs[1] == NULL); } DBVT_INLINE bool isinternal() const { return (!isleaf()); } union { btDbvtNode* childs[2]; @@ -196,7 +196,7 @@ struct btDbvntNode btDbvtVolume volume; btVector3 normal; btScalar angle; - DBVT_INLINE bool isleaf() const { return (childs[1] == 0); } + DBVT_INLINE bool isleaf() const { return (childs[1] == NULL); } DBVT_INLINE bool isinternal() const { return (!isleaf()); } btDbvntNode* childs[2]; void* data; @@ -207,8 +207,8 @@ struct btDbvntNode , angle(0) , data(n->data) { - childs[0] = 0; - childs[1] = 0; + childs[0] = NULL; + childs[1] = NULL; } ~btDbvntNode() @@ -311,7 +311,7 @@ struct btDbvt btDbvt(); ~btDbvt(); void clear(); - bool empty() const { return (0 == m_root); } + bool empty() const { return (NULL == m_root); } void optimizeBottomUp(); void optimizeTopDown(int bu_treshold = 128); void optimizeIncremental(int passes); @@ -323,7 +323,7 @@ struct btDbvt bool update(btDbvtNode* leaf, btDbvtVolume& volume, btScalar margin); void remove(btDbvtNode* leaf); void write(IWriter* iwriter) const; - void clone(btDbvt& dest, IClone* iclone = 0) const; + void clone(btDbvt& dest, IClone* iclone = NULL) const; static int maxdepth(const btDbvtNode* node); static int countLeaves(const btDbvtNode* node); static void extractLeaves(const btDbvtNode* node, btAlignedObjectArray& leaves); diff --git a/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.h b/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.h index f35775d07d..57c0104663 100644 --- a/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.h +++ b/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.h @@ -50,7 +50,7 @@ struct btDbvtProxy : btBroadphaseProxy /* ctor */ btDbvtProxy(const btVector3& aabbMin, const btVector3& aabbMax, void* userPtr, int collisionFilterGroup, int collisionFilterMask) : btBroadphaseProxy(aabbMin, aabbMax, userPtr, collisionFilterGroup, collisionFilterMask) { - links[0] = links[1] = 0; + links[0] = links[1] = NULL; } }; @@ -101,7 +101,7 @@ struct btDbvtBroadphase : btBroadphaseInterface } m_profiling; #endif /* Methods */ - btDbvtBroadphase(btOverlappingPairCache* paircache = 0); + btDbvtBroadphase(btOverlappingPairCache* paircache = NULL); ~btDbvtBroadphase() BT_OVERRIDE; void collide(btDispatcher* dispatcher); void optimize(); diff --git a/src/BulletCollision/BroadphaseCollision/btDispatcher.h b/src/BulletCollision/BroadphaseCollision/btDispatcher.h index d59441cf55..5e78e07505 100644 --- a/src/BulletCollision/BroadphaseCollision/btDispatcher.h +++ b/src/BulletCollision/BroadphaseCollision/btDispatcher.h @@ -40,7 +40,7 @@ struct btDispatcherInfo m_dispatchFunc(DISPATCH_DISCRETE), m_timeOfImpact(btScalar(1.)), m_useContinuous(true), - m_debugDraw(0), + m_debugDraw(NULL), m_enableSatConvex(false), m_enableSPU(true), m_useEpa(true), diff --git a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h index 0fc6665c67..2da26b983f 100644 --- a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h +++ b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h @@ -121,7 +121,7 @@ btHashedOverlappingPairCache : public btOverlappingPairCache virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy * proxy0, btBroadphaseProxy * proxy1) BT_OVERRIDE { if (!needsBroadphaseCollision(proxy0, proxy1)) - return 0; + return NULL; return internalAddPair(proxy0, proxy1); } @@ -387,7 +387,7 @@ class btNullPairCache : public btOverlappingPairCache } btOverlapFilterCallback* getOverlapFilterCallback() BT_OVERRIDE { - return 0; + return NULL; } virtual void setOverlapFilterCallback(btOverlapFilterCallback* /*callback*/) BT_OVERRIDE { @@ -399,7 +399,7 @@ class btNullPairCache : public btOverlappingPairCache virtual btBroadphasePair* findPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/) BT_OVERRIDE { - return 0; + return NULL; } virtual bool hasDeferredRemoval() BT_OVERRIDE @@ -413,12 +413,12 @@ class btNullPairCache : public btOverlappingPairCache virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/) BT_OVERRIDE { - return 0; + return NULL; } virtual void* removeOverlappingPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/, btDispatcher* /*dispatcher*/) BT_OVERRIDE { - return 0; + return NULL; } virtual void removeOverlappingPairsContainingProxy(btBroadphaseProxy* /*proxy0*/, btDispatcher* /*dispatcher*/) BT_OVERRIDE diff --git a/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h b/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h index 9b8c4ada60..0f5e6006ca 100644 --- a/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h +++ b/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h @@ -74,7 +74,7 @@ class btSimpleBroadphase : public btBroadphaseInterface proxy->SetNextFree(m_firstFreeHandle); m_firstFreeHandle = handle; - proxy->m_clientObject = 0; + proxy->m_clientObject = NULL; m_numHandles--; } @@ -103,7 +103,7 @@ class btSimpleBroadphase : public btBroadphaseInterface protected: public: - btSimpleBroadphase(int maxProxies = 16384, btOverlappingPairCache* overlappingPairCache = 0); + btSimpleBroadphase(int maxProxies = 16384, btOverlappingPairCache* overlappingPairCache = NULL); virtual ~btSimpleBroadphase() BT_OVERRIDE; static bool aabbOverlap(btSimpleBroadphaseProxy* proxy0, btSimpleBroadphaseProxy* proxy1); diff --git a/src/BulletCollision/CollisionDispatch/btCollisionCreateFunc.h b/src/BulletCollision/CollisionDispatch/btCollisionCreateFunc.h index 597f260222..95ea59bb38 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionCreateFunc.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionCreateFunc.h @@ -37,7 +37,7 @@ struct btCollisionAlgorithmCreateFunc { (void)body0Wrap; (void)body1Wrap; - return 0; + return NULL; } }; #endif //BT_COLLISION_CREATE_FUNC diff --git a/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h b/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h index dd6ec79349..0e0d08c07b 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h @@ -89,7 +89,7 @@ class btCollisionDispatcher : public btDispatcher btPersistentManifold** getInternalManifoldPointer() BT_OVERRIDE { - return m_manifoldsPtr.size() ? &m_manifoldsPtr[0] : 0; + return m_manifoldsPtr.size() ? &m_manifoldsPtr[0] : NULL; } btPersistentManifold* getManifoldByIndexInternal(int index) BT_OVERRIDE diff --git a/src/BulletCollision/CollisionDispatch/btCollisionWorld.h b/src/BulletCollision/CollisionDispatch/btCollisionWorld.h index dbcd124c06..1147416233 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionWorld.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionWorld.h @@ -206,12 +206,12 @@ class btCollisionWorld } bool hasHit() const { - return (m_collisionObject != 0); + return (m_collisionObject != NULL); } RayResultCallback() : m_closestHitFraction(btScalar(1.)), - m_collisionObject(0), + m_collisionObject(NULL), m_collisionFilterGroup(btBroadphaseProxy::DefaultFilter), m_collisionFilterMask(btBroadphaseProxy::AllFilter), //@BP Mod @@ -364,7 +364,7 @@ class btCollisionWorld ClosestConvexResultCallback(const btVector3& convexFromWorld, const btVector3& convexToWorld) : m_convexFromWorld(convexFromWorld), m_convexToWorld(convexToWorld), - m_hitCollisionObject(0) + m_hitCollisionObject(NULL) { } diff --git a/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h b/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h index fd52c575e9..2a5bff04b4 100644 --- a/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h +++ b/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h @@ -18,6 +18,7 @@ subject to the following restrictions: #include "btCollisionConfiguration.h" #include "LinearMath/btOverride.h" +#include class btVoronoiSimplexSolver; class btConvexPenetrationDepthSolver; @@ -31,8 +32,8 @@ struct btDefaultCollisionConstructionInfo int m_useEpaPenetrationAlgorithm; btDefaultCollisionConstructionInfo() - : m_persistentManifoldPool(0), - m_collisionAlgorithmPool(0), + : m_persistentManifoldPool(NULL), + m_collisionAlgorithmPool(NULL), m_defaultMaxPersistentManifoldPoolSize(4096), m_defaultMaxCollisionAlgorithmPoolSize(4096), m_customCollisionAlgorithmMaxElementSize(0), diff --git a/src/BulletCollision/CollisionDispatch/btGhostObject.h b/src/BulletCollision/CollisionDispatch/btGhostObject.h index 69e9332b76..e48c23d037 100644 --- a/src/BulletCollision/CollisionDispatch/btGhostObject.h +++ b/src/BulletCollision/CollisionDispatch/btGhostObject.h @@ -46,9 +46,9 @@ btGhostObject : public btCollisionObject void rayTest(const btVector3& rayFromWorld, const btVector3& rayToWorld, btCollisionWorld::RayResultCallback& resultCallback) const; ///this method is mainly for expert/internal use only. - virtual void addOverlappingObjectInternal(btBroadphaseProxy * otherProxy, btBroadphaseProxy* thisProxy = 0); + virtual void addOverlappingObjectInternal(btBroadphaseProxy * otherProxy, btBroadphaseProxy* thisProxy = NULL); ///this method is mainly for expert/internal use only. - virtual void removeOverlappingObjectInternal(btBroadphaseProxy * otherProxy, btDispatcher * dispatcher, btBroadphaseProxy* thisProxy = 0); + virtual void removeOverlappingObjectInternal(btBroadphaseProxy * otherProxy, btDispatcher * dispatcher, btBroadphaseProxy* thisProxy = NULL); int getNumOverlappingObjects() const { @@ -83,13 +83,13 @@ btGhostObject : public btCollisionObject { if (colObj->getInternalType() == CO_GHOST_OBJECT) return (const btGhostObject*)colObj; - return 0; + return NULL; } static btGhostObject* upcast(btCollisionObject * colObj) { if (colObj->getInternalType() == CO_GHOST_OBJECT) return (btGhostObject*)colObj; - return 0; + return NULL; } }; @@ -103,9 +103,9 @@ class btPairCachingGhostObject : public btGhostObject virtual ~btPairCachingGhostObject() BT_OVERRIDE; ///this method is mainly for expert/internal use only. - virtual void addOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btBroadphaseProxy* thisProxy = 0) BT_OVERRIDE; + virtual void addOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btBroadphaseProxy* thisProxy = NULL) BT_OVERRIDE; - virtual void removeOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btDispatcher* dispatcher, btBroadphaseProxy* thisProxy = 0) BT_OVERRIDE; + virtual void removeOverlappingObjectInternal(btBroadphaseProxy* otherProxy, btDispatcher* dispatcher, btBroadphaseProxy* thisProxy = NULL) BT_OVERRIDE; btHashedOverlappingPairCache* getOverlappingPairCache() { @@ -135,7 +135,7 @@ class btGhostPairCallback : public btOverlappingPairCallback ghost0->addOverlappingObjectInternal(proxy1, proxy0); if (ghost1) ghost1->addOverlappingObjectInternal(proxy0, proxy1); - return 0; + return NULL; } virtual void* removeOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1, btDispatcher* dispatcher) BT_OVERRIDE @@ -148,7 +148,7 @@ class btGhostPairCallback : public btOverlappingPairCallback ghost0->removeOverlappingObjectInternal(proxy1, dispatcher, proxy0); if (ghost1) ghost1->removeOverlappingObjectInternal(proxy0, dispatcher, proxy1); - return 0; + return NULL; } virtual void removeOverlappingPairsContainingProxy(btBroadphaseProxy* /*proxy0*/, btDispatcher* /*dispatcher*/) BT_OVERRIDE diff --git a/src/BulletCollision/CollisionShapes/btCollisionShape.h b/src/BulletCollision/CollisionShapes/btCollisionShape.h index 16f9e0c77a..32667074d2 100644 --- a/src/BulletCollision/CollisionShapes/btCollisionShape.h +++ b/src/BulletCollision/CollisionShapes/btCollisionShape.h @@ -35,7 +35,7 @@ btCollisionShape public: BT_DECLARE_ALIGNED_ALLOCATOR(); - btCollisionShape() : m_shapeType(INVALID_SHAPE_PROXYTYPE), m_userPointer(0), m_userIndex(-1), m_userIndex2(-1) + btCollisionShape() : m_shapeType(INVALID_SHAPE_PROXYTYPE), m_userPointer(NULL), m_userIndex(-1), m_userIndex2(-1) { } diff --git a/src/BulletCollision/CollisionShapes/btTriangleInfoMap.h b/src/BulletCollision/CollisionShapes/btTriangleInfoMap.h index 8ee35ef5fa..339ba57c4a 100644 --- a/src/BulletCollision/CollisionShapes/btTriangleInfoMap.h +++ b/src/BulletCollision/CollisionShapes/btTriangleInfoMap.h @@ -128,7 +128,7 @@ SIMD_FORCE_INLINE const char* btTriangleInfoMap::serialize(void* dataBuffer, btS tmapData->m_hashTableSize = m_hashTable.size(); - tmapData->m_hashTablePtr = tmapData->m_hashTableSize ? (int*)serializer->getUniquePointer((void*)&m_hashTable[0]) : 0; + tmapData->m_hashTablePtr = tmapData->m_hashTableSize ? (int*)serializer->getUniquePointer((void*)&m_hashTable[0]) : NULL; if (tmapData->m_hashTablePtr) { //serialize an int buffer @@ -144,7 +144,7 @@ SIMD_FORCE_INLINE const char* btTriangleInfoMap::serialize(void* dataBuffer, btS } tmapData->m_nextSize = m_next.size(); - tmapData->m_nextPtr = tmapData->m_nextSize ? (int*)serializer->getUniquePointer((void*)&m_next[0]) : 0; + tmapData->m_nextPtr = tmapData->m_nextSize ? (int*)serializer->getUniquePointer((void*)&m_next[0]) : NULL; if (tmapData->m_nextPtr) { int sz = sizeof(int); @@ -159,7 +159,7 @@ SIMD_FORCE_INLINE const char* btTriangleInfoMap::serialize(void* dataBuffer, btS } tmapData->m_numValues = m_valueArray.size(); - tmapData->m_valueArrayPtr = tmapData->m_numValues ? (btTriangleInfoData*)serializer->getUniquePointer((void*)&m_valueArray[0]) : 0; + tmapData->m_valueArrayPtr = tmapData->m_numValues ? (btTriangleInfoData*)serializer->getUniquePointer((void*)&m_valueArray[0]) : NULL; if (tmapData->m_valueArrayPtr) { int sz = sizeof(btTriangleInfoData); @@ -177,7 +177,7 @@ SIMD_FORCE_INLINE const char* btTriangleInfoMap::serialize(void* dataBuffer, btS } tmapData->m_numKeys = m_keyArray.size(); - tmapData->m_keyArrayPtr = tmapData->m_numKeys ? (int*)serializer->getUniquePointer((void*)&m_keyArray[0]) : 0; + tmapData->m_keyArrayPtr = tmapData->m_numKeys ? (int*)serializer->getUniquePointer((void*)&m_keyArray[0]) : NULL; if (tmapData->m_keyArrayPtr) { int sz = sizeof(int); diff --git a/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h b/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h index 31323282cd..1d49c1539e 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h +++ b/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h @@ -52,7 +52,7 @@ class btManifoldPoint { public: btManifoldPoint() - : m_userPersistentData(0), + : m_userPersistentData(NULL), m_contactPointFlags(0), m_appliedImpulse(0.f), m_prevRHS(0.f), @@ -83,7 +83,7 @@ class btManifoldPoint m_partId1(-1), m_index0(-1), m_index1(-1), - m_userPersistentData(0), + m_userPersistentData(NULL), m_contactPointFlags(0), m_appliedImpulse(0.f), m_prevRHS(0.f), diff --git a/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h b/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h index b07e48688e..3856587816 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h +++ b/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h @@ -171,7 +171,7 @@ btPersistentManifold : public btTypedObject { m_pointCache[index] = m_pointCache[lastUsedIndex]; //get rid of duplicated userPersistentData pointer - m_pointCache[lastUsedIndex].m_userPersistentData = 0; + m_pointCache[lastUsedIndex].m_userPersistentData = NULL; m_pointCache[lastUsedIndex].m_appliedImpulse = 0.f; m_pointCache[lastUsedIndex].m_prevRHS = 0.f; m_pointCache[lastUsedIndex].m_contactPointFlags = 0; @@ -180,7 +180,7 @@ btPersistentManifold : public btTypedObject m_pointCache[lastUsedIndex].m_lifeTime = 0; } - btAssert(m_pointCache[lastUsedIndex].m_userPersistentData == 0); + btAssert(m_pointCache[lastUsedIndex].m_userPersistentData == NULL); m_cachedPoints--; if (gContactEndedCallback && m_cachedPoints == 0) diff --git a/src/BulletDynamics/Dynamics/btDynamicsWorld.h b/src/BulletDynamics/Dynamics/btDynamicsWorld.h index 8af1782c42..2c278e4019 100644 --- a/src/BulletDynamics/Dynamics/btDynamicsWorld.h +++ b/src/BulletDynamics/Dynamics/btDynamicsWorld.h @@ -50,7 +50,7 @@ class btDynamicsWorld : public btCollisionWorld public: btDynamicsWorld(btDispatcher* dispatcher, btBroadphaseInterface* broadphase, btCollisionConfiguration* collisionConfiguration) - : btCollisionWorld(dispatcher, broadphase, collisionConfiguration), m_internalTickCallback(0), m_internalPreTickCallback(0), m_worldUserInfo(0) + : btCollisionWorld(dispatcher, broadphase, collisionConfiguration), m_internalTickCallback(NULL), m_internalPreTickCallback(NULL), m_worldUserInfo(NULL) { } @@ -100,13 +100,13 @@ class btDynamicsWorld : public btCollisionWorld virtual btTypedConstraint* getConstraint(int index) { (void)index; - return 0; + return NULL; } virtual const btTypedConstraint* getConstraint(int index) const { (void)index; - return 0; + return NULL; } virtual btDynamicsWorldType getWorldType() const = 0; @@ -114,7 +114,7 @@ class btDynamicsWorld : public btCollisionWorld virtual void clearForces() = 0; /// Set the callback for when an internal tick (simulation substep) happens, optional user info - void setInternalTickCallback(btInternalTickCallback cb, void* worldUserInfo = 0, bool isPreTick = false) + void setInternalTickCallback(btInternalTickCallback cb, void* worldUserInfo = NULL, bool isPreTick = false) { if (isPreTick) { diff --git a/src/BulletDynamics/Dynamics/btRigidBody.h b/src/BulletDynamics/Dynamics/btRigidBody.h index 219000aa72..f695c65d85 100644 --- a/src/BulletDynamics/Dynamics/btRigidBody.h +++ b/src/BulletDynamics/Dynamics/btRigidBody.h @@ -191,13 +191,13 @@ class btRigidBody : public btCollisionObject { if (colObj->getInternalType() & btCollisionObject::CO_RIGID_BODY) return (const btRigidBody*)colObj; - return 0; + return NULL; } static btRigidBody* upcast(btCollisionObject* colObj) { if (colObj->getInternalType() & btCollisionObject::CO_RIGID_BODY) return (btRigidBody*)colObj; - return 0; + return NULL; } /// continuous collision detection needs prediction @@ -585,7 +585,7 @@ class btRigidBody : public btCollisionObject //is this rigidbody added to a btCollisionWorld/btDynamicsWorld/btBroadphase? bool isInWorld() const { - return (getBroadphaseProxy() != 0); + return (getBroadphaseProxy() != NULL); } void addConstraintRef(btTypedConstraint* c); diff --git a/src/LinearMath/btAlignedAllocator.h b/src/LinearMath/btAlignedAllocator.h index f6bbcdbbf1..48f20a9d1d 100644 --- a/src/LinearMath/btAlignedAllocator.h +++ b/src/LinearMath/btAlignedAllocator.h @@ -86,7 +86,7 @@ class btAlignedAllocator pointer address(reference ref) const { return &ref; } const_pointer address(const_reference ref) const { return &ref; } - pointer allocate(size_type n, const_pointer* hint = 0) + pointer allocate(size_type n, const_pointer* hint = NULL) { (void)hint; return reinterpret_cast(btAlignedAlloc(sizeof(value_type) * n, Alignment)); diff --git a/src/LinearMath/btAlignedObjectArray.h b/src/LinearMath/btAlignedObjectArray.h index ebdc91833e..9e0551338a 100644 --- a/src/LinearMath/btAlignedObjectArray.h +++ b/src/LinearMath/btAlignedObjectArray.h @@ -84,7 +84,7 @@ class btAlignedObjectArray { //PCK: added this line m_ownsMemory = true; - m_data = 0; + m_data = NULL; m_size = 0; m_capacity = 0; } @@ -101,7 +101,7 @@ class btAlignedObjectArray { if (size) return m_allocator.allocate(size); - return 0; + return NULL; } SIMD_FORCE_INLINE void deallocate() @@ -113,7 +113,7 @@ class btAlignedObjectArray { m_allocator.deallocate(m_data); } - m_data = 0; + m_data = NULL; } } diff --git a/src/LinearMath/btDefaultMotionState.h b/src/LinearMath/btDefaultMotionState.h index 7c9ef81ec5..a7a7c12784 100644 --- a/src/LinearMath/btDefaultMotionState.h +++ b/src/LinearMath/btDefaultMotionState.h @@ -18,7 +18,7 @@ btDefaultMotionState : public btMotionState : m_graphicsWorldTrans(startTrans), m_centerOfMassOffset(centerOfMassOffset), m_startWorldTrans(startTrans), - m_userPointer(0) + m_userPointer(NULL) { } diff --git a/src/LinearMath/btSerializer.h b/src/LinearMath/btSerializer.h index c7e23a78f9..07503bb3cd 100644 --- a/src/LinearMath/btSerializer.h +++ b/src/LinearMath/btSerializer.h @@ -187,7 +187,7 @@ class btDefaultSerializer : public btSerializer void** ptr = m_chunkP.find(oldPtr); if (ptr && *ptr) return *ptr; - return 0; + return NULL; } virtual void writeDNA() @@ -220,9 +220,9 @@ class btDefaultSerializer : public btSerializer memcpy(m_dna, bdnaOrg, dnalen); m_dnaLength = dnalen; - int* intPtr = 0; - short* shtPtr = 0; - char* cp = 0; + int* intPtr = NULL; + short* shtPtr = NULL; + char* cp = NULL; int dataLen = 0; intPtr = (int*)m_dna; @@ -366,17 +366,17 @@ class btDefaultSerializer : public btSerializer public: btHashMap m_skipPointers; - btDefaultSerializer(int totalSize = 0, unsigned char* buffer = 0) + btDefaultSerializer(int totalSize = 0, unsigned char* buffer = NULL) : m_uniqueIdGenerator(0), m_totalSize(totalSize), m_currentSize(0), - m_dna(0), + m_dna(NULL), m_dnaLength(0), m_serializationFlags(0) { - if (buffer == 0) + if (buffer == NULL) { - m_buffer = m_totalSize ? (unsigned char*)btAlignedAlloc(totalSize, 16) : 0; + m_buffer = m_totalSize ? (unsigned char*)btAlignedAlloc(totalSize, 16) : NULL; m_ownsBuffer = true; } else @@ -537,7 +537,7 @@ class btDefaultSerializer : public btSerializer { btAssert(m_uniqueIdGenerator >= 0); if (!oldPtr) - return 0; + return NULL; btPointerUid* uptr = (btPointerUid*)m_uniquePointers.find(oldPtr); if (uptr) @@ -548,7 +548,7 @@ class btDefaultSerializer : public btSerializer void** ptr2 = m_skipPointers[oldPtr]; if (ptr2) { - return 0; + return NULL; } m_uniqueIdGenerator++; @@ -589,7 +589,7 @@ class btDefaultSerializer : public btSerializer virtual unsigned char* internalAlloc(size_t size) { - unsigned char* ptr = 0; + unsigned char* ptr = NULL; if (m_totalSize) { @@ -627,7 +627,7 @@ class btDefaultSerializer : public btSerializer const char* const* namePtr = m_nameMap.find(ptr); if (namePtr && *namePtr) return *namePtr; - return 0; + return NULL; } virtual void registerNameForPointer(const void* ptr, const char* name) BT_OVERRIDE From 273c1f885ab9095a59389f4c614114cf4a5e20ea Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 00:58:33 +0100 Subject: [PATCH 24/57] Compiler warnings - zero as nullptr - NULL - examples --- examples/DeformableDemo/LoadDeformed.cpp | 2 +- examples/StandaloneMain/hellovr_opengl_main.cpp | 8 ++++---- examples/ThirdPartyLibs/Eigen/src/Core/DenseStorage.h | 6 +++--- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/examples/DeformableDemo/LoadDeformed.cpp b/examples/DeformableDemo/LoadDeformed.cpp index 9f1309a089..d5fe181524 100644 --- a/examples/DeformableDemo/LoadDeformed.cpp +++ b/examples/DeformableDemo/LoadDeformed.cpp @@ -184,7 +184,7 @@ class LoadDeformed : public CommonDeformableBodyBase : CommonDeformableBodyBase(helper) { steps = 0; - psb = nullptr; + psb = NULL; reset_frame = 0; sim_time = 0; (void)filename; diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index e5744ef538..b11f30bd25 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -562,7 +562,7 @@ bool CMainApplication::BInitGL() { //const GLvoid *userParam=0; //glDebugMessageCallback(DebugCallback, userParam); - //glDebugMessageControl( GL_DONT_CARE, GL_DONT_CARE, GL_DONT_CARE, 0, nullptr, GL_TRUE ); + //glDebugMessageControl( GL_DONT_CARE, GL_DONT_CARE, GL_DONT_CARE, 0, NULL, GL_TRUE ); //glEnable(GL_DEBUG_OUTPUT_SYNCHRONOUS); } @@ -617,8 +617,8 @@ void CMainApplication::Shutdown() { if (m_glSceneVertBuffer) { - //glDebugMessageControl( GL_DONT_CARE, GL_DONT_CARE, GL_DONT_CARE, 0, nullptr, GL_FALSE ); - //glDebugMessageCallback(nullptr, nullptr); + //glDebugMessageControl( GL_DONT_CARE, GL_DONT_CARE, GL_DONT_CARE, 0, NULL, GL_FALSE ); + //glDebugMessageCallback(NULL, NULL); glDeleteBuffers(1, &m_glSceneVertBuffer); glDeleteBuffers(1, &m_glIDVertBuffer); glDeleteBuffers(1, &m_glIDIndexBuffer); @@ -1498,7 +1498,7 @@ bool CMainApplication::CreateFrameBuffer(int nWidth, int nHeight, FramebufferDes glBindTexture(GL_TEXTURE_2D, framebufferDesc.m_nResolveTextureId); glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAX_LEVEL, 0); - glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA8, nWidth, nHeight, 0, GL_RGBA, GL_UNSIGNED_BYTE, nullptr); + glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA8, nWidth, nHeight, 0, GL_RGBA, GL_UNSIGNED_BYTE, NULL); glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_TEXTURE_2D, framebufferDesc.m_nResolveTextureId, 0); // check FBO status diff --git a/examples/ThirdPartyLibs/Eigen/src/Core/DenseStorage.h b/examples/ThirdPartyLibs/Eigen/src/Core/DenseStorage.h index 08ef6c5306..b05db269d9 100644 --- a/examples/ThirdPartyLibs/Eigen/src/Core/DenseStorage.h +++ b/examples/ThirdPartyLibs/Eigen/src/Core/DenseStorage.h @@ -449,7 +449,7 @@ template class DenseStorage class DenseStorage class DenseStorage Date: Sat, 9 Mar 2024 00:58:42 +0100 Subject: [PATCH 25/57] Compiler warnings - zero as nullptr - NULL - openvr --- .../osx64/OpenVR.framework/Headers/openvr.h | 90 +++++++++---------- .../OpenVR.framework/Headers/openvr_driver.h | 56 ++++++------ .../Versions/A/Headers/openvr.h | 90 +++++++++---------- .../Versions/A/Headers/openvr_driver.h | 56 ++++++------ .../Versions/Current/Headers/openvr.h | 90 +++++++++---------- .../Versions/Current/Headers/openvr_driver.h | 56 ++++++------ .../ThirdPartyLibs/openvr/headers/openvr.h | 90 +++++++++---------- .../openvr/headers/openvr_driver.h | 56 ++++++------ .../openvr/samples/shared/compat.h | 4 +- .../openvr/samples/shared/pathtools.cpp | 4 +- 10 files changed, 296 insertions(+), 296 deletions(-) diff --git a/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Headers/openvr.h b/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Headers/openvr.h index 80461f9687..f9dd38b11c 100644 --- a/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Headers/openvr.h +++ b/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Headers/openvr.h @@ -1278,7 +1278,7 @@ class IVRSystem * [macOS Only] * Returns an id that should be used by the application. */ - virtual void GetOutputDevice(uint64_t *pnDevice, ETextureType textureType, VkInstance_T *pInstance = nullptr) = 0; + virtual void GetOutputDevice(uint64_t *pnDevice, ETextureType textureType, VkInstance_T *pInstance = NULL) = 0; // ------------------------------------ // Display Mode methods @@ -1640,13 +1640,13 @@ class IVRApplications // --------------- Application properties --------------- // /** Returns a value for an application property. The required buffer size to fit this value will be returned. */ - virtual uint32_t GetApplicationPropertyString(const char *pchAppKey, EVRApplicationProperty eProperty, VR_OUT_STRING() char *pchPropertyValueBuffer, uint32_t unPropertyValueBufferLen, EVRApplicationError *peError = nullptr) = 0; + virtual uint32_t GetApplicationPropertyString(const char *pchAppKey, EVRApplicationProperty eProperty, VR_OUT_STRING() char *pchPropertyValueBuffer, uint32_t unPropertyValueBufferLen, EVRApplicationError *peError = NULL) = 0; /** Returns a bool value for an application property. Returns false in all error cases. */ - virtual bool GetApplicationPropertyBool(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = nullptr) = 0; + virtual bool GetApplicationPropertyBool(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = NULL) = 0; /** Returns a uint64 value for an application property. Returns 0 in all error cases. */ - virtual uint64_t GetApplicationPropertyUint64(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = nullptr) = 0; + virtual uint64_t GetApplicationPropertyUint64(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = NULL) = 0; /** Sets the application auto-launch flag. This is only valid for applications which return true for VRApplicationProperty_IsDashboardOverlay_Bool. */ virtual EVRApplicationError SetApplicationAutoLaunch(const char *pchAppKey, bool bAutoLaunch) = 0; @@ -1733,22 +1733,22 @@ class IVRSettings virtual const char *GetSettingsErrorNameFromEnum(EVRSettingsError eError) = 0; // Returns true if file sync occurred (force or settings dirty) - virtual bool Sync(bool bForce = false, EVRSettingsError *peError = nullptr) = 0; + virtual bool Sync(bool bForce = false, EVRSettingsError *peError = NULL) = 0; - virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = nullptr) = 0; + virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = NULL) = 0; // Users of the system need to provide a proper default in default.vrsettings in the resources/settings/ directory // of either the runtime or the driver_xxx directory. Otherwise the default will be false, 0, 0.0 or "" - virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = nullptr) = 0; + virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = NULL) = 0; - virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = nullptr) = 0; - virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; + virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = NULL) = 0; + virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; }; //----------------------------------------------------------------------------- @@ -2386,7 +2386,7 @@ namespace vr struct NotificationBitmap_t { NotificationBitmap_t() - : m_pImageData(nullptr), m_nWidth(0), m_nHeight(0), m_nBytesPerPixel(0){}; + : m_pImageData(NULL), m_nWidth(0), m_nHeight(0), m_nBytesPerPixel(0){}; void *m_pImageData; int32_t m_nWidth; @@ -2940,7 +2940,7 @@ class IVROverlay // --------------------------------------------- /** Show the message overlay. This will block and return you a result. **/ - virtual VRMessageOverlayResponse ShowMessageOverlay(const char *pchText, const char *pchCaption, const char *pchButton0Text, const char *pchButton1Text = nullptr, const char *pchButton2Text = nullptr, const char *pchButton3Text = nullptr) = 0; + virtual VRMessageOverlayResponse ShowMessageOverlay(const char *pchText, const char *pchCaption, const char *pchButton0Text, const char *pchButton1Text = NULL, const char *pchButton2Text = NULL, const char *pchButton3Text = NULL) = 0; /** If the calling process owns the overlay and it's open, this will close it. **/ virtual void CloseMessageOverlay() = 0; @@ -3256,7 +3256,7 @@ class IVRScreenshots * is the VR screenshot in the correct format. They should be * in the same aspect ratio. Formats per type: * VRScreenshotType_Mono: the VR filename is ignored (can be - * nullptr), this is a normal flat single shot. + * NULL), this is a normal flat single shot. * VRScreenshotType_Stereo: The VR image should be a * side-by-side with the left eye image on the left. * VRScreenshotType_Cubemap: The VR image should be six square @@ -3387,7 +3387,7 @@ namespace vr * * pStartupInfo is reserved for future use. */ -inline IVRSystem *VR_Init(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo = nullptr); +inline IVRSystem *VR_Init(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo = NULL); /** unloads vrclient.dll. Any interface pointers from the interface are * invalid after this point */ @@ -3466,7 +3466,7 @@ class COpenVRContext IVRSystem *VRSystem() { CheckClear(); - if (m_pVRSystem == nullptr) + if (m_pVRSystem == NULL) { EVRInitError eError; m_pVRSystem = (IVRSystem *)VR_GetGenericInterface(IVRSystem_Version, &eError); @@ -3476,7 +3476,7 @@ class COpenVRContext IVRChaperone *VRChaperone() { CheckClear(); - if (m_pVRChaperone == nullptr) + if (m_pVRChaperone == NULL) { EVRInitError eError; m_pVRChaperone = (IVRChaperone *)VR_GetGenericInterface(IVRChaperone_Version, &eError); @@ -3487,7 +3487,7 @@ class COpenVRContext IVRChaperoneSetup *VRChaperoneSetup() { CheckClear(); - if (m_pVRChaperoneSetup == nullptr) + if (m_pVRChaperoneSetup == NULL) { EVRInitError eError; m_pVRChaperoneSetup = (IVRChaperoneSetup *)VR_GetGenericInterface(IVRChaperoneSetup_Version, &eError); @@ -3498,7 +3498,7 @@ class COpenVRContext IVRCompositor *VRCompositor() { CheckClear(); - if (m_pVRCompositor == nullptr) + if (m_pVRCompositor == NULL) { EVRInitError eError; m_pVRCompositor = (IVRCompositor *)VR_GetGenericInterface(IVRCompositor_Version, &eError); @@ -3509,7 +3509,7 @@ class COpenVRContext IVROverlay *VROverlay() { CheckClear(); - if (m_pVROverlay == nullptr) + if (m_pVROverlay == NULL) { EVRInitError eError; m_pVROverlay = (IVROverlay *)VR_GetGenericInterface(IVROverlay_Version, &eError); @@ -3520,7 +3520,7 @@ class COpenVRContext IVRResources *VRResources() { CheckClear(); - if (m_pVRResources == nullptr) + if (m_pVRResources == NULL) { EVRInitError eError; m_pVRResources = (IVRResources *)VR_GetGenericInterface(IVRResources_Version, &eError); @@ -3531,7 +3531,7 @@ class COpenVRContext IVRScreenshots *VRScreenshots() { CheckClear(); - if (m_pVRScreenshots == nullptr) + if (m_pVRScreenshots == NULL) { EVRInitError eError; m_pVRScreenshots = (IVRScreenshots *)VR_GetGenericInterface(IVRScreenshots_Version, &eError); @@ -3542,7 +3542,7 @@ class COpenVRContext IVRRenderModels *VRRenderModels() { CheckClear(); - if (m_pVRRenderModels == nullptr) + if (m_pVRRenderModels == NULL) { EVRInitError eError; m_pVRRenderModels = (IVRRenderModels *)VR_GetGenericInterface(IVRRenderModels_Version, &eError); @@ -3553,7 +3553,7 @@ class COpenVRContext IVRExtendedDisplay *VRExtendedDisplay() { CheckClear(); - if (m_pVRExtendedDisplay == nullptr) + if (m_pVRExtendedDisplay == NULL) { EVRInitError eError; m_pVRExtendedDisplay = (IVRExtendedDisplay *)VR_GetGenericInterface(IVRExtendedDisplay_Version, &eError); @@ -3564,7 +3564,7 @@ class COpenVRContext IVRSettings *VRSettings() { CheckClear(); - if (m_pVRSettings == nullptr) + if (m_pVRSettings == NULL) { EVRInitError eError; m_pVRSettings = (IVRSettings *)VR_GetGenericInterface(IVRSettings_Version, &eError); @@ -3575,7 +3575,7 @@ class COpenVRContext IVRApplications *VRApplications() { CheckClear(); - if (m_pVRApplications == nullptr) + if (m_pVRApplications == NULL) { EVRInitError eError; m_pVRApplications = (IVRApplications *)VR_GetGenericInterface(IVRApplications_Version, &eError); @@ -3586,7 +3586,7 @@ class COpenVRContext IVRTrackedCamera *VRTrackedCamera() { CheckClear(); - if (m_pVRTrackedCamera == nullptr) + if (m_pVRTrackedCamera == NULL) { EVRInitError eError; m_pVRTrackedCamera = (IVRTrackedCamera *)VR_GetGenericInterface(IVRTrackedCamera_Version, &eError); @@ -3643,19 +3643,19 @@ inline IVRDriverManager *VR_CALLTYPE VRDriverManager() { return OpenVRInternal_M inline void COpenVRContext::Clear() { - m_pVRSystem = nullptr; - m_pVRChaperone = nullptr; - m_pVRChaperoneSetup = nullptr; - m_pVRCompositor = nullptr; - m_pVROverlay = nullptr; - m_pVRRenderModels = nullptr; - m_pVRExtendedDisplay = nullptr; - m_pVRSettings = nullptr; - m_pVRApplications = nullptr; - m_pVRTrackedCamera = nullptr; - m_pVRResources = nullptr; - m_pVRScreenshots = nullptr; - m_pVRDriverManager = nullptr; + m_pVRSystem = NULL; + m_pVRChaperone = NULL; + m_pVRChaperoneSetup = NULL; + m_pVRCompositor = NULL; + m_pVROverlay = NULL; + m_pVRRenderModels = NULL; + m_pVRExtendedDisplay = NULL; + m_pVRSettings = NULL; + m_pVRApplications = NULL; + m_pVRTrackedCamera = NULL; + m_pVRResources = NULL; + m_pVRScreenshots = NULL; + m_pVRDriverManager = NULL; } VR_INTERFACE uint32_t VR_CALLTYPE VR_InitInternal2(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo); @@ -3664,7 +3664,7 @@ VR_INTERFACE void VR_CALLTYPE VR_ShutdownInternal(); /** Finds the active installation of vrclient.dll and initializes it */ inline IVRSystem *VR_Init(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo) { - IVRSystem *pVRSystem = nullptr; + IVRSystem *pVRSystem = NULL; EVRInitError eError; VRToken() = VR_InitInternal2(&eError, eApplicationType, pStartupInfo); diff --git a/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Headers/openvr_driver.h b/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Headers/openvr_driver.h index b07699f82c..efe8938a19 100644 --- a/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Headers/openvr_driver.h +++ b/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Headers/openvr_driver.h @@ -1323,22 +1323,22 @@ class IVRSettings virtual const char *GetSettingsErrorNameFromEnum(EVRSettingsError eError) = 0; // Returns true if file sync occurred (force or settings dirty) - virtual bool Sync(bool bForce = false, EVRSettingsError *peError = nullptr) = 0; + virtual bool Sync(bool bForce = false, EVRSettingsError *peError = NULL) = 0; - virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = nullptr) = 0; + virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = NULL) = 0; // Users of the system need to provide a proper default in default.vrsettings in the resources/settings/ directory // of either the runtime or the driver_xxx directory. Otherwise the default will be false, 0, 0.0 or "" - virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = nullptr) = 0; + virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = NULL) = 0; - virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = nullptr) = 0; - virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; + virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = NULL) = 0; + virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; }; //----------------------------------------------------------------------------- @@ -1792,7 +1792,7 @@ class IVRDriverContext public: /** Returns the requested interface. If the interface was not available it will return NULL and fill * out the error. */ - virtual void *GetGenericInterface(const char *pchInterfaceVersion, EVRInitError *peError = nullptr) = 0; + virtual void *GetGenericInterface(const char *pchInterfaceVersion, EVRInitError *peError = NULL) = 0; /** Returns the property container handle for this driver */ virtual DriverHandle_t GetDriverHandle() = 0; @@ -1928,7 +1928,7 @@ class CVRPropertyHelpers /** Returns a string property as a std::string. If the device index is not valid or the property is not a string type this function will * return an empty string. */ - std::string GetStringProperty(vr::PropertyContainerHandle_t ulContainer, vr::ETrackedDeviceProperty prop, vr::ETrackedPropertyError *peError = nullptr); + std::string GetStringProperty(vr::PropertyContainerHandle_t ulContainer, vr::ETrackedDeviceProperty prop, vr::ETrackedPropertyError *peError = NULL); /** Sets a scaler property. The new value will be returned on any subsequent call to get this property in any process. */ ETrackedPropertyError SetBoolProperty(PropertyContainerHandle_t ulContainerHandle, ETrackedDeviceProperty prop, bool bNewValue); @@ -2389,7 +2389,7 @@ static const char *const k_InterfaceVersions[] = IVRVirtualDisplay_Version, IVRDriverManager_Version, IVRResources_Version, - nullptr}; + NULL}; inline IVRDriverContext *&VRDriverContext() { @@ -2400,7 +2400,7 @@ inline IVRDriverContext *&VRDriverContext() class COpenVRDriverContext { public: - COpenVRDriverContext() : m_propertyHelpers(nullptr), m_hiddenAreaHelpers(nullptr) { Clear(); } + COpenVRDriverContext() : m_propertyHelpers(NULL), m_hiddenAreaHelpers(NULL) { Clear(); } void Clear(); EVRInitError InitServer(); @@ -2408,7 +2408,7 @@ class COpenVRDriverContext IVRSettings *VRSettings() { - if (m_pVRSettings == nullptr) + if (m_pVRSettings == NULL) { EVRInitError eError; m_pVRSettings = (IVRSettings *)VRDriverContext()->GetGenericInterface(IVRSettings_Version, &eError); @@ -2418,7 +2418,7 @@ class COpenVRDriverContext IVRProperties *VRPropertiesRaw() { - if (m_pVRProperties == nullptr) + if (m_pVRProperties == NULL) { EVRInitError eError; m_pVRProperties = (IVRProperties *)VRDriverContext()->GetGenericInterface(IVRProperties_Version, &eError); @@ -2442,7 +2442,7 @@ class COpenVRDriverContext IVRServerDriverHost *VRServerDriverHost() { - if (m_pVRServerDriverHost == nullptr) + if (m_pVRServerDriverHost == NULL) { EVRInitError eError; m_pVRServerDriverHost = (IVRServerDriverHost *)VRDriverContext()->GetGenericInterface(IVRServerDriverHost_Version, &eError); @@ -2452,7 +2452,7 @@ class COpenVRDriverContext IVRWatchdogHost *VRWatchdogHost() { - if (m_pVRWatchdogHost == nullptr) + if (m_pVRWatchdogHost == NULL) { EVRInitError eError; m_pVRWatchdogHost = (IVRWatchdogHost *)VRDriverContext()->GetGenericInterface(IVRWatchdogHost_Version, &eError); @@ -2462,7 +2462,7 @@ class COpenVRDriverContext IVRDriverLog *VRDriverLog() { - if (m_pVRDriverLog == nullptr) + if (m_pVRDriverLog == NULL) { EVRInitError eError; m_pVRDriverLog = (IVRDriverLog *)VRDriverContext()->GetGenericInterface(IVRDriverLog_Version, &eError); @@ -2527,13 +2527,13 @@ inline IVRResources *VR_CALLTYPE VRResources() { return OpenVRInternal_ModuleSer inline void COpenVRDriverContext::Clear() { - m_pVRSettings = nullptr; - m_pVRProperties = nullptr; - m_pVRServerDriverHost = nullptr; - m_pVRDriverLog = nullptr; - m_pVRWatchdogHost = nullptr; - m_pVRDriverManager = nullptr; - m_pVRResources = nullptr; + m_pVRSettings = NULL; + m_pVRProperties = NULL; + m_pVRServerDriverHost = NULL; + m_pVRDriverLog = NULL; + m_pVRWatchdogHost = NULL; + m_pVRDriverManager = NULL; + m_pVRResources = NULL; } inline EVRInitError COpenVRDriverContext::InitServer() @@ -2566,7 +2566,7 @@ inline EVRInitError InitWatchdogDriverContext(IVRDriverContext *pContext) inline void CleanupDriverContext() { - VRDriverContext() = nullptr; + VRDriverContext() = NULL; OpenVRInternal_ModuleServerDriverContext().Clear(); } diff --git a/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/A/Headers/openvr.h b/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/A/Headers/openvr.h index 80461f9687..f9dd38b11c 100644 --- a/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/A/Headers/openvr.h +++ b/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/A/Headers/openvr.h @@ -1278,7 +1278,7 @@ class IVRSystem * [macOS Only] * Returns an id that should be used by the application. */ - virtual void GetOutputDevice(uint64_t *pnDevice, ETextureType textureType, VkInstance_T *pInstance = nullptr) = 0; + virtual void GetOutputDevice(uint64_t *pnDevice, ETextureType textureType, VkInstance_T *pInstance = NULL) = 0; // ------------------------------------ // Display Mode methods @@ -1640,13 +1640,13 @@ class IVRApplications // --------------- Application properties --------------- // /** Returns a value for an application property. The required buffer size to fit this value will be returned. */ - virtual uint32_t GetApplicationPropertyString(const char *pchAppKey, EVRApplicationProperty eProperty, VR_OUT_STRING() char *pchPropertyValueBuffer, uint32_t unPropertyValueBufferLen, EVRApplicationError *peError = nullptr) = 0; + virtual uint32_t GetApplicationPropertyString(const char *pchAppKey, EVRApplicationProperty eProperty, VR_OUT_STRING() char *pchPropertyValueBuffer, uint32_t unPropertyValueBufferLen, EVRApplicationError *peError = NULL) = 0; /** Returns a bool value for an application property. Returns false in all error cases. */ - virtual bool GetApplicationPropertyBool(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = nullptr) = 0; + virtual bool GetApplicationPropertyBool(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = NULL) = 0; /** Returns a uint64 value for an application property. Returns 0 in all error cases. */ - virtual uint64_t GetApplicationPropertyUint64(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = nullptr) = 0; + virtual uint64_t GetApplicationPropertyUint64(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = NULL) = 0; /** Sets the application auto-launch flag. This is only valid for applications which return true for VRApplicationProperty_IsDashboardOverlay_Bool. */ virtual EVRApplicationError SetApplicationAutoLaunch(const char *pchAppKey, bool bAutoLaunch) = 0; @@ -1733,22 +1733,22 @@ class IVRSettings virtual const char *GetSettingsErrorNameFromEnum(EVRSettingsError eError) = 0; // Returns true if file sync occurred (force or settings dirty) - virtual bool Sync(bool bForce = false, EVRSettingsError *peError = nullptr) = 0; + virtual bool Sync(bool bForce = false, EVRSettingsError *peError = NULL) = 0; - virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = nullptr) = 0; + virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = NULL) = 0; // Users of the system need to provide a proper default in default.vrsettings in the resources/settings/ directory // of either the runtime or the driver_xxx directory. Otherwise the default will be false, 0, 0.0 or "" - virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = nullptr) = 0; + virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = NULL) = 0; - virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = nullptr) = 0; - virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; + virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = NULL) = 0; + virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; }; //----------------------------------------------------------------------------- @@ -2386,7 +2386,7 @@ namespace vr struct NotificationBitmap_t { NotificationBitmap_t() - : m_pImageData(nullptr), m_nWidth(0), m_nHeight(0), m_nBytesPerPixel(0){}; + : m_pImageData(NULL), m_nWidth(0), m_nHeight(0), m_nBytesPerPixel(0){}; void *m_pImageData; int32_t m_nWidth; @@ -2940,7 +2940,7 @@ class IVROverlay // --------------------------------------------- /** Show the message overlay. This will block and return you a result. **/ - virtual VRMessageOverlayResponse ShowMessageOverlay(const char *pchText, const char *pchCaption, const char *pchButton0Text, const char *pchButton1Text = nullptr, const char *pchButton2Text = nullptr, const char *pchButton3Text = nullptr) = 0; + virtual VRMessageOverlayResponse ShowMessageOverlay(const char *pchText, const char *pchCaption, const char *pchButton0Text, const char *pchButton1Text = NULL, const char *pchButton2Text = NULL, const char *pchButton3Text = NULL) = 0; /** If the calling process owns the overlay and it's open, this will close it. **/ virtual void CloseMessageOverlay() = 0; @@ -3256,7 +3256,7 @@ class IVRScreenshots * is the VR screenshot in the correct format. They should be * in the same aspect ratio. Formats per type: * VRScreenshotType_Mono: the VR filename is ignored (can be - * nullptr), this is a normal flat single shot. + * NULL), this is a normal flat single shot. * VRScreenshotType_Stereo: The VR image should be a * side-by-side with the left eye image on the left. * VRScreenshotType_Cubemap: The VR image should be six square @@ -3387,7 +3387,7 @@ namespace vr * * pStartupInfo is reserved for future use. */ -inline IVRSystem *VR_Init(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo = nullptr); +inline IVRSystem *VR_Init(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo = NULL); /** unloads vrclient.dll. Any interface pointers from the interface are * invalid after this point */ @@ -3466,7 +3466,7 @@ class COpenVRContext IVRSystem *VRSystem() { CheckClear(); - if (m_pVRSystem == nullptr) + if (m_pVRSystem == NULL) { EVRInitError eError; m_pVRSystem = (IVRSystem *)VR_GetGenericInterface(IVRSystem_Version, &eError); @@ -3476,7 +3476,7 @@ class COpenVRContext IVRChaperone *VRChaperone() { CheckClear(); - if (m_pVRChaperone == nullptr) + if (m_pVRChaperone == NULL) { EVRInitError eError; m_pVRChaperone = (IVRChaperone *)VR_GetGenericInterface(IVRChaperone_Version, &eError); @@ -3487,7 +3487,7 @@ class COpenVRContext IVRChaperoneSetup *VRChaperoneSetup() { CheckClear(); - if (m_pVRChaperoneSetup == nullptr) + if (m_pVRChaperoneSetup == NULL) { EVRInitError eError; m_pVRChaperoneSetup = (IVRChaperoneSetup *)VR_GetGenericInterface(IVRChaperoneSetup_Version, &eError); @@ -3498,7 +3498,7 @@ class COpenVRContext IVRCompositor *VRCompositor() { CheckClear(); - if (m_pVRCompositor == nullptr) + if (m_pVRCompositor == NULL) { EVRInitError eError; m_pVRCompositor = (IVRCompositor *)VR_GetGenericInterface(IVRCompositor_Version, &eError); @@ -3509,7 +3509,7 @@ class COpenVRContext IVROverlay *VROverlay() { CheckClear(); - if (m_pVROverlay == nullptr) + if (m_pVROverlay == NULL) { EVRInitError eError; m_pVROverlay = (IVROverlay *)VR_GetGenericInterface(IVROverlay_Version, &eError); @@ -3520,7 +3520,7 @@ class COpenVRContext IVRResources *VRResources() { CheckClear(); - if (m_pVRResources == nullptr) + if (m_pVRResources == NULL) { EVRInitError eError; m_pVRResources = (IVRResources *)VR_GetGenericInterface(IVRResources_Version, &eError); @@ -3531,7 +3531,7 @@ class COpenVRContext IVRScreenshots *VRScreenshots() { CheckClear(); - if (m_pVRScreenshots == nullptr) + if (m_pVRScreenshots == NULL) { EVRInitError eError; m_pVRScreenshots = (IVRScreenshots *)VR_GetGenericInterface(IVRScreenshots_Version, &eError); @@ -3542,7 +3542,7 @@ class COpenVRContext IVRRenderModels *VRRenderModels() { CheckClear(); - if (m_pVRRenderModels == nullptr) + if (m_pVRRenderModels == NULL) { EVRInitError eError; m_pVRRenderModels = (IVRRenderModels *)VR_GetGenericInterface(IVRRenderModels_Version, &eError); @@ -3553,7 +3553,7 @@ class COpenVRContext IVRExtendedDisplay *VRExtendedDisplay() { CheckClear(); - if (m_pVRExtendedDisplay == nullptr) + if (m_pVRExtendedDisplay == NULL) { EVRInitError eError; m_pVRExtendedDisplay = (IVRExtendedDisplay *)VR_GetGenericInterface(IVRExtendedDisplay_Version, &eError); @@ -3564,7 +3564,7 @@ class COpenVRContext IVRSettings *VRSettings() { CheckClear(); - if (m_pVRSettings == nullptr) + if (m_pVRSettings == NULL) { EVRInitError eError; m_pVRSettings = (IVRSettings *)VR_GetGenericInterface(IVRSettings_Version, &eError); @@ -3575,7 +3575,7 @@ class COpenVRContext IVRApplications *VRApplications() { CheckClear(); - if (m_pVRApplications == nullptr) + if (m_pVRApplications == NULL) { EVRInitError eError; m_pVRApplications = (IVRApplications *)VR_GetGenericInterface(IVRApplications_Version, &eError); @@ -3586,7 +3586,7 @@ class COpenVRContext IVRTrackedCamera *VRTrackedCamera() { CheckClear(); - if (m_pVRTrackedCamera == nullptr) + if (m_pVRTrackedCamera == NULL) { EVRInitError eError; m_pVRTrackedCamera = (IVRTrackedCamera *)VR_GetGenericInterface(IVRTrackedCamera_Version, &eError); @@ -3643,19 +3643,19 @@ inline IVRDriverManager *VR_CALLTYPE VRDriverManager() { return OpenVRInternal_M inline void COpenVRContext::Clear() { - m_pVRSystem = nullptr; - m_pVRChaperone = nullptr; - m_pVRChaperoneSetup = nullptr; - m_pVRCompositor = nullptr; - m_pVROverlay = nullptr; - m_pVRRenderModels = nullptr; - m_pVRExtendedDisplay = nullptr; - m_pVRSettings = nullptr; - m_pVRApplications = nullptr; - m_pVRTrackedCamera = nullptr; - m_pVRResources = nullptr; - m_pVRScreenshots = nullptr; - m_pVRDriverManager = nullptr; + m_pVRSystem = NULL; + m_pVRChaperone = NULL; + m_pVRChaperoneSetup = NULL; + m_pVRCompositor = NULL; + m_pVROverlay = NULL; + m_pVRRenderModels = NULL; + m_pVRExtendedDisplay = NULL; + m_pVRSettings = NULL; + m_pVRApplications = NULL; + m_pVRTrackedCamera = NULL; + m_pVRResources = NULL; + m_pVRScreenshots = NULL; + m_pVRDriverManager = NULL; } VR_INTERFACE uint32_t VR_CALLTYPE VR_InitInternal2(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo); @@ -3664,7 +3664,7 @@ VR_INTERFACE void VR_CALLTYPE VR_ShutdownInternal(); /** Finds the active installation of vrclient.dll and initializes it */ inline IVRSystem *VR_Init(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo) { - IVRSystem *pVRSystem = nullptr; + IVRSystem *pVRSystem = NULL; EVRInitError eError; VRToken() = VR_InitInternal2(&eError, eApplicationType, pStartupInfo); diff --git a/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/A/Headers/openvr_driver.h b/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/A/Headers/openvr_driver.h index b07699f82c..efe8938a19 100644 --- a/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/A/Headers/openvr_driver.h +++ b/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/A/Headers/openvr_driver.h @@ -1323,22 +1323,22 @@ class IVRSettings virtual const char *GetSettingsErrorNameFromEnum(EVRSettingsError eError) = 0; // Returns true if file sync occurred (force or settings dirty) - virtual bool Sync(bool bForce = false, EVRSettingsError *peError = nullptr) = 0; + virtual bool Sync(bool bForce = false, EVRSettingsError *peError = NULL) = 0; - virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = nullptr) = 0; + virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = NULL) = 0; // Users of the system need to provide a proper default in default.vrsettings in the resources/settings/ directory // of either the runtime or the driver_xxx directory. Otherwise the default will be false, 0, 0.0 or "" - virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = nullptr) = 0; + virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = NULL) = 0; - virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = nullptr) = 0; - virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; + virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = NULL) = 0; + virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; }; //----------------------------------------------------------------------------- @@ -1792,7 +1792,7 @@ class IVRDriverContext public: /** Returns the requested interface. If the interface was not available it will return NULL and fill * out the error. */ - virtual void *GetGenericInterface(const char *pchInterfaceVersion, EVRInitError *peError = nullptr) = 0; + virtual void *GetGenericInterface(const char *pchInterfaceVersion, EVRInitError *peError = NULL) = 0; /** Returns the property container handle for this driver */ virtual DriverHandle_t GetDriverHandle() = 0; @@ -1928,7 +1928,7 @@ class CVRPropertyHelpers /** Returns a string property as a std::string. If the device index is not valid or the property is not a string type this function will * return an empty string. */ - std::string GetStringProperty(vr::PropertyContainerHandle_t ulContainer, vr::ETrackedDeviceProperty prop, vr::ETrackedPropertyError *peError = nullptr); + std::string GetStringProperty(vr::PropertyContainerHandle_t ulContainer, vr::ETrackedDeviceProperty prop, vr::ETrackedPropertyError *peError = NULL); /** Sets a scaler property. The new value will be returned on any subsequent call to get this property in any process. */ ETrackedPropertyError SetBoolProperty(PropertyContainerHandle_t ulContainerHandle, ETrackedDeviceProperty prop, bool bNewValue); @@ -2389,7 +2389,7 @@ static const char *const k_InterfaceVersions[] = IVRVirtualDisplay_Version, IVRDriverManager_Version, IVRResources_Version, - nullptr}; + NULL}; inline IVRDriverContext *&VRDriverContext() { @@ -2400,7 +2400,7 @@ inline IVRDriverContext *&VRDriverContext() class COpenVRDriverContext { public: - COpenVRDriverContext() : m_propertyHelpers(nullptr), m_hiddenAreaHelpers(nullptr) { Clear(); } + COpenVRDriverContext() : m_propertyHelpers(NULL), m_hiddenAreaHelpers(NULL) { Clear(); } void Clear(); EVRInitError InitServer(); @@ -2408,7 +2408,7 @@ class COpenVRDriverContext IVRSettings *VRSettings() { - if (m_pVRSettings == nullptr) + if (m_pVRSettings == NULL) { EVRInitError eError; m_pVRSettings = (IVRSettings *)VRDriverContext()->GetGenericInterface(IVRSettings_Version, &eError); @@ -2418,7 +2418,7 @@ class COpenVRDriverContext IVRProperties *VRPropertiesRaw() { - if (m_pVRProperties == nullptr) + if (m_pVRProperties == NULL) { EVRInitError eError; m_pVRProperties = (IVRProperties *)VRDriverContext()->GetGenericInterface(IVRProperties_Version, &eError); @@ -2442,7 +2442,7 @@ class COpenVRDriverContext IVRServerDriverHost *VRServerDriverHost() { - if (m_pVRServerDriverHost == nullptr) + if (m_pVRServerDriverHost == NULL) { EVRInitError eError; m_pVRServerDriverHost = (IVRServerDriverHost *)VRDriverContext()->GetGenericInterface(IVRServerDriverHost_Version, &eError); @@ -2452,7 +2452,7 @@ class COpenVRDriverContext IVRWatchdogHost *VRWatchdogHost() { - if (m_pVRWatchdogHost == nullptr) + if (m_pVRWatchdogHost == NULL) { EVRInitError eError; m_pVRWatchdogHost = (IVRWatchdogHost *)VRDriverContext()->GetGenericInterface(IVRWatchdogHost_Version, &eError); @@ -2462,7 +2462,7 @@ class COpenVRDriverContext IVRDriverLog *VRDriverLog() { - if (m_pVRDriverLog == nullptr) + if (m_pVRDriverLog == NULL) { EVRInitError eError; m_pVRDriverLog = (IVRDriverLog *)VRDriverContext()->GetGenericInterface(IVRDriverLog_Version, &eError); @@ -2527,13 +2527,13 @@ inline IVRResources *VR_CALLTYPE VRResources() { return OpenVRInternal_ModuleSer inline void COpenVRDriverContext::Clear() { - m_pVRSettings = nullptr; - m_pVRProperties = nullptr; - m_pVRServerDriverHost = nullptr; - m_pVRDriverLog = nullptr; - m_pVRWatchdogHost = nullptr; - m_pVRDriverManager = nullptr; - m_pVRResources = nullptr; + m_pVRSettings = NULL; + m_pVRProperties = NULL; + m_pVRServerDriverHost = NULL; + m_pVRDriverLog = NULL; + m_pVRWatchdogHost = NULL; + m_pVRDriverManager = NULL; + m_pVRResources = NULL; } inline EVRInitError COpenVRDriverContext::InitServer() @@ -2566,7 +2566,7 @@ inline EVRInitError InitWatchdogDriverContext(IVRDriverContext *pContext) inline void CleanupDriverContext() { - VRDriverContext() = nullptr; + VRDriverContext() = NULL; OpenVRInternal_ModuleServerDriverContext().Clear(); } diff --git a/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/Current/Headers/openvr.h b/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/Current/Headers/openvr.h index 80461f9687..f9dd38b11c 100644 --- a/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/Current/Headers/openvr.h +++ b/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/Current/Headers/openvr.h @@ -1278,7 +1278,7 @@ class IVRSystem * [macOS Only] * Returns an id that should be used by the application. */ - virtual void GetOutputDevice(uint64_t *pnDevice, ETextureType textureType, VkInstance_T *pInstance = nullptr) = 0; + virtual void GetOutputDevice(uint64_t *pnDevice, ETextureType textureType, VkInstance_T *pInstance = NULL) = 0; // ------------------------------------ // Display Mode methods @@ -1640,13 +1640,13 @@ class IVRApplications // --------------- Application properties --------------- // /** Returns a value for an application property. The required buffer size to fit this value will be returned. */ - virtual uint32_t GetApplicationPropertyString(const char *pchAppKey, EVRApplicationProperty eProperty, VR_OUT_STRING() char *pchPropertyValueBuffer, uint32_t unPropertyValueBufferLen, EVRApplicationError *peError = nullptr) = 0; + virtual uint32_t GetApplicationPropertyString(const char *pchAppKey, EVRApplicationProperty eProperty, VR_OUT_STRING() char *pchPropertyValueBuffer, uint32_t unPropertyValueBufferLen, EVRApplicationError *peError = NULL) = 0; /** Returns a bool value for an application property. Returns false in all error cases. */ - virtual bool GetApplicationPropertyBool(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = nullptr) = 0; + virtual bool GetApplicationPropertyBool(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = NULL) = 0; /** Returns a uint64 value for an application property. Returns 0 in all error cases. */ - virtual uint64_t GetApplicationPropertyUint64(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = nullptr) = 0; + virtual uint64_t GetApplicationPropertyUint64(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = NULL) = 0; /** Sets the application auto-launch flag. This is only valid for applications which return true for VRApplicationProperty_IsDashboardOverlay_Bool. */ virtual EVRApplicationError SetApplicationAutoLaunch(const char *pchAppKey, bool bAutoLaunch) = 0; @@ -1733,22 +1733,22 @@ class IVRSettings virtual const char *GetSettingsErrorNameFromEnum(EVRSettingsError eError) = 0; // Returns true if file sync occurred (force or settings dirty) - virtual bool Sync(bool bForce = false, EVRSettingsError *peError = nullptr) = 0; + virtual bool Sync(bool bForce = false, EVRSettingsError *peError = NULL) = 0; - virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = nullptr) = 0; + virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = NULL) = 0; // Users of the system need to provide a proper default in default.vrsettings in the resources/settings/ directory // of either the runtime or the driver_xxx directory. Otherwise the default will be false, 0, 0.0 or "" - virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = nullptr) = 0; + virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = NULL) = 0; - virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = nullptr) = 0; - virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; + virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = NULL) = 0; + virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; }; //----------------------------------------------------------------------------- @@ -2386,7 +2386,7 @@ namespace vr struct NotificationBitmap_t { NotificationBitmap_t() - : m_pImageData(nullptr), m_nWidth(0), m_nHeight(0), m_nBytesPerPixel(0){}; + : m_pImageData(NULL), m_nWidth(0), m_nHeight(0), m_nBytesPerPixel(0){}; void *m_pImageData; int32_t m_nWidth; @@ -2940,7 +2940,7 @@ class IVROverlay // --------------------------------------------- /** Show the message overlay. This will block and return you a result. **/ - virtual VRMessageOverlayResponse ShowMessageOverlay(const char *pchText, const char *pchCaption, const char *pchButton0Text, const char *pchButton1Text = nullptr, const char *pchButton2Text = nullptr, const char *pchButton3Text = nullptr) = 0; + virtual VRMessageOverlayResponse ShowMessageOverlay(const char *pchText, const char *pchCaption, const char *pchButton0Text, const char *pchButton1Text = NULL, const char *pchButton2Text = NULL, const char *pchButton3Text = NULL) = 0; /** If the calling process owns the overlay and it's open, this will close it. **/ virtual void CloseMessageOverlay() = 0; @@ -3256,7 +3256,7 @@ class IVRScreenshots * is the VR screenshot in the correct format. They should be * in the same aspect ratio. Formats per type: * VRScreenshotType_Mono: the VR filename is ignored (can be - * nullptr), this is a normal flat single shot. + * NULL), this is a normal flat single shot. * VRScreenshotType_Stereo: The VR image should be a * side-by-side with the left eye image on the left. * VRScreenshotType_Cubemap: The VR image should be six square @@ -3387,7 +3387,7 @@ namespace vr * * pStartupInfo is reserved for future use. */ -inline IVRSystem *VR_Init(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo = nullptr); +inline IVRSystem *VR_Init(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo = NULL); /** unloads vrclient.dll. Any interface pointers from the interface are * invalid after this point */ @@ -3466,7 +3466,7 @@ class COpenVRContext IVRSystem *VRSystem() { CheckClear(); - if (m_pVRSystem == nullptr) + if (m_pVRSystem == NULL) { EVRInitError eError; m_pVRSystem = (IVRSystem *)VR_GetGenericInterface(IVRSystem_Version, &eError); @@ -3476,7 +3476,7 @@ class COpenVRContext IVRChaperone *VRChaperone() { CheckClear(); - if (m_pVRChaperone == nullptr) + if (m_pVRChaperone == NULL) { EVRInitError eError; m_pVRChaperone = (IVRChaperone *)VR_GetGenericInterface(IVRChaperone_Version, &eError); @@ -3487,7 +3487,7 @@ class COpenVRContext IVRChaperoneSetup *VRChaperoneSetup() { CheckClear(); - if (m_pVRChaperoneSetup == nullptr) + if (m_pVRChaperoneSetup == NULL) { EVRInitError eError; m_pVRChaperoneSetup = (IVRChaperoneSetup *)VR_GetGenericInterface(IVRChaperoneSetup_Version, &eError); @@ -3498,7 +3498,7 @@ class COpenVRContext IVRCompositor *VRCompositor() { CheckClear(); - if (m_pVRCompositor == nullptr) + if (m_pVRCompositor == NULL) { EVRInitError eError; m_pVRCompositor = (IVRCompositor *)VR_GetGenericInterface(IVRCompositor_Version, &eError); @@ -3509,7 +3509,7 @@ class COpenVRContext IVROverlay *VROverlay() { CheckClear(); - if (m_pVROverlay == nullptr) + if (m_pVROverlay == NULL) { EVRInitError eError; m_pVROverlay = (IVROverlay *)VR_GetGenericInterface(IVROverlay_Version, &eError); @@ -3520,7 +3520,7 @@ class COpenVRContext IVRResources *VRResources() { CheckClear(); - if (m_pVRResources == nullptr) + if (m_pVRResources == NULL) { EVRInitError eError; m_pVRResources = (IVRResources *)VR_GetGenericInterface(IVRResources_Version, &eError); @@ -3531,7 +3531,7 @@ class COpenVRContext IVRScreenshots *VRScreenshots() { CheckClear(); - if (m_pVRScreenshots == nullptr) + if (m_pVRScreenshots == NULL) { EVRInitError eError; m_pVRScreenshots = (IVRScreenshots *)VR_GetGenericInterface(IVRScreenshots_Version, &eError); @@ -3542,7 +3542,7 @@ class COpenVRContext IVRRenderModels *VRRenderModels() { CheckClear(); - if (m_pVRRenderModels == nullptr) + if (m_pVRRenderModels == NULL) { EVRInitError eError; m_pVRRenderModels = (IVRRenderModels *)VR_GetGenericInterface(IVRRenderModels_Version, &eError); @@ -3553,7 +3553,7 @@ class COpenVRContext IVRExtendedDisplay *VRExtendedDisplay() { CheckClear(); - if (m_pVRExtendedDisplay == nullptr) + if (m_pVRExtendedDisplay == NULL) { EVRInitError eError; m_pVRExtendedDisplay = (IVRExtendedDisplay *)VR_GetGenericInterface(IVRExtendedDisplay_Version, &eError); @@ -3564,7 +3564,7 @@ class COpenVRContext IVRSettings *VRSettings() { CheckClear(); - if (m_pVRSettings == nullptr) + if (m_pVRSettings == NULL) { EVRInitError eError; m_pVRSettings = (IVRSettings *)VR_GetGenericInterface(IVRSettings_Version, &eError); @@ -3575,7 +3575,7 @@ class COpenVRContext IVRApplications *VRApplications() { CheckClear(); - if (m_pVRApplications == nullptr) + if (m_pVRApplications == NULL) { EVRInitError eError; m_pVRApplications = (IVRApplications *)VR_GetGenericInterface(IVRApplications_Version, &eError); @@ -3586,7 +3586,7 @@ class COpenVRContext IVRTrackedCamera *VRTrackedCamera() { CheckClear(); - if (m_pVRTrackedCamera == nullptr) + if (m_pVRTrackedCamera == NULL) { EVRInitError eError; m_pVRTrackedCamera = (IVRTrackedCamera *)VR_GetGenericInterface(IVRTrackedCamera_Version, &eError); @@ -3643,19 +3643,19 @@ inline IVRDriverManager *VR_CALLTYPE VRDriverManager() { return OpenVRInternal_M inline void COpenVRContext::Clear() { - m_pVRSystem = nullptr; - m_pVRChaperone = nullptr; - m_pVRChaperoneSetup = nullptr; - m_pVRCompositor = nullptr; - m_pVROverlay = nullptr; - m_pVRRenderModels = nullptr; - m_pVRExtendedDisplay = nullptr; - m_pVRSettings = nullptr; - m_pVRApplications = nullptr; - m_pVRTrackedCamera = nullptr; - m_pVRResources = nullptr; - m_pVRScreenshots = nullptr; - m_pVRDriverManager = nullptr; + m_pVRSystem = NULL; + m_pVRChaperone = NULL; + m_pVRChaperoneSetup = NULL; + m_pVRCompositor = NULL; + m_pVROverlay = NULL; + m_pVRRenderModels = NULL; + m_pVRExtendedDisplay = NULL; + m_pVRSettings = NULL; + m_pVRApplications = NULL; + m_pVRTrackedCamera = NULL; + m_pVRResources = NULL; + m_pVRScreenshots = NULL; + m_pVRDriverManager = NULL; } VR_INTERFACE uint32_t VR_CALLTYPE VR_InitInternal2(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo); @@ -3664,7 +3664,7 @@ VR_INTERFACE void VR_CALLTYPE VR_ShutdownInternal(); /** Finds the active installation of vrclient.dll and initializes it */ inline IVRSystem *VR_Init(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo) { - IVRSystem *pVRSystem = nullptr; + IVRSystem *pVRSystem = NULL; EVRInitError eError; VRToken() = VR_InitInternal2(&eError, eApplicationType, pStartupInfo); diff --git a/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/Current/Headers/openvr_driver.h b/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/Current/Headers/openvr_driver.h index b07699f82c..efe8938a19 100644 --- a/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/Current/Headers/openvr_driver.h +++ b/examples/ThirdPartyLibs/openvr/bin/osx64/OpenVR.framework/Versions/Current/Headers/openvr_driver.h @@ -1323,22 +1323,22 @@ class IVRSettings virtual const char *GetSettingsErrorNameFromEnum(EVRSettingsError eError) = 0; // Returns true if file sync occurred (force or settings dirty) - virtual bool Sync(bool bForce = false, EVRSettingsError *peError = nullptr) = 0; + virtual bool Sync(bool bForce = false, EVRSettingsError *peError = NULL) = 0; - virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = nullptr) = 0; + virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = NULL) = 0; // Users of the system need to provide a proper default in default.vrsettings in the resources/settings/ directory // of either the runtime or the driver_xxx directory. Otherwise the default will be false, 0, 0.0 or "" - virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = nullptr) = 0; + virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = NULL) = 0; - virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = nullptr) = 0; - virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; + virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = NULL) = 0; + virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; }; //----------------------------------------------------------------------------- @@ -1792,7 +1792,7 @@ class IVRDriverContext public: /** Returns the requested interface. If the interface was not available it will return NULL and fill * out the error. */ - virtual void *GetGenericInterface(const char *pchInterfaceVersion, EVRInitError *peError = nullptr) = 0; + virtual void *GetGenericInterface(const char *pchInterfaceVersion, EVRInitError *peError = NULL) = 0; /** Returns the property container handle for this driver */ virtual DriverHandle_t GetDriverHandle() = 0; @@ -1928,7 +1928,7 @@ class CVRPropertyHelpers /** Returns a string property as a std::string. If the device index is not valid or the property is not a string type this function will * return an empty string. */ - std::string GetStringProperty(vr::PropertyContainerHandle_t ulContainer, vr::ETrackedDeviceProperty prop, vr::ETrackedPropertyError *peError = nullptr); + std::string GetStringProperty(vr::PropertyContainerHandle_t ulContainer, vr::ETrackedDeviceProperty prop, vr::ETrackedPropertyError *peError = NULL); /** Sets a scaler property. The new value will be returned on any subsequent call to get this property in any process. */ ETrackedPropertyError SetBoolProperty(PropertyContainerHandle_t ulContainerHandle, ETrackedDeviceProperty prop, bool bNewValue); @@ -2389,7 +2389,7 @@ static const char *const k_InterfaceVersions[] = IVRVirtualDisplay_Version, IVRDriverManager_Version, IVRResources_Version, - nullptr}; + NULL}; inline IVRDriverContext *&VRDriverContext() { @@ -2400,7 +2400,7 @@ inline IVRDriverContext *&VRDriverContext() class COpenVRDriverContext { public: - COpenVRDriverContext() : m_propertyHelpers(nullptr), m_hiddenAreaHelpers(nullptr) { Clear(); } + COpenVRDriverContext() : m_propertyHelpers(NULL), m_hiddenAreaHelpers(NULL) { Clear(); } void Clear(); EVRInitError InitServer(); @@ -2408,7 +2408,7 @@ class COpenVRDriverContext IVRSettings *VRSettings() { - if (m_pVRSettings == nullptr) + if (m_pVRSettings == NULL) { EVRInitError eError; m_pVRSettings = (IVRSettings *)VRDriverContext()->GetGenericInterface(IVRSettings_Version, &eError); @@ -2418,7 +2418,7 @@ class COpenVRDriverContext IVRProperties *VRPropertiesRaw() { - if (m_pVRProperties == nullptr) + if (m_pVRProperties == NULL) { EVRInitError eError; m_pVRProperties = (IVRProperties *)VRDriverContext()->GetGenericInterface(IVRProperties_Version, &eError); @@ -2442,7 +2442,7 @@ class COpenVRDriverContext IVRServerDriverHost *VRServerDriverHost() { - if (m_pVRServerDriverHost == nullptr) + if (m_pVRServerDriverHost == NULL) { EVRInitError eError; m_pVRServerDriverHost = (IVRServerDriverHost *)VRDriverContext()->GetGenericInterface(IVRServerDriverHost_Version, &eError); @@ -2452,7 +2452,7 @@ class COpenVRDriverContext IVRWatchdogHost *VRWatchdogHost() { - if (m_pVRWatchdogHost == nullptr) + if (m_pVRWatchdogHost == NULL) { EVRInitError eError; m_pVRWatchdogHost = (IVRWatchdogHost *)VRDriverContext()->GetGenericInterface(IVRWatchdogHost_Version, &eError); @@ -2462,7 +2462,7 @@ class COpenVRDriverContext IVRDriverLog *VRDriverLog() { - if (m_pVRDriverLog == nullptr) + if (m_pVRDriverLog == NULL) { EVRInitError eError; m_pVRDriverLog = (IVRDriverLog *)VRDriverContext()->GetGenericInterface(IVRDriverLog_Version, &eError); @@ -2527,13 +2527,13 @@ inline IVRResources *VR_CALLTYPE VRResources() { return OpenVRInternal_ModuleSer inline void COpenVRDriverContext::Clear() { - m_pVRSettings = nullptr; - m_pVRProperties = nullptr; - m_pVRServerDriverHost = nullptr; - m_pVRDriverLog = nullptr; - m_pVRWatchdogHost = nullptr; - m_pVRDriverManager = nullptr; - m_pVRResources = nullptr; + m_pVRSettings = NULL; + m_pVRProperties = NULL; + m_pVRServerDriverHost = NULL; + m_pVRDriverLog = NULL; + m_pVRWatchdogHost = NULL; + m_pVRDriverManager = NULL; + m_pVRResources = NULL; } inline EVRInitError COpenVRDriverContext::InitServer() @@ -2566,7 +2566,7 @@ inline EVRInitError InitWatchdogDriverContext(IVRDriverContext *pContext) inline void CleanupDriverContext() { - VRDriverContext() = nullptr; + VRDriverContext() = NULL; OpenVRInternal_ModuleServerDriverContext().Clear(); } diff --git a/examples/ThirdPartyLibs/openvr/headers/openvr.h b/examples/ThirdPartyLibs/openvr/headers/openvr.h index 80461f9687..f9dd38b11c 100644 --- a/examples/ThirdPartyLibs/openvr/headers/openvr.h +++ b/examples/ThirdPartyLibs/openvr/headers/openvr.h @@ -1278,7 +1278,7 @@ class IVRSystem * [macOS Only] * Returns an id that should be used by the application. */ - virtual void GetOutputDevice(uint64_t *pnDevice, ETextureType textureType, VkInstance_T *pInstance = nullptr) = 0; + virtual void GetOutputDevice(uint64_t *pnDevice, ETextureType textureType, VkInstance_T *pInstance = NULL) = 0; // ------------------------------------ // Display Mode methods @@ -1640,13 +1640,13 @@ class IVRApplications // --------------- Application properties --------------- // /** Returns a value for an application property. The required buffer size to fit this value will be returned. */ - virtual uint32_t GetApplicationPropertyString(const char *pchAppKey, EVRApplicationProperty eProperty, VR_OUT_STRING() char *pchPropertyValueBuffer, uint32_t unPropertyValueBufferLen, EVRApplicationError *peError = nullptr) = 0; + virtual uint32_t GetApplicationPropertyString(const char *pchAppKey, EVRApplicationProperty eProperty, VR_OUT_STRING() char *pchPropertyValueBuffer, uint32_t unPropertyValueBufferLen, EVRApplicationError *peError = NULL) = 0; /** Returns a bool value for an application property. Returns false in all error cases. */ - virtual bool GetApplicationPropertyBool(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = nullptr) = 0; + virtual bool GetApplicationPropertyBool(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = NULL) = 0; /** Returns a uint64 value for an application property. Returns 0 in all error cases. */ - virtual uint64_t GetApplicationPropertyUint64(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = nullptr) = 0; + virtual uint64_t GetApplicationPropertyUint64(const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = NULL) = 0; /** Sets the application auto-launch flag. This is only valid for applications which return true for VRApplicationProperty_IsDashboardOverlay_Bool. */ virtual EVRApplicationError SetApplicationAutoLaunch(const char *pchAppKey, bool bAutoLaunch) = 0; @@ -1733,22 +1733,22 @@ class IVRSettings virtual const char *GetSettingsErrorNameFromEnum(EVRSettingsError eError) = 0; // Returns true if file sync occurred (force or settings dirty) - virtual bool Sync(bool bForce = false, EVRSettingsError *peError = nullptr) = 0; + virtual bool Sync(bool bForce = false, EVRSettingsError *peError = NULL) = 0; - virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = nullptr) = 0; + virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = NULL) = 0; // Users of the system need to provide a proper default in default.vrsettings in the resources/settings/ directory // of either the runtime or the driver_xxx directory. Otherwise the default will be false, 0, 0.0 or "" - virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = nullptr) = 0; + virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = NULL) = 0; - virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = nullptr) = 0; - virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; + virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = NULL) = 0; + virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; }; //----------------------------------------------------------------------------- @@ -2386,7 +2386,7 @@ namespace vr struct NotificationBitmap_t { NotificationBitmap_t() - : m_pImageData(nullptr), m_nWidth(0), m_nHeight(0), m_nBytesPerPixel(0){}; + : m_pImageData(NULL), m_nWidth(0), m_nHeight(0), m_nBytesPerPixel(0){}; void *m_pImageData; int32_t m_nWidth; @@ -2940,7 +2940,7 @@ class IVROverlay // --------------------------------------------- /** Show the message overlay. This will block and return you a result. **/ - virtual VRMessageOverlayResponse ShowMessageOverlay(const char *pchText, const char *pchCaption, const char *pchButton0Text, const char *pchButton1Text = nullptr, const char *pchButton2Text = nullptr, const char *pchButton3Text = nullptr) = 0; + virtual VRMessageOverlayResponse ShowMessageOverlay(const char *pchText, const char *pchCaption, const char *pchButton0Text, const char *pchButton1Text = NULL, const char *pchButton2Text = NULL, const char *pchButton3Text = NULL) = 0; /** If the calling process owns the overlay and it's open, this will close it. **/ virtual void CloseMessageOverlay() = 0; @@ -3256,7 +3256,7 @@ class IVRScreenshots * is the VR screenshot in the correct format. They should be * in the same aspect ratio. Formats per type: * VRScreenshotType_Mono: the VR filename is ignored (can be - * nullptr), this is a normal flat single shot. + * NULL), this is a normal flat single shot. * VRScreenshotType_Stereo: The VR image should be a * side-by-side with the left eye image on the left. * VRScreenshotType_Cubemap: The VR image should be six square @@ -3387,7 +3387,7 @@ namespace vr * * pStartupInfo is reserved for future use. */ -inline IVRSystem *VR_Init(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo = nullptr); +inline IVRSystem *VR_Init(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo = NULL); /** unloads vrclient.dll. Any interface pointers from the interface are * invalid after this point */ @@ -3466,7 +3466,7 @@ class COpenVRContext IVRSystem *VRSystem() { CheckClear(); - if (m_pVRSystem == nullptr) + if (m_pVRSystem == NULL) { EVRInitError eError; m_pVRSystem = (IVRSystem *)VR_GetGenericInterface(IVRSystem_Version, &eError); @@ -3476,7 +3476,7 @@ class COpenVRContext IVRChaperone *VRChaperone() { CheckClear(); - if (m_pVRChaperone == nullptr) + if (m_pVRChaperone == NULL) { EVRInitError eError; m_pVRChaperone = (IVRChaperone *)VR_GetGenericInterface(IVRChaperone_Version, &eError); @@ -3487,7 +3487,7 @@ class COpenVRContext IVRChaperoneSetup *VRChaperoneSetup() { CheckClear(); - if (m_pVRChaperoneSetup == nullptr) + if (m_pVRChaperoneSetup == NULL) { EVRInitError eError; m_pVRChaperoneSetup = (IVRChaperoneSetup *)VR_GetGenericInterface(IVRChaperoneSetup_Version, &eError); @@ -3498,7 +3498,7 @@ class COpenVRContext IVRCompositor *VRCompositor() { CheckClear(); - if (m_pVRCompositor == nullptr) + if (m_pVRCompositor == NULL) { EVRInitError eError; m_pVRCompositor = (IVRCompositor *)VR_GetGenericInterface(IVRCompositor_Version, &eError); @@ -3509,7 +3509,7 @@ class COpenVRContext IVROverlay *VROverlay() { CheckClear(); - if (m_pVROverlay == nullptr) + if (m_pVROverlay == NULL) { EVRInitError eError; m_pVROverlay = (IVROverlay *)VR_GetGenericInterface(IVROverlay_Version, &eError); @@ -3520,7 +3520,7 @@ class COpenVRContext IVRResources *VRResources() { CheckClear(); - if (m_pVRResources == nullptr) + if (m_pVRResources == NULL) { EVRInitError eError; m_pVRResources = (IVRResources *)VR_GetGenericInterface(IVRResources_Version, &eError); @@ -3531,7 +3531,7 @@ class COpenVRContext IVRScreenshots *VRScreenshots() { CheckClear(); - if (m_pVRScreenshots == nullptr) + if (m_pVRScreenshots == NULL) { EVRInitError eError; m_pVRScreenshots = (IVRScreenshots *)VR_GetGenericInterface(IVRScreenshots_Version, &eError); @@ -3542,7 +3542,7 @@ class COpenVRContext IVRRenderModels *VRRenderModels() { CheckClear(); - if (m_pVRRenderModels == nullptr) + if (m_pVRRenderModels == NULL) { EVRInitError eError; m_pVRRenderModels = (IVRRenderModels *)VR_GetGenericInterface(IVRRenderModels_Version, &eError); @@ -3553,7 +3553,7 @@ class COpenVRContext IVRExtendedDisplay *VRExtendedDisplay() { CheckClear(); - if (m_pVRExtendedDisplay == nullptr) + if (m_pVRExtendedDisplay == NULL) { EVRInitError eError; m_pVRExtendedDisplay = (IVRExtendedDisplay *)VR_GetGenericInterface(IVRExtendedDisplay_Version, &eError); @@ -3564,7 +3564,7 @@ class COpenVRContext IVRSettings *VRSettings() { CheckClear(); - if (m_pVRSettings == nullptr) + if (m_pVRSettings == NULL) { EVRInitError eError; m_pVRSettings = (IVRSettings *)VR_GetGenericInterface(IVRSettings_Version, &eError); @@ -3575,7 +3575,7 @@ class COpenVRContext IVRApplications *VRApplications() { CheckClear(); - if (m_pVRApplications == nullptr) + if (m_pVRApplications == NULL) { EVRInitError eError; m_pVRApplications = (IVRApplications *)VR_GetGenericInterface(IVRApplications_Version, &eError); @@ -3586,7 +3586,7 @@ class COpenVRContext IVRTrackedCamera *VRTrackedCamera() { CheckClear(); - if (m_pVRTrackedCamera == nullptr) + if (m_pVRTrackedCamera == NULL) { EVRInitError eError; m_pVRTrackedCamera = (IVRTrackedCamera *)VR_GetGenericInterface(IVRTrackedCamera_Version, &eError); @@ -3643,19 +3643,19 @@ inline IVRDriverManager *VR_CALLTYPE VRDriverManager() { return OpenVRInternal_M inline void COpenVRContext::Clear() { - m_pVRSystem = nullptr; - m_pVRChaperone = nullptr; - m_pVRChaperoneSetup = nullptr; - m_pVRCompositor = nullptr; - m_pVROverlay = nullptr; - m_pVRRenderModels = nullptr; - m_pVRExtendedDisplay = nullptr; - m_pVRSettings = nullptr; - m_pVRApplications = nullptr; - m_pVRTrackedCamera = nullptr; - m_pVRResources = nullptr; - m_pVRScreenshots = nullptr; - m_pVRDriverManager = nullptr; + m_pVRSystem = NULL; + m_pVRChaperone = NULL; + m_pVRChaperoneSetup = NULL; + m_pVRCompositor = NULL; + m_pVROverlay = NULL; + m_pVRRenderModels = NULL; + m_pVRExtendedDisplay = NULL; + m_pVRSettings = NULL; + m_pVRApplications = NULL; + m_pVRTrackedCamera = NULL; + m_pVRResources = NULL; + m_pVRScreenshots = NULL; + m_pVRDriverManager = NULL; } VR_INTERFACE uint32_t VR_CALLTYPE VR_InitInternal2(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo); @@ -3664,7 +3664,7 @@ VR_INTERFACE void VR_CALLTYPE VR_ShutdownInternal(); /** Finds the active installation of vrclient.dll and initializes it */ inline IVRSystem *VR_Init(EVRInitError *peError, EVRApplicationType eApplicationType, const char *pStartupInfo) { - IVRSystem *pVRSystem = nullptr; + IVRSystem *pVRSystem = NULL; EVRInitError eError; VRToken() = VR_InitInternal2(&eError, eApplicationType, pStartupInfo); diff --git a/examples/ThirdPartyLibs/openvr/headers/openvr_driver.h b/examples/ThirdPartyLibs/openvr/headers/openvr_driver.h index b07699f82c..efe8938a19 100644 --- a/examples/ThirdPartyLibs/openvr/headers/openvr_driver.h +++ b/examples/ThirdPartyLibs/openvr/headers/openvr_driver.h @@ -1323,22 +1323,22 @@ class IVRSettings virtual const char *GetSettingsErrorNameFromEnum(EVRSettingsError eError) = 0; // Returns true if file sync occurred (force or settings dirty) - virtual bool Sync(bool bForce = false, EVRSettingsError *peError = nullptr) = 0; + virtual bool Sync(bool bForce = false, EVRSettingsError *peError = NULL) = 0; - virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = nullptr) = 0; - virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = nullptr) = 0; + virtual void SetBool(const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetInt32(const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetFloat(const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = NULL) = 0; + virtual void SetString(const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = NULL) = 0; // Users of the system need to provide a proper default in default.vrsettings in the resources/settings/ directory // of either the runtime or the driver_xxx directory. Otherwise the default will be false, 0, 0.0 or "" - virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; - virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = nullptr) = 0; + virtual bool GetBool(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual int32_t GetInt32(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual float GetFloat(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; + virtual void GetString(const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = NULL) = 0; - virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = nullptr) = 0; - virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr) = 0; + virtual void RemoveSection(const char *pchSection, EVRSettingsError *peError = NULL) = 0; + virtual void RemoveKeyInSection(const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = NULL) = 0; }; //----------------------------------------------------------------------------- @@ -1792,7 +1792,7 @@ class IVRDriverContext public: /** Returns the requested interface. If the interface was not available it will return NULL and fill * out the error. */ - virtual void *GetGenericInterface(const char *pchInterfaceVersion, EVRInitError *peError = nullptr) = 0; + virtual void *GetGenericInterface(const char *pchInterfaceVersion, EVRInitError *peError = NULL) = 0; /** Returns the property container handle for this driver */ virtual DriverHandle_t GetDriverHandle() = 0; @@ -1928,7 +1928,7 @@ class CVRPropertyHelpers /** Returns a string property as a std::string. If the device index is not valid or the property is not a string type this function will * return an empty string. */ - std::string GetStringProperty(vr::PropertyContainerHandle_t ulContainer, vr::ETrackedDeviceProperty prop, vr::ETrackedPropertyError *peError = nullptr); + std::string GetStringProperty(vr::PropertyContainerHandle_t ulContainer, vr::ETrackedDeviceProperty prop, vr::ETrackedPropertyError *peError = NULL); /** Sets a scaler property. The new value will be returned on any subsequent call to get this property in any process. */ ETrackedPropertyError SetBoolProperty(PropertyContainerHandle_t ulContainerHandle, ETrackedDeviceProperty prop, bool bNewValue); @@ -2389,7 +2389,7 @@ static const char *const k_InterfaceVersions[] = IVRVirtualDisplay_Version, IVRDriverManager_Version, IVRResources_Version, - nullptr}; + NULL}; inline IVRDriverContext *&VRDriverContext() { @@ -2400,7 +2400,7 @@ inline IVRDriverContext *&VRDriverContext() class COpenVRDriverContext { public: - COpenVRDriverContext() : m_propertyHelpers(nullptr), m_hiddenAreaHelpers(nullptr) { Clear(); } + COpenVRDriverContext() : m_propertyHelpers(NULL), m_hiddenAreaHelpers(NULL) { Clear(); } void Clear(); EVRInitError InitServer(); @@ -2408,7 +2408,7 @@ class COpenVRDriverContext IVRSettings *VRSettings() { - if (m_pVRSettings == nullptr) + if (m_pVRSettings == NULL) { EVRInitError eError; m_pVRSettings = (IVRSettings *)VRDriverContext()->GetGenericInterface(IVRSettings_Version, &eError); @@ -2418,7 +2418,7 @@ class COpenVRDriverContext IVRProperties *VRPropertiesRaw() { - if (m_pVRProperties == nullptr) + if (m_pVRProperties == NULL) { EVRInitError eError; m_pVRProperties = (IVRProperties *)VRDriverContext()->GetGenericInterface(IVRProperties_Version, &eError); @@ -2442,7 +2442,7 @@ class COpenVRDriverContext IVRServerDriverHost *VRServerDriverHost() { - if (m_pVRServerDriverHost == nullptr) + if (m_pVRServerDriverHost == NULL) { EVRInitError eError; m_pVRServerDriverHost = (IVRServerDriverHost *)VRDriverContext()->GetGenericInterface(IVRServerDriverHost_Version, &eError); @@ -2452,7 +2452,7 @@ class COpenVRDriverContext IVRWatchdogHost *VRWatchdogHost() { - if (m_pVRWatchdogHost == nullptr) + if (m_pVRWatchdogHost == NULL) { EVRInitError eError; m_pVRWatchdogHost = (IVRWatchdogHost *)VRDriverContext()->GetGenericInterface(IVRWatchdogHost_Version, &eError); @@ -2462,7 +2462,7 @@ class COpenVRDriverContext IVRDriverLog *VRDriverLog() { - if (m_pVRDriverLog == nullptr) + if (m_pVRDriverLog == NULL) { EVRInitError eError; m_pVRDriverLog = (IVRDriverLog *)VRDriverContext()->GetGenericInterface(IVRDriverLog_Version, &eError); @@ -2527,13 +2527,13 @@ inline IVRResources *VR_CALLTYPE VRResources() { return OpenVRInternal_ModuleSer inline void COpenVRDriverContext::Clear() { - m_pVRSettings = nullptr; - m_pVRProperties = nullptr; - m_pVRServerDriverHost = nullptr; - m_pVRDriverLog = nullptr; - m_pVRWatchdogHost = nullptr; - m_pVRDriverManager = nullptr; - m_pVRResources = nullptr; + m_pVRSettings = NULL; + m_pVRProperties = NULL; + m_pVRServerDriverHost = NULL; + m_pVRDriverLog = NULL; + m_pVRWatchdogHost = NULL; + m_pVRDriverManager = NULL; + m_pVRResources = NULL; } inline EVRInitError COpenVRDriverContext::InitServer() @@ -2566,7 +2566,7 @@ inline EVRInitError InitWatchdogDriverContext(IVRDriverContext *pContext) inline void CleanupDriverContext() { - VRDriverContext() = nullptr; + VRDriverContext() = NULL; OpenVRInternal_ModuleServerDriverContext().Clear(); } diff --git a/examples/ThirdPartyLibs/openvr/samples/shared/compat.h b/examples/ThirdPartyLibs/openvr/samples/shared/compat.h index a3b2f32151..d7ada5674e 100644 --- a/examples/ThirdPartyLibs/openvr/samples/shared/compat.h +++ b/examples/ThirdPartyLibs/openvr/samples/shared/compat.h @@ -16,8 +16,8 @@ #define _stricmp strcmp #define stricmp strcmp #define strnicmp strncasecmp -#define strcpy_s(dst, n, src) int(strncpy(dst, src, n) != nullptr) -#define fopen_s(fd, path, mode) int((*fd = fopen(path, mode)) != nullptr) +#define strcpy_s(dst, n, src) int(strncpy(dst, src, n) != NULL) +#define fopen_s(fd, path, mode) int((*fd = fopen(path, mode)) != NULL) #define _vsnprintf_s(buffer, size, fmt, ap) vsnprintf(buffer, size, fmt, ap) #define OutputDebugStringA(x) fprintf(stderr, "%s\n", x) diff --git a/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp b/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp index b6ba420723..4bca37f45a 100644 --- a/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp +++ b/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp @@ -451,7 +451,7 @@ bool Path_IsAppBundle(const std::string &sPath) { #if defined(OSX) NSBundle *bundle = [NSBundle bundleWithPath:[NSString stringWithUTF8String:sPath.c_str()]]; - bool bisAppBundle = (nullptr != bundle); + bool bisAppBundle = (NULL != bundle); [bundle release]; return bisAppBundle; #else @@ -704,7 +704,7 @@ bool Path_WriteStringToTextFileAtomic(const std::string &strFilename, const char #if defined(_WIN32) std::wstring wsFilename = UTF8to16(strFilename.c_str()); std::wstring wsTmpFilename = UTF8to16(strTmpFilename.c_str()); - if (!::ReplaceFileW(wsFilename.c_str(), wsTmpFilename.c_str(), nullptr, 0, 0, 0)) + if (!::ReplaceFileW(wsFilename.c_str(), wsTmpFilename.c_str(), NULL, 0, 0, 0)) { // if we couldn't ReplaceFile, try a non-atomic write as a fallback if (!Path_WriteStringToTextFile(strFilename, pchData)) From 9d0a50271897c5b03be8f5e85d3c523289dbdd94 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 15:53:15 +0100 Subject: [PATCH 26/57] Compiler warnings - shadow --- .../btBvhTriangleMeshShape.cpp | 12 ++--- .../CollisionShapes/btCompoundShape.cpp | 6 +-- .../CollisionShapes/btConvexPolyhedron.cpp | 6 +-- .../CollisionShapes/btOptimizedBvh.cpp | 14 ++--- .../btStridingMeshInterface.cpp | 30 +++++------ .../CollisionShapes/btTriangleShape.h | 6 +-- .../NarrowPhaseCollision/btGjkEpa2.cpp | 6 +-- .../btGjkPairDetector.cpp | 10 ++-- .../btMinkowskiPenetrationDepthSolver.cpp | 8 +-- .../btPolyhedralContactClipping.cpp | 4 +- .../btConeTwistConstraint.cpp | 8 +-- .../btSequentialImpulseConstraintSolverMt.cpp | 2 +- .../Dynamics/btDiscreteDynamicsWorld.cpp | 10 ++-- .../Featherstone/btMultiBody.cpp | 34 ++++++------ .../Featherstone/btMultiBodyDynamicsWorld.cpp | 52 +++++++++---------- .../btMultiBodyMLCPConstraintSolver.cpp | 6 +-- .../MLCPSolvers/btDantzigLCP.cpp | 8 +-- .../MLCPSolvers/btMLCPSolver.cpp | 6 +-- 18 files changed, 114 insertions(+), 114 deletions(-) diff --git a/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp b/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp index 4f001c5a5e..2b5ebc5f5f 100644 --- a/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp +++ b/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp @@ -401,9 +401,9 @@ const char* btBvhTriangleMeshShape::serialize(void* dataBuffer, btSerializer* se #endif //BT_USE_DOUBLE_PRECISION int sz = m_bvh->calculateSerializeBufferSizeNew(); - btChunk* chunk = serializer->allocate(sz, 1); - const char* structType = m_bvh->serialize(chunk->m_oldPtr, serializer); - serializer->finalizeChunk(chunk, structType, BT_QUANTIZED_BVH_CODE, m_bvh); + btChunk* serializerChunk = serializer->allocate(sz, 1); + const char* structType = m_bvh->serialize(serializerChunk->m_oldPtr, serializer); + serializer->finalizeChunk(serializerChunk, structType, BT_QUANTIZED_BVH_CODE, m_bvh); } } else @@ -423,9 +423,9 @@ const char* btBvhTriangleMeshShape::serialize(void* dataBuffer, btSerializer* se { trimeshData->m_triangleInfoMap = (btTriangleInfoMapData*)serializer->getUniquePointer(m_triangleInfoMap); int sz = m_triangleInfoMap->calculateSerializeBufferSize(); - btChunk* chunk = serializer->allocate(sz, 1); - const char* structType = m_triangleInfoMap->serialize(chunk->m_oldPtr, serializer); - serializer->finalizeChunk(chunk, structType, BT_TRIANLGE_INFO_MAP, m_triangleInfoMap); + btChunk* serializerChunk = serializer->allocate(sz, 1); + const char* structType = m_triangleInfoMap->serialize(serializerChunk->m_oldPtr, serializer); + serializer->finalizeChunk(serializerChunk, structType, BT_TRIANLGE_INFO_MAP, m_triangleInfoMap); } } else diff --git a/src/BulletCollision/CollisionShapes/btCompoundShape.cpp b/src/BulletCollision/CollisionShapes/btCompoundShape.cpp index fd7828b104..a89b353b7e 100644 --- a/src/BulletCollision/CollisionShapes/btCompoundShape.cpp +++ b/src/BulletCollision/CollisionShapes/btCompoundShape.cpp @@ -321,9 +321,9 @@ const char* btCompoundShape::serialize(void* dataBuffer, btSerializer* serialize //don't serialize shapes that already have been serialized if (!serializer->findPointer(m_children[i].m_childShape)) { - btChunk* chunk = serializer->allocate(m_children[i].m_childShape->calculateSerializeBufferSize(), 1); - const char* structType = m_children[i].m_childShape->serialize(chunk->m_oldPtr, serializer); - serializer->finalizeChunk(chunk, structType, BT_SHAPE_CODE, m_children[i].m_childShape); + btChunk* serializerChunk = serializer->allocate(m_children[i].m_childShape->calculateSerializeBufferSize(), 1); + const char* structType = m_children[i].m_childShape->serialize(serializerChunk->m_oldPtr, serializer); + serializer->finalizeChunk(serializerChunk, structType, BT_SHAPE_CODE, m_children[i].m_childShape); } memPtr->m_childShapeType = m_children[i].m_childShapeType; diff --git a/src/BulletCollision/CollisionShapes/btConvexPolyhedron.cpp b/src/BulletCollision/CollisionShapes/btConvexPolyhedron.cpp index 9694f4ddb3..7162d1e504 100644 --- a/src/BulletCollision/CollisionShapes/btConvexPolyhedron.cpp +++ b/src/BulletCollision/CollisionShapes/btConvexPolyhedron.cpp @@ -252,7 +252,7 @@ void btConvexPolyhedron::initialize2() else { // Refine the box - const btScalar Step = (m_radius - r) / 1024.0f; + const btScalar RefineStep = (m_radius - r) / 1024.0f; const int e0 = (1 << LargestExtent) & 3; const int e1 = (1 << e0) & 3; @@ -260,8 +260,8 @@ void btConvexPolyhedron::initialize2() { const btScalar Saved0 = m_extents[e0]; const btScalar Saved1 = m_extents[e1]; - m_extents[e0] += Step; - m_extents[e1] += Step; + m_extents[e0] += RefineStep; + m_extents[e1] += RefineStep; if (!testContainment()) { diff --git a/src/BulletCollision/CollisionShapes/btOptimizedBvh.cpp b/src/BulletCollision/CollisionShapes/btOptimizedBvh.cpp index 3ff92781a7..92c4b06e3c 100644 --- a/src/BulletCollision/CollisionShapes/btOptimizedBvh.cpp +++ b/src/BulletCollision/CollisionShapes/btOptimizedBvh.cpp @@ -336,15 +336,15 @@ void btOptimizedBvh::updateBvhNodes(btStridingMeshInterface* meshInterface, int btQuantizedBvhNode* rightChildNode = leftChildNode->isLeafNode() ? &m_quantizedContiguousNodes[i + 2] : &m_quantizedContiguousNodes[i + 1 + leftChildNode->getEscapeIndex()]; { - for (int i = 0; i < 3; i++) + for (int j = 0; j < 3; j++) { - curNode.m_quantizedAabbMin[i] = leftChildNode->m_quantizedAabbMin[i]; - if (curNode.m_quantizedAabbMin[i] > rightChildNode->m_quantizedAabbMin[i]) - curNode.m_quantizedAabbMin[i] = rightChildNode->m_quantizedAabbMin[i]; + curNode.m_quantizedAabbMin[j] = leftChildNode->m_quantizedAabbMin[j]; + if (curNode.m_quantizedAabbMin[j] > rightChildNode->m_quantizedAabbMin[j]) + curNode.m_quantizedAabbMin[j] = rightChildNode->m_quantizedAabbMin[j]; - curNode.m_quantizedAabbMax[i] = leftChildNode->m_quantizedAabbMax[i]; - if (curNode.m_quantizedAabbMax[i] < rightChildNode->m_quantizedAabbMax[i]) - curNode.m_quantizedAabbMax[i] = rightChildNode->m_quantizedAabbMax[i]; + curNode.m_quantizedAabbMax[j] = leftChildNode->m_quantizedAabbMax[j]; + if (curNode.m_quantizedAabbMax[j] < rightChildNode->m_quantizedAabbMax[j]) + curNode.m_quantizedAabbMax[j] = rightChildNode->m_quantizedAabbMax[j]; } } } diff --git a/src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp b/src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp index 113e7e428d..d37efb2375 100644 --- a/src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp +++ b/src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp @@ -258,8 +258,8 @@ const char* btStridingMeshInterface::serialize(void* dataBuffer, btSerializer* s if (numindices) { - btChunk* chunk = serializer->allocate(sizeof(btIntIndexData), numindices); - btIntIndexData* tmpIndices = (btIntIndexData*)chunk->m_oldPtr; + btChunk* serializerChunk = serializer->allocate(sizeof(btIntIndexData), numindices); + btIntIndexData* tmpIndices = (btIntIndexData*)serializerChunk->m_oldPtr; memPtr->m_indices32 = (btIntIndexData*)serializer->getUniquePointer(tmpIndices); for (gfxindex = 0; gfxindex < numtriangles; gfxindex++) { @@ -268,7 +268,7 @@ const char* btStridingMeshInterface::serialize(void* dataBuffer, btSerializer* s tmpIndices[gfxindex * 3 + 1].m_value = tri_indices[1]; tmpIndices[gfxindex * 3 + 2].m_value = tri_indices[2]; } - serializer->finalizeChunk(chunk, "btIntIndexData", BT_ARRAY_CODE, (void*)chunk->m_oldPtr); + serializer->finalizeChunk(serializerChunk, "btIntIndexData", BT_ARRAY_CODE, (void*)serializerChunk->m_oldPtr); } break; } @@ -276,8 +276,8 @@ const char* btStridingMeshInterface::serialize(void* dataBuffer, btSerializer* s { if (numtriangles) { - btChunk* chunk = serializer->allocate(sizeof(btShortIntIndexTripletData), numtriangles); - btShortIntIndexTripletData* tmpIndices = (btShortIntIndexTripletData*)chunk->m_oldPtr; + btChunk* serializerChunk = serializer->allocate(sizeof(btShortIntIndexTripletData), numtriangles); + btShortIntIndexTripletData* tmpIndices = (btShortIntIndexTripletData*)serializerChunk->m_oldPtr; memPtr->m_3indices16 = (btShortIntIndexTripletData*)serializer->getUniquePointer(tmpIndices); for (gfxindex = 0; gfxindex < numtriangles; gfxindex++) { @@ -289,7 +289,7 @@ const char* btStridingMeshInterface::serialize(void* dataBuffer, btSerializer* s tmpIndices[gfxindex].m_pad[0] = 0; tmpIndices[gfxindex].m_pad[1] = 0; } - serializer->finalizeChunk(chunk, "btShortIntIndexTripletData", BT_ARRAY_CODE, (void*)chunk->m_oldPtr); + serializer->finalizeChunk(serializerChunk, "btShortIntIndexTripletData", BT_ARRAY_CODE, (void*)serializerChunk->m_oldPtr); } break; } @@ -297,8 +297,8 @@ const char* btStridingMeshInterface::serialize(void* dataBuffer, btSerializer* s { if (numtriangles) { - btChunk* chunk = serializer->allocate(sizeof(btCharIndexTripletData), numtriangles); - btCharIndexTripletData* tmpIndices = (btCharIndexTripletData*)chunk->m_oldPtr; + btChunk* serializerChunk = serializer->allocate(sizeof(btCharIndexTripletData), numtriangles); + btCharIndexTripletData* tmpIndices = (btCharIndexTripletData*)serializerChunk->m_oldPtr; memPtr->m_3indices8 = (btCharIndexTripletData*)serializer->getUniquePointer(tmpIndices); for (gfxindex = 0; gfxindex < numtriangles; gfxindex++) { @@ -309,7 +309,7 @@ const char* btStridingMeshInterface::serialize(void* dataBuffer, btSerializer* s // Fill padding with zeros to appease msan. tmpIndices[gfxindex].m_pad = 0; } - serializer->finalizeChunk(chunk, "btCharIndexTripletData", BT_ARRAY_CODE, (void*)chunk->m_oldPtr); + serializer->finalizeChunk(serializerChunk, "btCharIndexTripletData", BT_ARRAY_CODE, (void*)serializerChunk->m_oldPtr); } break; } @@ -328,8 +328,8 @@ const char* btStridingMeshInterface::serialize(void* dataBuffer, btSerializer* s if (numverts) { - btChunk* chunk = serializer->allocate(sizeof(btVector3FloatData), numverts); - btVector3FloatData* tmpVertices = (btVector3FloatData*)chunk->m_oldPtr; + btChunk* serializerChunk = serializer->allocate(sizeof(btVector3FloatData), numverts); + btVector3FloatData* tmpVertices = (btVector3FloatData*)serializerChunk->m_oldPtr; memPtr->m_vertices3f = (btVector3FloatData*)serializer->getUniquePointer(tmpVertices); for (int i = 0; i < numverts; i++) { @@ -338,7 +338,7 @@ const char* btStridingMeshInterface::serialize(void* dataBuffer, btSerializer* s tmpVertices[i].m_floats[1] = graphicsbase[1]; tmpVertices[i].m_floats[2] = graphicsbase[2]; } - serializer->finalizeChunk(chunk, "btVector3FloatData", BT_ARRAY_CODE, (void*)chunk->m_oldPtr); + serializer->finalizeChunk(serializerChunk, "btVector3FloatData", BT_ARRAY_CODE, (void*)serializerChunk->m_oldPtr); } break; } @@ -347,8 +347,8 @@ const char* btStridingMeshInterface::serialize(void* dataBuffer, btSerializer* s { if (numverts) { - btChunk* chunk = serializer->allocate(sizeof(btVector3DoubleData), numverts); - btVector3DoubleData* tmpVertices = (btVector3DoubleData*)chunk->m_oldPtr; + btChunk* serializerChunk = serializer->allocate(sizeof(btVector3DoubleData), numverts); + btVector3DoubleData* tmpVertices = (btVector3DoubleData*)serializerChunk->m_oldPtr; memPtr->m_vertices3d = (btVector3DoubleData*)serializer->getUniquePointer(tmpVertices); for (int i = 0; i < numverts; i++) { @@ -357,7 +357,7 @@ const char* btStridingMeshInterface::serialize(void* dataBuffer, btSerializer* s tmpVertices[i].m_floats[1] = graphicsbase[1]; tmpVertices[i].m_floats[2] = graphicsbase[2]; } - serializer->finalizeChunk(chunk, "btVector3DoubleData", BT_ARRAY_CODE, (void*)chunk->m_oldPtr); + serializer->finalizeChunk(serializerChunk, "btVector3DoubleData", BT_ARRAY_CODE, (void*)serializerChunk->m_oldPtr); } break; } diff --git a/src/BulletCollision/CollisionShapes/btTriangleShape.h b/src/BulletCollision/CollisionShapes/btTriangleShape.h index 190cbdae69..1f5125be73 100644 --- a/src/BulletCollision/CollisionShapes/btTriangleShape.h +++ b/src/BulletCollision/CollisionShapes/btTriangleShape.h @@ -141,10 +141,10 @@ btTriangleShape : public btPolyhedralConvexShape btVector3 edge = pb - pa; btVector3 edgeNormal = edge.cross(normal); edgeNormal.normalize(); - btScalar dist = pt.dot(edgeNormal); + btScalar distance = pt.dot(edgeNormal); btScalar edgeConst = pa.dot(edgeNormal); - dist -= edgeConst; - if (dist < -tolerance) + distance -= edgeConst; + if (distance < -tolerance) return false; } diff --git a/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.cpp b/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.cpp index 228860477e..4c4cf9b37f 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.cpp @@ -1044,12 +1044,12 @@ btScalar btGjkEpaSolver2::SignedDistance(const btVector3& position, results.witnesses[1] = wtrs0 * w1; const btVector3 delta = results.witnesses[1] - results.witnesses[0]; - const btScalar margin = shape0->getMarginNonVirtual() + + const btScalar marginNv = shape0->getMarginNonVirtual() + shape1.getMarginNonVirtual(); const btScalar length = delta.length(); results.normal = delta / length; - results.witnesses[0] += results.normal * margin; - results.distance = length - margin; + results.witnesses[0] += results.normal * marginNv; + results.distance = length - marginNv; return results.distance; } else diff --git a/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp b/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp index bee8c330d2..e4c4fb2bfc 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp @@ -552,10 +552,10 @@ static int btDoSimplex3(btSimplex *simplex, btVector3 *dir) } else { - btSupportVector tmp; - btSupportCopy(&tmp, C); + btSupportVector tmpVec; + btSupportCopy(&tmpVec, C); btSimplexSet(simplex, 0, B); - btSimplexSet(simplex, 1, &tmp); + btSimplexSet(simplex, 1, &tmpVec); btVec3Copy(dir, &ABC); btVec3Scale(dir, -btScalar(1)); @@ -767,8 +767,8 @@ void btGjkPairDetector::getClosestPointsNonVirtual(const ClosestPointInput &inpu // check if farthest point in Minkowski difference in direction dir // isn't somewhere before origin (the test on negative dot product) // - because if it is, objects are not intersecting at all. - btScalar delta = lastSupV.dot(dir); - if (delta < 0) + btScalar deltaDiff = lastSupV.dot(dir); + if (deltaDiff < 0) { //no intersection, besides margin status = -1; diff --git a/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.cpp b/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.cpp index dcb29808cb..d4a330b4c3 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.cpp @@ -92,10 +92,10 @@ bool btMinkowskiPenetrationDepthSolver::calcPenDepth(btSimplexSolverInterface& s int numPDA = convexA->getNumPreferredPenetrationDirections(); if (numPDA) { - for (int i = 0; i < numPDA; i++) + for (int j = 0; j < numPDA; j++) { btVector3 norm; - convexA->getPreferredPenetrationDirection(i, norm); + convexA->getPreferredPenetrationDirection(j, norm); norm = transA.getBasis() * norm; getPenetrationDirections()[numSampleDirections] = norm; separatingAxisInABatch[numSampleDirections] = (-norm) * transA.getBasis(); @@ -109,10 +109,10 @@ bool btMinkowskiPenetrationDepthSolver::calcPenDepth(btSimplexSolverInterface& s int numPDB = convexB->getNumPreferredPenetrationDirections(); if (numPDB) { - for (int i = 0; i < numPDB; i++) + for (int j = 0; j < numPDB; j++) { btVector3 norm; - convexB->getPreferredPenetrationDirection(i, norm); + convexB->getPreferredPenetrationDirection(j, norm); norm = transB.getBasis() * norm; getPenetrationDirections()[numSampleDirections] = norm; separatingAxisInABatch[numSampleDirections] = (-norm) * transA.getBasis(); diff --git a/src/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.cpp b/src/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.cpp index bfbd99c86b..0ea98471b6 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.cpp @@ -486,7 +486,7 @@ void btPolyhedralContactClipping::clipFaceAgainstHull(const btVector3& separatin if (depth <= maxDist) { - btVector3 point = pVtxIn->at(i); + btVector3 pointVtx = pVtxIn->at(i); #ifdef ONLY_REPORT_DEEPEST_POINT curMaxDist = depth; #else @@ -497,7 +497,7 @@ void btPolyhedralContactClipping::clipFaceAgainstHull(const btVector3& separatin printf("likely wrong separatingNormal passed in\n"); } #endif - resultOut.addContactPoint(separatingNormal, point, depth); + resultOut.addContactPoint(separatingNormal, pointVtx, depth); #endif } } diff --git a/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp b/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp index a9af4cf2da..729fd9d6d0 100644 --- a/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp +++ b/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp @@ -191,9 +191,9 @@ void btConeTwistConstraint::getInfo2NonVirtual(btConstraintInfo2* info, const bt J2[srow + 0] = -ax1[0]; J2[srow + 1] = -ax1[1]; J2[srow + 2] = -ax1[2]; - btScalar k = info->fps * m_biasFactor; + btScalar kb = info->fps * m_biasFactor; - info->m_constraintError[srow] = k * m_swingCorrection; + info->m_constraintError[srow] = kb * m_swingCorrection; if (m_flags & BT_CONETWIST_FLAGS_ANG_CFM) { info->cfm[srow] = m_angCFM; @@ -215,8 +215,8 @@ void btConeTwistConstraint::getInfo2NonVirtual(btConstraintInfo2* info, const bt J2[srow + 0] = -ax1[0]; J2[srow + 1] = -ax1[1]; J2[srow + 2] = -ax1[2]; - btScalar k = info->fps * m_biasFactor; - info->m_constraintError[srow] = k * m_twistCorrection; + btScalar kb = info->fps * m_biasFactor; + info->m_constraintError[srow] = kb * m_twistCorrection; if (m_flags & BT_CONETWIST_FLAGS_ANG_CFM) { info->cfm[srow] = m_angCFM; diff --git a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp index 06f1d39923..711e65f08e 100644 --- a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp +++ b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp @@ -478,7 +478,7 @@ void btSequentialImpulseConstraintSolverMt::internalAllocContactConstraints(cons { m_rollingFrictionIndexTable[contactIndex] = rollingFrictionIndex; // allocate 3 (although we may use only 2 sometimes) - for (int i = 0; i < 3; i++) + for (int j = 0; j < 3; j++) { m_tmpSolverContactRollingFrictionConstraintPool[rollingFrictionIndex].m_frictionIndex = contactIndex; rollingFrictionIndex++; diff --git a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp index 907043a8b0..0db17abe8e 100644 --- a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp +++ b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp @@ -1328,12 +1328,12 @@ void btDiscreteDynamicsWorld::debugDrawConstraint(btTypedConstraint* constraint) if (drawFrames) getDebugDrawer()->drawTransform(tr, dbgDrawSize); if (drawLimits) { - btTransform tr = pSlider->getUseLinearReferenceFrameA() ? pSlider->getCalculatedTransformA() : pSlider->getCalculatedTransformB(); - btVector3 li_min = tr * btVector3(pSlider->getLowerLinLimit(), 0.f, 0.f); - btVector3 li_max = tr * btVector3(pSlider->getUpperLinLimit(), 0.f, 0.f); + btTransform tf = pSlider->getUseLinearReferenceFrameA() ? pSlider->getCalculatedTransformA() : pSlider->getCalculatedTransformB(); + btVector3 li_min = tf * btVector3(pSlider->getLowerLinLimit(), 0.f, 0.f); + btVector3 li_max = tf * btVector3(pSlider->getUpperLinLimit(), 0.f, 0.f); getDebugDrawer()->drawLine(li_min, li_max, btVector3(0, 0, 0)); - btVector3 normal = tr.getBasis().getColumn(0); - btVector3 axis = tr.getBasis().getColumn(1); + btVector3 normal = tf.getBasis().getColumn(0); + btVector3 axis = tf.getBasis().getColumn(1); btScalar a_min = pSlider->getLowerAngLimit(); btScalar a_max = pSlider->getUpperAngLimit(); const btVector3& center = pSlider->getCalculatedTransformB().getOrigin(); diff --git a/src/BulletDynamics/Featherstone/btMultiBody.cpp b/src/BulletDynamics/Featherstone/btMultiBody.cpp index ba0f0ea2a8..e6797cb1a7 100644 --- a/src/BulletDynamics/Featherstone/btMultiBody.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBody.cpp @@ -1343,12 +1343,12 @@ void btMultiBody::solveImatrix(const btVector3 &rhs_top, const btVector3 &rhs_bo //multiply result = invI * rhs { btVector3 vtop = invI_upper_left * rhs_top; - btVector3 tmp; - tmp = invIupper_right * rhs_bot; - vtop += tmp; + btVector3 tmpVec; + tmpVec = invIupper_right * rhs_bot; + vtop += tmpVec; btVector3 vbot = invI_lower_left * rhs_top; - tmp = invI_lower_right * rhs_bot; - vbot += tmp; + tmpVec = invI_lower_right * rhs_bot; + vbot += tmpVec; result[0] = vtop[0]; result[1] = vtop[1]; result[2] = vtop[2]; @@ -1408,12 +1408,12 @@ void btMultiBody::solveImatrix(const btSpatialForceVector &rhs, btSpatialMotionV //multiply result = invI * rhs { btVector3 vtop = invI_upper_left * rhs.getLinear(); - btVector3 tmp; - tmp = invIupper_right * rhs.getAngular(); - vtop += tmp; + btVector3 tmpVec; + tmpVec = invIupper_right * rhs.getAngular(); + vtop += tmpVec; btVector3 vbot = invI_lower_left * rhs.getLinear(); - tmp = invI_lower_right * rhs.getAngular(); - vbot += tmp; + tmpVec = invI_lower_right * rhs.getAngular(); + vbot += tmpVec; result.setVector(vtop, vbot); } } @@ -1950,7 +1950,7 @@ void btMultiBody::fillConstraintJacobianMultiDof(int link, { // temporary space int num_links = getNumLinks(); - int m_dofCount = getNumDofs(); + int dofCount = getNumDofs(); scratch_v.resize(3 * num_links + 3); //(num_links + base) offsets + (num_links + base) normals_lin + (num_links + base) normals_ang scratch_m.resize(num_links + 1); @@ -1963,12 +1963,12 @@ void btMultiBody::fillConstraintJacobianMultiDof(int link, v_ptr += num_links + 1; btAssert(v_ptr - &scratch_v[0] == scratch_v.size()); - //scratch_r.resize(m_dofCount); - //btScalar *results = m_dofCount > 0 ? &scratch_r[0] : 0; + //scratch_r.resize(dofCount); + //btScalar *results = dofCount > 0 ? &scratch_r[0] : 0; - scratch_r1.resize(m_dofCount+num_links); - btScalar * results = m_dofCount > 0 ? &scratch_r1[0] : 0; - btScalar* links = num_links? &scratch_r1[m_dofCount] : 0; + scratch_r1.resize(dofCount+num_links); + btScalar * results = dofCount > 0 ? &scratch_r1[0] : 0; + btScalar* links = num_links? &scratch_r1[dofCount] : 0; int numLinksChildToRoot=0; int l = link; while (l != -1) @@ -2002,7 +2002,7 @@ void btMultiBody::fillConstraintJacobianMultiDof(int link, n_local_ang[0] = rot_from_world[0] * normal_ang_world; // Set remaining jac values to zero for now. - for (int i = 6; i < 6 + m_dofCount; ++i) + for (int i = 6; i < 6 + dofCount; ++i) { jac[i] = 0; } diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp index 7763d4988b..4d3d62dcbb 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp @@ -149,11 +149,11 @@ void btMultiBodyDynamicsWorld::updateActivationState(btScalar timeStep) } for (int b = 0; b < body->getNumLinks(); b++) { - btMultiBodyLinkCollider* col = body->getLink(b).m_collider; - if (col && col->getActivationState() == ACTIVE_TAG) + btMultiBodyLinkCollider* collider = body->getLink(b).m_collider; + if (collider && collider->getActivationState() == ACTIVE_TAG) { - col->setActivationState(WANTS_DEACTIVATION); - col->setDeactivationTime(0.f); + collider->setActivationState(WANTS_DEACTIVATION); + collider->setDeactivationTime(0.f); } } } @@ -165,9 +165,9 @@ void btMultiBodyDynamicsWorld::updateActivationState(btScalar timeStep) for (int b = 0; b < body->getNumLinks(); b++) { - btMultiBodyLinkCollider* col = body->getLink(b).m_collider; - if (col && col->getActivationState() != DISABLE_DEACTIVATION) - col->setActivationState(ACTIVE_TAG); + btMultiBodyLinkCollider* collider = body->getLink(b).m_collider; + if (collider && collider->getActivationState() != DISABLE_DEACTIVATION) + collider->setActivationState(ACTIVE_TAG); } } } @@ -353,9 +353,9 @@ void btMultiBodyDynamicsWorld::solveExternalForces(btContactSolverInfo& solverIn { BT_PROFILE("btMultiBody stepVelocities"); - for (int i = 0; i < this->m_multiBodies.size(); i++) + for (int j = 0; j < this->m_multiBodies.size(); j++) { - btMultiBody* bod = m_multiBodies[i]; + btMultiBody* bod = m_multiBodies[j]; bool isSleeping = false; @@ -451,8 +451,8 @@ void btMultiBodyDynamicsWorld::solveExternalForces(btContactSolverInfo& solverIn { void operator()(btScalar dt, const btScalar* pDer, const btScalar* pCurVal, btScalar* pVal, int size) { - for (int i = 0; i < size; ++i) - pVal[i] = pCurVal[i] + dt * pDer[i]; + for (int k = 0; k < size; ++k) + pVal[k] = pCurVal[k] + dt * pDer[k]; } } pEulerIntegrate; @@ -463,8 +463,8 @@ void btMultiBodyDynamicsWorld::solveExternalForces(btContactSolverInfo& solverIn { btScalar* pVel = const_cast(pBody->getVelocityVector()); - for (int i = 0; i < pBody->getNumDofs() + 6; ++i) - pVel[i] = pData[i]; + for (int k = 0; k < pBody->getNumDofs() + 6; ++k) + pVel[k] = pData[k]; } } pCopyToVelocityVector; // @@ -472,8 +472,8 @@ void btMultiBodyDynamicsWorld::solveExternalForces(btContactSolverInfo& solverIn { void operator()(const btScalar* pSrc, btScalar* pDst, int start, int size) { - for (int i = 0; i < size; ++i) - pDst[i] = pSrc[start + i]; + for (int k = 0; k < size; ++k) + pDst[k] = pSrc[start + k]; } } pCopy; // @@ -529,10 +529,10 @@ void btMultiBodyDynamicsWorld::solveExternalForces(btContactSolverInfo& solverIn delta_q.resize(numDofs); btAlignedObjectArray delta_qd; delta_qd.resize(numDofs); - for (int i = 0; i < numDofs; ++i) + for (int j = 0; j < numDofs; ++j) { - delta_q[i] = h / btScalar(6.) * (scratch_qd0[i] + 2 * scratch_qd1[i] + 2 * scratch_qd2[i] + scratch_qd3[i]); - delta_qd[i] = h / btScalar(6.) * (scratch_qdd0[i] + 2 * scratch_qdd1[i] + 2 * scratch_qdd2[i] + scratch_qdd3[i]); + delta_q[j] = h / btScalar(6.) * (scratch_qd0[j] + 2 * scratch_qd1[j] + 2 * scratch_qd2[j] + scratch_qd3[j]); + delta_qd[j] = h / btScalar(6.) * (scratch_qdd0[j] + 2 * scratch_qdd1[j] + 2 * scratch_qdd2[j] + scratch_qdd3[j]); //delta_q[i] = h*scratch_qd0[i]; //delta_qd[i] = h*scratch_qdd0[i]; } @@ -545,8 +545,8 @@ void btMultiBodyDynamicsWorld::solveExternalForces(btContactSolverInfo& solverIn btScalar* pRealBuf = const_cast(bod->getVelocityVector()); pRealBuf += 6 + bod->getNumDofs() + bod->getNumDofs() * bod->getNumDofs(); - for (int i = 0; i < numDofs; ++i) - pRealBuf[i] = delta_q[i]; + for (int j = 0; j < numDofs; ++j) + pRealBuf[j] = delta_q[j]; //bod->stepPositionsMultiDof(1, 0, &delta_q[0]); bod->setPosUpdated(true); @@ -591,9 +591,9 @@ void btMultiBodyDynamicsWorld::integrateMultiBodyTransforms(btScalar timeStep) { isSleeping = true; } - for (int b = 0; b < bod->getNumLinks(); b++) + for (int l = 0; l < bod->getNumLinks(); l++) { - if (bod->getLink(b).m_collider && bod->getLink(b).m_collider->getActivationState() == ISLAND_SLEEPING) + if (bod->getLink(l).m_collider && bod->getLink(l).m_collider->getActivationState() == ISLAND_SLEEPING) isSleeping = true; } @@ -640,9 +640,9 @@ void btMultiBodyDynamicsWorld::predictMultiBodyTransforms(btScalar timeStep) { isSleeping = true; } - for (int b = 0; b < bod->getNumLinks(); b++) + for (int l = 0; l < bod->getNumLinks(); l++) { - if (bod->getLink(b).m_collider && bod->getLink(b).m_collider->getActivationState() == ISLAND_SLEEPING) + if (bod->getLink(l).m_collider && bod->getLink(l).m_collider->getActivationState() == ISLAND_SLEEPING) isSleeping = true; } @@ -816,8 +816,8 @@ void btMultiBodyDynamicsWorld::clearMultiBodyForces() if (!isSleeping) { - btMultiBody* bod = m_multiBodies[i]; - bod->clearForcesAndTorques(); + btMultiBody* body = m_multiBodies[i]; + body->clearForcesAndTorques(); } } } diff --git a/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp b/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp index f2186a93e9..74a23cba89 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp @@ -540,9 +540,9 @@ void btMultiBodyMLCPConstraintSolver::createMLCPFastRigidBody(const btContactSol { for (int i = 0; i < m_allConstraintPtrArray.size(); i++) { - const btSolverConstraint& c = *m_allConstraintPtrArray[i]; - m_x[i] = c.m_appliedImpulse; - m_xSplit[i] = c.m_appliedPushImpulse; + const btSolverConstraint& sc = *m_allConstraintPtrArray[i]; + m_x[i] = sc.m_appliedImpulse; + m_xSplit[i] = sc.m_appliedPushImpulse; } } else diff --git a/src/BulletDynamics/MLCPSolvers/btDantzigLCP.cpp b/src/BulletDynamics/MLCPSolvers/btDantzigLCP.cpp index d13c39b677..6064daf1c5 100644 --- a/src/BulletDynamics/MLCPSolvers/btDantzigLCP.cpp +++ b/src/BulletDynamics/MLCPSolvers/btDantzigLCP.cpp @@ -1283,9 +1283,9 @@ btLCP::btLCP(int _n, int _nskip, int _nub, btScalar *_Adata, btScalar *_x, btSca } { - int *p = m_p; + int *mp = m_p; const int n = m_n; - for (int k = 0; k < n; ++k) p[k] = k; // initially unpermuted + for (int k = 0; k < n; ++k) mp[k] = k; // initially unpermuted } /* @@ -1798,14 +1798,14 @@ void btLCP::solve1(btScalar *a, int i, int dir, int only_transfer) if (dir > 0) { int *C = m_C; - btScalar *tmp = m_tmp; + tmp = m_tmp; const int nC = m_nC; for (int j = 0; j < nC; ++j) a[C[j]] = -tmp[j]; } else { int *C = m_C; - btScalar *tmp = m_tmp; + tmp = m_tmp; const int nC = m_nC; for (int j = 0; j < nC; ++j) a[C[j]] = tmp[j]; } diff --git a/src/BulletDynamics/MLCPSolvers/btMLCPSolver.cpp b/src/BulletDynamics/MLCPSolvers/btMLCPSolver.cpp index ed4e0b686d..5b3fefcf58 100644 --- a/src/BulletDynamics/MLCPSolvers/btMLCPSolver.cpp +++ b/src/BulletDynamics/MLCPSolvers/btMLCPSolver.cpp @@ -442,9 +442,9 @@ void btMLCPSolver::createMLCPFast(const btContactSolverInfo& infoGlobal) { for (int i = 0; i < m_allConstraintPtrArray.size(); i++) { - const btSolverConstraint& c = *m_allConstraintPtrArray[i]; - m_x[i] = c.m_appliedImpulse; - m_xSplit[i] = c.m_appliedPushImpulse; + const btSolverConstraint& sc = *m_allConstraintPtrArray[i]; + m_x[i] = sc.m_appliedImpulse; + m_xSplit[i] = sc.m_appliedPushImpulse; } } else From 1be983a8e2bbeb0738168a562619e88c1708ea19 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 16:01:26 +0100 Subject: [PATCH 27/57] Compiler warnings - switch default --- src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp b/src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp index 6f06447039..c830703582 100644 --- a/src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp +++ b/src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp @@ -162,6 +162,9 @@ void getProcessorInformation(btProcessorInfo* procInfo) case RelationProcessorPackage: procInfo->numPhysicalPackages++; break; + + default: + break; } } free(buf); From c1030e15ef85d18d889bd71c163804db417fdaa0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 22:34:12 +0100 Subject: [PATCH 28/57] Compiler warnings - switch default without case statement --- .../SharedMemoryInProcessPhysicsC_API.cpp | 26 ++++++++++--------- 1 file changed, 14 insertions(+), 12 deletions(-) diff --git a/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp b/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp index eef4a8dd2e..9d23a17fa5 100644 --- a/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp +++ b/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp @@ -420,12 +420,13 @@ class InProcessGraphicsServerSharedMemory : public PhysicsClientSharedMemory virtual bool submitClientCommand(const struct SharedMemoryCommand& command) { - switch (command.m_type) - { - default: - { - } - } + (void)command; + // switch (command.m_type) + // { + // default: + // { + // } + // } return true; } @@ -508,12 +509,13 @@ class InProcessGraphicsServerSharedMemoryMainThread : public PhysicsClientShared virtual bool submitClientCommand(const struct SharedMemoryCommand& command) { - switch (command.m_type) - { - default: - { - } - } + (void)command; + // switch (command.m_type) + // { + // default: + // { + // } + // } return true; } From 8bf973a222cacd4652c77a7bba36c7416bd72382 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 18:51:11 +0100 Subject: [PATCH 29/57] Compiler warnings - array-parameter --- examples/SharedMemory/PhysicsClientC_API.cpp | 48 +++---- examples/SharedMemory/PhysicsClientC_API.h | 136 +++++++++---------- 2 files changed, 92 insertions(+), 92 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 631a2e4c33..4669057057 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -1642,7 +1642,7 @@ B3_SHARED_API int b3CreateCollisionShapeAddBox(b3SharedMemoryCommandHandle comma return -1; } -B3_SHARED_API int b3CreateVisualShapeAddBox(b3SharedMemoryCommandHandle commandHandle, const double halfExtents[/*3*/]) +B3_SHARED_API int b3CreateVisualShapeAddBox(b3SharedMemoryCommandHandle commandHandle, const double halfExtents[3]) { return b3CreateCollisionShapeAddBox(commandHandle, halfExtents); } @@ -1676,7 +1676,7 @@ B3_SHARED_API int b3CreateVisualShapeAddCapsule(b3SharedMemoryCommandHandle comm return b3CreateCollisionShapeAddCapsule(commandHandle, radius, height); } -B3_SHARED_API int b3CreateCollisionShapeAddHeightfield(b3SharedMemoryCommandHandle commandHandle, const char* fileName, const double meshScale[/*3*/], double textureScaling) +B3_SHARED_API int b3CreateCollisionShapeAddHeightfield(b3SharedMemoryCommandHandle commandHandle, const char* fileName, const double meshScale[3], double textureScaling) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; b3Assert(command); @@ -1706,7 +1706,7 @@ B3_SHARED_API int b3CreateCollisionShapeAddHeightfield(b3SharedMemoryCommandHand return -1; } -B3_SHARED_API int b3CreateCollisionShapeAddHeightfield2(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], double textureScaling, float* heightfieldData, int numHeightfieldRows, int numHeightfieldColumns, int replaceHeightfieldIndex) +B3_SHARED_API int b3CreateCollisionShapeAddHeightfield2(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[3], double textureScaling, float* heightfieldData, int numHeightfieldRows, int numHeightfieldColumns, int replaceHeightfieldIndex) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -1789,7 +1789,7 @@ B3_SHARED_API int b3CreateCollisionShapeAddPlane(b3SharedMemoryCommandHandle com } return -1; } -B3_SHARED_API int b3CreateVisualShapeAddPlane(b3SharedMemoryCommandHandle commandHandle, const double planeNormal[/*3*/], double planeConstant) +B3_SHARED_API int b3CreateVisualShapeAddPlane(b3SharedMemoryCommandHandle commandHandle, const double planeNormal[3], double planeConstant) { return b3CreateCollisionShapeAddPlane(commandHandle, planeNormal, planeConstant); } @@ -1822,7 +1822,7 @@ B3_SHARED_API int b3CreateCollisionShapeAddMesh(b3SharedMemoryCommandHandle comm return -1; } -B3_SHARED_API int b3CreateCollisionShapeAddConvexMesh(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices) +B3_SHARED_API int b3CreateCollisionShapeAddConvexMesh(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[3], const double* vertices, int numVertices) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -1857,7 +1857,7 @@ B3_SHARED_API int b3CreateCollisionShapeAddConvexMesh(b3PhysicsClientHandle phys return -1; } -B3_SHARED_API int b3CreateCollisionShapeAddConcaveMesh(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices, const int* indices, int numIndices) +B3_SHARED_API int b3CreateCollisionShapeAddConcaveMesh(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[3], const double* vertices, int numVertices, const int* indices, int numIndices) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -1914,7 +1914,7 @@ B3_SHARED_API int b3CreateCollisionShapeAddConcaveMesh(b3PhysicsClientHandle phy return -1; } -B3_SHARED_API int b3CreateVisualShapeAddMesh2(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices, const int* indices, int numIndices, const double* normals, int numNormals, const double* uvs, int numUVs) +B3_SHARED_API int b3CreateVisualShapeAddMesh2(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[3], const double* vertices, int numVertices, const int* indices, int numIndices, const double* normals, int numNormals, const double* uvs, int numUVs) { if (numUVs == 0 && numNormals == 0) { @@ -1990,7 +1990,7 @@ B3_SHARED_API int b3CreateVisualShapeAddMesh2(b3PhysicsClientHandle physClient, } -B3_SHARED_API int b3CreateVisualShapeAddMesh(b3SharedMemoryCommandHandle commandHandle, const char* fileName, const double meshScale[/*3*/]) +B3_SHARED_API int b3CreateVisualShapeAddMesh(b3SharedMemoryCommandHandle commandHandle, const char* fileName, const double meshScale[3]) { return b3CreateCollisionShapeAddMesh(commandHandle, fileName, meshScale); } @@ -2034,12 +2034,12 @@ B3_SHARED_API void b3CreateCollisionShapeSetChildTransform(b3SharedMemoryCommand } } -B3_SHARED_API void b3CreateVisualShapeSetChildTransform(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double childPosition[/*3*/], const double childOrientation[/*4*/]) +B3_SHARED_API void b3CreateVisualShapeSetChildTransform(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double childPosition[3], const double childOrientation[4]) { b3CreateCollisionShapeSetChildTransform(commandHandle, shapeIndex, childPosition, childOrientation); } -B3_SHARED_API void b3CreateVisualShapeSetRGBAColor(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double rgbaColor[/*4*/]) +B3_SHARED_API void b3CreateVisualShapeSetRGBAColor(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double rgbaColor[4]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; b3Assert(command); @@ -2057,7 +2057,7 @@ B3_SHARED_API void b3CreateVisualShapeSetRGBAColor(b3SharedMemoryCommandHandle c } } -B3_SHARED_API void b3CreateVisualShapeSetSpecularColor(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double specularColor[/*3*/]) +B3_SHARED_API void b3CreateVisualShapeSetSpecularColor(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double specularColor[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; b3Assert(command); @@ -3651,7 +3651,7 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitChangeUserConstraintCommand(b3Ph return (b3SharedMemoryCommandHandle)command; } -B3_SHARED_API int b3InitChangeUserConstraintSetPivotInB(b3SharedMemoryCommandHandle commandHandle, const double jointChildPivot[]) +B3_SHARED_API int b3InitChangeUserConstraintSetPivotInB(b3SharedMemoryCommandHandle commandHandle, const double jointChildPivot[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; b3Assert(command); @@ -3666,7 +3666,7 @@ B3_SHARED_API int b3InitChangeUserConstraintSetPivotInB(b3SharedMemoryCommandHan command->m_userConstraintArguments.m_childFrame[2] = jointChildPivot[2]; return 0; } -B3_SHARED_API int b3InitChangeUserConstraintSetFrameInB(b3SharedMemoryCommandHandle commandHandle, const double jointChildFrameOrn[]) +B3_SHARED_API int b3InitChangeUserConstraintSetFrameInB(b3SharedMemoryCommandHandle commandHandle, const double jointChildFrameOrn[4]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; b3Assert(command); @@ -4968,7 +4968,7 @@ B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapeB(b3SharedMemoryComma command->m_requestContactPointArguments.m_collisionShapeB = collisionShapeB; } -B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapePositionA(b3SharedMemoryCommandHandle commandHandle, const double collisionShapePositionA[/*3*/]) +B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapePositionA(b3SharedMemoryCommandHandle commandHandle, const double collisionShapePositionA[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; b3Assert(command); @@ -4979,7 +4979,7 @@ B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapePositionA(b3SharedMem command->m_requestContactPointArguments.m_collisionShapePositionA[2] = collisionShapePositionA[2]; } -B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapePositionB(b3SharedMemoryCommandHandle commandHandle, const double collisionShapePositionB[/*3*/]) +B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapePositionB(b3SharedMemoryCommandHandle commandHandle, const double collisionShapePositionB[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; b3Assert(command); @@ -4990,7 +4990,7 @@ B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapePositionB(b3SharedMem command->m_requestContactPointArguments.m_collisionShapePositionB[2] = collisionShapePositionB[2]; } -B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapeOrientationA(b3SharedMemoryCommandHandle commandHandle, const double collisionShapeOrientationA[/*4*/]) +B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapeOrientationA(b3SharedMemoryCommandHandle commandHandle, const double collisionShapeOrientationA[4]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; b3Assert(command); @@ -5002,7 +5002,7 @@ B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapeOrientationA(b3Shared command->m_requestContactPointArguments.m_collisionShapeOrientationA[3] = collisionShapeOrientationA[3]; } -B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapeOrientationB(b3SharedMemoryCommandHandle commandHandle, const double collisionShapeOrientationB[/*4*/]) +B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapeOrientationB(b3SharedMemoryCommandHandle commandHandle, const double collisionShapeOrientationB[4]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; b3Assert(command); @@ -6374,7 +6374,7 @@ B3_SHARED_API void b3InvertTransform(const double pos[3], const double orn[4], d outOrn[3] = invOrn[3]; } -B3_SHARED_API void b3QuaternionSlerp(const double startQuat[/*4*/], const double endQuat[/*4*/], double interpolationFraction, double outOrn[/*4*/]) +B3_SHARED_API void b3QuaternionSlerp(const double startQuat[4], const double endQuat[4], double interpolationFraction, double outOrn[4]) { b3Quaternion start(startQuat[0], startQuat[1], startQuat[2], startQuat[3]); b3Quaternion end(endQuat[0], endQuat[1], endQuat[2], endQuat[3]); @@ -6385,7 +6385,7 @@ B3_SHARED_API void b3QuaternionSlerp(const double startQuat[/*4*/], const double outOrn[3] = result[3]; } -B3_SHARED_API void b3RotateVector(const double quat[/*4*/], const double vec[/*3*/], double vecOut[/*3*/]) +B3_SHARED_API void b3RotateVector(const double quat[4], const double vec[3], double vecOut[3]) { b3Quaternion q(quat[0], quat[1], quat[2], quat[3]); b3Vector3 v = b3MakeVector3(vec[0], vec[1], vec[2]); @@ -6395,7 +6395,7 @@ B3_SHARED_API void b3RotateVector(const double quat[/*4*/], const double vec[/*3 vecOut[2] = vout[2]; } -B3_SHARED_API void b3CalculateVelocityQuaternion(const double startQuat[/*4*/], const double endQuat[/*4*/], double deltaTime, double angVelOut[/*3*/]) +B3_SHARED_API void b3CalculateVelocityQuaternion(const double startQuat[4], const double endQuat[4], double deltaTime, double angVelOut[3]) { b3Quaternion start(startQuat[0], startQuat[1], startQuat[2], startQuat[3]); b3Quaternion end(endQuat[0], endQuat[1], endQuat[2], endQuat[3]); @@ -6407,7 +6407,7 @@ B3_SHARED_API void b3CalculateVelocityQuaternion(const double startQuat[/*4*/], angVelOut[2] = angVel[2]; } -B3_SHARED_API void b3GetQuaternionFromAxisAngle(const double axis[/*3*/], double angle, double outQuat[/*4*/]) +B3_SHARED_API void b3GetQuaternionFromAxisAngle(const double axis[3], double angle, double outQuat[4]) { b3Quaternion quat(b3MakeVector3(axis[0], axis[1], axis[2]), angle); outQuat[0] = quat[0]; @@ -6415,7 +6415,7 @@ B3_SHARED_API void b3GetQuaternionFromAxisAngle(const double axis[/*3*/], double outQuat[2] = quat[2]; outQuat[3] = quat[3]; } -B3_SHARED_API void b3GetAxisAngleFromQuaternion(const double quat[/*4*/], double axis[/*3*/], double* angle) +B3_SHARED_API void b3GetAxisAngleFromQuaternion(const double quat[4], double axis[3], double* angle) { b3Quaternion q(quat[0], quat[1], quat[2], quat[3]); b3Vector3 ax = q.getAxis(); @@ -6425,7 +6425,7 @@ B3_SHARED_API void b3GetAxisAngleFromQuaternion(const double quat[/*4*/], double *angle = q.getAngle(); } -B3_SHARED_API void b3GetQuaternionDifference(const double startQuat[/*4*/], const double endQuat[/*4*/], double outOrn[/*4*/]) +B3_SHARED_API void b3GetQuaternionDifference(const double startQuat[4], const double endQuat[4], double outOrn[4]) { b3Quaternion orn0(startQuat[0], startQuat[1], startQuat[2], startQuat[3]); b3Quaternion orn1a(endQuat[0], endQuat[1], endQuat[2], endQuat[3]); @@ -6481,7 +6481,7 @@ static bool MyMatrixToEulerXYZ(const b3Matrix3x3& mat, b3Vector3& xyz) } -B3_SHARED_API void b3GetAxisDifferenceQuaternion(const double startQuat[/*4*/], const double endQuat[/*4*/], double axisOut[/*3*/]) +B3_SHARED_API void b3GetAxisDifferenceQuaternion(const double startQuat[4], const double endQuat[4], double axisOut[3]) { b3Quaternion currentQuat(startQuat[0], startQuat[1], startQuat[2], startQuat[3]); b3Quaternion desiredQuat(endQuat[0], endQuat[1], endQuat[2], endQuat[3]); diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 5632729425..011de2bdaf 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -101,7 +101,7 @@ extern "C" const double* linkWorldVelocities[]); B3_SHARED_API b3SharedMemoryCommandHandle b3RequestCollisionInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId); - B3_SHARED_API int b3GetStatusAABB(b3SharedMemoryStatusHandle statusHandle, int linkIndex, double aabbMin[/*3*/], double aabbMax[/*3*/]); + B3_SHARED_API int b3GetStatusAABB(b3SharedMemoryStatusHandle statusHandle, int linkIndex, double aabbMin[3], double aabbMax[3]); ///If you re-connected to an existing server, or server changed otherwise, sync the body info and user constraints etc. B3_SHARED_API b3SharedMemoryCommandHandle b3InitSyncBodyInfoCommand(b3PhysicsClientHandle physClient); @@ -187,8 +187,8 @@ extern "C" ///change parameters of an existing user constraint B3_SHARED_API b3SharedMemoryCommandHandle b3InitChangeUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId); - B3_SHARED_API int b3InitChangeUserConstraintSetPivotInB(b3SharedMemoryCommandHandle commandHandle, const double jointChildPivot[/*3*/]); - B3_SHARED_API int b3InitChangeUserConstraintSetFrameInB(b3SharedMemoryCommandHandle commandHandle, const double jointChildFrameOrn[/*4*/]); + B3_SHARED_API int b3InitChangeUserConstraintSetPivotInB(b3SharedMemoryCommandHandle commandHandle, const double jointChildPivot[3]); + B3_SHARED_API int b3InitChangeUserConstraintSetFrameInB(b3SharedMemoryCommandHandle commandHandle, const double jointChildFrameOrn[4]); B3_SHARED_API int b3InitChangeUserConstraintSetMaxForce(b3SharedMemoryCommandHandle commandHandle, double maxAppliedForce); B3_SHARED_API int b3InitChangeUserConstraintSetGearRatio(b3SharedMemoryCommandHandle commandHandle, double gearRatio); B3_SHARED_API int b3InitChangeUserConstraintSetGearAuxLink(b3SharedMemoryCommandHandle commandHandle, int gearAuxLink); @@ -227,18 +227,18 @@ extern "C" B3_SHARED_API void b3ConfigureOpenGLVisualizerSetShadowMapWorldSize(b3SharedMemoryCommandHandle commandHandle, int shadowMapWorldSize); B3_SHARED_API void b3ConfigureOpenGLVisualizerSetRemoteSyncTransformInterval(b3SharedMemoryCommandHandle commandHandle, double remoteSyncTransformInterval); - B3_SHARED_API void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[/*3*/]); + B3_SHARED_API void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[3]); B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestOpenGLVisualizerCameraCommand(b3PhysicsClientHandle physClient); B3_SHARED_API int b3GetStatusOpenGLVisualizerCamera(b3SharedMemoryStatusHandle statusHandle, struct b3OpenGLVisualizerCameraInfo* camera); /// Add/remove user-specific debug lines and debug text messages - B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3PhysicsClientHandle physClient, const double fromXYZ[/*3*/], const double toXYZ[/*3*/], const double colorRGB[/*3*/], double lineWidth, double lifeTime); + B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3PhysicsClientHandle physClient, const double fromXYZ[3], const double toXYZ[3], const double colorRGB[3], double lineWidth, double lifeTime); B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddPoints3D(b3PhysicsClientHandle physClient, const double positionsXYZ[/*3n*/], const double colorsRGB[/*3*/], double pointSize, double lifeTime, int pointNum); - B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle physClient, const char* txt, const double positionXYZ[/*3*/], const double colorRGB[/*3*/], double textSize, double lifeTime); + B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle physClient, const char* txt, const double positionXYZ[3], const double colorRGB[3], double textSize, double lifeTime); B3_SHARED_API void b3UserDebugTextSetOptionFlags(b3SharedMemoryCommandHandle commandHandle, int optionFlags); - B3_SHARED_API void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle commandHandle, const double orientation[/*4*/]); + B3_SHARED_API void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle commandHandle, const double orientation[4]); B3_SHARED_API void b3UserDebugItemSetReplaceItemUniqueId(b3SharedMemoryCommandHandle commandHandle, int replaceItem); B3_SHARED_API void b3UserDebugItemSetParentObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex); @@ -252,7 +252,7 @@ extern "C" B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserRemoveAllParameters(b3PhysicsClientHandle physClient); B3_SHARED_API b3SharedMemoryCommandHandle b3InitDebugDrawingCommand(b3PhysicsClientHandle physClient); - B3_SHARED_API void b3SetDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex, const double objectColorRGB[/*3*/]); + B3_SHARED_API void b3SetDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex, const double objectColorRGB[3]); B3_SHARED_API void b3RemoveDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex); ///All debug items unique Ids are positive: a negative unique Id means failure. @@ -261,10 +261,10 @@ extern "C" ///request an image from a simulated camera, using a software renderer. B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient); B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestCameraImage2(b3SharedMemoryCommandHandle commandHandle); - B3_SHARED_API void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[/*16*/], float projectionMatrix[/*16*/]); + B3_SHARED_API void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[16], float projectionMatrix[16]); B3_SHARED_API void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle commandHandle, int width, int height); - B3_SHARED_API void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[/*3*/]); - B3_SHARED_API void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[/*3*/]); + B3_SHARED_API void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[3]); + B3_SHARED_API void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[3]); B3_SHARED_API void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHandle, float lightDistance); B3_SHARED_API void b3RequestCameraImageSetLightAmbientCoeff(b3SharedMemoryCommandHandle commandHandle, float lightAmbientCoeff); B3_SHARED_API void b3RequestCameraImageSetLightDiffuseCoeff(b3SharedMemoryCommandHandle commandHandle, float lightDiffuseCoeff); @@ -276,21 +276,21 @@ extern "C" B3_SHARED_API void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData); ///set projective texture camera matrices. - B3_SHARED_API void b3RequestCameraImageSetProjectiveTextureMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[/*16*/], float projectionMatrix[/*16*/]); + B3_SHARED_API void b3RequestCameraImageSetProjectiveTextureMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[16], float projectionMatrix[16]); ///compute a view matrix, helper function for b3RequestCameraImageSetCameraMatrices - B3_SHARED_API void b3ComputeViewMatrixFromPositions(const float cameraPosition[/*3*/], const float cameraTargetPosition[/*3*/], const float cameraUp[/*3*/], float viewMatrix[/*16*/]); - B3_SHARED_API void b3ComputeViewMatrixFromYawPitchRoll(const float cameraTargetPosition[/*3*/], float distance, float yaw, float pitch, float roll, int upAxis, float viewMatrix[/*16*/]); - B3_SHARED_API void b3ComputePositionFromViewMatrix(const float viewMatrix[/*16*/], float cameraPosition[/*3*/], float cameraTargetPosition[/*3*/], float cameraUp[/*3*/]); + B3_SHARED_API void b3ComputeViewMatrixFromPositions(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], float viewMatrix[16]); + B3_SHARED_API void b3ComputeViewMatrixFromYawPitchRoll(const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis, float viewMatrix[16]); + B3_SHARED_API void b3ComputePositionFromViewMatrix(const float viewMatrix[16], float cameraPosition[3], float cameraTargetPosition[3], float cameraUp[3]); ///compute a projection matrix, helper function for b3RequestCameraImageSetCameraMatrices - B3_SHARED_API void b3ComputeProjectionMatrix(float left, float right, float bottom, float top, float nearVal, float farVal, float projectionMatrix[/*16*/]); - B3_SHARED_API void b3ComputeProjectionMatrixFOV(float fov, float aspect, float nearVal, float farVal, float projectionMatrix[/*16*/]); + B3_SHARED_API void b3ComputeProjectionMatrix(float left, float right, float bottom, float top, float nearVal, float farVal, float projectionMatrix[16]); + B3_SHARED_API void b3ComputeProjectionMatrixFOV(float fov, float aspect, float nearVal, float farVal, float projectionMatrix[16]); /* obsolete, please use b3ComputeViewProjectionMatrices */ - B3_SHARED_API void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, const float cameraPosition[/*3*/], const float cameraTargetPosition[/*3*/], const float cameraUp[/*3*/]); + B3_SHARED_API void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3]); /* obsolete, please use b3ComputeViewProjectionMatrices */ - B3_SHARED_API void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[/*3*/], float distance, float yaw, float pitch, float roll, int upAxis); + B3_SHARED_API void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis); /* obsolete, please use b3ComputeViewProjectionMatrices */ B3_SHARED_API void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle commandHandle, float left, float right, float bottom, float top, float nearVal, float farVal); /* obsolete, please use b3ComputeViewProjectionMatrices */ @@ -314,15 +314,15 @@ extern "C" B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapeA(b3SharedMemoryCommandHandle commandHandle, int collisionShapeA); B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapeB(b3SharedMemoryCommandHandle commandHandle, int collisionShapeB); - B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapePositionA(b3SharedMemoryCommandHandle commandHandle, const double collisionShapePositionA[/*3*/]); - B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapePositionB(b3SharedMemoryCommandHandle commandHandle, const double collisionShapePositionB[/*3*/]); - B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapeOrientationA(b3SharedMemoryCommandHandle commandHandle, const double collisionShapeOrientationA[/*4*/]); - B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapeOrientationB(b3SharedMemoryCommandHandle commandHandle, const double collisionShapeOrientationB[/*4*/]); + B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapePositionA(b3SharedMemoryCommandHandle commandHandle, const double collisionShapePositionA[3]); + B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapePositionB(b3SharedMemoryCommandHandle commandHandle, const double collisionShapePositionB[3]); + B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapeOrientationA(b3SharedMemoryCommandHandle commandHandle, const double collisionShapeOrientationA[4]); + B3_SHARED_API void b3SetClosestDistanceFilterCollisionShapeOrientationB(b3SharedMemoryCommandHandle commandHandle, const double collisionShapeOrientationB[4]); B3_SHARED_API void b3GetClosestPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointInfo); ///get all the bodies that touch a given axis aligned bounding box specified in world space (min and max coordinates) - B3_SHARED_API b3SharedMemoryCommandHandle b3InitAABBOverlapQuery(b3PhysicsClientHandle physClient, const double aabbMin[/*3*/], const double aabbMax[/*3*/]); + B3_SHARED_API b3SharedMemoryCommandHandle b3InitAABBOverlapQuery(b3PhysicsClientHandle physClient, const double aabbMin[3], const double aabbMax[3]); B3_SHARED_API void b3GetAABBOverlapResults(b3PhysicsClientHandle physClient, struct b3AABBOverlapData* data); //request visual shape information @@ -340,10 +340,10 @@ extern "C" B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId); B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape2(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex); B3_SHARED_API void b3UpdateVisualShapeTexture(b3SharedMemoryCommandHandle commandHandle, int textureUniqueId); - B3_SHARED_API void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, const double rgbaColor[/*4*/]); + B3_SHARED_API void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, const double rgbaColor[4]); B3_SHARED_API void b3UpdateVisualShapeFlags(b3SharedMemoryCommandHandle commandHandle, int flags); - B3_SHARED_API void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle commandHandle, const double specularColor[/*3*/]); + B3_SHARED_API void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle commandHandle, const double specularColor[3]); B3_SHARED_API b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient); B3_SHARED_API b3SharedMemoryCommandHandle b3InitPhysicsParamCommand2(b3SharedMemoryCommandHandle commandHandle); @@ -450,11 +450,11 @@ extern "C" ///compute the joint positions to move the end effector to a desired target using inverse kinematics B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateInverseKinematicsCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId); - B3_SHARED_API void b3CalculateInverseKinematicsAddTargetPurePosition(b3SharedMemoryCommandHandle commandHandle, int endEffectorLinkIndex, const double targetPosition[/*3*/]); + B3_SHARED_API void b3CalculateInverseKinematicsAddTargetPurePosition(b3SharedMemoryCommandHandle commandHandle, int endEffectorLinkIndex, const double targetPosition[3]); B3_SHARED_API void b3CalculateInverseKinematicsAddTargetsPurePosition(b3SharedMemoryCommandHandle commandHandle, int numEndEffectorLinkIndices, const int* endEffectorIndices, const double* targetPositions); - B3_SHARED_API void b3CalculateInverseKinematicsAddTargetPositionWithOrientation(b3SharedMemoryCommandHandle commandHandle, int endEffectorLinkIndex, const double targetPosition[/*3*/], const double targetOrientation[/*4*/]); - B3_SHARED_API void b3CalculateInverseKinematicsPosWithNullSpaceVel(b3SharedMemoryCommandHandle commandHandle, int numDof, int endEffectorLinkIndex, const double targetPosition[/*3*/], const double* lowerLimit, const double* upperLimit, const double* jointRange, const double* restPose); - B3_SHARED_API void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(b3SharedMemoryCommandHandle commandHandle, int numDof, int endEffectorLinkIndex, const double targetPosition[/*3*/], const double targetOrientation[/*4*/], const double* lowerLimit, const double* upperLimit, const double* jointRange, const double* restPose); + B3_SHARED_API void b3CalculateInverseKinematicsAddTargetPositionWithOrientation(b3SharedMemoryCommandHandle commandHandle, int endEffectorLinkIndex, const double targetPosition[3], const double targetOrientation[4]); + B3_SHARED_API void b3CalculateInverseKinematicsPosWithNullSpaceVel(b3SharedMemoryCommandHandle commandHandle, int numDof, int endEffectorLinkIndex, const double targetPosition[3], const double* lowerLimit, const double* upperLimit, const double* jointRange, const double* restPose); + B3_SHARED_API void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(b3SharedMemoryCommandHandle commandHandle, int numDof, int endEffectorLinkIndex, const double targetPosition[3], const double targetOrientation[4], const double* lowerLimit, const double* upperLimit, const double* jointRange, const double* restPose); B3_SHARED_API void b3CalculateInverseKinematicsSetJointDamping(b3SharedMemoryCommandHandle commandHandle, int numDof, const double* jointDampingCoeff); B3_SHARED_API void b3CalculateInverseKinematicsSelectSolver(b3SharedMemoryCommandHandle commandHandle, int solver); B3_SHARED_API int b3GetStatusInverseKinematicsJointPositions(b3SharedMemoryStatusHandle statusHandle, @@ -516,18 +516,18 @@ extern "C" B3_SHARED_API b3SharedMemoryCommandHandle b3CreateCollisionShapeCommandInit(b3PhysicsClientHandle physClient); B3_SHARED_API int b3CreateCollisionShapeAddSphere(b3SharedMemoryCommandHandle commandHandle, double radius); - B3_SHARED_API int b3CreateCollisionShapeAddBox(b3SharedMemoryCommandHandle commandHandle, const double halfExtents[/*3*/]); + B3_SHARED_API int b3CreateCollisionShapeAddBox(b3SharedMemoryCommandHandle commandHandle, const double halfExtents[3]); B3_SHARED_API int b3CreateCollisionShapeAddCapsule(b3SharedMemoryCommandHandle commandHandle, double radius, double height); B3_SHARED_API int b3CreateCollisionShapeAddCylinder(b3SharedMemoryCommandHandle commandHandle, double radius, double height); - B3_SHARED_API int b3CreateCollisionShapeAddHeightfield(b3SharedMemoryCommandHandle commandHandle, const char* fileName, const double meshScale[/*3*/], double textureScaling); - B3_SHARED_API int b3CreateCollisionShapeAddHeightfield2(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], double textureScaling, float* heightfieldData, int numHeightfieldRows, int numHeightfieldColumns, int replaceHeightfieldIndex); + B3_SHARED_API int b3CreateCollisionShapeAddHeightfield(b3SharedMemoryCommandHandle commandHandle, const char* fileName, const double meshScale[3], double textureScaling); + B3_SHARED_API int b3CreateCollisionShapeAddHeightfield2(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[3], double textureScaling, float* heightfieldData, int numHeightfieldRows, int numHeightfieldColumns, int replaceHeightfieldIndex); - B3_SHARED_API int b3CreateCollisionShapeAddPlane(b3SharedMemoryCommandHandle commandHandle, const double planeNormal[/*3*/], double planeConstant); - B3_SHARED_API int b3CreateCollisionShapeAddMesh(b3SharedMemoryCommandHandle commandHandle, const char* fileName, const double meshScale[/*3*/]); - B3_SHARED_API int b3CreateCollisionShapeAddConvexMesh(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices); - B3_SHARED_API int b3CreateCollisionShapeAddConcaveMesh(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices, const int* indices, int numIndices); + B3_SHARED_API int b3CreateCollisionShapeAddPlane(b3SharedMemoryCommandHandle commandHandle, const double planeNormal[3], double planeConstant); + B3_SHARED_API int b3CreateCollisionShapeAddMesh(b3SharedMemoryCommandHandle commandHandle, const char* fileName, const double meshScale[3]); + B3_SHARED_API int b3CreateCollisionShapeAddConvexMesh(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[3], const double* vertices, int numVertices); + B3_SHARED_API int b3CreateCollisionShapeAddConcaveMesh(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[3], const double* vertices, int numVertices, const int* indices, int numIndices); B3_SHARED_API void b3CreateCollisionSetFlag(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, int flags); - B3_SHARED_API void b3CreateCollisionShapeSetChildTransform(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double childPosition[/*3*/], const double childOrientation[/*4*/]); + B3_SHARED_API void b3CreateCollisionShapeSetChildTransform(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double childPosition[3], const double childOrientation[4]); B3_SHARED_API int b3GetStatusCollisionShapeUniqueId(b3SharedMemoryStatusHandle statusHandle); B3_SHARED_API b3SharedMemoryCommandHandle b3InitRemoveCollisionShapeCommand(b3PhysicsClientHandle physClient, int collisionShapeId); @@ -547,33 +547,33 @@ extern "C" B3_SHARED_API b3SharedMemoryCommandHandle b3CreateVisualShapeCommandInit(b3PhysicsClientHandle physClient); B3_SHARED_API int b3CreateVisualShapeAddSphere(b3SharedMemoryCommandHandle commandHandle, double radius); - B3_SHARED_API int b3CreateVisualShapeAddBox(b3SharedMemoryCommandHandle commandHandle, const double halfExtents[/*3*/]); + B3_SHARED_API int b3CreateVisualShapeAddBox(b3SharedMemoryCommandHandle commandHandle, const double halfExtents[3]); B3_SHARED_API int b3CreateVisualShapeAddCapsule(b3SharedMemoryCommandHandle commandHandle, double radius, double height); B3_SHARED_API int b3CreateVisualShapeAddCylinder(b3SharedMemoryCommandHandle commandHandle, double radius, double height); - B3_SHARED_API int b3CreateVisualShapeAddPlane(b3SharedMemoryCommandHandle commandHandle, const double planeNormal[/*3*/], double planeConstant); - B3_SHARED_API int b3CreateVisualShapeAddMesh(b3SharedMemoryCommandHandle commandHandle, const char* fileName, const double meshScale[/*3*/]); - B3_SHARED_API int b3CreateVisualShapeAddMesh2(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[/*3*/], const double* vertices, int numVertices, const int* indices, int numIndices, const double* normals, int numNormals, const double* uvs, int numUVs); + B3_SHARED_API int b3CreateVisualShapeAddPlane(b3SharedMemoryCommandHandle commandHandle, const double planeNormal[3], double planeConstant); + B3_SHARED_API int b3CreateVisualShapeAddMesh(b3SharedMemoryCommandHandle commandHandle, const char* fileName, const double meshScale[3]); + B3_SHARED_API int b3CreateVisualShapeAddMesh2(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double meshScale[3], const double* vertices, int numVertices, const int* indices, int numIndices, const double* normals, int numNormals, const double* uvs, int numUVs); B3_SHARED_API void b3CreateVisualSetFlag(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, int flags); - B3_SHARED_API void b3CreateVisualShapeSetChildTransform(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double childPosition[/*3*/], const double childOrientation[/*4*/]); - B3_SHARED_API void b3CreateVisualShapeSetSpecularColor(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double specularColor[/*3*/]); - B3_SHARED_API void b3CreateVisualShapeSetRGBAColor(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double rgbaColor[/*4*/]); + B3_SHARED_API void b3CreateVisualShapeSetChildTransform(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double childPosition[3], const double childOrientation[4]); + B3_SHARED_API void b3CreateVisualShapeSetSpecularColor(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double specularColor[3]); + B3_SHARED_API void b3CreateVisualShapeSetRGBAColor(b3SharedMemoryCommandHandle commandHandle, int shapeIndex, const double rgbaColor[4]); B3_SHARED_API int b3GetStatusVisualShapeUniqueId(b3SharedMemoryStatusHandle statusHandle); B3_SHARED_API b3SharedMemoryCommandHandle b3CreateMultiBodyCommandInit(b3PhysicsClientHandle physClient); - B3_SHARED_API int b3CreateMultiBodyBase(b3SharedMemoryCommandHandle commandHandle, double mass, int collisionShapeUnique, int visualShapeUniqueId, const double basePosition[/*3*/], const double baseOrientation[/*4*/], const double baseInertialFramePosition[/*3*/], const double baseInertialFrameOrientation[/*4*/]); + B3_SHARED_API int b3CreateMultiBodyBase(b3SharedMemoryCommandHandle commandHandle, double mass, int collisionShapeUnique, int visualShapeUniqueId, const double basePosition[3], const double baseOrientation[4], const double baseInertialFramePosition[3], const double baseInertialFrameOrientation[4]); B3_SHARED_API int b3CreateMultiBodyLink(b3SharedMemoryCommandHandle commandHandle, double linkMass, double linkCollisionShapeIndex, double linkVisualShapeIndex, - const double linkPosition[/*3*/], - const double linkOrientation[/*4*/], - const double linkInertialFramePosition[/*3*/], - const double linkInertialFrameOrientation[/*4*/], + const double linkPosition[3], + const double linkOrientation[4], + const double linkInertialFramePosition[3], + const double linkInertialFrameOrientation[4], int linkParentIndex, int linkJointType, - const double linkJointAxis[/*3*/]); + const double linkJointAxis[3]); //batch creation is an performance feature to create a large number of multi bodies in one command B3_SHARED_API int b3CreateMultiBodySetBatchPositions(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, double* batchPositions, int numBatchObjects); @@ -602,9 +602,9 @@ extern "C" B3_SHARED_API int b3CreatePoseCommandSetBasePosition(b3SharedMemoryCommandHandle commandHandle, double startPosX, double startPosY, double startPosZ); B3_SHARED_API int b3CreatePoseCommandSetBaseOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW); - B3_SHARED_API int b3CreatePoseCommandSetBaseLinearVelocity(b3SharedMemoryCommandHandle commandHandle, const double linVel[/*3*/]); - B3_SHARED_API int b3CreatePoseCommandSetBaseAngularVelocity(b3SharedMemoryCommandHandle commandHandle, const double angVel[/*3*/]); - B3_SHARED_API int b3CreatePoseCommandSetBaseScaling(b3SharedMemoryCommandHandle commandHandle, double scaling[/* 3*/]); + B3_SHARED_API int b3CreatePoseCommandSetBaseLinearVelocity(b3SharedMemoryCommandHandle commandHandle, const double linVel[3]); + B3_SHARED_API int b3CreatePoseCommandSetBaseAngularVelocity(b3SharedMemoryCommandHandle commandHandle, const double angVel[3]); + B3_SHARED_API int b3CreatePoseCommandSetBaseScaling(b3SharedMemoryCommandHandle commandHandle, double scaling[3]); B3_SHARED_API int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHandle, int numJointPositions, const double* jointPositions); @@ -653,7 +653,7 @@ extern "C" // Sets the number of threads to use to compute the ray intersections for the batch. Specify 0 to let Bullet decide, 1 (default) for single core execution, 2 or more to select the number of threads to use. B3_SHARED_API void b3RaycastBatchSetNumThreads(b3SharedMemoryCommandHandle commandHandle, int numThreads); //max num rays for b3RaycastBatchAddRay is MAX_RAY_INTERSECTION_BATCH_SIZE - B3_SHARED_API void b3RaycastBatchAddRay(b3SharedMemoryCommandHandle commandHandle, const double rayFromWorld[/*3*/], const double rayToWorld[/*3*/]); + B3_SHARED_API void b3RaycastBatchAddRay(b3SharedMemoryCommandHandle commandHandle, const double rayFromWorld[3], const double rayToWorld[3]); //max num rays for b3RaycastBatchAddRays is MAX_RAY_INTERSECTION_BATCH_SIZE_STREAMING B3_SHARED_API void b3RaycastBatchAddRays(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, const double* rayFromWorld, const double* rayToWorld, int numRays); B3_SHARED_API void b3RaycastBatchSetParentObject(b3SharedMemoryCommandHandle commandHandle, int parentObjectUniqueId, int parentLinkIndex); @@ -665,8 +665,8 @@ extern "C" /// Apply external force at the body (or link) center of mass, in world space/Cartesian coordinates. B3_SHARED_API b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandle physClient); - B3_SHARED_API void b3ApplyExternalForce(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double force[/*3*/], const double position[/*3*/], int flag); - B3_SHARED_API void b3ApplyExternalTorque(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double torque[/*3*/], int flag); + B3_SHARED_API void b3ApplyExternalForce(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double force[3], const double position[3], int flag); + B3_SHARED_API void b3ApplyExternalTorque(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double torque[3], int flag); ///experiments of robots interacting with non-rigid objects (such as btSoftBody) B3_SHARED_API b3SharedMemoryCommandHandle b3LoadSoftBodyCommandInit(b3PhysicsClientHandle physClient, const char* fileName); @@ -697,8 +697,8 @@ extern "C" B3_SHARED_API void b3GetVREventsData(b3PhysicsClientHandle physClient, struct b3VREventsData* vrEventsData); B3_SHARED_API b3SharedMemoryCommandHandle b3SetVRCameraStateCommandInit(b3PhysicsClientHandle physClient); - B3_SHARED_API int b3SetVRCameraRootPosition(b3SharedMemoryCommandHandle commandHandle, const double rootPos[/*3*/]); - B3_SHARED_API int b3SetVRCameraRootOrientation(b3SharedMemoryCommandHandle commandHandle, const double rootOrn[/*4*/]); + B3_SHARED_API int b3SetVRCameraRootPosition(b3SharedMemoryCommandHandle commandHandle, const double rootPos[3]); + B3_SHARED_API int b3SetVRCameraRootOrientation(b3SharedMemoryCommandHandle commandHandle, const double rootOrn[4]); B3_SHARED_API int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId); B3_SHARED_API int b3SetVRCameraTrackingObjectFlag(b3SharedMemoryCommandHandle commandHandle, int flag); @@ -735,15 +735,15 @@ extern "C" B3_SHARED_API b3SharedMemoryCommandHandle b3SetAdditionalSearchPath(b3PhysicsClientHandle physClient, const char* path); - B3_SHARED_API void b3MultiplyTransforms(const double posA[/*3*/], const double ornA[/*4*/], const double posB[/*3*/], const double ornB[/*4*/], double outPos[/*3*/], double outOrn[/*4*/]); - B3_SHARED_API void b3InvertTransform(const double pos[/*3*/], const double orn[/*4*/], double outPos[/*3*/], double outOrn[/*4*/]); - B3_SHARED_API void b3QuaternionSlerp(const double startQuat[/*4*/], const double endQuat[/*4*/], double interpolationFraction, double outOrn[/*4*/]); - B3_SHARED_API void b3GetQuaternionFromAxisAngle(const double axis[/*3*/], double angle, double outQuat[/*4*/]); - B3_SHARED_API void b3GetAxisAngleFromQuaternion(const double quat[/*4*/], double axis[/*3*/], double* angle); - B3_SHARED_API void b3GetQuaternionDifference(const double startQuat[/*4*/], const double endQuat[/*4*/], double outOrn[/*4*/]); - B3_SHARED_API void b3GetAxisDifferenceQuaternion(const double startQuat[/*4*/], const double endQuat[/*4*/], double axisOut[/*3*/]); - B3_SHARED_API void b3CalculateVelocityQuaternion(const double startQuat[/*4*/], const double endQuat[/*4*/], double deltaTime, double angVelOut[/*3*/]); - B3_SHARED_API void b3RotateVector(const double quat[/*4*/], const double vec[/*3*/], double vecOut[/*3*/]); + B3_SHARED_API void b3MultiplyTransforms(const double posA[3], const double ornA[4], const double posB[3], const double ornB[4], double outPos[3], double outOrn[4]); + B3_SHARED_API void b3InvertTransform(const double pos[3], const double orn[4], double outPos[3], double outOrn[4]); + B3_SHARED_API void b3QuaternionSlerp(const double startQuat[4], const double endQuat[4], double interpolationFraction, double outOrn[4]); + B3_SHARED_API void b3GetQuaternionFromAxisAngle(const double axis[3], double angle, double outQuat[4]); + B3_SHARED_API void b3GetAxisAngleFromQuaternion(const double quat[4], double axis[3], double* angle); + B3_SHARED_API void b3GetQuaternionDifference(const double startQuat[4], const double endQuat[4], double outOrn[4]); + B3_SHARED_API void b3GetAxisDifferenceQuaternion(const double startQuat[4], const double endQuat[4], double axisOut[3]); + B3_SHARED_API void b3CalculateVelocityQuaternion(const double startQuat[4], const double endQuat[4], double deltaTime, double angVelOut[3]); + B3_SHARED_API void b3RotateVector(const double quat[4], const double vec[3], double vecOut[3]); #ifdef BT_ENABLE_VHACD B3_SHARED_API void b3VHACD(const char* fileNameInput, const char* fileNameOutput, const char* fileNameLogging, From b2cde58106bb52c062652a0f4ce39cdaf4ea2c22 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 16:02:53 +0100 Subject: [PATCH 30/57] Compiler warnings - documentation --- src/LinearMath/btMatrix3x3.h | 6 +++--- src/LinearMath/btQuadWord.h | 28 ++++++++++++++-------------- src/LinearMath/btQuaternion.h | 18 +++++++++--------- src/LinearMath/btVector3.h | 18 +++++++++--------- 4 files changed, 35 insertions(+), 35 deletions(-) diff --git a/src/LinearMath/btMatrix3x3.h b/src/LinearMath/btMatrix3x3.h index 4391a52cd8..d43d51ca2f 100644 --- a/src/LinearMath/btMatrix3x3.h +++ b/src/LinearMath/btMatrix3x3.h @@ -708,7 +708,7 @@ btMatrix3x3 * @param rot stores the rotation from the coordinate system in which the matrix is diagonal to the original * coordinate system, i.e., old_this = rot * new_this * rot^T. * @param threshold See iteration - * @param iteration The iteration stops when all off-diagonal elements are less than the threshold multiplied + * @param maxSteps The iteration stops when all off-diagonal elements are less than the threshold multiplied * by the sum of the absolute values of the diagonal, or when maxSteps have been executed. * * Note that this matrix is assumed to be symmetric. @@ -794,8 +794,8 @@ btMatrix3x3 /**@brief Calculate the matrix cofactor * @param r1 The first row to use for calculating the cofactor * @param c1 The first column to use for calculating the cofactor - * @param r1 The second row to use for calculating the cofactor - * @param c1 The second column to use for calculating the cofactor + * @param r2 The second row to use for calculating the cofactor + * @param c2 The second column to use for calculating the cofactor * See http://en.wikipedia.org/wiki/Cofactor_(linear_algebra) for more details */ btScalar cofac(int r1, int c1, int r2, int c2) const diff --git a/src/LinearMath/btQuadWord.h b/src/LinearMath/btQuadWord.h index 851596b178..682a13c344 100644 --- a/src/LinearMath/btQuadWord.h +++ b/src/LinearMath/btQuadWord.h @@ -142,9 +142,9 @@ class btQuadWord } /**@brief Set x,y,z and zero w - * @param x Value of x - * @param y Value of y - * @param z Value of z + * @param _x Value of x + * @param _y Value of y + * @param _z Value of z */ SIMD_FORCE_INLINE void setValue(const btScalar& _x, const btScalar& _y, const btScalar& _z) { @@ -162,10 +162,10 @@ class btQuadWord } */ /**@brief Set the values - * @param x Value of x - * @param y Value of y - * @param z Value of z - * @param w Value of w + * @param _x Value of x + * @param _y Value of y + * @param _z Value of z + * @param _w Value of w */ SIMD_FORCE_INLINE void setValue(const btScalar& _x, const btScalar& _y, const btScalar& _z, const btScalar& _w) { @@ -181,9 +181,9 @@ class btQuadWord } /**@brief Three argument constructor (zeros w) - * @param x Value of x - * @param y Value of y - * @param z Value of z + * @param _x Value of x + * @param _y Value of y + * @param _z Value of z */ SIMD_FORCE_INLINE btQuadWord(const btScalar& _x, const btScalar& _y, const btScalar& _z) { @@ -191,10 +191,10 @@ class btQuadWord } /**@brief Initializing constructor - * @param x Value of x - * @param y Value of y - * @param z Value of z - * @param w Value of w + * @param _x Value of x + * @param _y Value of y + * @param _z Value of z + * @param _w Value of w */ SIMD_FORCE_INLINE btQuadWord(const btScalar& _x, const btScalar& _y, const btScalar& _z, const btScalar& _w) { diff --git a/src/LinearMath/btQuaternion.h b/src/LinearMath/btQuaternion.h index 9f891062fb..3a8187e63a 100644 --- a/src/LinearMath/btQuaternion.h +++ b/src/LinearMath/btQuaternion.h @@ -84,8 +84,8 @@ class btQuaternion : public btQuadWord { } /**@brief Axis angle Constructor - * @param axis The axis which the rotation is around - * @param angle The magnitude of the rotation around the angle (Radians) */ + * @param _axis The axis which the rotation is around + * @param _angle The magnitude of the rotation around the angle (Radians) */ btQuaternion(const btVector3& _axis, const btScalar& _angle) { setRotation(_axis, _angle); @@ -104,7 +104,7 @@ class btQuaternion : public btQuadWord } /**@brief Set the rotation using axis angle notation * @param axis The axis around which to rotate - * @param angle The magnitude of the rotation in Radians */ + * @param _angle The magnitude of the rotation in Radians */ void setRotation(const btVector3& axis, const btScalar& _angle) { btScalar d = axis.length(); @@ -134,9 +134,9 @@ class btQuaternion : public btQuadWord cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw); } /**@brief Set the quaternion using euler angles - * @param yaw Angle around Z - * @param pitch Angle around Y - * @param roll Angle around X */ + * @param yawZ Angle around Z + * @param pitchY Angle around Y + * @param rollX Angle around X */ void setEulerZYX(const btScalar& yawZ, const btScalar& pitchY, const btScalar& rollX) { btScalar halfYaw = btScalar(yawZ) * btScalar(0.5); @@ -155,9 +155,9 @@ class btQuaternion : public btQuadWord } /**@brief Get the euler angles from this quaternion - * @param yaw Angle around Z - * @param pitch Angle around Y - * @param roll Angle around X */ + * @param yawZ Angle around Z + * @param pitchY Angle around Y + * @param rollX Angle around X */ void getEulerZYX(btScalar& yawZ, btScalar& pitchY, btScalar& rollX) const { btScalar squ; diff --git a/src/LinearMath/btVector3.h b/src/LinearMath/btVector3.h index 9da162772c..942f1a063e 100644 --- a/src/LinearMath/btVector3.h +++ b/src/LinearMath/btVector3.h @@ -119,9 +119,9 @@ btVector3 } /**@brief Constructor from scalars - * @param x X value - * @param y Y value - * @param z Z value + * @param _x X value + * @param _y Y value + * @param _z Z value */ SIMD_FORCE_INLINE btVector3(const btScalar& _x, const btScalar& _y, const btScalar& _z) { @@ -155,7 +155,7 @@ btVector3 #endif // #if defined (BT_USE_SSE_IN_API) || defined (BT_USE_NEON) /**@brief Add a vector to this one - * @param The vector to add to this one */ + * @param v The vector to add to this one */ SIMD_FORCE_INLINE btVector3& operator+=(const btVector3& v) { #if defined(BT_USE_SSE_IN_API) && defined(BT_USE_SSE) @@ -171,7 +171,7 @@ btVector3 } /**@brief Subtract a vector from this one - * @param The vector to subtract */ + * @param v The vector to subtract */ SIMD_FORCE_INLINE btVector3& operator-=(const btVector3& v) { #if defined(BT_USE_SSE_IN_API) && defined(BT_USE_SSE) @@ -1190,10 +1190,10 @@ class btVector4 : public btVector3 } */ /**@brief Set the values - * @param x Value of x - * @param y Value of y - * @param z Value of z - * @param w Value of w + * @param _x Value of x + * @param _y Value of y + * @param _z Value of z + * @param _w Value of w */ SIMD_FORCE_INLINE void setValue(const btScalar& _x, const btScalar& _y, const btScalar& _z, const btScalar& _w) { From 26f1a1c72a42ddb667948f2e9deb7510364ff83f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 15:22:17 +0100 Subject: [PATCH 31/57] Compiler warnings - multiline comment --- examples/OpenGLWindow/GLInstancingRenderer.cpp | 4 ++-- examples/ThirdPartyLibs/stb_image/stb_truetype.h | 2 +- src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp | 2 +- src/Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.cpp | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/OpenGLWindow/GLInstancingRenderer.cpp b/examples/OpenGLWindow/GLInstancingRenderer.cpp index 910e3d73f1..919de88a23 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.cpp +++ b/examples/OpenGLWindow/GLInstancingRenderer.cpp @@ -2217,8 +2217,8 @@ void GLInstancingRenderer::renderSceneInternal(int orgRenderMode) #ifdef OLD_SHADOWMAP_INIT glTexImage2D(GL_TEXTURE_2D, 0, GL_DEPTH_COMPONENT16, shadowMapWidth, shadowMapHeight, 0, GL_DEPTH_COMPONENT, GL_FLOAT, 0); -#else //OLD_SHADOWMAP_INIT \ - //Reduce size of shadowMap if glTexImage2D call fails as may happen in some cases \ +#else //OLD_SHADOWMAP_INIT + //Reduce size of shadowMap if glTexImage2D call fails as may happen in some cases //https://github.com/bulletphysics/bullet3/issues/40 int size; diff --git a/examples/ThirdPartyLibs/stb_image/stb_truetype.h b/examples/ThirdPartyLibs/stb_image/stb_truetype.h index 22fe6e45dd..1510d4b589 100644 --- a/examples/ThirdPartyLibs/stb_image/stb_truetype.h +++ b/examples/ThirdPartyLibs/stb_image/stb_truetype.h @@ -707,7 +707,7 @@ extern "C" }; #endif -#ifndef stbtt_vertex // you can predefine this to use different values \ +#ifndef stbtt_vertex // you can predefine this to use different values // (we share this with other code at RAD) #define stbtt_vertex_type short // can't use stbtt_int16 because that's not visible in the header file typedef struct diff --git a/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp b/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp index c9613ef012..90ab7f33e0 100644 --- a/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp +++ b/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp @@ -100,7 +100,7 @@ int b3OpenCLUtils_clewInit() const char* cl = "OpenCL.dll"; #elif defined __APPLE__ const char* cl = "/System/Library/Frameworks/OpenCL.framework/Versions/Current/OpenCL"; -#else //presumable Linux? \ +#else //presumable Linux? //linux (tested on Ubuntu 12.10 with Catalyst 13.4 beta drivers, not that there is no symbolic link from libOpenCL.so const char* cl = "libOpenCL.so.1"; result = clewInit(cl); diff --git a/src/Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.cpp b/src/Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.cpp index a13d91d64f..187e1eff7f 100644 --- a/src/Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.cpp +++ b/src/Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.cpp @@ -123,7 +123,7 @@ void b3RadixSort32CL::executeHost(b3AlignedObjectArray& inout, int s printf("tables[%d]=%d]\n", i, tables[i]); } } -#endif //TEST \ +#endif //TEST // prefix scan int sum = 0; for (int i = 0; i < NUM_TABLES; i++) From c2d61b28dbca675f26b00dd20aca82bdee1373ec Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 18:26:07 +0100 Subject: [PATCH 32/57] Compiler warnings - invalid utf8 --- .../GIMPACTUtils/btGImpactConvexDecompositionShape.h | 2 +- Extras/VHACD/src/vhacdVolume.cpp | 2 +- examples/OpenGLWindow/TwFonts.h | 11 +++++++++-- src/BulletCollision/Gimpact/btGImpactShape.h | 2 +- 4 files changed, 12 insertions(+), 5 deletions(-) diff --git a/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.h b/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.h index 47a327065c..4adddf3dc3 100644 --- a/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.h +++ b/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.h @@ -1,5 +1,5 @@ /*! \file btGImpactConvexDecompositionShape.h -\author Francisco León Nájera +\author Francisco León Nájera */ /* This source file is part of GIMPACT Library. diff --git a/Extras/VHACD/src/vhacdVolume.cpp b/Extras/VHACD/src/vhacdVolume.cpp index 8f45440710..063b5fdfef 100644 --- a/Extras/VHACD/src/vhacdVolume.cpp +++ b/Extras/VHACD/src/vhacdVolume.cpp @@ -27,7 +27,7 @@ namespace VHACD { /********************************************************/ /* AABB-triangle overlap test code */ -/* by Tomas Akenine-Möller */ +/* by Tomas Akenine-Möller */ /* Function: int triBoxOverlap(float boxcenter[3], */ /* float boxhalfsize[3],float triverts[3][3]); */ /* History: */ diff --git a/examples/OpenGLWindow/TwFonts.h b/examples/OpenGLWindow/TwFonts.h index 6980ae4bdb..d7eac3b3e9 100644 --- a/examples/OpenGLWindow/TwFonts.h +++ b/examples/OpenGLWindow/TwFonts.h @@ -12,7 +12,10 @@ #if !defined ANT_TW_FONTS_INCLUDED #define ANT_TW_FONTS_INCLUDED - +#if defined(__clang__) && __clang_major__ > 16 +#pragma clang diagnostic push +#pragma clang diagnostic ignored "-Winvalid-utf8" +#endif //#include /* @@ -21,7 +24,7 @@ A source bitmap includes 224 characters starting from ascii char 32 (i.e. space) !"#$%&'()*+,-./0123456789:;<=>? @ABCDEFGHIJKLMNOPQRSTUVWXYZ[\]^_ `abcdefghijklmnopqrstuvwxyz{|}~ -€‚ƒ„…†‡ˆ‰Š‹ŒŽ‘’“”•–—˜™š›œžŸ +€‚ƒ„…†‡ˆ‰Š‹ŒŽ‘’“”•–—˜™š›œžŸ  ¡¢£¤¥¦§¨©ª«¬­®¯°±²³´µ¶·¸¹º»¼½¾¿ ÀÁÂÃÄÅÆÇÈÉÊËÌÍÎÏÐÑÒÓÔÕÖ×ØÙÚÛÜÝÞß àáâãäåæçèéêëìíîïðñòóôõö÷øùúûüýþÿ @@ -59,4 +62,8 @@ extern CTexFont *g_DefaultFixed1Font; void TwGenerateDefaultFonts(); void TwDeleteDefaultFonts(); +#if defined(__clang__) && __clang_major__ > 16 +#pragma clang diagnostic pop +#endif + #endif // !defined ANT_TW_FONTS_INCLUDED diff --git a/src/BulletCollision/Gimpact/btGImpactShape.h b/src/BulletCollision/Gimpact/btGImpactShape.h index cc91079579..db5b1f3507 100644 --- a/src/BulletCollision/Gimpact/btGImpactShape.h +++ b/src/BulletCollision/Gimpact/btGImpactShape.h @@ -1,5 +1,5 @@ /*! \file btGImpactShape.h -\author Francisco Len Nßjera +\author Francisco León Nájera */ /* This source file is part of GIMPACT Library. From 444cecea32a84ff0e675473f2a6b5cab25af5043 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 16:07:12 +0100 Subject: [PATCH 33/57] Compiler warnings - format --- src/LinearMath/btQuadWord.h | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/src/LinearMath/btQuadWord.h b/src/LinearMath/btQuadWord.h index 682a13c344..73be64e045 100644 --- a/src/LinearMath/btQuadWord.h +++ b/src/LinearMath/btQuadWord.h @@ -187,7 +187,10 @@ class btQuadWord */ SIMD_FORCE_INLINE btQuadWord(const btScalar& _x, const btScalar& _y, const btScalar& _z) { - m_floats[0] = _x, m_floats[1] = _y, m_floats[2] = _z, m_floats[3] = 0.0f; + m_floats[0] = _x; + m_floats[1] = _y; + m_floats[2] = _z; + m_floats[3] = 0.0f; } /**@brief Initializing constructor @@ -198,7 +201,10 @@ class btQuadWord */ SIMD_FORCE_INLINE btQuadWord(const btScalar& _x, const btScalar& _y, const btScalar& _z, const btScalar& _w) { - m_floats[0] = _x, m_floats[1] = _y, m_floats[2] = _z, m_floats[3] = _w; + m_floats[0] = _x; + m_floats[1] = _y; + m_floats[2] = _z; + m_floats[3] = _w; } /**@brief Set each element to the max of the current values and the values of another btQuadWord From 2370237cc0d81b0964bff0333d6cb65b67de94a5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 17:18:58 +0100 Subject: [PATCH 34/57] Compiler warnings - format-overflow --- .../PhysicsClientSharedMemory.cpp | 21 +++++++++++-------- 1 file changed, 12 insertions(+), 9 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.cpp b/examples/SharedMemory/PhysicsClientSharedMemory.cpp index 23a7bafaec..1c60d12cef 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsClientSharedMemory.cpp @@ -887,43 +887,47 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() int numU = command.m_sendActualStateArgs.m_numDegreeOfFreedomU; b3Printf("size Q = %d, size U = %d\n", numQ, numU); char msg[1024]; + #define customMin(a,b) (a < b ? a : b) + #define currPos(buf) (buf + customMin(1000,strlen(buf))) { - sprintf(msg, "Q=["); + snprintf(msg,1024, "Q=["); for (int i = 0; i < numQ; i++) { if (i < numQ - 1) { - sprintf(msg, "%s%f,", msg, + snprintf(currPos(msg),1024, "%f,", m_data->m_cachedState.m_actualStateQ[i]); } else { - sprintf(msg, "%s%f", msg, + snprintf(currPos(msg),1024, "%f", m_data->m_cachedState.m_actualStateQ[i]); } } - sprintf(msg, "%s]", msg); + snprintf(currPos(msg),1024, "]"); } b3Printf(msg); - sprintf(msg, "U=["); + snprintf(currPos(msg),1024, "U=["); for (int i = 0; i < numU; i++) { if (i < numU - 1) { - sprintf(msg, "%s%f,", msg, + snprintf(currPos(msg),1024, "%f,", m_data->m_cachedState.m_actualStateQdot[i]); } else { - sprintf(msg, "%s%f", msg, + snprintf(currPos(msg),1024, "%f", m_data->m_cachedState.m_actualStateQdot[i]); } } - sprintf(msg, "%s]", msg); + snprintf(currPos(msg),1024, "]"); + #undef customMin + #undef currPos b3Printf(msg); b3Printf("\n"); } @@ -2227,4 +2231,3 @@ void PhysicsClientSharedMemory::popProfileTiming() delete sample; } } - From f2b838f1329f8a6c76a72f201e17f7b73a49ed30 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 22:33:51 +0100 Subject: [PATCH 35/57] Compiler warnings - superfluous semicolon --- Extras/HACD/hacdVector.inl | 2 +- .../Serialize/BulletFileLoader/btBulletFile.h | 2 +- .../btBulletWorldImporter.h | 2 +- .../btBulletXmlWorldImporter.h | 2 +- .../BulletXmlWorldImporter/string_split.cpp | 2 +- .../BulletXmlWorldImporter/string_split.h | 2 +- Extras/VHACD/inc/vhacdVector.inl | 4 +- Extras/VHACD/inc/vhacdVolume.h | 2 +- examples/Evolution/NN3DWalkersTimeWarpBase.h | 4 +- .../GwenGUISupport/gwenUserInterface.h | 4 +- .../ExampleBrowser/OpenGLExampleBrowser.cpp | 4 +- .../ImportURDFDemo/BulletUrdfImporter.cpp | 6 +-- .../Importers/ImportURDFDemo/UrdfParser.h | 2 +- .../ImportURDFDemo/urdfLexicalCast.h | 2 +- .../OpenGLWindow/Win32InternalWindowData.h | 2 +- .../ReducedDeformableDemo/FrictionSlope.cpp | 2 +- examples/SharedMemory/BodyJointInfoUtility.h | 2 +- .../PhysicsClientSharedMemory.cpp | 2 +- .../SharedMemory/PhysicsServerExample.cpp | 6 +-- .../collisionFilterPlugin.h | 2 +- .../plugins/pdControlPlugin/pdControlPlugin.h | 2 +- .../tinyRendererPlugin/tinyRendererPlugin.h | 2 +- .../StandaloneMain/hellovr_opengl_main.cpp | 2 +- examples/ThirdPartyLibs/Gwen/BaseRender.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/Base.h | 4 +- .../ThirdPartyLibs/Gwen/Controls/Button.cpp | 2 +- .../Gwen/Controls/TabControl.cpp | 4 +- .../ThirdPartyLibs/Gwen/Controls/TreeNode.cpp | 6 +-- examples/ThirdPartyLibs/Gwen/Gwen.h | 2 +- examples/ThirdPartyLibs/Gwen/InputHandler.h | 4 +- .../Gwen/Renderers/OpenGL_DebugFont.cpp | 4 +- examples/ThirdPartyLibs/Gwen/Skin.h | 2 +- .../Wavefront/tiny_obj_loader.cpp | 2 +- .../Wavefront/tiny_obj_loader.h | 2 +- .../clsocket/src/SimpleSocket.h | 52 +++++++++---------- .../ThirdPartyLibs/clsocket/src/StatTimer.h | 24 ++++----- .../shared/b3Contact4Data.h | 4 +- .../shared/b3MprPenetration.h | 2 +- .../b3GpuSapBroadphase.cpp | 8 +-- .../RigidBody/b3GpuNarrowPhase.cpp | 2 +- .../Bullet2FileLoader/b3BulletFile.h | 2 +- .../CollisionShapes/btBoxShape.cpp | 2 +- .../NarrowPhaseCollision/btMprPenetration.h | 2 +- 43 files changed, 97 insertions(+), 97 deletions(-) diff --git a/Extras/HACD/hacdVector.inl b/Extras/HACD/hacdVector.inl index b1f0c1b2a3..912e4bad1b 100644 --- a/Extras/HACD/hacdVector.inl +++ b/Extras/HACD/hacdVector.inl @@ -156,7 +156,7 @@ namespace HACD m_data[2] = rhs.m_data[2]; } template - inline Vec3::~Vec3(void){}; + inline Vec3::~Vec3(void){} template inline Vec3::Vec3() {} diff --git a/Extras/Serialize/BulletFileLoader/btBulletFile.h b/Extras/Serialize/BulletFileLoader/btBulletFile.h index d7c1cb7e07..78bfda4027 100644 --- a/Extras/Serialize/BulletFileLoader/btBulletFile.h +++ b/Extras/Serialize/BulletFileLoader/btBulletFile.h @@ -75,6 +75,6 @@ class btBulletFile : public bFile void addStruct(const char* structType, void* data, int len, void* oldPtr, int code); }; -}; // namespace bParse +} // namespace bParse #endif //BT_BULLET_FILE_H diff --git a/Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.h b/Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.h index 0a856bc3b5..f1f7a686ab 100644 --- a/Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.h +++ b/Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.h @@ -24,7 +24,7 @@ namespace bParse { class btBulletFile; -}; +} ///The btBulletWorldImporter is a starting point to import .bullet files. ///note that not all data is converted yet. You are expected to override or modify this class. diff --git a/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.h b/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.h index aa88c088a2..6393055157 100644 --- a/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.h +++ b/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.h @@ -23,7 +23,7 @@ class btDynamicsWorld; namespace tinyxml2 { class XMLNode; -}; +} struct btConvexInternalShapeData; struct btCollisionShapeData; diff --git a/Extras/Serialize/BulletXmlWorldImporter/string_split.cpp b/Extras/Serialize/BulletXmlWorldImporter/string_split.cpp index 4325126b3e..d32c8a1775 100644 --- a/Extras/Serialize/BulletXmlWorldImporter/string_split.cpp +++ b/Extras/Serialize/BulletXmlWorldImporter/string_split.cpp @@ -34,7 +34,7 @@ void split(btAlignedObjectArray &pieces, const std::string &vector_ str_array_free(strArray); } -}; // namespace bullet_utils +} // namespace bullet_utils /* Append an item to a dynamically allocated array of strings. On failure, return NULL, in which case the original array is intact. The item diff --git a/Extras/Serialize/BulletXmlWorldImporter/string_split.h b/Extras/Serialize/BulletXmlWorldImporter/string_split.h index 16d629d610..78353780d7 100644 --- a/Extras/Serialize/BulletXmlWorldImporter/string_split.h +++ b/Extras/Serialize/BulletXmlWorldImporter/string_split.h @@ -27,7 +27,7 @@ subject to the following restrictions: namespace bullet_utils { void split(btAlignedObjectArray& pieces, const std::string& vector_str, const std::string& separator); -}; +} ///The string split C code is by Lars Wirzenius ///See http://stackoverflow.com/questions/2531605/how-to-split-a-string-with-a-delimiter-larger-than-one-single-char diff --git a/Extras/VHACD/inc/vhacdVector.inl b/Extras/VHACD/inc/vhacdVector.inl index 7e87c602f6..0fd96afc07 100644 --- a/Extras/VHACD/inc/vhacdVector.inl +++ b/Extras/VHACD/inc/vhacdVector.inl @@ -156,7 +156,7 @@ namespace VHACD m_data[2] = rhs.m_data[2]; } template - inline Vec3::~Vec3(void){}; + inline Vec3::~Vec3(void){} template inline Vec3::Vec3() {} @@ -333,7 +333,7 @@ namespace VHACD m_data[1] = rhs.m_data[1]; } template - inline Vec2::~Vec2(void){}; + inline Vec2::~Vec2(void){} template inline Vec2::Vec2() {} diff --git a/Extras/VHACD/inc/vhacdVolume.h b/Extras/VHACD/inc/vhacdVolume.h index 1362833497..feebe98b5c 100644 --- a/Extras/VHACD/inc/vhacdVolume.h +++ b/Extras/VHACD/inc/vhacdVolume.h @@ -268,7 +268,7 @@ int TriBoxOverlap(const Vec3& boxcenter, const Vec3& boxhalfsize const Vec3& triver1, const Vec3& triver2); template inline void ComputeAlignedPoint(const T* const /*points*/, const unsigned int /*idx*/, const Vec3& /*barycenter*/, - const double (& /*rot*/)[3][3], Vec3& /*pt*/){}; + const double (& /*rot*/)[3][3], Vec3& /*pt*/){} template <> inline void ComputeAlignedPoint(const float* const points, const unsigned int idx, const Vec3& barycenter, const double (&rot)[3][3], Vec3& pt) { diff --git a/examples/Evolution/NN3DWalkersTimeWarpBase.h b/examples/Evolution/NN3DWalkersTimeWarpBase.h index 20665c5b39..583a2bff4a 100644 --- a/examples/Evolution/NN3DWalkersTimeWarpBase.h +++ b/examples/Evolution/NN3DWalkersTimeWarpBase.h @@ -53,7 +53,7 @@ static double /*8*/ QUINCENTUPLE_SPEED = 500; static double /*9*/ MILLITUPLE_SPEED = 1000; static double /*0*/ MAX_SPEED = MILLITUPLE_SPEED; static double /**/ NUM_SPEEDS = 10; -}; // namespace SimulationSpeeds +} // namespace SimulationSpeeds // add speeds from the namespace here static double speeds[] = { @@ -104,7 +104,7 @@ static char NNCGSOLVER[] = "NNCG Solver"; static char DANZIGSOLVER[] = "Danzig Solver"; static char LEMKESOLVER[] = "Lemke Solver"; -}; // namespace SolverType +} // namespace SolverType static const char* solverTypes[NUM_SOLVERS]; diff --git a/examples/ExampleBrowser/GwenGUISupport/gwenUserInterface.h b/examples/ExampleBrowser/GwenGUISupport/gwenUserInterface.h index 5f246180ef..2d49e78666 100644 --- a/examples/ExampleBrowser/GwenGUISupport/gwenUserInterface.h +++ b/examples/ExampleBrowser/GwenGUISupport/gwenUserInterface.h @@ -13,8 +13,8 @@ namespace Gwen namespace Renderer { class Base; -}; -}; // namespace Gwen +} +} // namespace Gwen class GwenUserInterface { GwenInternalData* m_data; diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index 93a54913c4..d7bfd0697e 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -534,7 +534,7 @@ static void saveCurrentSettings(int /*currentEntry*/, const char* startFileName) fclose(f); } -}; +} static void loadCurrentSettings(const char* startFileName, b3CommandLineArgs& args) { @@ -554,7 +554,7 @@ static void loadCurrentSettings(const char* startFileName, b3CommandLineArgs& ar } fclose(f); } -}; +} void MyComboBoxCallback(int comboId, const char* item) { diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index 65d1c2fe03..19fe2ef406 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -320,7 +320,7 @@ int BulletURDFImporter::getRootLinkIndex() const return m_data->m_urdfParser.getModel().m_rootLinks[0]->m_linkIndex; } return -1; -}; +} void BulletURDFImporter::getLinkChildIndices(int linkIndex, btAlignedObjectArray& childLinkIndices) const { @@ -527,7 +527,7 @@ bool BulletURDFImporter::getJointInfo3(int urdfLinkIndex, btTransform& parent2jo } return false; -}; +} bool BulletURDFImporter::getJointInfo(int urdfLinkIndex, btTransform& parent2joint, btTransform& linkTransformInWorld, btVector3& jointAxisInJointSpace, int& jointType, btScalar& jointLowerLimit, btScalar& jointUpperLimit, btScalar& jointDamping, btScalar& jointFriction) const { @@ -1535,7 +1535,7 @@ class btCompoundShape* BulletURDFImporter::convertLinkCollisionShapes(int linkIn const struct UrdfModel* BulletURDFImporter::getUrdfModel() const { return &m_data->m_urdfParser.getModel(); -}; +} const struct UrdfDeformable& BulletURDFImporter::getDeformableModel() const { diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.h b/examples/Importers/ImportURDFDemo/UrdfParser.h index 8256099a5f..71d2d2fcd3 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.h +++ b/examples/Importers/ImportURDFDemo/UrdfParser.h @@ -335,7 +335,7 @@ struct UrdfModel namespace tinyxml2 { class XMLElement; -}; +} class UrdfParser { diff --git a/examples/Importers/ImportURDFDemo/urdfLexicalCast.h b/examples/Importers/ImportURDFDemo/urdfLexicalCast.h index 664813653a..f8e63edca4 100644 --- a/examples/Importers/ImportURDFDemo/urdfLexicalCast.h +++ b/examples/Importers/ImportURDFDemo/urdfLexicalCast.h @@ -8,6 +8,6 @@ T urdfLexicalCast(const char* txt) { double result = atof(txt); return result; -}; +} #endif diff --git a/examples/OpenGLWindow/Win32InternalWindowData.h b/examples/OpenGLWindow/Win32InternalWindowData.h index 542ab74ceb..12d66e2864 100644 --- a/examples/OpenGLWindow/Win32InternalWindowData.h +++ b/examples/OpenGLWindow/Win32InternalWindowData.h @@ -7,7 +7,7 @@ struct InternalData2 { HWND m_hWnd; - ; + int m_fullWindowWidth; //includes borders etc int m_fullWindowHeight; diff --git a/examples/ReducedDeformableDemo/FrictionSlope.cpp b/examples/ReducedDeformableDemo/FrictionSlope.cpp index cceb464d34..4dabea1629 100644 --- a/examples/ReducedDeformableDemo/FrictionSlope.cpp +++ b/examples/ReducedDeformableDemo/FrictionSlope.cpp @@ -162,7 +162,7 @@ namespace FrictionSlopeHelper ground->setLinearVelocity(btVector3(0, 0, 0)); ground->setAngularVelocity(btVector3(0, 0, 0)); } -}; +} void FrictionSlope::initPhysics() { diff --git a/examples/SharedMemory/BodyJointInfoUtility.h b/examples/SharedMemory/BodyJointInfoUtility.h index 0be4814b20..57b9df095f 100644 --- a/examples/SharedMemory/BodyJointInfoUtility.h +++ b/examples/SharedMemory/BodyJointInfoUtility.h @@ -7,7 +7,7 @@ namespace Bullet { class btMultiBodyDoubleData; class btMultiBodyFloatData; -}; // namespace Bullet +} // namespace Bullet inline char* strDup(const char* const str) { diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.cpp b/examples/SharedMemory/PhysicsClientSharedMemory.cpp index 1c60d12cef..2919b2a0e2 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsClientSharedMemory.cpp @@ -523,7 +523,7 @@ void addJointInfoFromConstraint(int linkIndex, const T* con, U* bodyJoints, bool info.m_flags |= JOINT_HAS_MOTORIZED_POWER; } bodyJoints->m_jointInfo.push_back(info); -}; +} const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() { diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 342fa25929..7926733caa 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -64,7 +64,7 @@ static void loadCurrentSettingsVR(b3CommandLineArgs& args) } fclose(f); } -}; +} //remember the settings (you don't want to re-tune again and again...) @@ -79,7 +79,7 @@ static void saveCurrentSettingsVR(const btVector3& VRTeleportPos1) fprintf(f, "--camRotZ= %f\n", gVRTeleportRotZ); fclose(f); } -}; +} bool gDebugRenderToggle = false; void MotionThreadFunc(void* userPtr, void* lsMemory); void* MotionlsMemoryFunc(); @@ -134,7 +134,7 @@ enum MultiThreadedGUIHelperCommunicationEnums eGUIHelperResetCamera, eGUIHelperChangeGraphicsInstanceFlags, eGUIHelperSetRgbBackground, - eGUIUserDebugAddPoints, + eGUIUserDebugAddPoints }; #include diff --git a/examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.h b/examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.h index 27e39223dc..28b15eab7d 100644 --- a/examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.h +++ b/examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.h @@ -17,7 +17,7 @@ extern "C" B3_SHARED_API struct b3PluginCollisionInterface* getCollisionInterface_collisionFilterPlugin(struct b3PluginContext* context); #ifdef __cplusplus -}; +} #endif #endif //#define COLLISION_FILTER_PLUGIN_H diff --git a/examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h b/examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h index 1fc869122b..f573949554 100644 --- a/examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h +++ b/examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h @@ -24,7 +24,7 @@ extern "C" B3_SHARED_API int preTickPluginCallback_pdControlPlugin(struct b3PluginContext* context); #ifdef __cplusplus -}; +} #endif #endif //#define PID_CONTROL_PLUGIN_H diff --git a/examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.h b/examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.h index a7a4a0b0fc..9755f5dca0 100644 --- a/examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.h +++ b/examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.h @@ -17,7 +17,7 @@ extern "C" B3_SHARED_API struct UrdfRenderingInterface* getRenderInterface_tinyRendererPlugin(struct b3PluginContext* context); #ifdef __cplusplus -}; +} #endif #endif //#define TEST_PLUGIN_H diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index b11f30bd25..29113ce19d 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -293,7 +293,7 @@ CMainApplication::CMainApplication(int argc, char *argv[]) } // other initialization tasks are done in BInit memset(m_rDevClassChar, 0, sizeof(m_rDevClassChar)); -}; +} //----------------------------------------------------------------------------- // Purpose: Destructor diff --git a/examples/ThirdPartyLibs/Gwen/BaseRender.cpp b/examples/ThirdPartyLibs/Gwen/BaseRender.cpp index 570bad0168..73a813a991 100644 --- a/examples/ThirdPartyLibs/Gwen/BaseRender.cpp +++ b/examples/ThirdPartyLibs/Gwen/BaseRender.cpp @@ -48,7 +48,7 @@ void Base::DrawLinedRect(Gwen::Rect rect) DrawFilledRect(Gwen::Rect(rect.x, rect.y, 1, rect.h)); DrawFilledRect(Gwen::Rect(rect.x + rect.w - 1, rect.y, 1, rect.h)); -}; +} void Base::DrawPixel(int x, int y) { diff --git a/examples/ThirdPartyLibs/Gwen/Controls/Base.h b/examples/ThirdPartyLibs/Gwen/Controls/Base.h index 3cdfaef4c0..367069c593 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/Base.h +++ b/examples/ThirdPartyLibs/Gwen/Controls/Base.h @@ -30,7 +30,7 @@ namespace ControlsInternal class ColorDisplay; class Resizer; -}; // namespace ControlsInternal +} // namespace ControlsInternal namespace Pos { @@ -60,7 +60,7 @@ class Canvas; namespace Layout { class TableRow; -}; +} class GWEN_EXPORT Base : public Event::Handler { diff --git a/examples/ThirdPartyLibs/Gwen/Controls/Button.cpp b/examples/ThirdPartyLibs/Gwen/Controls/Button.cpp index 3fc5183877..8c3bee2e0d 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/Button.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/Button.cpp @@ -163,4 +163,4 @@ void Button::OnMouseDoubleClickLeft(int x, int y) { OnMouseClickLeft(x, y, true); onDoubleClick.Call(this); -}; \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/TabControl.cpp b/examples/ThirdPartyLibs/Gwen/Controls/TabControl.cpp index a7d586e381..0c724787ba 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/TabControl.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/TabControl.cpp @@ -36,8 +36,8 @@ class TabControlInner : public Base Gwen::Rect m_ButtonRect; }; -}; // namespace Controls -}; // namespace Gwen +} // namespace Controls +} // namespace Gwen using namespace Gwen; using namespace Gwen::Controls; diff --git a/examples/ThirdPartyLibs/Gwen/Controls/TreeNode.cpp b/examples/ThirdPartyLibs/Gwen/Controls/TreeNode.cpp index 3968a38291..b20503f4ac 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/TreeNode.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/TreeNode.cpp @@ -125,8 +125,8 @@ void TreeNode::PostLayout(Skin::Base* /*skin*/) } } -void TreeNode::SetText(const UnicodeString& text) { m_Title->SetText(text); }; -void TreeNode::SetText(const String& text) { m_Title->SetText(text); }; +void TreeNode::SetText(const UnicodeString& text) { m_Title->SetText(text); } +void TreeNode::SetText(const String& text) { m_Title->SetText(text); } UnicodeString TreeNode::GetText() const { @@ -336,4 +336,4 @@ void TreeNode::iterate(int action, int* curIndex, int* targetIndex) pChild->iterate(action, curIndex, targetIndex); } } -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Gwen.h b/examples/ThirdPartyLibs/Gwen/Gwen.h index 6e54d53984..2817e8e27b 100644 --- a/examples/ThirdPartyLibs/Gwen/Gwen.h +++ b/examples/ThirdPartyLibs/Gwen/Gwen.h @@ -62,7 +62,7 @@ static const Color Grey(200, 200, 200, 255); static const Color GreyLight(230, 230, 230, 255); static const Color GwenPink(255, 65, 199, 255); -}; // namespace Colors +} // namespace Colors extern GWEN_EXPORT Controls::Base* HoveredControl; extern GWEN_EXPORT Controls::Base* KeyboardFocus; diff --git a/examples/ThirdPartyLibs/Gwen/InputHandler.h b/examples/ThirdPartyLibs/Gwen/InputHandler.h index 29f35af945..13a1aa6242 100644 --- a/examples/ThirdPartyLibs/Gwen/InputHandler.h +++ b/examples/ThirdPartyLibs/Gwen/InputHandler.h @@ -53,7 +53,7 @@ enum Redo, SelectAll }; -}; +} // For use in panels bool GWEN_EXPORT IsKeyDown(int iKey); @@ -74,6 +74,6 @@ bool GWEN_EXPORT OnMouseClicked(Controls::Base* pCanvas, int iButton, bool bDown bool GWEN_EXPORT OnKeyEvent(Controls::Base* pCanvas, int iKey, bool bDown); void GWEN_EXPORT OnCanvasThink(Controls::Base* pControl); -}; // namespace Input +} // namespace Input } // namespace Gwen #endif diff --git a/examples/ThirdPartyLibs/Gwen/Renderers/OpenGL_DebugFont.cpp b/examples/ThirdPartyLibs/Gwen/Renderers/OpenGL_DebugFont.cpp index e3044a239f..10f3d78264 100644 --- a/examples/ThirdPartyLibs/Gwen/Renderers/OpenGL_DebugFont.cpp +++ b/examples/ThirdPartyLibs/Gwen/Renderers/OpenGL_DebugFont.cpp @@ -298,13 +298,13 @@ void OpenGL_DebugFont::StartClip() glScissor(retinaScale * rect.x * Scale(), retinaScale * rect.y * Scale(), retinaScale * rect.w * Scale(), retinaScale * rect.h * Scale()); glEnable(GL_SCISSOR_TEST); //glDisable( GL_SCISSOR_TEST ); -}; +} void OpenGL_DebugFont::EndClip() { Flush(); glDisable(GL_SCISSOR_TEST); -}; +} void OpenGL_DebugFont::RenderText(Gwen::Font* pFont, Gwen::Point pos, const Gwen::UnicodeString& text) { diff --git a/examples/ThirdPartyLibs/Gwen/Skin.h b/examples/ThirdPartyLibs/Gwen/Skin.h index 2541ae997d..41903194ff 100644 --- a/examples/ThirdPartyLibs/Gwen/Skin.h +++ b/examples/ThirdPartyLibs/Gwen/Skin.h @@ -127,6 +127,6 @@ class GWEN_EXPORT Base Gwen::Font m_DefaultFont; Gwen::Renderer::Base* m_Render; }; -}; // namespace Skin +} // namespace Skin } // namespace Gwen #endif diff --git a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp index 8e92be5d88..b00666b42f 100644 --- a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp +++ b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp @@ -880,4 +880,4 @@ LoadObj( return err.str(); } -}; // namespace bt_tinyobj +} // namespace bt_tinyobj diff --git a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h index f05da52c7c..b5c19893b4 100644 --- a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h +++ b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h @@ -94,6 +94,6 @@ LoadObj( CommonFileIOInterface* fileIO); #endif -}; // namespace bt_tinyobj +} // namespace bt_tinyobj #endif // _BT_TINY_OBJ_LOADER_H diff --git a/examples/ThirdPartyLibs/clsocket/src/SimpleSocket.h b/examples/ThirdPartyLibs/clsocket/src/SimpleSocket.h index c276d7c390..b163341ce3 100644 --- a/examples/ThirdPartyLibs/clsocket/src/SimpleSocket.h +++ b/examples/ThirdPartyLibs/clsocket/src/SimpleSocket.h @@ -281,7 +281,7 @@ class CSimpleSocket uint8 *GetData(void) { return m_pBuffer; - }; + } /// Returns the number of bytes received on the last call to /// CSocket::Receive(). @@ -289,7 +289,7 @@ class CSimpleSocket int32 GetBytesReceived(void) { return m_nBytesReceived; - }; + } /// Returns the number of bytes sent on the last call to /// CSocket::Send(). @@ -297,7 +297,7 @@ class CSimpleSocket int32 GetBytesSent(void) { return m_nBytesSent; - }; + } /// Controls the actions taken when CSimpleSocket::Close is executed on a /// socket object that has unsent data. The default value for this option @@ -328,7 +328,7 @@ class CSimpleSocket int32 GetConnectTimeoutSec(void) { return m_stConnectTimeout.tv_sec; - }; + } /// Gets the timeout value that specifies the maximum number of microseconds /// a call to CSimpleSocket::Open waits until it completes. @@ -336,7 +336,7 @@ class CSimpleSocket int32 GetConnectTimeoutUSec(void) { return m_stConnectTimeout.tv_usec; - }; + } /// Sets the timeout value that specifies the maximum amount of time a call /// to CSimpleSocket::Receive waits until it completes. Use the method @@ -352,7 +352,7 @@ class CSimpleSocket { m_stConnectTimeout.tv_sec = nConnectTimeoutSec; m_stConnectTimeout.tv_usec = nConnectTimeoutUsec; - }; + } /// Gets the timeout value that specifies the maximum number of seconds a /// a call to CSimpleSocket::Receive waits until it completes. @@ -360,7 +360,7 @@ class CSimpleSocket int32 GetReceiveTimeoutSec(void) { return m_stRecvTimeout.tv_sec; - }; + } /// Gets the timeout value that specifies the maximum number of microseconds /// a call to CSimpleSocket::Receive waits until it completes. @@ -368,7 +368,7 @@ class CSimpleSocket int32 GetReceiveTimeoutUSec(void) { return m_stRecvTimeout.tv_usec; - }; + } /// Sets the timeout value that specifies the maximum amount of time a call /// to CSimpleSocket::Receive waits until it completes. Use the method @@ -394,7 +394,7 @@ class CSimpleSocket bool GetMulticast() { return m_bIsMulticast; - }; + } /// Bind socket to a specific interface when using multicast. /// @return true if successfully bound to interface @@ -406,7 +406,7 @@ class CSimpleSocket int32 GetSendTimeoutSec(void) { return m_stSendTimeout.tv_sec; - }; + } /// Gets the timeout value that specifies the maximum number of microseconds /// a call to CSimpleSocket::Send waits until it completes. @@ -414,7 +414,7 @@ class CSimpleSocket int32 GetSendTimeoutUSec(void) { return m_stSendTimeout.tv_usec; - }; + } /// Gets the timeout value that specifies the maximum amount of time a call /// to CSimpleSocket::Send waits until it completes. @@ -428,7 +428,7 @@ class CSimpleSocket CSocketError GetSocketError(void) { return m_socketErrno; - }; + } /* CSocketError GetSocketError(void) { CSocketError err = m_socketErrno; @@ -443,14 +443,14 @@ class CSimpleSocket uint32 GetTotalTimeMs() { return m_timer.GetMilliSeconds(); - }; + } /// Get the total time the of the last operation in microseconds. /// @return number of microseconds or last operation. uint32 GetTotalTimeUsec() { return m_timer.GetMicroSeconds(); - }; + } /// Return Differentiated Services Code Point (DSCP) value currently set on the socket object. /// @return DSCP for current socket object. @@ -468,42 +468,42 @@ class CSimpleSocket SOCKET GetSocketDescriptor() { return m_socket; - }; + } /// Return socket descriptor /// @return socket descriptor which is a signed 32 bit integer. CSocketType GetSocketType() { return m_nSocketType; - }; + } /// Returns clients Internet host address as a string in standard numbers-and-dots notation. /// @return NULL if invalid const char *GetClientAddr() { return inet_ntoa(m_stClientSockaddr.sin_addr); - }; + } /// Returns the port number on which the client is connected. /// @return client port number. uint16 GetClientPort() { return m_stClientSockaddr.sin_port; - }; + } /// Returns server Internet host address as a string in standard numbers-and-dots notation. /// @return NULL if invalid const char *GetServerAddr() { return inet_ntoa(m_stServerSockaddr.sin_addr); - }; + } /// Returns the port number on which the server is connected. /// @return server port number. uint16 GetServerPort() { return ntohs(m_stServerSockaddr.sin_port); - }; + } /// Get the TCP receive buffer window size for the current socket object. ///

\b NOTE: Linux will set the receive buffer to twice the value passed. @@ -511,7 +511,7 @@ class CSimpleSocket uint32 GetReceiveWindowSize() { return GetWindowSize(SO_RCVBUF); - }; + } /// Get the TCP send buffer window size for the current socket object. ///

\b NOTE: Linux will set the send buffer to twice the value passed. @@ -519,7 +519,7 @@ class CSimpleSocket uint32 GetSendWindowSize() { return GetWindowSize(SO_SNDBUF); - }; + } /// Set the TCP receive buffer window size for the current socket object. ///

\b NOTE: Linux will set the receive buffer to twice the value passed. @@ -527,7 +527,7 @@ class CSimpleSocket uint32 SetReceiveWindowSize(uint32 nWindowSize) { return SetWindowSize(SO_RCVBUF, nWindowSize); - }; + } /// Set the TCP send buffer window size for the current socket object. ///

\b NOTE: Linux will set the send buffer to twice the value passed. @@ -535,7 +535,7 @@ class CSimpleSocket uint32 SetSendWindowSize(uint32 nWindowSize) { return SetWindowSize(SO_SNDBUF, nWindowSize); - }; + } /// Disable the Nagle algorithm (Set TCP_NODELAY to true) /// @return false if failed to set socket option otherwise return true; @@ -551,14 +551,14 @@ class CSimpleSocket void SetSocketError(CSimpleSocket::CSocketError error) { m_socketErrno = error; - }; + } /// Set object socket handle to that specified as parameter /// @param socket value of socket descriptor void SetSocketHandle(SOCKET socket) { m_socket = socket; - }; + } private: /// Generic function used to get the send/receive window size diff --git a/examples/ThirdPartyLibs/clsocket/src/StatTimer.h b/examples/ThirdPartyLibs/clsocket/src/StatTimer.h index 89d4cfa802..404c6dbe03 100644 --- a/examples/ThirdPartyLibs/clsocket/src/StatTimer.h +++ b/examples/ThirdPartyLibs/clsocket/src/StatTimer.h @@ -71,36 +71,36 @@ class CStatTimer { public: - CStatTimer(){}; + CStatTimer(){} - ~CStatTimer(){}; + ~CStatTimer(){} void Initialize() { memset(&m_startTime, 0, sizeof(struct timeval)); memset(&m_endTime, 0, sizeof(struct timeval)); - }; + } - struct timeval GetStartTime() { return m_startTime; }; - void SetStartTime() { GET_CLOCK_COUNT(&m_startTime); }; + struct timeval GetStartTime() { return m_startTime; } + void SetStartTime() { GET_CLOCK_COUNT(&m_startTime); } - struct timeval GetEndTime() { return m_endTime; }; - void SetEndTime() { GET_CLOCK_COUNT(&m_endTime); }; + struct timeval GetEndTime() { return m_endTime; } + void SetEndTime() { GET_CLOCK_COUNT(&m_endTime); } - uint32 GetMilliSeconds() { return (CalcTotalUSec() / MILLISECONDS_CONVERSION); }; - uint32 GetMicroSeconds() { return (CalcTotalUSec()); }; - uint32 GetSeconds() { return (CalcTotalUSec() / MICROSECONDS_CONVERSION); }; + uint32 GetMilliSeconds() { return (CalcTotalUSec() / MILLISECONDS_CONVERSION); } + uint32 GetMicroSeconds() { return (CalcTotalUSec()); } + uint32 GetSeconds() { return (CalcTotalUSec() / MICROSECONDS_CONVERSION); } uint32 GetCurrentTime() { struct timeval tmpTime; GET_CLOCK_COUNT(&tmpTime); return ((tmpTime.tv_sec * MICROSECONDS_CONVERSION) + tmpTime.tv_usec); - }; + } private: uint32 CalcTotalUSec() { return (((m_endTime.tv_sec - m_startTime.tv_sec) * MICROSECONDS_CONVERSION) + - (m_endTime.tv_usec - m_startTime.tv_usec)); }; + (m_endTime.tv_usec - m_startTime.tv_usec)); } private: struct timeval m_startTime; diff --git a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3Contact4Data.h b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3Contact4Data.h index d5f6daa993..5ca48bad84 100644 --- a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3Contact4Data.h +++ b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3Contact4Data.h @@ -26,11 +26,11 @@ struct b3Contact4Data inline int b3Contact4Data_getNumPoints(const struct b3Contact4Data* contact) { return (int)contact->m_worldNormalOnB.w; -}; +} inline void b3Contact4Data_setNumPoints(struct b3Contact4Data* contact, int numPoints) { contact->m_worldNormalOnB.w = (float)numPoints; -}; +} #endif //B3_CONTACT4DATA_H \ No newline at end of file diff --git a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3MprPenetration.h b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3MprPenetration.h index 756d239565..966e6538c1 100644 --- a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3MprPenetration.h +++ b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3MprPenetration.h @@ -883,6 +883,6 @@ inline int b3MprPenetration(int pairIndex, int bodyIndexA, int bodyIndexB, }; return 0; -}; +} #endif //B3_MPR_PENETRATION_H diff --git a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.cpp b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.cpp index be1d12cfe7..d9a00a912a 100644 --- a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.cpp +++ b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.cpp @@ -186,7 +186,7 @@ static unsigned int FloatFlip(float fl) unsigned int f = *(unsigned int*)&fl; unsigned int mask = -(int)(f >> 31) | 0x80000000; return f ^ mask; -}; +} void b3GpuSapBroadphase::init3dSap() { @@ -251,17 +251,17 @@ static bool b3PairCmp(const b3Int4& p, const b3Int4& q) static bool operator==(const b3Int4& a, const b3Int4& b) { return a.x == b.x && a.y == b.y; -}; +} static bool operator<(const b3Int4& a, const b3Int4& b) { return a.x < b.x || (a.x == b.x && a.y < b.y); -}; +} static bool operator>(const b3Int4& a, const b3Int4& b) { return a.x > b.x || (a.x == b.x && a.y > b.y); -}; +} b3AlignedObjectArray addedHostPairs; b3AlignedObjectArray removedHostPairs; diff --git a/src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.cpp b/src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.cpp index 3ab919bf95..a2c384d489 100644 --- a/src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.cpp +++ b/src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.cpp @@ -676,7 +676,7 @@ cl_mem b3GpuNarrowPhase::getBodiesGpu() const struct b3RigidBodyData* b3GpuNarrowPhase::getBodiesCpu() const { return &m_data->m_bodyBufferCPU->at(0); -}; +} int b3GpuNarrowPhase::getNumBodiesGpu() const { diff --git a/src/Bullet3Serialize/Bullet2FileLoader/b3BulletFile.h b/src/Bullet3Serialize/Bullet2FileLoader/b3BulletFile.h index ede1d378ae..d4a29f654d 100644 --- a/src/Bullet3Serialize/Bullet2FileLoader/b3BulletFile.h +++ b/src/Bullet3Serialize/Bullet2FileLoader/b3BulletFile.h @@ -69,6 +69,6 @@ class b3BulletFile : public bFile void addStruct(const char* structType, void* data, int len, void* oldPtr, int code); }; -}; // namespace bParse +} // namespace bParse #endif //B3_BULLET_FILE_H diff --git a/src/BulletCollision/CollisionShapes/btBoxShape.cpp b/src/BulletCollision/CollisionShapes/btBoxShape.cpp index cb91d023e4..51f8a112a5 100644 --- a/src/BulletCollision/CollisionShapes/btBoxShape.cpp +++ b/src/BulletCollision/CollisionShapes/btBoxShape.cpp @@ -23,7 +23,7 @@ btBoxShape::btBoxShape(const btVector3& boxHalfExtents) m_implicitShapeDimensions = (boxHalfExtents * m_localScaling) - margin; setSafeMargin(boxHalfExtents); -}; +} void btBoxShape::getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const { diff --git a/src/BulletCollision/NarrowPhaseCollision/btMprPenetration.h b/src/BulletCollision/NarrowPhaseCollision/btMprPenetration.h index 6c14ad43f1..a976f26d87 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btMprPenetration.h +++ b/src/BulletCollision/NarrowPhaseCollision/btMprPenetration.h @@ -861,7 +861,7 @@ inline int btMprPenetration(const btConvexTemplate &a, const btConvexTemplate &b }; return result; -}; +} template inline int btComputeMprPenetration(const btConvexTemplate &a, const btConvexTemplate &b, const btMprCollisionDescription &colDesc, btMprDistanceTemplate *distInfo) From b19b368ae014e9f08a8f52a75f71a4319482b9b2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 02:18:00 +0100 Subject: [PATCH 36/57] Compiler warnings - comma at end of enum --- Extras/Serialize/BulletFileLoader/bFile.h | 2 +- .../BulletWorldImporter/btWorldImporter.h | 4 +- examples/Collision/CollisionTutorialBullet2.h | 2 +- .../Internal/RealTimeBullet3CollisionSdk.cpp | 2 +- examples/CommonInterfaces/CommonCallbacks.h | 2 +- .../CommonGraphicsAppInterface.h | 4 +- .../CommonInterfaces/CommonRenderInterface.h | 4 +- examples/ExtendedTutorials/RigidBodyFromObj.h | 2 +- examples/Heightfield/HeightfieldExample.cpp | 4 +- .../ImportMeshUtility/b3ImportMeshUtility.h | 2 +- .../Importers/ImportURDFDemo/SDFAudioTypes.h | 2 +- .../Importers/ImportURDFDemo/URDFJointTypes.h | 8 +- .../Importers/ImportURDFDemo/UrdfParser.h | 4 +- .../MultiThreading/MultiThreadingExample.h | 2 +- .../MultiThreading/b3ThreadSupportInterface.h | 2 +- examples/OpenGLWindow/GLRenderToTexture.h | 2 +- examples/OpenGLWindow/Win32Window.cpp | 2 +- .../RoboticsLearning/GripperGraspExample.h | 2 +- examples/RoboticsLearning/KukaGraspExample.h | 2 +- examples/RoboticsLearning/R2D2GraspExample.h | 2 +- .../SharedMemory/GraphicsSharedMemoryPublic.h | 2 +- examples/SharedMemory/IKTrajectoryHelper.h | 2 +- examples/SharedMemory/PhysicsClientExample.h | 2 +- examples/SharedMemory/PhysicsClientUDP.cpp | 2 +- examples/SharedMemory/PhysicsServerExample.h | 2 +- examples/SharedMemory/SharedMemoryCommands.h | 48 +++++------ examples/SharedMemory/SharedMemoryPublic.h | 80 +++++++++---------- examples/SharedMemory/b3PluginManager.h | 2 +- .../b3RobotSimulatorClientAPI_NoDirect.h | 2 +- .../plugins/pdControlPlugin/pdControlPlugin.h | 2 +- .../plugins/stablePDPlugin/Shape.h | 2 +- examples/ThirdPartyLibs/Gwen/Controls/Base.h | 2 +- .../ThirdPartyLibs/Gwen/Controls/TreeNode.h | 2 +- examples/Tutorial/Tutorial.cpp | 2 +- examples/Tutorial/Tutorial.h | 2 +- examples/Utils/RobotLoggingUtil.h | 2 +- .../shared/b3Collidable.h | 2 +- .../ParallelPrimitives/b3BoundSearchCL.h | 2 +- .../ParallelPrimitives/b3RadixSort32CL.h | 2 +- .../RigidBody/b3GpuGenericConstraint.h | 4 +- src/Bullet3OpenCL/RigidBody/b3Solver.h | 4 +- .../Bullet2FileLoader/b3File.h | 2 +- .../NarrowPhaseCollision/btManifoldPoint.h | 2 +- .../ConstraintSolver/btConstraintSolver.h | 2 +- .../ConstraintSolver/btContactSolverInfo.h | 2 +- src/BulletDynamics/Dynamics/btRigidBody.h | 2 +- .../Featherstone/btMultiBodyConstraint.h | 2 +- .../Featherstone/btMultiBodyLink.h | 2 +- .../TaskScheduler/btTaskScheduler.cpp | 4 +- src/LinearMath/btSerializer.h | 2 +- 50 files changed, 123 insertions(+), 123 deletions(-) diff --git a/Extras/Serialize/BulletFileLoader/bFile.h b/Extras/Serialize/BulletFileLoader/bFile.h index f6fae97ed8..ba044c9e32 100644 --- a/Extras/Serialize/BulletFileLoader/bFile.h +++ b/Extras/Serialize/BulletFileLoader/bFile.h @@ -42,7 +42,7 @@ enum bFileVerboseMode FD_VERBOSE_EXPORT_XML = 1, FD_VERBOSE_DUMP_DNA_TYPE_DEFINITIONS = 2, FD_VERBOSE_DUMP_CHUNKS = 4, - FD_VERBOSE_DUMP_FILE_INFO = 8, + FD_VERBOSE_DUMP_FILE_INFO = 8 }; // ----------------------------------------------------- // class bFile diff --git a/Extras/Serialize/BulletWorldImporter/btWorldImporter.h b/Extras/Serialize/BulletWorldImporter/btWorldImporter.h index ba087fba72..d4ad886456 100644 --- a/Extras/Serialize/BulletWorldImporter/btWorldImporter.h +++ b/Extras/Serialize/BulletWorldImporter/btWorldImporter.h @@ -60,7 +60,7 @@ struct btRigidBodyFloatData; enum btWorldImporterFlags { - eRESTORE_EXISTING_OBJECTS = 1, //don't create new objects + eRESTORE_EXISTING_OBJECTS = 1 //don't create new objects }; class btWorldImporter @@ -224,4 +224,4 @@ class btWorldImporter virtual btGearConstraint* createGearConstraint(btRigidBody& rbA, btRigidBody& rbB, const btVector3& axisInA, const btVector3& axisInB, btScalar ratio); }; -#endif //BT_WORLD_IMPORTER_H \ No newline at end of file +#endif //BT_WORLD_IMPORTER_H diff --git a/examples/Collision/CollisionTutorialBullet2.h b/examples/Collision/CollisionTutorialBullet2.h index 6ed76f243f..59b95ae025 100644 --- a/examples/Collision/CollisionTutorialBullet2.h +++ b/examples/Collision/CollisionTutorialBullet2.h @@ -4,7 +4,7 @@ enum EnumCollisionTutorialTypes { TUT_SPHERE_PLANE_BULLET2 = 0, - TUT_SPHERE_PLANE_RTB3, + TUT_SPHERE_PLANE_RTB3 }; class CommonExampleInterface* CollisionTutorialBullet2CreateFunc(struct CommonExampleOptions& options); diff --git a/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp b/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp index 4d69ff2d7d..de15aec205 100644 --- a/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp +++ b/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp @@ -27,7 +27,7 @@ enum RTB3ShapeTypes RTB3_SHAPE_PLANE, RTB3_SHAPE_CAPSULE, MAX_NUM_SINGLE_SHAPE_TYPES, - RTB3_SHAPE_COMPOUND_INTERNAL, + RTB3_SHAPE_COMPOUND_INTERNAL }; diff --git a/examples/CommonInterfaces/CommonCallbacks.h b/examples/CommonInterfaces/CommonCallbacks.h index 3047d143e2..e523bdf691 100644 --- a/examples/CommonInterfaces/CommonCallbacks.h +++ b/examples/CommonInterfaces/CommonCallbacks.h @@ -41,7 +41,7 @@ enum B3G_SHIFT, B3G_CONTROL, B3G_ALT, - B3G_RETURN, + B3G_RETURN }; diff --git a/examples/CommonInterfaces/CommonGraphicsAppInterface.h b/examples/CommonInterfaces/CommonGraphicsAppInterface.h index dc09ef9e24..e7cb8d86f8 100644 --- a/examples/CommonInterfaces/CommonGraphicsAppInterface.h +++ b/examples/CommonInterfaces/CommonGraphicsAppInterface.h @@ -30,7 +30,7 @@ enum EnumSphereLevelOfDetail SPHERE_LOD_POINT_SPRITE = 0, SPHERE_LOD_LOW, SPHERE_LOD_MEDIUM, - SPHERE_LOD_HIGH, + SPHERE_LOD_HIGH }; struct CommonGraphicsApp @@ -39,7 +39,7 @@ struct CommonGraphicsApp { eDrawText3D_OrtogonalFaceCamera = 1, eDrawText3D_TrueType = 2, - eDrawText3D_TrackObject = 4, + eDrawText3D_TrackObject = 4 }; class CommonWindowInterface* m_window; struct CommonRenderInterface* m_renderer; diff --git a/examples/CommonInterfaces/CommonRenderInterface.h b/examples/CommonInterfaces/CommonRenderInterface.h index 8a85ba94e8..8787c2a750 100644 --- a/examples/CommonInterfaces/CommonRenderInterface.h +++ b/examples/CommonInterfaces/CommonRenderInterface.h @@ -13,7 +13,7 @@ enum { B3_INSTANCE_TRANSPARANCY = 1, B3_INSTANCE_TEXTURE = 2, - B3_INSTANCE_DOUBLE_SIDED = 4, + B3_INSTANCE_DOUBLE_SIDED = 4 }; enum @@ -25,7 +25,7 @@ enum B3_USE_SHADOWMAP_RENDERMODE_REFLECTION, B3_USE_SHADOWMAP_RENDERMODE_REFLECTION_PLANE, B3_USE_PROJECTIVE_TEXTURE_RENDERMODE, - B3_SEGMENTATION_MASK_RENDERMODE, + B3_SEGMENTATION_MASK_RENDERMODE }; struct GfxVertexFormat0 diff --git a/examples/ExtendedTutorials/RigidBodyFromObj.h b/examples/ExtendedTutorials/RigidBodyFromObj.h index cd133a3391..80675cecd3 100644 --- a/examples/ExtendedTutorials/RigidBodyFromObj.h +++ b/examples/ExtendedTutorials/RigidBodyFromObj.h @@ -20,7 +20,7 @@ enum ObjToRigidBodyOptionsEnum { ObjUseConvexHullForRendering = 1, OptimizeConvexObj = 2, - ComputePolyhedralFeatures = 4, + ComputePolyhedralFeatures = 4 }; class CommonExampleInterface* ET_RigidBodyFromObjCreateFunc(struct CommonExampleOptions& options); diff --git a/examples/Heightfield/HeightfieldExample.cpp b/examples/Heightfield/HeightfieldExample.cpp index ac9cbcac3d..5212cd7c5f 100644 --- a/examples/Heightfield/HeightfieldExample.cpp +++ b/examples/Heightfield/HeightfieldExample.cpp @@ -44,8 +44,8 @@ static const btScalar s_deltaPhase = 0.25 * 2.0 * SIMD_PI; enum eTerrainModel { eRadial = 0, // deterministic eFractal = 1, // random - eCSVFile = 2,//csv file used in DeepLoco for example - eImageFile = 3,//terrain from png/jpg files, asset from https://www.beamng.com/threads/tutorial-adding-heightmap-roads-using-blender.16356/ + eCSVFile = 2, //csv file used in DeepLoco for example + eImageFile = 3 //terrain from png/jpg files, asset from https://www.beamng.com/threads/tutorial-adding-heightmap-roads-using-blender.16356/ }; diff --git a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.h b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.h index 1cff27b15c..e8442964b9 100644 --- a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.h +++ b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.h @@ -6,7 +6,7 @@ enum b3ImportMeshDataFlags { B3_IMPORT_MESH_HAS_RGBA_COLOR=1, - B3_IMPORT_MESH_HAS_SPECULAR_COLOR=2, + B3_IMPORT_MESH_HAS_SPECULAR_COLOR=2 }; struct b3ImportMeshData diff --git a/examples/Importers/ImportURDFDemo/SDFAudioTypes.h b/examples/Importers/ImportURDFDemo/SDFAudioTypes.h index d3928f3b8d..78718ff95d 100644 --- a/examples/Importers/ImportURDFDemo/SDFAudioTypes.h +++ b/examples/Importers/ImportURDFDemo/SDFAudioTypes.h @@ -9,7 +9,7 @@ struct SDFAudioSource enum { SDFAudioSourceValid = 1, - SDFAudioSourceLooping = 2, + SDFAudioSourceLooping = 2 }; int m_flags; //repeat mode (0 = no repeat, 1 = loop forever) diff --git a/examples/Importers/ImportURDFDemo/URDFJointTypes.h b/examples/Importers/ImportURDFDemo/URDFJointTypes.h index fff0fee2ea..515b197b0d 100644 --- a/examples/Importers/ImportURDFDemo/URDFJointTypes.h +++ b/examples/Importers/ImportURDFDemo/URDFJointTypes.h @@ -12,7 +12,7 @@ enum UrdfJointTypes URDFFloatingJoint, URDFPlanarJoint, URDFFixedJoint, - URDFSphericalJoint, + URDFSphericalJoint }; @@ -26,7 +26,7 @@ enum URDF_LinkContactFlags URDF_CONTACT_HAS_ROLLING_FRICTION = 32, URDF_CONTACT_HAS_SPINNING_FRICTION = 64, URDF_CONTACT_HAS_RESTITUTION = 128, - URDF_CONTACT_HAS_FRICTION_ANCHOR = 256, + URDF_CONTACT_HAS_FRICTION_ANCHOR = 256 }; @@ -63,7 +63,7 @@ enum UrdfCollisionFlags { URDF_FORCE_CONCAVE_TRIMESH = 1, URDF_HAS_COLLISION_GROUP = 2, - URDF_HAS_COLLISION_MASK = 4, + URDF_HAS_COLLISION_MASK = 4 }; struct UrdfMaterialColor @@ -104,7 +104,7 @@ enum ConvertURDFFlags CUF_IGNORE_VISUAL_SHAPES = 1 << 20, CUF_IGNORE_COLLISION_SHAPES = 1 << 21, CUF_PRINT_URDF_INFO = 1 << 22, - CUF_GOOGLEY_UNDEFINED_COLORS = 1 << 23, + CUF_GOOGLEY_UNDEFINED_COLORS = 1 << 23 }; diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.h b/examples/Importers/ImportURDFDemo/UrdfParser.h index 71d2d2fcd3..10b8822cde 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.h +++ b/examples/Importers/ImportURDFDemo/UrdfParser.h @@ -56,7 +56,7 @@ enum UrdfGeomTypes URDF_GEOM_CAPSULE, //non-standard URDF URDF_GEOM_CDF, //signed-distance-field, non-standard URDF URDF_GEOM_HEIGHTFIELD, //heightfield, non-standard URDF - URDF_GEOM_UNKNOWN, + URDF_GEOM_UNKNOWN }; struct UrdfGeometry @@ -82,7 +82,7 @@ struct UrdfGeometry FILE_OBJ = 3, FILE_CDF = 4, MEMORY_VERTICES = 5, - FILE_VTK = 6, + FILE_VTK = 6 }; int m_meshFileType; diff --git a/examples/MultiThreading/MultiThreadingExample.h b/examples/MultiThreading/MultiThreadingExample.h index 6bc142c3cc..18bf66eec6 100644 --- a/examples/MultiThreading/MultiThreadingExample.h +++ b/examples/MultiThreading/MultiThreadingExample.h @@ -3,7 +3,7 @@ enum EnumMultiThreadingExampleTypes { - SINGLE_SIM_THREAD = 0, + SINGLE_SIM_THREAD = 0 }; class CommonExampleInterface* MultiThreadingExampleCreateFunc(struct CommonExampleOptions& options); diff --git a/examples/MultiThreading/b3ThreadSupportInterface.h b/examples/MultiThreading/b3ThreadSupportInterface.h index add5e3a049..05773fa6bf 100644 --- a/examples/MultiThreading/b3ThreadSupportInterface.h +++ b/examples/MultiThreading/b3ThreadSupportInterface.h @@ -18,7 +18,7 @@ subject to the following restrictions: enum { - B3_THREAD_SCHEDULE_TASK = 1, + B3_THREAD_SCHEDULE_TASK = 1 }; #include "Bullet3Common/b3Scalar.h" //for B3_ATTRIBUTE_ALIGNED16 diff --git a/examples/OpenGLWindow/GLRenderToTexture.h b/examples/OpenGLWindow/GLRenderToTexture.h index 081f2ec91d..1086d637f7 100644 --- a/examples/OpenGLWindow/GLRenderToTexture.h +++ b/examples/OpenGLWindow/GLRenderToTexture.h @@ -8,7 +8,7 @@ enum { RENDERTEXTURE_COLOR = 1, - RENDERTEXTURE_DEPTH, + RENDERTEXTURE_DEPTH }; struct GLRenderToTexture { diff --git a/examples/OpenGLWindow/Win32Window.cpp b/examples/OpenGLWindow/Win32Window.cpp index 863eda477c..15b33a9245 100644 --- a/examples/OpenGLWindow/Win32Window.cpp +++ b/examples/OpenGLWindow/Win32Window.cpp @@ -27,7 +27,7 @@ enum { INTERNAL_SHIFT_MODIFIER = 1, INTERNAL_ALT_MODIFIER = 2, - INTERNAL_CONTROL_MODIFIER = 4, + INTERNAL_CONTROL_MODIFIER = 4 }; void Win32Window::pumpMessage() diff --git a/examples/RoboticsLearning/GripperGraspExample.h b/examples/RoboticsLearning/GripperGraspExample.h index 110068b8ee..0119333e68 100644 --- a/examples/RoboticsLearning/GripperGraspExample.h +++ b/examples/RoboticsLearning/GripperGraspExample.h @@ -23,7 +23,7 @@ enum GripperGraspExampleOptions eONE_MOTOR_GRASP = 4, eGRASP_SOFT_BODY = 8, eSOFTBODY_MULTIBODY_COUPLING = 16, - eGRASP_DEFORMABLE_CLOTH = 32, + eGRASP_DEFORMABLE_CLOTH = 32 }; class CommonExampleInterface* GripperGraspExampleCreateFunc(struct CommonExampleOptions& options); diff --git a/examples/RoboticsLearning/KukaGraspExample.h b/examples/RoboticsLearning/KukaGraspExample.h index b5175c8fa1..8308bade34 100644 --- a/examples/RoboticsLearning/KukaGraspExample.h +++ b/examples/RoboticsLearning/KukaGraspExample.h @@ -18,7 +18,7 @@ subject to the following restrictions: enum KukaGraspExampleOptions { - eKUKA_GRASP_DLS_IK = 1, + eKUKA_GRASP_DLS_IK = 1 }; class CommonExampleInterface* KukaGraspExampleCreateFunc(struct CommonExampleOptions& options); diff --git a/examples/RoboticsLearning/R2D2GraspExample.h b/examples/RoboticsLearning/R2D2GraspExample.h index 5e8c674a9e..f6069a1d5e 100644 --- a/examples/RoboticsLearning/R2D2GraspExample.h +++ b/examples/RoboticsLearning/R2D2GraspExample.h @@ -20,7 +20,7 @@ enum RobotLearningExampleOptions { eROBOTIC_LEARN_GRASP = 1, eROBOTIC_LEARN_COMPLIANT_CONTACT = 2, - eROBOTIC_LEARN_ROLLING_FRICTION = 4, + eROBOTIC_LEARN_ROLLING_FRICTION = 4 }; class CommonExampleInterface* R2D2GraspExampleCreateFunc(struct CommonExampleOptions& options); diff --git a/examples/SharedMemory/GraphicsSharedMemoryPublic.h b/examples/SharedMemory/GraphicsSharedMemoryPublic.h index 4a80736bdc..95b917fd84 100644 --- a/examples/SharedMemory/GraphicsSharedMemoryPublic.h +++ b/examples/SharedMemory/GraphicsSharedMemoryPublic.h @@ -24,7 +24,7 @@ enum EnumGraphicsSharedMemoryClientCommand GFX_CMD_GET_CAMERA_INFO, GFX_CMD_CHANGE_SCALING, //don't go beyond this command! - GFX_CMD_MAX_CLIENT_COMMANDS, + GFX_CMD_MAX_CLIENT_COMMANDS }; enum EnumGraphicsSharedMemoryServerStatus diff --git a/examples/SharedMemory/IKTrajectoryHelper.h b/examples/SharedMemory/IKTrajectoryHelper.h index cdbe7a230d..54c3861d6b 100644 --- a/examples/SharedMemory/IKTrajectoryHelper.h +++ b/examples/SharedMemory/IKTrajectoryHelper.h @@ -13,7 +13,7 @@ enum IK2_Method IK2_VEL_DLS_WITH_NULLSPACE, IK2_VEL_DLS_WITH_ORIENTATION_NULLSPACE, IK2_VEL_SDLS, - IK2_VEL_SDLS_WITH_ORIENTATION, + IK2_VEL_SDLS_WITH_ORIENTATION }; class IKTrajectoryHelper diff --git a/examples/SharedMemory/PhysicsClientExample.h b/examples/SharedMemory/PhysicsClientExample.h index f1c3dc458a..d330c06df1 100644 --- a/examples/SharedMemory/PhysicsClientExample.h +++ b/examples/SharedMemory/PhysicsClientExample.h @@ -5,7 +5,7 @@ enum ClientExampleOptions { eCLIENTEXAMPLE_LOOPBACK = 1, eCLIENTEXAMPLE_DIRECT = 2, - eCLIENTEXAMPLE_SERVER = 3, + eCLIENTEXAMPLE_SERVER = 3 }; class CommonExampleInterface* PhysicsClientCreateFunc(struct CommonExampleOptions& options); diff --git a/examples/SharedMemory/PhysicsClientUDP.cpp b/examples/SharedMemory/PhysicsClientUDP.cpp index 886e61b893..f79dbbf69a 100644 --- a/examples/SharedMemory/PhysicsClientUDP.cpp +++ b/examples/SharedMemory/PhysicsClientUDP.cpp @@ -297,7 +297,7 @@ enum UDPCommandEnums eUDP_Connected, eUDP_ConnectionFailed, eUDP_DisconnectRequest, - eUDP_Disconnected, + eUDP_Disconnected }; diff --git a/examples/SharedMemory/PhysicsServerExample.h b/examples/SharedMemory/PhysicsServerExample.h index 63f40146a5..73751a3674 100644 --- a/examples/SharedMemory/PhysicsServerExample.h +++ b/examples/SharedMemory/PhysicsServerExample.h @@ -5,7 +5,7 @@ enum PhysicsServerOptions { PHYSICS_SERVER_ENABLE_COMMAND_LOGGING = 1, PHYSICS_SERVER_REPLAY_FROM_COMMAND_LOG = 2, - PHYSICS_SERVER_USE_RTC_CLOCK = 4, + PHYSICS_SERVER_USE_RTC_CLOCK = 4 }; ///Don't use PhysicsServerCreateFuncInternal directly diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 37fc351457..d71e7873dc 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -62,7 +62,7 @@ inline enum EnumSdfArgsUpdateFlags { - SDF_ARGS_FILE_NAME = 1, + SDF_ARGS_FILE_NAME = 1 }; struct SdfArgs @@ -81,7 +81,7 @@ struct FileArgs enum EnumLoadStateArgsUpdateFlags { CMD_LOAD_STATE_HAS_STATEID = 1, - CMD_LOAD_STATE_HAS_FILENAME = 2, + CMD_LOAD_STATE_HAS_FILENAME = 2 }; enum EnumUrdfArgsUpdateFlags @@ -92,7 +92,7 @@ enum EnumUrdfArgsUpdateFlags URDF_ARGS_USE_MULTIBODY = 8, URDF_ARGS_USE_FIXED_BASE = 16, URDF_ARGS_HAS_CUSTOM_URDF_FLAGS = 32, - URDF_ARGS_USE_GLOBAL_SCALING = 64, + URDF_ARGS_USE_GLOBAL_SCALING = 64 }; struct UrdfArgs @@ -123,7 +123,7 @@ enum CustomCommandEnum CMD_CUSTOM_COMMAND_LOAD_PLUGIN = 1, CMD_CUSTOM_COMMAND_UNLOAD_PLUGIN = 2, CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND = 4, - CMD_CUSTOM_COMMAND_LOAD_PLUGIN_POSTFIX = 8, + CMD_CUSTOM_COMMAND_LOAD_PLUGIN_POSTFIX = 8 }; struct b3CustomCommand @@ -174,7 +174,7 @@ enum EnumChangeDynamicsInfoFlags CHANGE_DYNAMICS_INFO_SET_JOINT_LIMITS = 1 << 18, CHANGE_DYNAMICS_INFO_SET_JOINT_LIMIT_MAX_FORCE = 1 << 19, CHANGE_DYNAMICS_INFO_SET_DYNAMIC_TYPE = 1 << 20, - CHANGE_DYNAMICS_INFO_SET_SLEEP_THRESHOLD = 1 << 21, + CHANGE_DYNAMICS_INFO_SET_SLEEP_THRESHOLD = 1 << 21 }; struct ChangeDynamicsInfoArgs @@ -232,7 +232,7 @@ enum EnumInitPoseFlags INIT_POSE_HAS_BASE_LINEAR_VELOCITY = 8, INIT_POSE_HAS_BASE_ANGULAR_VELOCITY = 16, INIT_POSE_HAS_JOINT_VELOCITY = 32, - INIT_POSE_HAS_SCALING=64, + INIT_POSE_HAS_SCALING=64 }; ///InitPoseArgs is mainly to initialize (teleport) the robot in a particular position @@ -286,7 +286,7 @@ enum EnumRequestPixelDataUpdateFlags REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF = 128, REQUEST_PIXEL_ARGS_SET_SPECULAR_COEFF = 256, REQUEST_PIXEL_ARGS_HAS_FLAGS = 512, - REQUEST_PIXEL_ARGS_HAS_PROJECTIVE_TEXTURE_MATRICES = 1024, + REQUEST_PIXEL_ARGS_HAS_PROJECTIVE_TEXTURE_MATRICES = 1024 //don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h @@ -304,7 +304,7 @@ enum EnumRequestContactDataUpdateFlags CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_POSITION_A = 64, CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_POSITION_B = 128, CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_ORIENTATION_A = 256, - CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_ORIENTATION_B = 512, + CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_ORIENTATION_B = 512 }; @@ -378,7 +378,7 @@ enum EnumUpdateVisualShapeData CMD_UPDATE_VISUAL_SHAPE_TEXTURE = 1, CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR = 2, CMD_UPDATE_VISUAL_SHAPE_SPECULAR_COLOR = 4, - CMD_UPDATE_VISUAL_SHAPE_FLAGS = 8, + CMD_UPDATE_VISUAL_SHAPE_FLAGS = 8 }; @@ -481,7 +481,7 @@ enum EnumSimDesiredStateUpdateFlags SIM_DESIRED_STATE_HAS_KP = 8, SIM_DESIRED_STATE_HAS_MAX_FORCE = 16, SIM_DESIRED_STATE_HAS_RHS_CLAMP = 32, - SIM_DESIRED_STATE_HAS_DAMPING = 64, + SIM_DESIRED_STATE_HAS_DAMPING = 64 }; enum EnumSimParamUpdateFlags @@ -516,7 +516,7 @@ enum EnumSimParamUpdateFlags SIM_PARAM_UPDATE_WARM_STARTING_FACTOR = 1 << 27, SIM_PARAM_UPDATE_ARTICULATED_WARM_STARTING_FACTOR = 1 << 28, SIM_PARAM_UPDATE_SPARSE_SDF = 1 << 29, - SIM_PARAM_UPDATE_NUM_NONCONTACT_INNER_ITERATIONS = 1 << 30, + SIM_PARAM_UPDATE_NUM_NONCONTACT_INNER_ITERATIONS = 1 << 30 }; enum EnumLoadSoftBodyUpdateFlags @@ -539,12 +539,12 @@ enum EnumLoadSoftBodyUpdateFlags LOAD_SOFT_BODY_SIM_MESH = 1<<15, LOAD_SOFT_BODY_SET_REPULSION_STIFFNESS = 1<<16, LOAD_SOFT_BODY_SET_DAMPING_SPRING_MODE = 1<<17, - LOAD_SOFT_BODY_SET_GRAVITY_FACTOR = 1<<18, + LOAD_SOFT_BODY_SET_GRAVITY_FACTOR = 1<<18 }; enum EnumSimParamInternalSimFlags { - SIM_PARAM_INTERNAL_CREATE_ROBOT_ASSETS = 1, + SIM_PARAM_INTERNAL_CREATE_ROBOT_ASSETS = 1 }; ///Controlling a robot involves sending the desired state to its joint motor controllers. @@ -634,7 +634,7 @@ struct b3RequestCollisionInfoArgs enum EnumSensorTypes { SENSOR_FORCE_TORQUE = 1, - SENSOR_IMU = 2, + SENSOR_IMU = 2 }; struct CreateSensorArgs @@ -660,7 +660,7 @@ enum EnumBoxShapeFlags BOX_SHAPE_HAS_HALF_EXTENTS = 4, BOX_SHAPE_HAS_MASS = 8, BOX_SHAPE_HAS_COLLISION_SHAPE_TYPE = 16, - BOX_SHAPE_HAS_COLOR = 32, + BOX_SHAPE_HAS_COLOR = 32 }; ///This command will be replaced to allow arbitrary collision shape types struct CreateBoxShapeArgs @@ -717,7 +717,7 @@ enum EnumExternalForcePrivateFlags // EF_LINK_FRAME=1, // EF_WORLD_FRAME=2, EF_TORQUE = 4, - EF_FORCE = 8, + EF_FORCE = 8 }; struct ExternalForceArgs @@ -732,7 +732,7 @@ struct ExternalForceArgs enum EnumSdfRequestInfoFlags { - SDF_REQUEST_INFO_BODY = 1, + SDF_REQUEST_INFO_BODY = 1 //SDF_REQUEST_INFO_CAMERA=2, }; @@ -787,7 +787,7 @@ struct CalculateMassMatrixResultArgs enum b3EnumCollisionFilterFlags { B3_COLLISION_FILTER_PAIR = 1, - B3_COLLISION_FILTER_GROUP_MASK = 2, + B3_COLLISION_FILTER_GROUP_MASK = 2 }; struct b3CollisionFilterArgs @@ -829,7 +829,7 @@ struct CalculateInverseKinematicsResultArgs enum EnumBodyChangeFlags { - BODY_DELETE_FLAG = 1, + BODY_DELETE_FLAG = 1 }; enum EnumUserDebugDrawFlags @@ -847,7 +847,7 @@ enum EnumUserDebugDrawFlags USER_DEBUG_HAS_PARENT_OBJECT = 1024, USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID = 2048, USER_DEBUG_REMOVE_ALL_PARAMETERS = 4096, - USER_DEBUG_HAS_POINTS = 8192, + USER_DEBUG_HAS_POINTS = 8192 }; struct UserDebugDrawArgs @@ -911,7 +911,7 @@ enum eVRCameraEnums VR_CAMERA_ROOT_POSITION = 1, VR_CAMERA_ROOT_ORIENTATION = 2, VR_CAMERA_ROOT_TRACKING_OBJECT = 4, - VR_CAMERA_FLAG = 8, + VR_CAMERA_FLAG = 8 }; enum eStateLoggingEnums @@ -966,7 +966,7 @@ enum InternalOpenGLVisualizerUpdateFlags COV_SET_SHADOWMAP_WORLD_SIZE = 16, COV_SET_REMOTE_SYNC_TRANSFORM_INTERVAL = 32, COV_SET_SHADOWMAP_INTENSITY = 64, - COV_SET_RGB_BACKGROUND = 128, + COV_SET_RGB_BACKGROUND = 128 }; struct ConfigureOpenGLVisualizerRequest @@ -987,7 +987,7 @@ struct ConfigureOpenGLVisualizerRequest enum { - URDF_GEOM_HAS_RADIUS = 1, + URDF_GEOM_HAS_RADIUS = 1 }; struct b3CreateUserShapeData @@ -1045,7 +1045,7 @@ enum eCreateMultiBodyEnum { MULTI_BODY_HAS_BASE = 1, MULT_BODY_USE_MAXIMAL_COORDINATES = 2, - MULT_BODY_HAS_FLAGS = 4, + MULT_BODY_HAS_FLAGS = 4 }; struct b3CreateMultiBodyArgs { diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 4e3f6d3f3f..39f00900d0 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -121,7 +121,7 @@ enum EnumSharedMemoryClientCommand CMD_REQUEST_TETRA_MESH_DATA, //don't go beyond this command! - CMD_MAX_CLIENT_COMMANDS, + CMD_MAX_CLIENT_COMMANDS }; enum EnumSharedMemoryServerStatus @@ -255,7 +255,7 @@ enum EnumSharedMemoryServerStatus enum JointInfoFlags { - JOINT_HAS_MOTORIZED_POWER = 1, + JOINT_HAS_MOTORIZED_POWER = 1 }; enum @@ -286,7 +286,7 @@ enum b3JointInfoFlags { eJointChangeMaxForce = 1, eJointChangeChildFramePosition = 2, - eJointChangeChildFrameOrientation = 4, + eJointChangeChildFrameOrientation = 4 }; struct b3JointInfo @@ -317,7 +317,7 @@ enum UserDataValueType // Data represents generic byte array. USER_DATA_VALUE_TYPE_BYTES = 0, // Data represents C-string - USER_DATA_VALUE_TYPE_STRING = 1, + USER_DATA_VALUE_TYPE_STRING = 1 }; struct b3UserDataValue @@ -341,7 +341,7 @@ enum EnumUserConstraintFlags USER_CONSTRAINT_CHANGE_RELATIVE_POSITION_TARGET = 512, USER_CONSTRAINT_CHANGE_ERP = 1024, USER_CONSTRAINT_REQUEST_STATE = 2048, - USER_CONSTRAINT_ADD_SOFT_BODY_ANCHOR = 4096, + USER_CONSTRAINT_ADD_SOFT_BODY_ANCHOR = 4096 }; struct b3UserConstraint @@ -375,14 +375,14 @@ enum DynamicsActivationState eActivationStateWakeUp = 4, eActivationStateSleep = 8, eActivationStateEnableWakeup = 16, - eActivationStateDisableWakeup = 32, + eActivationStateDisableWakeup = 32 }; enum b3BodyType { BT_RIGID_BODY = 1, BT_MULTI_BODY = 2, - BT_SOFT_BODY = 3, + BT_SOFT_BODY = 3 }; struct b3DynamicsInfo @@ -411,7 +411,7 @@ struct b3DynamicsInfo // copied from btMultiBodyLink.h enum SensorType { - eSensorForceTorqueType = 1, + eSensorForceTorqueType = 1 }; struct b3JointSensorState @@ -471,13 +471,13 @@ enum eMeshDataFlags B3_MESH_DATA_SIMULATION_MESH = 1, B3_MESH_DATA_SIMULATION_INDICES = 2, B3_MESH_DATA_GRAPHICS_INDICES = 4, - B3_MESH_DATA_SIMULATION_MESH_VELOCITY = 8, + B3_MESH_DATA_SIMULATION_MESH_VELOCITY = 8 }; enum eMeshDataEnum { B3_MESH_DATA_COLLISIONSHAPEINDEX=1, - B3_MESH_DATA_FLAGS=2, + B3_MESH_DATA_FLAGS=2 }; struct b3MeshData @@ -488,7 +488,7 @@ struct b3MeshData enum eTetraMeshDataEnum { - B3_TETRA_MESH_DATA_FLAGS=2, + B3_TETRA_MESH_DATA_FLAGS=2 }; struct b3TetraMeshData @@ -527,7 +527,7 @@ enum b3VREventType VR_CONTROLLER_MOVE_EVENT = 1, VR_CONTROLLER_BUTTON_EVENT = 2, VR_HMD_MOVE_EVENT = 4, - VR_GENERIC_TRACKER_MOVE_EVENT = 8, + VR_GENERIC_TRACKER_MOVE_EVENT = 8 }; #define MAX_VR_ANALOG_AXIS 5 @@ -545,19 +545,19 @@ enum b3VRButtonInfo { eButtonIsDown = 1, eButtonTriggered = 2, - eButtonReleased = 4, + eButtonReleased = 4 }; enum eVRDeviceTypeEnums { VR_DEVICE_CONTROLLER = 1, VR_DEVICE_HMD = 2, - VR_DEVICE_GENERIC_TRACKER = 4, + VR_DEVICE_GENERIC_TRACKER = 4 }; enum EVRCameraFlags { - VR_CAMERA_TRACK_OBJECT_ORIENTATION = 1, + VR_CAMERA_TRACK_OBJECT_ORIENTATION = 1 }; struct b3VRControllerEvent @@ -596,7 +596,7 @@ struct b3KeyboardEventsData enum eMouseEventTypeEnums { MOUSE_MOVE_EVENT = 1, - MOUSE_BUTTON_EVENT = 2, + MOUSE_BUTTON_EVENT = 2 }; struct b3MouseEvent @@ -625,7 +625,7 @@ enum b3NotificationType VISUAL_SHAPE_CHANGED = 6, TRANSFORM_CHANGED = 7, SIMULATION_STEPPED = 8, - SOFTBODY_CHANGED = 9, + SOFTBODY_CHANGED = 9 }; enum b3ResetSimulationFlags @@ -633,7 +633,7 @@ enum b3ResetSimulationFlags RESET_USE_DEFORMABLE_WORLD=1, RESET_USE_DISCRETE_DYNAMICS_WORLD=2, RESET_USE_SIMPLE_BROADPHASE=4, - RESET_USE_REDUCED_DEFORMABLE_WORLD=8, + RESET_USE_REDUCED_DEFORMABLE_WORLD=8 }; struct b3BodyNotificationArgs @@ -715,7 +715,7 @@ struct b3ContactPointData enum { CONTACT_QUERY_MODE_REPORT_EXISTING_CONTACT_POINTS = 0, - CONTACT_QUERY_MODE_COMPUTE_CLOSEST_POINTS = 1, + CONTACT_QUERY_MODE_COMPUTE_CLOSEST_POINTS = 1 }; enum b3StateLoggingType @@ -729,7 +729,7 @@ enum b3StateLoggingType STATE_LOGGING_PROFILE_TIMINGS = 6, STATE_LOGGING_ALL_COMMANDS = 7, STATE_REPLAY_ALL_COMMANDS = 8, - STATE_LOGGING_CUSTOM_TIMER = 9, + STATE_LOGGING_CUSTOM_TIMER = 9 }; struct b3ContactInformation @@ -777,7 +777,7 @@ typedef union { enum b3VisualShapeDataFlags { - eVISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS = 1, + eVISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS = 1 }; struct b3VisualShapeData @@ -820,7 +820,7 @@ struct b3CollisionShapeInformation enum eLinkStateFlags { ACTUAL_STATE_COMPUTE_LINKVELOCITY = 1, - ACTUAL_STATE_COMPUTE_FORWARD_KINEMATICS = 2, + ACTUAL_STATE_COMPUTE_FORWARD_KINEMATICS = 2 }; ///b3LinkState provides extra information such as the Cartesian world coordinates @@ -856,21 +856,21 @@ enum CONTROL_MODE_TORQUE, CONTROL_MODE_POSITION_VELOCITY_PD, CONTROL_MODE_PD, // The standard PD control implemented as soft constraint. - CONTROL_MODE_STABLE_PD, + CONTROL_MODE_STABLE_PD }; ///flags for b3ApplyExternalTorque and b3ApplyExternalForce enum EnumExternalForceFlags { EF_LINK_FRAME = 1, - EF_WORLD_FRAME = 2, + EF_WORLD_FRAME = 2 }; ///flags to pick the renderer for synthetic camera enum EnumRenderer { ER_TINY_RENDERER = (1 << 16), - ER_BULLET_HARDWARE_OPENGL = (1 << 17), + ER_BULLET_HARDWARE_OPENGL = (1 << 17) //ER_FIRE_RAYS=(1<<18), }; @@ -878,7 +878,7 @@ enum EnumRendererAuxFlags { ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX = 1, ER_USE_PROJECTIVE_TEXTURE = 2, - ER_NO_SEGMENTATION_MASK = 4, + ER_NO_SEGMENTATION_MASK = 4 }; ///flags to pick the IK solver and other options @@ -892,7 +892,7 @@ enum EnumCalculateInverseKinematicsFlags IK_HAS_JOINT_DAMPING = 128, IK_HAS_CURRENT_JOINT_POSITIONS = 256, IK_HAS_MAX_ITERATIONS = 512, - IK_HAS_RESIDUAL_THRESHOLD = 1024, + IK_HAS_RESIDUAL_THRESHOLD = 1024 }; enum b3ConfigureDebugVisualizerEnum @@ -913,14 +913,14 @@ enum b3ConfigureDebugVisualizerEnum COV_ENABLE_DEPTH_BUFFER_PREVIEW, COV_ENABLE_SEGMENTATION_MARK_PREVIEW, COV_ENABLE_PLANAR_REFLECTION, - COV_ENABLE_SINGLE_STEP_RENDERING, + COV_ENABLE_SINGLE_STEP_RENDERING }; enum b3AddUserDebugItemEnum { DEB_DEBUG_TEXT_ALWAYS_FACE_CAMERA = 1, DEB_DEBUG_TEXT_USE_TRUE_TYPE_FONTS = 2, - DEB_DEBUG_TEXT_HAS_TRACKING_OBJECT = 4, + DEB_DEBUG_TEXT_HAS_TRACKING_OBJECT = 4 }; enum eCONNECT_METHOD @@ -967,7 +967,7 @@ enum eURDF_Flags URDF_IGNORE_VISUAL_SHAPES = 1 << 20, URDF_IGNORE_COLLISION_SHAPES = 1 << 21, URDF_PRINT_URDF_INFO = 1 << 22, - URDF_GOOGLEY_UNDEFINED_COLORS = 1 << 23, + URDF_GOOGLEY_UNDEFINED_COLORS = 1 << 23 }; enum eUrdfGeomTypes //sync with UrdfParser UrdfGeomTypes @@ -980,33 +980,33 @@ enum eUrdfGeomTypes //sync with UrdfParser UrdfGeomTypes GEOM_CAPSULE, //non-standard URDF? GEOM_SDF, //signed-distance-field, non-standard URDF GEOM_HEIGHTFIELD, - GEOM_UNKNOWN, + GEOM_UNKNOWN }; enum eUrdfCollisionFlags { GEOM_FORCE_CONCAVE_TRIMESH = 1, GEOM_CONCAVE_INTERNAL_EDGE = 2, - GEOM_INITIALIZE_SAT_FEATURES = URDF_INITIALIZE_SAT_FEATURES, + GEOM_INITIALIZE_SAT_FEATURES = URDF_INITIALIZE_SAT_FEATURES }; enum eUrdfVisualFlags { GEOM_VISUAL_HAS_RGBA_COLOR = 1, - GEOM_VISUAL_HAS_SPECULAR_COLOR = 2, + GEOM_VISUAL_HAS_SPECULAR_COLOR = 2 }; enum eStateLoggingFlags { STATE_LOG_JOINT_MOTOR_TORQUES = 1, STATE_LOG_JOINT_USER_TORQUES = 2, - STATE_LOG_JOINT_TORQUES = STATE_LOG_JOINT_MOTOR_TORQUES + STATE_LOG_JOINT_USER_TORQUES, + STATE_LOG_JOINT_TORQUES = STATE_LOG_JOINT_MOTOR_TORQUES + STATE_LOG_JOINT_USER_TORQUES }; enum eJointFeedbackModes { JOINT_FEEDBACK_IN_WORLD_SPACE = 1, - JOINT_FEEDBACK_IN_JOINT_FRAME = 2, + JOINT_FEEDBACK_IN_JOINT_FRAME = 2 }; #define B3_MAX_PLUGIN_ARG_SIZE 128 @@ -1024,7 +1024,7 @@ struct b3PluginArguments enum eInternalSimFlags { eVRTinyGUI = 1<<1, - eDeformableAlternativeIndexing = 1<<2, + eDeformableAlternativeIndexing = 1<<2 }; struct b3PhysicsSimulationParameters @@ -1071,7 +1071,7 @@ enum eConstraintSolverTypes eConstraintSolverLCP_DANTZIG, eConstraintSolverLCP_LEMKE, eConstraintSolverLCP_NNCG, - eConstraintSolverLCP_BLOCK_PGS, + eConstraintSolverLCP_BLOCK_PGS }; struct b3ForwardDynamicsAnalyticsIslandData @@ -1103,7 +1103,7 @@ enum eDynamicTypes enum eFileIOActions { eAddFileIOAction = 1024,//avoid collision with eFileIOTypes - eRemoveFileIOAction, + eRemoveFileIOAction }; @@ -1112,12 +1112,12 @@ enum eFileIOTypes ePosixFileIO = 1, eZipFileIO, eCNSFileIO, - eInMemoryFileIO, + eInMemoryFileIO }; enum eEnumUpdateVisualShapeFlags { - eVISUAL_SHAPE_DOUBLE_SIDED = 4,//see B3_INSTANCE_DOUBLE_SIDED + eVISUAL_SHAPE_DOUBLE_SIDED = 4//see B3_INSTANCE_DOUBLE_SIDED }; //limits for vertices/indices in PyBullet::createCollisionShape diff --git a/examples/SharedMemory/b3PluginManager.h b/examples/SharedMemory/b3PluginManager.h index 240c3e2fc6..a0c8c6fb39 100644 --- a/examples/SharedMemory/b3PluginManager.h +++ b/examples/SharedMemory/b3PluginManager.h @@ -7,7 +7,7 @@ enum b3PluginManagerTickMode { B3_PRE_TICK_MODE = 1, B3_POST_TICK_MODE, - B3_PROCESS_CLIENT_COMMANDS_TICK, + B3_PROCESS_CLIENT_COMMANDS_TICK }; struct b3PluginFunctions diff --git a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h index 5c8f9e2ff8..f45ae8df4e 100644 --- a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h +++ b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h @@ -207,7 +207,7 @@ enum b3RobotSimulatorInverseKinematicsFlags B3_HAS_IK_TARGET_ORIENTATION = 1, B3_HAS_NULL_SPACE_VELOCITY = 2, B3_HAS_JOINT_DAMPING = 4, - B3_HAS_CURRENT_POSITIONS = 8, + B3_HAS_CURRENT_POSITIONS = 8 }; struct b3RobotSimulatorInverseKinematicArgs diff --git a/examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h b/examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h index f573949554..8d132cf48d 100644 --- a/examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h +++ b/examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h @@ -17,7 +17,7 @@ extern "C" enum PDControlCommandEnum { eSetPDControl = 1, - eRemovePDControl = 2, + eRemovePDControl = 2 }; //all the APIs below are optional diff --git a/examples/SharedMemory/plugins/stablePDPlugin/Shape.h b/examples/SharedMemory/plugins/stablePDPlugin/Shape.h index e58fdf0677..1088e4cbdb 100644 --- a/examples/SharedMemory/plugins/stablePDPlugin/Shape.h +++ b/examples/SharedMemory/plugins/stablePDPlugin/Shape.h @@ -13,7 +13,7 @@ class cShape eShapeSphere, eShapeCylinder, eShapePlane, - eShapeMax, + eShapeMax }; static bool ParseShape(const std::string& str, cShape::eShape& out_shape); diff --git a/examples/ThirdPartyLibs/Gwen/Controls/Base.h b/examples/ThirdPartyLibs/Gwen/Controls/Base.h index 367069c593..ef77b0e76f 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/Base.h +++ b/examples/ThirdPartyLibs/Gwen/Controls/Base.h @@ -44,7 +44,7 @@ enum CenterV = (1 << 5), CenterH = (1 << 6), Fill = (1 << 7), - Center = CenterV | CenterH, + Center = CenterV | CenterH }; } diff --git a/examples/ThirdPartyLibs/Gwen/Controls/TreeNode.h b/examples/ThirdPartyLibs/Gwen/Controls/TreeNode.h index c86812e064..cb98e09d11 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/TreeNode.h +++ b/examples/ThirdPartyLibs/Gwen/Controls/TreeNode.h @@ -18,7 +18,7 @@ enum ITERATE_ACTION_CLOSE, ITERATE_ACTION_FIND_SELECTED_INDEX, ITERATE_ACTION_DESELECT_INDEX, - ITERATE_ACTION_SELECT, + ITERATE_ACTION_SELECT }; namespace Gwen diff --git a/examples/Tutorial/Tutorial.cpp b/examples/Tutorial/Tutorial.cpp index 7fd3ecd733..788b4bcf61 100644 --- a/examples/Tutorial/Tutorial.cpp +++ b/examples/Tutorial/Tutorial.cpp @@ -118,7 +118,7 @@ void ComputeClosestPointsSphereSphere(const LWSphere& sphereA, const LWPose& sph enum LWRIGIDBODY_FLAGS { - LWFLAG_USE_QUATERNION_DERIVATIVE = 1, + LWFLAG_USE_QUATERNION_DERIVATIVE = 1 }; struct LWRigidBody diff --git a/examples/Tutorial/Tutorial.h b/examples/Tutorial/Tutorial.h index 33aee0a2be..5c4b56312b 100644 --- a/examples/Tutorial/Tutorial.h +++ b/examples/Tutorial/Tutorial.h @@ -6,7 +6,7 @@ enum EnumTutorialTypes TUT_VELOCITY = 0, TUT_ACCELERATION, TUT_COLLISION, - TUT_SOLVE_CONTACT_CONSTRAINT, + TUT_SOLVE_CONTACT_CONSTRAINT }; class CommonExampleInterface* TutorialCreateFunc(struct CommonExampleOptions& options); diff --git a/examples/Utils/RobotLoggingUtil.h b/examples/Utils/RobotLoggingUtil.h index 02d3e3c614..caf8cdc037 100644 --- a/examples/Utils/RobotLoggingUtil.h +++ b/examples/Utils/RobotLoggingUtil.h @@ -41,7 +41,7 @@ enum MINITAUR_LOG_ERROR eCorruptHeader = -2, eUnknownType = -3, eCorruptValue = -4, - eInvalidAABBAlignCheck = -5, + eInvalidAABBAlignCheck = -5 }; int readMinitaurLogFile(const char* fileName, btAlignedObjectArray& structNames, std::string& structTypes, btAlignedObjectArray& logRecords, bool verbose); diff --git a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3Collidable.h b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3Collidable.h index 9a8c668af2..947012c49a 100644 --- a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3Collidable.h +++ b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3Collidable.h @@ -14,7 +14,7 @@ enum b3ShapeTypes SHAPE_CONCAVE_TRIMESH = 5, SHAPE_COMPOUND_OF_CONVEX_HULLS = 6, SHAPE_SPHERE = 7, - MAX_NUM_SHAPE_TYPES, + MAX_NUM_SHAPE_TYPES }; typedef struct b3Collidable b3Collidable_t; diff --git a/src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.h b/src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.h index 0d633e3d23..5b22169186 100644 --- a/src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.h +++ b/src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.h @@ -34,7 +34,7 @@ class b3BoundSearchCL { BOUND_LOWER, BOUND_UPPER, - COUNT, + COUNT }; cl_context m_context; diff --git a/src/Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.h b/src/Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.h index 69caf182d7..f36d03669a 100644 --- a/src/Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.h +++ b/src/Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.h @@ -60,7 +60,7 @@ class b3RadixSort32CL BITS_PER_PASS = 4, NUM_BUCKET = (1 << BITS_PER_PASS), // if you change this, change nPerWI in kernel as well - NUM_WGS = 20 * 6, // cypress + NUM_WGS = 20 * 6 // cypress // NUM_WGS = 24*6, // cayman // NUM_WGS = 32*4, // nv }; diff --git a/src/Bullet3OpenCL/RigidBody/b3GpuGenericConstraint.h b/src/Bullet3OpenCL/RigidBody/b3GpuGenericConstraint.h index 1f163ba7d5..b652a1253a 100644 --- a/src/Bullet3OpenCL/RigidBody/b3GpuGenericConstraint.h +++ b/src/Bullet3OpenCL/RigidBody/b3GpuGenericConstraint.h @@ -20,7 +20,7 @@ subject to the following restrictions: struct b3RigidBodyData; enum B3_CONSTRAINT_FLAGS { - B3_CONSTRAINT_FLAG_ENABLED = 1, + B3_CONSTRAINT_FLAG_ENABLED = 1 }; enum b3GpuGenericConstraintType @@ -125,4 +125,4 @@ b3GpuGenericConstraint void getInfo2(b3GpuConstraintInfo2 * info, const b3RigidBodyData* bodies); }; -#endif //B3_GPU_GENERIC_CONSTRAINT_H \ No newline at end of file +#endif //B3_GPU_GENERIC_CONSTRAINT_H diff --git a/src/Bullet3OpenCL/RigidBody/b3Solver.h b/src/Bullet3OpenCL/RigidBody/b3Solver.h index ee63531d78..98e755eddc 100644 --- a/src/Bullet3OpenCL/RigidBody/b3Solver.h +++ b/src/Bullet3OpenCL/RigidBody/b3Solver.h @@ -37,7 +37,7 @@ enum B3_SOLVER_N_SPLIT_Z = 8, //, B3_SOLVER_N_CELLS = B3_SOLVER_N_SPLIT_X * B3_SOLVER_N_SPLIT_Y * B3_SOLVER_N_SPLIT_Z, B3_SOLVER_N_BATCHES = 8, //4,//8,//4, - B3_MAX_NUM_BATCHES = 128, + B3_MAX_NUM_BATCHES = 128 }; class b3SolverBase @@ -86,7 +86,7 @@ class b3Solver : public b3SolverBase enum { - DYNAMIC_CONTACT_ALLOCATION_THRESHOLD = 2000000, + DYNAMIC_CONTACT_ALLOCATION_THRESHOLD = 2000000 }; b3Solver(cl_context ctx, cl_device_id device, cl_command_queue queue, int pairCapacity); diff --git a/src/Bullet3Serialize/Bullet2FileLoader/b3File.h b/src/Bullet3Serialize/Bullet2FileLoader/b3File.h index bda229cfbd..260c2a158a 100644 --- a/src/Bullet3Serialize/Bullet2FileLoader/b3File.h +++ b/src/Bullet3Serialize/Bullet2FileLoader/b3File.h @@ -41,7 +41,7 @@ enum bFileVerboseMode FD_VERBOSE_EXPORT_XML = 1, FD_VERBOSE_DUMP_DNA_TYPE_DEFINITIONS = 2, FD_VERBOSE_DUMP_CHUNKS = 4, - FD_VERBOSE_DUMP_FILE_INFO = 8, + FD_VERBOSE_DUMP_FILE_INFO = 8 }; // ----------------------------------------------------- // class bFile diff --git a/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h b/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h index 1d49c1539e..a2b7ec96ca 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h +++ b/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h @@ -43,7 +43,7 @@ enum btContactPointFlags BT_CONTACT_FLAG_HAS_CONTACT_CFM = 2, BT_CONTACT_FLAG_HAS_CONTACT_ERP = 4, BT_CONTACT_FLAG_CONTACT_STIFFNESS_DAMPING = 8, - BT_CONTACT_FLAG_FRICTION_ANCHOR = 16, + BT_CONTACT_FLAG_FRICTION_ANCHOR = 16 }; /// ManifoldContactPoint collects and maintains persistent contactpoints. diff --git a/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h b/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h index 0eb1888fd9..0b4b7edf9b 100644 --- a/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h +++ b/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h @@ -35,7 +35,7 @@ enum btConstraintSolverType BT_MLCP_SOLVER = 2, BT_NNCG_SOLVER = 4, BT_MULTIBODY_SOLVER = 8, - BT_BLOCK_SOLVER = 16, + BT_BLOCK_SOLVER = 16 }; class btConstraintSolver diff --git a/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h b/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h index 630416776d..e824f648e1 100644 --- a/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h +++ b/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h @@ -31,7 +31,7 @@ enum btSolverMode SOLVER_INTERLEAVE_CONTACT_AND_FRICTION_CONSTRAINTS = 512, SOLVER_ALLOW_ZERO_LENGTH_FRICTION_DIRECTIONS = 1024, SOLVER_DISABLE_IMPLICIT_CONE_FRICTION = 2048, - SOLVER_USE_ARTICULATED_WARMSTARTING = 4096, + SOLVER_USE_ARTICULATED_WARMSTARTING = 4096 }; struct btContactSolverInfoData diff --git a/src/BulletDynamics/Dynamics/btRigidBody.h b/src/BulletDynamics/Dynamics/btRigidBody.h index f695c65d85..6122d3699a 100644 --- a/src/BulletDynamics/Dynamics/btRigidBody.h +++ b/src/BulletDynamics/Dynamics/btRigidBody.h @@ -46,7 +46,7 @@ enum btRigidBodyFlags BT_ENABLE_GYROSCOPIC_FORCE_EXPLICIT = 2, BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_WORLD = 4, BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY = 8, - BT_ENABLE_GYROPSCOPIC_FORCE = BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY, + BT_ENABLE_GYROPSCOPIC_FORCE = BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY }; ///The btRigidBody is the main class for rigid body objects. It is derived from btCollisionObject, so it keeps a pointer to a btCollisionShape. diff --git a/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h b/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h index f23d45801a..e9b2f03a1c 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h @@ -32,7 +32,7 @@ enum btTypedMultiBodyConstraintType MULTIBODY_CONSTRAINT_SPHERICAL_MOTOR, MULTIBODY_CONSTRAINT_FIXED, MULTIBODY_CONSTRAINT_SPHERICAL_LIMIT, - MAX_MULTIBODY_CONSTRAINT_TYPE, + MAX_MULTIBODY_CONSTRAINT_TYPE }; class btMultiBody; diff --git a/src/BulletDynamics/Featherstone/btMultiBodyLink.h b/src/BulletDynamics/Featherstone/btMultiBodyLink.h index 5a1429340f..f29f43a013 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyLink.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyLink.h @@ -23,7 +23,7 @@ subject to the following restrictions: enum btMultiBodyLinkFlags { BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION = 1, - BT_MULTIBODYLINKFLAGS_DISABLE_ALL_PARENT_COLLISION = 2, + BT_MULTIBODYLINKFLAGS_DISABLE_ALL_PARENT_COLLISION = 2 }; //both defines are now permanently enabled diff --git a/src/LinearMath/TaskScheduler/btTaskScheduler.cpp b/src/LinearMath/TaskScheduler/btTaskScheduler.cpp index 8d92b5ccf8..41ea85bba3 100644 --- a/src/LinearMath/TaskScheduler/btTaskScheduler.cpp +++ b/src/LinearMath/TaskScheduler/btTaskScheduler.cpp @@ -37,7 +37,7 @@ struct WorkerThreadStatus kInvalid, kWaitingForWork, kWorking, - kSleeping, + kSleeping }; }; @@ -54,7 +54,7 @@ WorkerThreadDirectives kInvalid, kGoToSleep, // go to sleep kStayAwakeButIdle, // wait for not checking job queue - kScanForJobs, // actively scan job queue for jobs + kScanForJobs // actively scan job queue for jobs }; WorkerThreadDirectives() { diff --git a/src/LinearMath/btSerializer.h b/src/LinearMath/btSerializer.h index 07503bb3cd..301b6c9680 100644 --- a/src/LinearMath/btSerializer.h +++ b/src/LinearMath/btSerializer.h @@ -60,7 +60,7 @@ enum btSerializationFlags BT_SERIALIZE_NO_BVH = 1, BT_SERIALIZE_NO_TRIANGLEINFOMAP = 2, BT_SERIALIZE_NO_DUPLICATE_ASSERT = 4, - BT_SERIALIZE_CONTACT_MANIFOLDS = 8, + BT_SERIALIZE_CONTACT_MANIFOLDS = 8 }; class btSerializer From 4f6cf882094397a6efe87d7c7fd8e3cfeb933920 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 02:41:13 +0100 Subject: [PATCH 37/57] Compiler warnings - comma at end of enum - openvr --- .../ThirdPartyLibs/openvr/headers/openvr.h | 82 +++++++++---------- 1 file changed, 41 insertions(+), 41 deletions(-) diff --git a/examples/ThirdPartyLibs/openvr/headers/openvr.h b/examples/ThirdPartyLibs/openvr/headers/openvr.h index f9dd38b11c..00afec6c14 100644 --- a/examples/ThirdPartyLibs/openvr/headers/openvr.h +++ b/examples/ThirdPartyLibs/openvr/headers/openvr.h @@ -109,14 +109,14 @@ enum ETextureType TextureType_OpenGL = 1, // Handle is an OpenGL texture name or an OpenGL render buffer name, depending on submit flags TextureType_Vulkan = 2, // Handle is a pointer to a VRVulkanTextureData_t structure TextureType_IOSurface = 3, // Handle is a macOS cross-process-sharable IOSurfaceRef - TextureType_DirectX12 = 4, // Handle is a pointer to a D3D12TextureData_t structure + TextureType_DirectX12 = 4 // Handle is a pointer to a D3D12TextureData_t structure }; enum EColorSpace { ColorSpace_Auto = 0, // Assumes 'gamma' for 8-bit per component formats, otherwise 'linear'. This mirrors the DXGI formats which have _SRGB variants. ColorSpace_Gamma = 1, // Texture data can be displayed directly on the display without any conversion (a.k.a. display native format). - ColorSpace_Linear = 2, // Same as gamma but has been converted to a linear representation using DXGI's sRGB conversion algorithm. + ColorSpace_Linear = 2 // Same as gamma but has been converted to a linear representation using DXGI's sRGB conversion algorithm. }; struct Texture_t @@ -138,7 +138,7 @@ enum ETrackingResult TrackingResult_Calibrating_OutOfRange = 101, TrackingResult_Running_OK = 200, - TrackingResult_Running_OutOfRange = 201, + TrackingResult_Running_OutOfRange = 201 }; typedef uint32_t DriverId_t; @@ -161,7 +161,7 @@ enum ETrackedDeviceClass TrackedDeviceClass_Controller = 2, // Tracked controllers TrackedDeviceClass_GenericTracker = 3, // Generic trackers, similar to controllers TrackedDeviceClass_TrackingReference = 4, // Camera and base stations that serve as tracking reference points - TrackedDeviceClass_DisplayRedirect = 5, // Accessories that aren't necessarily tracked themselves, but may redirect video output from other tracked devices + TrackedDeviceClass_DisplayRedirect = 5 // Accessories that aren't necessarily tracked themselves, but may redirect video output from other tracked devices }; /** Describes what specific role associated with a tracked device */ @@ -169,7 +169,7 @@ enum ETrackedControllerRole { TrackedControllerRole_Invalid = 0, // Invalid value for controller type TrackedControllerRole_LeftHand = 1, // Tracked device associated with the left hand - TrackedControllerRole_RightHand = 2, // Tracked device associated with the right hand + TrackedControllerRole_RightHand = 2 // Tracked device associated with the right hand }; /** describes a single pose for a tracked object */ @@ -192,7 +192,7 @@ enum ETrackingUniverseOrigin { TrackingUniverseSeated = 0, // Poses are provided relative to the seated zero pose TrackingUniverseStanding = 1, // Poses are provided relative to the safe bounds configured by the user - TrackingUniverseRawAndUncalibrated = 2, // Poses are provided in the coordinate system defined by the driver. It has Y up and is unified for devices of the same driver. You usually don't want this one. + TrackingUniverseRawAndUncalibrated = 2 // Poses are provided in the coordinate system defined by the driver. It has Y up and is unified for devices of the same driver. You usually don't want this one. }; // Refers to a single container of properties @@ -357,7 +357,7 @@ enum ETrackedDeviceProperty // Vendors are free to expose private debug data in this reserved region Prop_VendorSpecific_Reserved_Start = 10000, - Prop_VendorSpecific_Reserved_End = 10999, + Prop_VendorSpecific_Reserved_End = 10999 }; /** No string property will ever be longer than this length */ @@ -377,7 +377,7 @@ enum ETrackedPropertyError TrackedProp_StringExceedsMaximumLength = 8, TrackedProp_NotYetAvailable = 9, // The property value isn't known yet, but is expected soon. Call again later. TrackedProp_PermissionDenied = 10, - TrackedProp_InvalidOperation = 11, + TrackedProp_InvalidOperation = 11 }; /** Allows the application to control what part of the provided texture will be used in the @@ -412,7 +412,7 @@ enum EVRSubmitFlags Submit_Reserved = 0x04, // Set to indicate that pTexture is a pointer to a VRTextureWithPose_t. - Submit_TextureWithPose = 0x08, + Submit_TextureWithPose = 0x08 }; /** Data required for passing Vulkan textures to IVRCompositor::Submit. @@ -448,7 +448,7 @@ enum EVRState VRState_Ready_Alert = 4, VRState_NotReady = 5, VRState_Standby = 6, - VRState_Ready_Alert_Low = 7, + VRState_Ready_Alert_Low = 7 }; /** The types of events that could be posted (and what the parameters mean for each event type) */ @@ -593,7 +593,7 @@ enum EVREventType // Vendors are free to expose private events in this reserved region VREvent_VendorSpecific_Reserved_Start = 10000, - VREvent_VendorSpecific_Reserved_End = 19999, + VREvent_VendorSpecific_Reserved_End = 19999 }; /** Level of Hmd activity */ @@ -607,7 +607,7 @@ enum EDeviceActivityLevel k_EDeviceActivityLevel_Idle = 0, // No activity for the last 10 seconds k_EDeviceActivityLevel_UserInteraction = 1, // Activity (movement or prox sensor) is happening now k_EDeviceActivityLevel_UserInteraction_Timeout = 2, // No activity for the last 0.5 seconds - k_EDeviceActivityLevel_Standby = 3, // Idle for at least 5 seconds (configurable in Settings -> Power Management) + k_EDeviceActivityLevel_Standby = 3 // Idle for at least 5 seconds (configurable in Settings -> Power Management) }; /** VR controller button and axis IDs */ @@ -652,7 +652,7 @@ enum EVRMouseButton { VRMouseButton_Left = 0x0001, VRMouseButton_Right = 0x0002, - VRMouseButton_Middle = 0x0004, + VRMouseButton_Middle = 0x0004 }; /** used for simulated mouse events in overlay space */ @@ -847,7 +847,7 @@ enum EHiddenAreaMeshType k_eHiddenAreaMesh_Inverse = 1, k_eHiddenAreaMesh_LineLoop = 2, - k_eHiddenAreaMesh_Max = 3, + k_eHiddenAreaMesh_Max = 3 }; /** Identifies what kind of axis is on the controller at index n. Read this type @@ -858,7 +858,7 @@ enum EVRControllerAxisType k_eControllerAxis_None = 0, k_eControllerAxis_TrackPad = 1, k_eControllerAxis_Joystick = 2, - k_eControllerAxis_Trigger = 3, // Analog trigger data is in the X axis + k_eControllerAxis_Trigger = 3 // Analog trigger data is in the X axis }; /** contains information about one axis on the controller */ @@ -901,7 +901,7 @@ typedef VRControllerState001_t VRControllerState_t; enum EVRControllerEventOutputType { ControllerEventOutput_OSEvents = 0, - ControllerEventOutput_VREvents = 1, + ControllerEventOutput_VREvents = 1 }; /** Collision Bounds Style */ @@ -956,7 +956,7 @@ enum EVROverlayError VROverlayError_KeyboardAlreadyInUse = 26, VROverlayError_NoNeighbor = 27, VROverlayError_TooManyMaskPrimitives = 29, - VROverlayError_BadMaskPrimitive = 30, + VROverlayError_BadMaskPrimitive = 30 }; /** enum values to pass in to VR_Init to identify whether the application will @@ -982,7 +982,7 @@ enum EVRFirmwareError { VRFirmwareError_None = 0, VRFirmwareError_Success = 1, - VRFirmwareError_Fail = 2, + VRFirmwareError_Fail = 2 }; /** error codes for notifications */ @@ -992,7 +992,7 @@ enum EVRNotificationError VRNotificationError_InvalidNotificationId = 100, VRNotificationError_NotificationQueueFull = 101, VRNotificationError_InvalidOverlayHandle = 102, - VRNotificationError_SystemWithUserValueAlreadyExists = 103, + VRNotificationError_SystemWithUserValueAlreadyExists = 103 }; /** error codes returned by Vr_Init */ @@ -1091,7 +1091,7 @@ enum EVRInitError VRInitError_VendorSpecific_HmdFound_UserDataError = 1112, VRInitError_VendorSpecific_HmdFound_ConfigFailedSanityCheck = 1113, - VRInitError_Steam_SteamInstallationNotFound = 2000, + VRInitError_Steam_SteamInstallationNotFound = 2000 }; enum EVRScreenshotType @@ -1107,7 +1107,7 @@ enum EVRScreenshotType enum EVRScreenshotPropertyFilenames { VRScreenshotPropertyFilenames_Preview = 0, - VRScreenshotPropertyFilenames_VR = 1, + VRScreenshotPropertyFilenames_VR = 1 }; enum EVRTrackedCameraError @@ -1128,7 +1128,7 @@ enum EVRTrackedCameraError VRTrackedCameraError_SharedTextureFailure = 112, VRTrackedCameraError_NoFrameAvailable = 113, VRTrackedCameraError_InvalidArgument = 114, - VRTrackedCameraError_InvalidFrameBufferSize = 115, + VRTrackedCameraError_InvalidFrameBufferSize = 115 }; enum EVRTrackedCameraFrameType @@ -1527,7 +1527,7 @@ enum EVRApplicationError VRApplicationError_BufferTooSmall = 200, // The provided buffer was too small to fit the requested data VRApplicationError_PropertyNotSet = 201, // The requested property was not set VRApplicationError_UnknownProperty = 202, - VRApplicationError_InvalidParameter = 203, + VRApplicationError_InvalidParameter = 203 }; /** The maximum length of an application key */ @@ -1555,7 +1555,7 @@ enum EVRApplicationProperty VRApplicationProperty_IsInternal_Bool = 63, VRApplicationProperty_WantsCompositorPauseInStandby_Bool = 64, - VRApplicationProperty_LastLaunchTime_Uint64 = 70, + VRApplicationProperty_LastLaunchTime_Uint64 = 70 }; /** These are states the scene application startup process will go through. */ @@ -1566,7 +1566,7 @@ enum EVRApplicationTransitionState VRApplicationTransition_OldAppQuitSent = 10, VRApplicationTransition_WaitingForExternalLaunch = 11, - VRApplicationTransition_NewAppLaunched = 20, + VRApplicationTransition_NewAppLaunched = 20 }; struct AppOverrideKeys_t @@ -1721,7 +1721,7 @@ enum EVRSettingsError VRSettingsError_WriteFailed = 2, VRSettingsError_ReadFailed = 3, VRSettingsError_JsonParseFailed = 4, - VRSettingsError_UnsetSettingHasNoDefault = 5, // This will be returned if the setting does not appear in the appropriate default file and has not been set + VRSettingsError_UnsetSettingHasNoDefault = 5 // This will be returned if the setting does not appear in the appropriate default file and has not been set }; // The maximum length of a settings key @@ -1942,7 +1942,7 @@ enum ChaperoneCalibrationState ChaperoneCalibrationState_Error_BaseStationUninitialized = 201, // Tracking center hasn't be calibrated for at least one of the base stations ChaperoneCalibrationState_Error_BaseStationConflict = 202, // Tracking center is calibrated, but base stations disagree on the tracking space ChaperoneCalibrationState_Error_PlayAreaInvalid = 203, // Play Area hasn't been calibrated for the current tracking center - ChaperoneCalibrationState_Error_CollisionBoundsInvalid = 204, // Collision Bounds haven't been calibrated for the current tracking center + ChaperoneCalibrationState_Error_CollisionBoundsInvalid = 204 // Collision Bounds haven't been calibrated for the current tracking center }; /** HIGH LEVEL TRACKING SPACE ASSUMPTIONS: @@ -1995,12 +1995,12 @@ namespace vr enum EChaperoneConfigFile { EChaperoneConfigFile_Live = 1, // The live chaperone config, used by most applications and games - EChaperoneConfigFile_Temp = 2, // The temporary chaperone config, used to live-preview collision bounds in room setup + EChaperoneConfigFile_Temp = 2 // The temporary chaperone config, used to live-preview collision bounds in room setup }; enum EChaperoneImportFlags { - EChaperoneImport_BoundsOnly = 0x0001, + EChaperoneImport_BoundsOnly = 0x0001 }; /** Manages the working copy of the chaperone info. By default this will be the same as the @@ -2095,7 +2095,7 @@ enum EVRCompositorError VRCompositorError_SharedTexturesNotSupported = 106, VRCompositorError_IndexOutOfRange = 107, VRCompositorError_AlreadySubmitted = 108, - VRCompositorError_InvalidBounds = 109, + VRCompositorError_InvalidBounds = 109 }; const uint32_t VRCompositor_ReprojectionReason_Cpu = 0x01; @@ -2408,7 +2408,7 @@ enum EVRNotificationType /** System notifications are shown no matter what. It is expected, that the ulUserValue is used as ID. * If there is already a system notification in the queue with that ID it is not accepted into the queue * to prevent spamming with system notification */ - EVRNotificationType_Transient_SystemWithUserValue = 2, + EVRNotificationType_Transient_SystemWithUserValue = 2 }; enum EVRNotificationStyle @@ -2426,7 +2426,7 @@ enum EVRNotificationStyle EVRNotificationStyle_Contact_Enabled = 201, /** Used for notifications about contacts that are available and active. In Steam this is used for friends that are online and currently running a game. */ - EVRNotificationStyle_Contact_Active = 202, + EVRNotificationStyle_Contact_Active = 202 }; static const uint32_t k_unNotificationTextMaxSize = 256; @@ -2473,7 +2473,7 @@ static const uint32_t k_unMaxOverlayIntersectionMaskPrimitivesCount = 32; enum VROverlayInputMethod { VROverlayInputMethod_None = 0, // No input events will be generated automatically for this overlay - VROverlayInputMethod_Mouse = 1, // Tracked controllers will get mouse events automatically + VROverlayInputMethod_Mouse = 1 // Tracked controllers will get mouse events automatically }; /** Allows the caller to figure out which overlay transform getter to call. */ @@ -2482,7 +2482,7 @@ enum VROverlayTransformType VROverlayTransform_Absolute = 0, VROverlayTransform_TrackedDeviceRelative = 1, VROverlayTransform_SystemOverlay = 2, - VROverlayTransform_TrackedComponent = 3, + VROverlayTransform_TrackedComponent = 3 }; /** Overlay control settings */ @@ -2527,7 +2527,7 @@ enum VROverlayFlags VROverlayFlags_SortWithNonSceneOverlays = 14, // If set, the overlay will be shown in the dashboard, otherwise it will be hidden. - VROverlayFlags_VisibleInDashboard = 15, + VROverlayFlags_VisibleInDashboard = 15 }; enum VRMessageOverlayResponse @@ -2561,7 +2561,7 @@ enum EGamepadTextInputMode { k_EGamepadTextInputModeNormal = 0, k_EGamepadTextInputModePassword = 1, - k_EGamepadTextInputModeSubmit = 2, + k_EGamepadTextInputModeSubmit = 2 }; // Controls number of allowed lines for the Big Picture gamepad text entry @@ -2579,13 +2579,13 @@ enum EOverlayDirection OverlayDirection_Left = 2, OverlayDirection_Right = 3, - OverlayDirection_Count = 4, + OverlayDirection_Count = 4 }; enum EVROverlayIntersectionMaskPrimitiveType { OverlayIntersectionPrimitiveType_Rectangle, - OverlayIntersectionPrimitiveType_Circle, + OverlayIntersectionPrimitiveType_Circle }; struct IntersectionMaskRectangle_t @@ -2977,7 +2977,7 @@ enum EVRRenderModelError VRRenderModelError_NotEnoughNormals = 307, VRRenderModelError_NotEnoughTexCoords = 308, - VRRenderModelError_InvalidTexture = 400, + VRRenderModelError_InvalidTexture = 400 }; typedef uint32_t VRComponentProperties; @@ -2988,7 +2988,7 @@ enum EVRComponentProperty VRComponentProperty_IsVisible = (1 << 1), VRComponentProperty_IsTouched = (1 << 2), VRComponentProperty_IsPressed = (1 << 3), - VRComponentProperty_IsScrolled = (1 << 4), + VRComponentProperty_IsScrolled = (1 << 4) }; /** Describes state information about a render-model component, including transforms and other dynamic properties */ @@ -3240,7 +3240,7 @@ enum EVRScreenshotError VRScreenshotError_IncompatibleVersion = 100, VRScreenshotError_NotFound = 101, VRScreenshotError_BufferTooSmall = 102, - VRScreenshotError_ScreenshotAlreadyInProgress = 108, + VRScreenshotError_ScreenshotAlreadyInProgress = 108 }; /** Allows the application to generate screenshots */ From 573adb6856d529857aec98e90b667ced1daf5e3d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 02:25:50 +0100 Subject: [PATCH 38/57] Compiler warnings - newline at end of file --- Extras/HACD/hacdVersion.h | 2 +- Extras/Serialize/BulletFileLoader/autogenerated/bullet.h | 2 +- .../Serialize/BulletWorldImporter/btMultiBodyWorldImporter.cpp | 2 +- Extras/VHACD/inc/vhacdCircularList.h | 2 +- Extras/VHACD/inc/vhacdCircularList.inl | 2 +- Extras/VHACD/inc/vhacdManifoldMesh.h | 2 +- Extras/VHACD/inc/vhacdMesh.h | 2 +- Extras/VHACD/inc/vhacdSArray.h | 2 +- Extras/VHACD/inc/vhacdVector.h | 2 +- Extras/VHACD/inc/vhacdVector.inl | 2 +- Extras/VHACD/public/VHACD.h | 2 +- Extras/VHACD/src/vhacdManifoldMesh.cpp | 2 +- examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp | 2 +- examples/CommonInterfaces/CommonFileIOInterface.h | 2 +- examples/ExampleBrowser/ExampleBrowserInterface.h | 2 +- examples/ExampleBrowser/OpenGLGuiHelper.cpp | 2 +- examples/Heightfield/HeightfieldExample.h | 2 +- examples/Importers/ImportURDFDemo/MultiBodyCreationInterface.h | 2 +- examples/OpenGLWindow/OpenSans.cpp | 2 +- examples/OpenGLWindow/SimpleOpenGL2App.h | 2 +- examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp | 2 +- examples/OpenGLWindow/Win32InternalWindowData.h | 2 +- examples/OpenGLWindow/Win32Window.h | 2 +- examples/RenderingExamples/TimeSeriesCanvas.h | 2 +- examples/SharedMemory/InProcessMemory.cpp | 2 +- examples/SharedMemory/PhysicsClientSharedMemory2.h | 2 +- examples/SharedMemory/PhysicsServer.cpp | 2 +- examples/SharedMemory/b3RobotSimulatorClientAPI_InternalData.h | 2 +- examples/SharedMemory/plugins/b3PluginCollisionInterface.h | 2 +- examples/SharedMemory/plugins/b3PluginContext.h | 2 +- examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.h | 2 +- examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp | 2 +- examples/SharedMemory/plugins/stablePDPlugin/RBDModel.cpp | 2 +- examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.h | 2 +- examples/SharedMemory/plugins/stablePDPlugin/Shape.cpp | 2 +- examples/SharedMemory/plugins/stablePDPlugin/Shape.h | 2 +- examples/ThirdPartyLibs/BussIK/Node.cpp | 2 +- examples/ThirdPartyLibs/BussIK/Node.h | 2 +- examples/ThirdPartyLibs/BussIK/Tree.h | 2 +- examples/ThirdPartyLibs/BussIK/VectorRn.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Anim.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/Base.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/Canvas.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/CheckBox.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/ComboBox.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/Dialog/FileOpen.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/Dialog/FileSave.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/DockBase.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/DockedTabControl.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/HSVColorPicker.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/HorizontalScrollBar.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/HorizontalSlider.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/ImagePanel.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/Label.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/LabelClickable.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/ListBox.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/Menu.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/MenuStrip.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/NumericUpDown.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/PanelListPanel.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/ProgressBar.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/Properties.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/RadioButtonController.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/ResizableControl.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/Resizer.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/RichLabel.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/ScrollBarBar.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/ScrollBarButton.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/ScrollControl.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/SplitterBar.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/TabControl.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/TabStrip.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/Text.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/TextBox.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/TextBoxNumeric.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/VerticalScrollBar.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/VerticalSlider.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Controls/WindowControl.cpp | 2 +- examples/ThirdPartyLibs/Gwen/DragAndDrop.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Hook.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Platforms/Null.cpp | 2 +- examples/ThirdPartyLibs/Gwen/Platforms/Windows.cpp | 2 +- examples/ThirdPartyLibs/Gwen/events.cpp | 2 +- examples/ThirdPartyLibs/Gwen/inputhandler.cpp | 2 +- examples/ThirdPartyLibs/stb_image/stb_image_write.cpp | 2 +- examples/TinyRenderer/geometry.cpp | 2 +- examples/Utils/ChromeTraceUtil.h | 2 +- .../NarrowPhaseCollision/shared/b3BvhTraversal.h | 2 +- .../NarrowPhaseCollision/shared/b3Contact4Data.h | 2 +- src/Bullet3Common/b3Logging.h | 2 +- src/Bullet3Common/shared/b3Int2.h | 2 +- src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.cpp | 2 +- src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.cpp | 2 +- src/Bullet3Dynamics/b3CpuRigidBodyPipeline.h | 2 +- src/Bullet3Dynamics/shared/b3Inertia.h | 2 +- src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.h | 2 +- src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.h | 2 +- src/Bullet3OpenCL/NarrowphaseCollision/b3BvhInfo.h | 2 +- src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.cpp | 2 +- src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanFloat4CL.cpp | 2 +- src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp | 2 +- src/Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipeline.h | 2 +- src/BulletCollision/CollisionShapes/btCollisionShape.cpp | 2 +- src/BulletCollision/CollisionShapes/btConeShape.cpp | 2 +- .../BulletReducedDeformableBody/btReducedDeformableBody.cpp | 2 +- .../BulletReducedDeformableBody/btReducedDeformableBody.h | 2 +- .../btReducedDeformableBodyHelpers.h | 2 +- .../btReducedDeformableBodySolver.cpp | 2 +- .../BulletReducedDeformableBody/btReducedDeformableBodySolver.h | 2 +- .../btReducedDeformableContactConstraint.cpp | 2 +- .../btReducedDeformableContactConstraint.h | 2 +- src/BulletSoftBody/btDeformableBodySolver.cpp | 2 +- test/BulletDynamics/test_btKinematicCharacterController.cpp | 2 +- 113 files changed, 113 insertions(+), 113 deletions(-) diff --git a/Extras/HACD/hacdVersion.h b/Extras/HACD/hacdVersion.h index c9f7f28da9..1b7c016b84 100644 --- a/Extras/HACD/hacdVersion.h +++ b/Extras/HACD/hacdVersion.h @@ -17,4 +17,4 @@ #define HACD_VERSION_H #define HACD_VERSION_MAJOR 0 #define HACD_VERSION_MINOR 0 -#endif \ No newline at end of file +#endif diff --git a/Extras/Serialize/BulletFileLoader/autogenerated/bullet.h b/Extras/Serialize/BulletFileLoader/autogenerated/bullet.h index bfec77bb26..9da430b452 100644 --- a/Extras/Serialize/BulletFileLoader/autogenerated/bullet.h +++ b/Extras/Serialize/BulletFileLoader/autogenerated/bullet.h @@ -1577,4 +1577,4 @@ typedef struct bInvalidHandle { } -#endif//__BULLET_H__ \ No newline at end of file +#endif//__BULLET_H__ diff --git a/Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.cpp b/Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.cpp index 4a7f799314..9d6c952ec3 100644 --- a/Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.cpp +++ b/Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.cpp @@ -568,4 +568,4 @@ bool btMultiBodyWorldImporter::convertAllObjects(bParse::btBulletFile* bulletFil } } return result; -} \ No newline at end of file +} diff --git a/Extras/VHACD/inc/vhacdCircularList.h b/Extras/VHACD/inc/vhacdCircularList.h index 9e4b7ae3f7..dd41767b5b 100644 --- a/Extras/VHACD/inc/vhacdCircularList.h +++ b/Extras/VHACD/inc/vhacdCircularList.h @@ -81,4 +81,4 @@ class CircularList }; } // namespace VHACD #include "vhacdCircularList.inl" -#endif // VHACD_CIRCULAR_LIST_H \ No newline at end of file +#endif // VHACD_CIRCULAR_LIST_H diff --git a/Extras/VHACD/inc/vhacdCircularList.inl b/Extras/VHACD/inc/vhacdCircularList.inl index 2be5180524..efee82c935 100644 --- a/Extras/VHACD/inc/vhacdCircularList.inl +++ b/Extras/VHACD/inc/vhacdCircularList.inl @@ -158,4 +158,4 @@ namespace VHACD return (*this); } } -#endif \ No newline at end of file +#endif diff --git a/Extras/VHACD/inc/vhacdManifoldMesh.h b/Extras/VHACD/inc/vhacdManifoldMesh.h index 2c3ebe508f..f644891016 100644 --- a/Extras/VHACD/inc/vhacdManifoldMesh.h +++ b/Extras/VHACD/inc/vhacdManifoldMesh.h @@ -144,4 +144,4 @@ class TMMesh friend class ICHull; }; } // namespace VHACD -#endif // VHACD_MANIFOLD_MESH_H \ No newline at end of file +#endif // VHACD_MANIFOLD_MESH_H diff --git a/Extras/VHACD/inc/vhacdMesh.h b/Extras/VHACD/inc/vhacdMesh.h index e43da355b8..436202b26e 100644 --- a/Extras/VHACD/inc/vhacdMesh.h +++ b/Extras/VHACD/inc/vhacdMesh.h @@ -130,4 +130,4 @@ class Mesh double m_diag; }; } // namespace VHACD -#endif \ No newline at end of file +#endif diff --git a/Extras/VHACD/inc/vhacdSArray.h b/Extras/VHACD/inc/vhacdSArray.h index 353bb8dc81..79530ec183 100644 --- a/Extras/VHACD/inc/vhacdSArray.h +++ b/Extras/VHACD/inc/vhacdSArray.h @@ -161,4 +161,4 @@ class SArray size_t m_maxSize; }; } // namespace VHACD -#endif \ No newline at end of file +#endif diff --git a/Extras/VHACD/inc/vhacdVector.h b/Extras/VHACD/inc/vhacdVector.h index 5abbef0faa..a68da3e102 100644 --- a/Extras/VHACD/inc/vhacdVector.h +++ b/Extras/VHACD/inc/vhacdVector.h @@ -103,4 +103,4 @@ template const T ComputeVolume4(const Vec3& a, const Vec3& b, const Vec3& c, const Vec3& d); } // namespace VHACD #include "vhacdVector.inl" // template implementation -#endif \ No newline at end of file +#endif diff --git a/Extras/VHACD/inc/vhacdVector.inl b/Extras/VHACD/inc/vhacdVector.inl index 0fd96afc07..fd00e73ffc 100644 --- a/Extras/VHACD/inc/vhacdVector.inl +++ b/Extras/VHACD/inc/vhacdVector.inl @@ -359,4 +359,4 @@ namespace VHACD return ((aCROSSbp >= 0.0) && (bCROSScp >= 0.0) && (cCROSSap >= 0.0)); } } -#endif //VHACD_VECTOR_INL \ No newline at end of file +#endif //VHACD_VECTOR_INL diff --git a/Extras/VHACD/public/VHACD.h b/Extras/VHACD/public/VHACD.h index 2197a34ce5..e24faaf30b 100644 --- a/Extras/VHACD/public/VHACD.h +++ b/Extras/VHACD/public/VHACD.h @@ -120,4 +120,4 @@ class IVHACD }; IVHACD* CreateVHACD(void); } // namespace VHACD -#endif // VHACD_H \ No newline at end of file +#endif // VHACD_H diff --git a/Extras/VHACD/src/vhacdManifoldMesh.cpp b/Extras/VHACD/src/vhacdManifoldMesh.cpp index 8ff8aeb6c7..fe26fe48bc 100644 --- a/Extras/VHACD/src/vhacdManifoldMesh.cpp +++ b/Extras/VHACD/src/vhacdManifoldMesh.cpp @@ -232,4 +232,4 @@ bool TMMesh::CheckConsistancy() } return true; } -} // namespace VHACD \ No newline at end of file +} // namespace VHACD diff --git a/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp b/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp index de15aec205..6f4483a2a8 100644 --- a/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp +++ b/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp @@ -476,4 +476,4 @@ void RealTimeBullet3CollisionSdk::collideWorld(plCollisionWorldHandle worldHandl plCollisionSdkHandle RealTimeBullet3CollisionSdk::createRealTimeBullet3CollisionSdkHandle() { return (plCollisionSdkHandle) new RealTimeBullet3CollisionSdk(); -} \ No newline at end of file +} diff --git a/examples/CommonInterfaces/CommonFileIOInterface.h b/examples/CommonInterfaces/CommonFileIOInterface.h index beb25edd6b..835bd7d25b 100644 --- a/examples/CommonInterfaces/CommonFileIOInterface.h +++ b/examples/CommonInterfaces/CommonFileIOInterface.h @@ -25,4 +25,4 @@ struct CommonFileIOInterface virtual void enableFileCaching(bool enable) = 0; }; -#endif //COMMON_FILE_IO_INTERFACE_H \ No newline at end of file +#endif //COMMON_FILE_IO_INTERFACE_H diff --git a/examples/ExampleBrowser/ExampleBrowserInterface.h b/examples/ExampleBrowser/ExampleBrowserInterface.h index f4867987ba..7786bcb091 100644 --- a/examples/ExampleBrowser/ExampleBrowserInterface.h +++ b/examples/ExampleBrowser/ExampleBrowserInterface.h @@ -21,4 +21,4 @@ class ExampleBrowserInterface virtual void setSharedMemoryInterface(class SharedMemoryInterface* sharedMem) = 0; }; -#endif //EXAMPLE_BROWSER_GUI_H \ No newline at end of file +#endif //EXAMPLE_BROWSER_GUI_H diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index a35e9a91bf..232a825f6c 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -1552,4 +1552,4 @@ void OpenGLGuiHelper::computeSoftBodyVertices(btCollisionShape* collisionShape, void OpenGLGuiHelper::updateShape(int shapeIndex, float* vertices, int numVertices) { m_data->m_glApp->m_renderer->updateShape(shapeIndex, vertices, numVertices); -} \ No newline at end of file +} diff --git a/examples/Heightfield/HeightfieldExample.h b/examples/Heightfield/HeightfieldExample.h index 258e7f7017..461f2503a9 100644 --- a/examples/Heightfield/HeightfieldExample.h +++ b/examples/Heightfield/HeightfieldExample.h @@ -18,4 +18,4 @@ subject to the following restrictions: class CommonExampleInterface* HeightfieldExampleCreateFunc(struct CommonExampleOptions& options); -#endif //HEIGHTFIELD_EXAMPLE_H \ No newline at end of file +#endif //HEIGHTFIELD_EXAMPLE_H diff --git a/examples/Importers/ImportURDFDemo/MultiBodyCreationInterface.h b/examples/Importers/ImportURDFDemo/MultiBodyCreationInterface.h index 91a2e442b8..a1e69d4afc 100644 --- a/examples/Importers/ImportURDFDemo/MultiBodyCreationInterface.h +++ b/examples/Importers/ImportURDFDemo/MultiBodyCreationInterface.h @@ -39,4 +39,4 @@ class MultiBodyCreationInterface virtual void addLinkMapping(int urdfLinkIndex, int mbLinkIndex) = 0; }; -#endif //MULTIBODY_CREATION_INTERFACE_H \ No newline at end of file +#endif //MULTIBODY_CREATION_INTERFACE_H diff --git a/examples/OpenGLWindow/OpenSans.cpp b/examples/OpenGLWindow/OpenSans.cpp index 1d36286da4..b6fb20b4fa 100644 --- a/examples/OpenGLWindow/OpenSans.cpp +++ b/examples/OpenGLWindow/OpenSans.cpp @@ -217360,4 +217360,4 @@ unsigned char OpenSansData[] = { 0, 0, -}; \ No newline at end of file +}; diff --git a/examples/OpenGLWindow/SimpleOpenGL2App.h b/examples/OpenGLWindow/SimpleOpenGL2App.h index 48af6b6fa1..89bdc0b794 100644 --- a/examples/OpenGLWindow/SimpleOpenGL2App.h +++ b/examples/OpenGLWindow/SimpleOpenGL2App.h @@ -29,4 +29,4 @@ class SimpleOpenGL2App : public CommonGraphicsApp virtual void registerGrid(int xres, int yres, float color0[4], float color1[4]); }; -#endif //SIMPLE_OPENGL2_APP_H \ No newline at end of file +#endif //SIMPLE_OPENGL2_APP_H diff --git a/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp b/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp index 5d2bee2a94..98ba8436f0 100644 --- a/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp +++ b/examples/OpenGLWindow/SimpleOpenGL2Renderer.cpp @@ -667,4 +667,4 @@ void SimpleOpenGL2Renderer::updateShape(int shapeIndex, const float* vertices, i void SimpleOpenGL2Renderer::clearZBuffer() { glClear(GL_DEPTH_BUFFER_BIT); -} \ No newline at end of file +} diff --git a/examples/OpenGLWindow/Win32InternalWindowData.h b/examples/OpenGLWindow/Win32InternalWindowData.h index 12d66e2864..ec7c88f83c 100644 --- a/examples/OpenGLWindow/Win32InternalWindowData.h +++ b/examples/OpenGLWindow/Win32InternalWindowData.h @@ -62,4 +62,4 @@ struct InternalData2 } }; -#endif //WIN32_INTERNAL_WINDOW_DATA_H \ No newline at end of file +#endif //WIN32_INTERNAL_WINDOW_DATA_H diff --git a/examples/OpenGLWindow/Win32Window.h b/examples/OpenGLWindow/Win32Window.h index dcf8198056..8c39cd6a2a 100644 --- a/examples/OpenGLWindow/Win32Window.h +++ b/examples/OpenGLWindow/Win32Window.h @@ -75,4 +75,4 @@ class Win32Window : public CommonWindowInterface virtual bool isModifierKeyPressed(int key); }; -#endif //_WIN32_WINDOW_H \ No newline at end of file +#endif //_WIN32_WINDOW_H diff --git a/examples/RenderingExamples/TimeSeriesCanvas.h b/examples/RenderingExamples/TimeSeriesCanvas.h index 86e6e5dd4b..77bf7268f4 100644 --- a/examples/RenderingExamples/TimeSeriesCanvas.h +++ b/examples/RenderingExamples/TimeSeriesCanvas.h @@ -20,4 +20,4 @@ class TimeSeriesCanvas virtual void nextTick(); }; -#endif //TIME_SERIES_CANVAS_H \ No newline at end of file +#endif //TIME_SERIES_CANVAS_H diff --git a/examples/SharedMemory/InProcessMemory.cpp b/examples/SharedMemory/InProcessMemory.cpp index 9c09c7d587..6f50f39d17 100644 --- a/examples/SharedMemory/InProcessMemory.cpp +++ b/examples/SharedMemory/InProcessMemory.cpp @@ -43,4 +43,4 @@ void InProcessMemory::releaseSharedMemory(int /*key*/, int /*size*/) { //we don't release the memory here, but in the destructor instead, //so multiple users could 'share' the memory given some key -} \ No newline at end of file +} diff --git a/examples/SharedMemory/PhysicsClientSharedMemory2.h b/examples/SharedMemory/PhysicsClientSharedMemory2.h index 473ee0ec11..5bf0680607 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory2.h +++ b/examples/SharedMemory/PhysicsClientSharedMemory2.h @@ -14,4 +14,4 @@ class PhysicsClientSharedMemory2 : public PhysicsDirect void setSharedMemoryInterface(class SharedMemoryInterface* sharedMem); }; -#endif //PHYSICS_CLIENT_SHARED_MEMORY3_H \ No newline at end of file +#endif //PHYSICS_CLIENT_SHARED_MEMORY3_H diff --git a/examples/SharedMemory/PhysicsServer.cpp b/examples/SharedMemory/PhysicsServer.cpp index ba512881cb..35912724a8 100644 --- a/examples/SharedMemory/PhysicsServer.cpp +++ b/examples/SharedMemory/PhysicsServer.cpp @@ -2,4 +2,4 @@ PhysicsServer::~PhysicsServer() { -} \ No newline at end of file +} diff --git a/examples/SharedMemory/b3RobotSimulatorClientAPI_InternalData.h b/examples/SharedMemory/b3RobotSimulatorClientAPI_InternalData.h index 34994ddfee..95252982ca 100644 --- a/examples/SharedMemory/b3RobotSimulatorClientAPI_InternalData.h +++ b/examples/SharedMemory/b3RobotSimulatorClientAPI_InternalData.h @@ -15,4 +15,4 @@ struct b3RobotSimulatorClientAPI_InternalData } }; -#endif //B3_ROBOT_SIMULATOR_CLIENT_API_INTERNAL_DATA_H \ No newline at end of file +#endif //B3_ROBOT_SIMULATOR_CLIENT_API_INTERNAL_DATA_H diff --git a/examples/SharedMemory/plugins/b3PluginCollisionInterface.h b/examples/SharedMemory/plugins/b3PluginCollisionInterface.h index e0e39439e8..5062a044bd 100644 --- a/examples/SharedMemory/plugins/b3PluginCollisionInterface.h +++ b/examples/SharedMemory/plugins/b3PluginCollisionInterface.h @@ -29,4 +29,4 @@ struct b3PluginCollisionInterface int filterMode) = 0; }; -#endif //B3_PLUGIN_COLLISION_INTERFACE_H \ No newline at end of file +#endif //B3_PLUGIN_COLLISION_INTERFACE_H diff --git a/examples/SharedMemory/plugins/b3PluginContext.h b/examples/SharedMemory/plugins/b3PluginContext.h index 045c9c2a80..0342ce0eac 100644 --- a/examples/SharedMemory/plugins/b3PluginContext.h +++ b/examples/SharedMemory/plugins/b3PluginContext.h @@ -28,4 +28,4 @@ struct b3PluginContext class PhysicsCommandProcessorInterface* m_rpcCommandProcessorInterface; }; -#endif //B3_PLUGIN_CONTEXT_H \ No newline at end of file +#endif //B3_PLUGIN_CONTEXT_H diff --git a/examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.h b/examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.h index 0ae62c9ef8..a2724aa0cc 100644 --- a/examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.h +++ b/examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.h @@ -6,4 +6,4 @@ class btMultiBody; void btExtractJointBodyFromBullet(const btMultiBody* bulletMB, Eigen::MatrixXd& bodyDefs, Eigen::MatrixXd& jointMat); -#endif //BULLET_CONVERSION_H \ No newline at end of file +#endif //BULLET_CONVERSION_H diff --git a/examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp b/examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp index c44546081f..a835f904e3 100644 --- a/examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp +++ b/examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp @@ -760,4 +760,4 @@ void cMathUtil::ButterworthFilter(double dt, double cutoff, Eigen::VectorXd& out zp2 = zp1; zp1 = z; } -} \ No newline at end of file +} diff --git a/examples/SharedMemory/plugins/stablePDPlugin/RBDModel.cpp b/examples/SharedMemory/plugins/stablePDPlugin/RBDModel.cpp index a5980c5bbc..406f2a894f 100644 --- a/examples/SharedMemory/plugins/stablePDPlugin/RBDModel.cpp +++ b/examples/SharedMemory/plugins/stablePDPlugin/RBDModel.cpp @@ -257,4 +257,4 @@ void cRBDModel::UpdateMassMat() void cRBDModel::UpdateBiasForce() { cRBDUtil::BuildBiasForce(*this, mBiasForce); -} \ No newline at end of file +} diff --git a/examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.h b/examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.h index aae03ebdfd..f542ecc303 100644 --- a/examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.h +++ b/examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.h @@ -82,4 +82,4 @@ class cRBDUtil // builds the spatial inertial matrix in the coordinate frame of the parent joint static cSpAlg::tSpMat BuildInertiaSpatialMat(const Eigen::MatrixXd& body_defs, int part_id); -}; \ No newline at end of file +}; diff --git a/examples/SharedMemory/plugins/stablePDPlugin/Shape.cpp b/examples/SharedMemory/plugins/stablePDPlugin/Shape.cpp index 31b7fb04c0..b953ba859a 100644 --- a/examples/SharedMemory/plugins/stablePDPlugin/Shape.cpp +++ b/examples/SharedMemory/plugins/stablePDPlugin/Shape.cpp @@ -35,4 +35,4 @@ bool cShape::ParseShape(const std::string& str, eShape& out_shape) assert(false); } return succ; -} \ No newline at end of file +} diff --git a/examples/SharedMemory/plugins/stablePDPlugin/Shape.h b/examples/SharedMemory/plugins/stablePDPlugin/Shape.h index 1088e4cbdb..ff62643597 100644 --- a/examples/SharedMemory/plugins/stablePDPlugin/Shape.h +++ b/examples/SharedMemory/plugins/stablePDPlugin/Shape.h @@ -17,4 +17,4 @@ class cShape }; static bool ParseShape(const std::string& str, cShape::eShape& out_shape); -}; \ No newline at end of file +}; diff --git a/examples/ThirdPartyLibs/BussIK/Node.cpp b/examples/ThirdPartyLibs/BussIK/Node.cpp index fb5c24a203..07d6a0fd40 100644 --- a/examples/ThirdPartyLibs/BussIK/Node.cpp +++ b/examples/ThirdPartyLibs/BussIK/Node.cpp @@ -84,4 +84,4 @@ void Node::PrintNode() void Node::InitNode() { theta = 0.0; -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/BussIK/Node.h b/examples/ThirdPartyLibs/BussIK/Node.h index ad1d61adb1..d5f5b154b1 100644 --- a/examples/ThirdPartyLibs/BussIK/Node.h +++ b/examples/ThirdPartyLibs/BussIK/Node.h @@ -106,4 +106,4 @@ class Node Node* realparent; // pointer to real parent }; -#endif \ No newline at end of file +#endif diff --git a/examples/ThirdPartyLibs/BussIK/Tree.h b/examples/ThirdPartyLibs/BussIK/Tree.h index 737f57060d..f8ed78bac6 100644 --- a/examples/ThirdPartyLibs/BussIK/Tree.h +++ b/examples/ThirdPartyLibs/BussIK/Tree.h @@ -93,4 +93,4 @@ inline Node* Tree::GetSuccessor(const Node* node) const } } -#endif \ No newline at end of file +#endif diff --git a/examples/ThirdPartyLibs/BussIK/VectorRn.cpp b/examples/ThirdPartyLibs/BussIK/VectorRn.cpp index e456b677fe..f468ffe388 100644 --- a/examples/ThirdPartyLibs/BussIK/VectorRn.cpp +++ b/examples/ThirdPartyLibs/BussIK/VectorRn.cpp @@ -45,4 +45,4 @@ double VectorRn::MaxAbs() const t++; } return result; -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Anim.cpp b/examples/ThirdPartyLibs/Gwen/Anim.cpp index 9428498c72..e71980dd6f 100644 --- a/examples/ThirdPartyLibs/Gwen/Anim.cpp +++ b/examples/ThirdPartyLibs/Gwen/Anim.cpp @@ -137,4 +137,4 @@ bool Gwen::Anim::TimedAnimation::Finished() return m_bFinished; } -#endif \ No newline at end of file +#endif diff --git a/examples/ThirdPartyLibs/Gwen/Controls/Base.cpp b/examples/ThirdPartyLibs/Gwen/Controls/Base.cpp index effbb2da2e..d653ef450d 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/Base.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/Base.cpp @@ -1112,4 +1112,4 @@ void Base::Anim_HeightOut(float fLength, bool bHide, float fDelay, float fEase) Gwen::Anim::Add(this, new Gwen::Anim::Size::Height(Height(), 0, fLength, bHide, fDelay, fEase)); } -#endif \ No newline at end of file +#endif diff --git a/examples/ThirdPartyLibs/Gwen/Controls/Canvas.cpp b/examples/ThirdPartyLibs/Gwen/Controls/Canvas.cpp index d8ab0618df..563bdbcaae 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/Canvas.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/Canvas.cpp @@ -224,4 +224,4 @@ bool Canvas::InputMouseWheel(int val) if (Gwen::HoveredControl->GetCanvas() != this) return false; return Gwen::HoveredControl->OnMouseWheeled(val); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/CheckBox.cpp b/examples/ThirdPartyLibs/Gwen/Controls/CheckBox.cpp index a6961c7af5..f56f5431cf 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/CheckBox.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/CheckBox.cpp @@ -50,4 +50,4 @@ void CheckBox::SetChecked(bool bChecked) m_bChecked = bChecked; OnCheckStatusChanged(); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/ComboBox.cpp b/examples/ThirdPartyLibs/Gwen/Controls/ComboBox.cpp index 28de5ba50b..b23484e16a 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/ComboBox.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/ComboBox.cpp @@ -194,4 +194,4 @@ bool ComboBox::OnKeyDown(bool bDown) void ComboBox::RenderFocus(Gwen::Skin::Base* /*skin*/) { -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/Dialog/FileOpen.cpp b/examples/ThirdPartyLibs/Gwen/Controls/Dialog/FileOpen.cpp index 984f93ad85..3307c32a25 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/Dialog/FileOpen.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/Dialog/FileOpen.cpp @@ -21,4 +21,4 @@ void Gwen::Dialogs::FileOpenEx(bool bUseSystem, const String& Name, const String // // TODO: SHOW GWEN FILE SELECTION DIALOG // -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/Dialog/FileSave.cpp b/examples/ThirdPartyLibs/Gwen/Controls/Dialog/FileSave.cpp index ed787153e1..f7f9a582e1 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/Dialog/FileSave.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/Dialog/FileSave.cpp @@ -21,4 +21,4 @@ void Gwen::Dialogs::FileSaveEx(bool bUseSystem, const String& Name, const String // // TODO: SHOW GWEN FILE SELECTION DIALOG // -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/DockBase.cpp b/examples/ThirdPartyLibs/Gwen/Controls/DockBase.cpp index 9bf9f02f0e..70d9034c79 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/DockBase.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/DockBase.cpp @@ -340,4 +340,4 @@ void DockBase::RenderOver(Skin::Base* skin) render->SetDrawColor(Gwen::Color(255, 100, 255, 200)); render->DrawLinedRect(m_HoverRect); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/DockedTabControl.cpp b/examples/ThirdPartyLibs/Gwen/Controls/DockedTabControl.cpp index babaa6c2a4..4136fb24ed 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/DockedTabControl.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/DockedTabControl.cpp @@ -87,4 +87,4 @@ void DockedTabControl::MoveTabsTo(DockedTabControl* pTarget) } Invalidate(); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/HSVColorPicker.cpp b/examples/ThirdPartyLibs/Gwen/Controls/HSVColorPicker.cpp index c714b825a1..bb72bf9528 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/HSVColorPicker.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/HSVColorPicker.cpp @@ -161,4 +161,4 @@ void HSVColorPicker::ColorSliderChanged(Gwen::Controls::Base* /*pControl*/) if (m_LerpBox) m_LerpBox->SetColor(m_ColorSlider->GetSelectedColor(), true); Invalidate(); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/HorizontalScrollBar.cpp b/examples/ThirdPartyLibs/Gwen/Controls/HorizontalScrollBar.cpp index 452e857140..6928b0cd1c 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/HorizontalScrollBar.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/HorizontalScrollBar.cpp @@ -130,4 +130,4 @@ void HorizontalScrollBar::OnBarMoved(Controls::Base* control) } else InvalidateParent(); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/HorizontalSlider.cpp b/examples/ThirdPartyLibs/Gwen/Controls/HorizontalSlider.cpp index 1a8a724b0b..87edd17cb7 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/HorizontalSlider.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/HorizontalSlider.cpp @@ -40,4 +40,4 @@ void HorizontalSlider::Layout(Skin::Base* /*skin*/) void HorizontalSlider::Render(Skin::Base* skin) { skin->DrawSlider(this, true, m_bClampToNotches ? m_iNumNotches : 0, m_SliderBar->Width()); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/ImagePanel.cpp b/examples/ThirdPartyLibs/Gwen/Controls/ImagePanel.cpp index 913a27152e..e87b5dba01 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/ImagePanel.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/ImagePanel.cpp @@ -4,4 +4,4 @@ See license in Gwen.h */ -#include "Gwen/Controls/ImagePanel.h" \ No newline at end of file +#include "Gwen/Controls/ImagePanel.h" diff --git a/examples/ThirdPartyLibs/Gwen/Controls/Label.cpp b/examples/ThirdPartyLibs/Gwen/Controls/Label.cpp index f7e17b6938..802fb8a360 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/Label.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/Label.cpp @@ -68,4 +68,4 @@ Gwen::Point Label::GetCharacterPosition(int iChar) p.y += m_Text->Y(); return p; -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/LabelClickable.cpp b/examples/ThirdPartyLibs/Gwen/Controls/LabelClickable.cpp index 2f0aeceae9..8a30d47b81 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/LabelClickable.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/LabelClickable.cpp @@ -21,4 +21,4 @@ GWEN_CONTROL_CONSTRUCTOR(LabelClickable) void LabelClickable::Render(Skin::Base* /*skin*/) { //skin->DrawButton( this, IsDepressed(), IsToggle() && GetToggleState() ); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/ListBox.cpp b/examples/ThirdPartyLibs/Gwen/Controls/ListBox.cpp index 5f6e4c94c5..bede6c0263 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/ListBox.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/ListBox.cpp @@ -137,4 +137,4 @@ void ListBox::Clear() { UnselectAll(); m_Table->Clear(); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/Menu.cpp b/examples/ThirdPartyLibs/Gwen/Controls/Menu.cpp index 7b0b4cd4d1..e191e88c44 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/Menu.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/Menu.cpp @@ -163,4 +163,4 @@ void Menu::AddDivider() void MenuDivider::Render(Gwen::Skin::Base* skin) { skin->DrawMenuDivider(this); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/MenuStrip.cpp b/examples/ThirdPartyLibs/Gwen/Controls/MenuStrip.cpp index 56df401714..6a9757fbfa 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/MenuStrip.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/MenuStrip.cpp @@ -40,4 +40,4 @@ void MenuStrip::OnAddItem(MenuItem* item) bool MenuStrip::ShouldHoverOpenMenu() { return IsMenuOpen(); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/NumericUpDown.cpp b/examples/ThirdPartyLibs/Gwen/Controls/NumericUpDown.cpp index d2db77089b..e493ada339 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/NumericUpDown.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/NumericUpDown.cpp @@ -109,4 +109,4 @@ void NumericUpDown::OnEnter() { SyncNumberFromText(); SyncTextFromNumber(); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/PanelListPanel.cpp b/examples/ThirdPartyLibs/Gwen/Controls/PanelListPanel.cpp index f20fe68772..faff7f8313 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/PanelListPanel.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/PanelListPanel.cpp @@ -121,4 +121,4 @@ void PanelListPanel::Layout(Skin::Base* skin) DoHorizontalLayout(); else DoVerticalLayout(); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/ProgressBar.cpp b/examples/ThirdPartyLibs/Gwen/Controls/ProgressBar.cpp index 8ca43bf5d6..e282cd02f1 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/ProgressBar.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/ProgressBar.cpp @@ -44,4 +44,4 @@ void ProgressBar::SetValue(float val) void ProgressBar::Render(Skin::Base* skin) { skin->DrawProgressBar(this, m_bHorizontal, m_fProgress); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/Properties.cpp b/examples/ThirdPartyLibs/Gwen/Controls/Properties.cpp index bbf7f3629d..b222d14ffd 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/Properties.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/Properties.cpp @@ -120,4 +120,4 @@ void PropertyRow::SetProperty(Property::Base* prop) void PropertyRow::OnPropertyValueChanged(Gwen::Controls::Base* /*control*/) { onChange.Call(this); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/RadioButtonController.cpp b/examples/ThirdPartyLibs/Gwen/Controls/RadioButtonController.cpp index ca41ae6f70..67d90ccfd1 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/RadioButtonController.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/RadioButtonController.cpp @@ -69,4 +69,4 @@ LabeledRadioButton* RadioButtonController::AddOption(const Gwen::UnicodeString& Invalidate(); return lrb; -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/ResizableControl.cpp b/examples/ThirdPartyLibs/Gwen/Controls/ResizableControl.cpp index acb4ceb65b..96d2a9c610 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/ResizableControl.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/ResizableControl.cpp @@ -106,4 +106,4 @@ void ResizableControl::OnResizedInternal(Controls::Base* /*pControl*/) { onResize.Call(this); OnResized(); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/Resizer.cpp b/examples/ThirdPartyLibs/Gwen/Controls/Resizer.cpp index 5970c3fd7a..aea7acddcf 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/Resizer.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/Resizer.cpp @@ -112,4 +112,4 @@ void Resizer::SetResizeDir(int dir) if (dir & Pos::Top || dir & Pos::Bottom) return SetCursor(Gwen::CursorType::SizeNS); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/RichLabel.cpp b/examples/ThirdPartyLibs/Gwen/Controls/RichLabel.cpp index 3529be1a3d..bbd8083bd9 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/RichLabel.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/RichLabel.cpp @@ -204,4 +204,4 @@ void RichLabel::Layout(Gwen::Skin::Base* skin) { Rebuild(); } -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/ScrollBarBar.cpp b/examples/ThirdPartyLibs/Gwen/Controls/ScrollBarBar.cpp index 296b443a1d..164b8112ef 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/ScrollBarBar.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/ScrollBarBar.cpp @@ -53,4 +53,4 @@ void ScrollBarBar::Layout(Skin::Base* /*skin*/) void ScrollBarBar::MoveTo(int x, int y) { BaseClass::MoveTo(x, y); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/ScrollBarButton.cpp b/examples/ThirdPartyLibs/Gwen/Controls/ScrollBarButton.cpp index 7a6fd622da..b614b3e894 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/ScrollBarButton.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/ScrollBarButton.cpp @@ -40,4 +40,4 @@ void ScrollBarButton::SetDirectionRight() void ScrollBarButton::Render(Skin::Base* skin) { skin->DrawScrollButton(this, m_iDirection, m_bDepressed); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/ScrollControl.cpp b/examples/ThirdPartyLibs/Gwen/Controls/ScrollControl.cpp index 19585f97d6..f9c6e9781d 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/ScrollControl.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/ScrollControl.cpp @@ -241,4 +241,4 @@ void ScrollControl::ScrollToRight() void ScrollControl::Clear() { m_InnerPanel->RemoveAllChildren(); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/SplitterBar.cpp b/examples/ThirdPartyLibs/Gwen/Controls/SplitterBar.cpp index 6fb4386635..b0eef49e2a 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/SplitterBar.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/SplitterBar.cpp @@ -20,4 +20,4 @@ void SplitterBar::Render(Skin::Base* skin) void SplitterBar::Layout(Skin::Base* /*skin*/) { MoveTo(X(), Y()); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/TabControl.cpp b/examples/ThirdPartyLibs/Gwen/Controls/TabControl.cpp index 0c724787ba..f44f673da4 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/TabControl.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/TabControl.cpp @@ -238,4 +238,4 @@ void TabControl::ScrollPressLeft(Base* /*pFrom*/) void TabControl::ScrollPressRight(Base* /*pFrom*/) { m_iScrollOffset += 120; -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/TabStrip.cpp b/examples/ThirdPartyLibs/Gwen/Controls/TabStrip.cpp index 2c11276074..79b33f8efa 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/TabStrip.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/TabStrip.cpp @@ -176,4 +176,4 @@ void TabStrip::DragAndDrop_Hover(Gwen::DragAndDrop::Package* /*pPackage*/, int x void TabStrip::SetTabPosition(int iPos) { Dock(iPos); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/Text.cpp b/examples/ThirdPartyLibs/Gwen/Controls/Text.cpp index cda6a6f70b..1c18b79eb1 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/Text.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/Text.cpp @@ -111,4 +111,4 @@ int Text::GetClosestCharacter(Gwen::Point p) void Text::OnScaleChanged() { Invalidate(); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/TextBox.cpp b/examples/ThirdPartyLibs/Gwen/Controls/TextBox.cpp index fe161ab359..cedc7f91dd 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/TextBox.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/TextBox.cpp @@ -405,4 +405,4 @@ void TextBox::OnTextChanged() void TextBox::OnEnter() { onReturnPressed.Call(this); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/TextBoxNumeric.cpp b/examples/ThirdPartyLibs/Gwen/Controls/TextBoxNumeric.cpp index 79794ebf8d..e561c96a9c 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/TextBoxNumeric.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/TextBoxNumeric.cpp @@ -70,4 +70,4 @@ float TextBoxNumeric::GetFloatFromText() { double temp = GwenUtil_WideStringToFloat(GetText().c_str()); return temp; -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/VerticalScrollBar.cpp b/examples/ThirdPartyLibs/Gwen/Controls/VerticalScrollBar.cpp index 1696d3786e..1a3ccdca12 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/VerticalScrollBar.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/VerticalScrollBar.cpp @@ -134,4 +134,4 @@ void VerticalScrollBar::OnBarMoved(Controls::Base* control) } else InvalidateParent(); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/VerticalSlider.cpp b/examples/ThirdPartyLibs/Gwen/Controls/VerticalSlider.cpp index ee0d97363e..703ec7ded9 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/VerticalSlider.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/VerticalSlider.cpp @@ -40,4 +40,4 @@ void VerticalSlider::Layout(Skin::Base* /*skin*/) void VerticalSlider::Render(Skin::Base* skin) { skin->DrawSlider(this, false, m_bClampToNotches ? m_iNumNotches : 0, m_SliderBar->Height()); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Controls/WindowControl.cpp b/examples/ThirdPartyLibs/Gwen/Controls/WindowControl.cpp index e555f29afc..f56a77ecff 100644 --- a/examples/ThirdPartyLibs/Gwen/Controls/WindowControl.cpp +++ b/examples/ThirdPartyLibs/Gwen/Controls/WindowControl.cpp @@ -142,4 +142,4 @@ void WindowControl::CloseButtonPressed(Gwen::Controls::Base* /*pFromPanel*/) void WindowControl::RenderFocus(Gwen::Skin::Base* /*skin*/) { -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/DragAndDrop.cpp b/examples/ThirdPartyLibs/Gwen/DragAndDrop.cpp index 06bf0064b5..c2819ad918 100644 --- a/examples/ThirdPartyLibs/Gwen/DragAndDrop.cpp +++ b/examples/ThirdPartyLibs/Gwen/DragAndDrop.cpp @@ -231,4 +231,4 @@ void DragAndDrop::RenderOverlay(Gwen::Controls::Canvas* /*pCanvas*/, Skin::Base* CurrentPackage->drawcontrol->DoRender(skin); skin->GetRender()->SetRenderOffset(pntOld); -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/Hook.cpp b/examples/ThirdPartyLibs/Gwen/Hook.cpp index 30a3c58c25..9c918c7bc4 100644 --- a/examples/ThirdPartyLibs/Gwen/Hook.cpp +++ b/examples/ThirdPartyLibs/Gwen/Hook.cpp @@ -28,4 +28,4 @@ HookList& Gwen::Hook::GetHookList() return g_HookList; } -#endif \ No newline at end of file +#endif diff --git a/examples/ThirdPartyLibs/Gwen/Platforms/Null.cpp b/examples/ThirdPartyLibs/Gwen/Platforms/Null.cpp index 73aeffcc34..7363cf03c7 100644 --- a/examples/ThirdPartyLibs/Gwen/Platforms/Null.cpp +++ b/examples/ThirdPartyLibs/Gwen/Platforms/Null.cpp @@ -51,4 +51,4 @@ bool Gwen::Platform::FileSave(const String& /*Name*/, const String& /*StartPath* return false; } -#endif // ndef WIN32 \ No newline at end of file +#endif // ndef WIN32 diff --git a/examples/ThirdPartyLibs/Gwen/Platforms/Windows.cpp b/examples/ThirdPartyLibs/Gwen/Platforms/Windows.cpp index 9510bc49e2..a5406f479f 100644 --- a/examples/ThirdPartyLibs/Gwen/Platforms/Windows.cpp +++ b/examples/ThirdPartyLibs/Gwen/Platforms/Windows.cpp @@ -234,4 +234,4 @@ bool Gwen::Platform::FileSave(const String& Name, const String& StartPath, const return true; } -#endif // WIN32 \ No newline at end of file +#endif // WIN32 diff --git a/examples/ThirdPartyLibs/Gwen/events.cpp b/examples/ThirdPartyLibs/Gwen/events.cpp index 8d894464b7..f0dc641d4f 100644 --- a/examples/ThirdPartyLibs/Gwen/events.cpp +++ b/examples/ThirdPartyLibs/Gwen/events.cpp @@ -102,4 +102,4 @@ void Caller::RemoveHandler(Event::Handler* pObject) ++iter; } } -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/Gwen/inputhandler.cpp b/examples/ThirdPartyLibs/Gwen/inputhandler.cpp index 9f57ef6d75..b4d7e62c87 100644 --- a/examples/ThirdPartyLibs/Gwen/inputhandler.cpp +++ b/examples/ThirdPartyLibs/Gwen/inputhandler.cpp @@ -362,4 +362,4 @@ bool Gwen::Input::OnKeyEvent(Controls::Base* pCanvas, int iKey, bool bDown) } return false; -} \ No newline at end of file +} diff --git a/examples/ThirdPartyLibs/stb_image/stb_image_write.cpp b/examples/ThirdPartyLibs/stb_image/stb_image_write.cpp index 2009b05d5d..87c663a587 100644 --- a/examples/ThirdPartyLibs/stb_image/stb_image_write.cpp +++ b/examples/ThirdPartyLibs/stb_image/stb_image_write.cpp @@ -1,2 +1,2 @@ #define STB_IMAGE_WRITE_IMPLEMENTATION -#include "stb_image_write.h" \ No newline at end of file +#include "stb_image_write.h" diff --git a/examples/TinyRenderer/geometry.cpp b/examples/TinyRenderer/geometry.cpp index f4e0ee8f67..cea6fb40d0 100644 --- a/examples/TinyRenderer/geometry.cpp +++ b/examples/TinyRenderer/geometry.cpp @@ -22,4 +22,4 @@ template <> vec<2, float>::vec(const vec<2, int> &v) : x(v.x), y(v.y) { } -} \ No newline at end of file +} diff --git a/examples/Utils/ChromeTraceUtil.h b/examples/Utils/ChromeTraceUtil.h index 6b5e53dc94..e293013b07 100644 --- a/examples/Utils/ChromeTraceUtil.h +++ b/examples/Utils/ChromeTraceUtil.h @@ -6,4 +6,4 @@ void b3ChromeUtilsStartTimings(); void b3ChromeUtilsStopTimingsAndWriteJsonFile(const char* fileNamePrefix); void b3ChromeUtilsEnableProfiling(); -#endif //B3_CHROME_TRACE_UTIL_H \ No newline at end of file +#endif //B3_CHROME_TRACE_UTIL_H diff --git a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3BvhTraversal.h b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3BvhTraversal.h index e46ebdf16a..6f2e18928b 100644 --- a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3BvhTraversal.h +++ b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3BvhTraversal.h @@ -120,4 +120,4 @@ void b3BvhTraversal(__global const b3Int4* pairs, } } } -} \ No newline at end of file +} diff --git a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3Contact4Data.h b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3Contact4Data.h index 5ca48bad84..aac9d4c82c 100644 --- a/src/Bullet3Collision/NarrowPhaseCollision/shared/b3Contact4Data.h +++ b/src/Bullet3Collision/NarrowPhaseCollision/shared/b3Contact4Data.h @@ -33,4 +33,4 @@ inline void b3Contact4Data_setNumPoints(struct b3Contact4Data* contact, int numP contact->m_worldNormalOnB.w = (float)numPoints; } -#endif //B3_CONTACT4DATA_H \ No newline at end of file +#endif //B3_CONTACT4DATA_H diff --git a/src/Bullet3Common/b3Logging.h b/src/Bullet3Common/b3Logging.h index f61149de77..5f12927deb 100644 --- a/src/Bullet3Common/b3Logging.h +++ b/src/Bullet3Common/b3Logging.h @@ -71,4 +71,4 @@ extern "C" } #endif -#endif //B3_LOGGING_H \ No newline at end of file +#endif //B3_LOGGING_H diff --git a/src/Bullet3Common/shared/b3Int2.h b/src/Bullet3Common/shared/b3Int2.h index 013c40db33..b34aec381f 100644 --- a/src/Bullet3Common/shared/b3Int2.h +++ b/src/Bullet3Common/shared/b3Int2.h @@ -74,4 +74,4 @@ inline b3Int2 b3MakeInt2(int x, int y) #define b3MakeInt2 (int2) #endif //__cplusplus -#endif \ No newline at end of file +#endif diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.cpp b/src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.cpp index fe79f4a956..241b26cb18 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.cpp +++ b/src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.cpp @@ -100,4 +100,4 @@ void b3FixedConstraint::getInfo2(b3ConstraintInfo2* info, const b3RigidBodyData* { info->m_constraintError[(3 + j) * info->rowskip] = k * diff[j]; } -} \ No newline at end of file +} diff --git a/src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.cpp b/src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.cpp index 64f8f1a5d2..6e6e013585 100644 --- a/src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.cpp +++ b/src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.cpp @@ -1693,4 +1693,4 @@ b3Scalar b3PgsJacobiSolver::solveGroupCacheFriendlyFinish(b3RigidBodyData* bodie void b3PgsJacobiSolver::reset() { m_btSeed2 = 0; -} \ No newline at end of file +} diff --git a/src/Bullet3Dynamics/b3CpuRigidBodyPipeline.h b/src/Bullet3Dynamics/b3CpuRigidBodyPipeline.h index 9c65419f26..da33ea2bfd 100644 --- a/src/Bullet3Dynamics/b3CpuRigidBodyPipeline.h +++ b/src/Bullet3Dynamics/b3CpuRigidBodyPipeline.h @@ -59,4 +59,4 @@ class b3CpuRigidBodyPipeline int getNumBodies() const; }; -#endif //B3_CPU_RIGIDBODY_PIPELINE_H \ No newline at end of file +#endif //B3_CPU_RIGIDBODY_PIPELINE_H diff --git a/src/Bullet3Dynamics/shared/b3Inertia.h b/src/Bullet3Dynamics/shared/b3Inertia.h index 602a1335aa..c196d9402e 100644 --- a/src/Bullet3Dynamics/shared/b3Inertia.h +++ b/src/Bullet3Dynamics/shared/b3Inertia.h @@ -11,4 +11,4 @@ struct b3Inertia b3Mat3x3 m_initInvInertia; }; -#endif //B3_INERTIA_H \ No newline at end of file +#endif //B3_INERTIA_H diff --git a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.h b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.h index b76cb43b68..8ee4741e52 100644 --- a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.h +++ b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.h @@ -77,4 +77,4 @@ class b3GpuGridBroadphase : public b3GpuBroadphaseInterface virtual b3OpenCLArray& getLargeAabbIndicesGPU(); }; -#endif //B3_GPU_GRID_BROADPHASE_H \ No newline at end of file +#endif //B3_GPU_GRID_BROADPHASE_H diff --git a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.h b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.h index d17590b14a..433f0ad92f 100644 --- a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.h +++ b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.h @@ -140,4 +140,4 @@ class b3GpuSapBroadphase : public b3GpuBroadphaseInterface virtual b3OpenCLArray& getLargeAabbIndicesGPU(); }; -#endif //B3_GPU_SAP_BROADPHASE_H \ No newline at end of file +#endif //B3_GPU_SAP_BROADPHASE_H diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3BvhInfo.h b/src/Bullet3OpenCL/NarrowphaseCollision/b3BvhInfo.h index 27835bb747..db4202c5c9 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3BvhInfo.h +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3BvhInfo.h @@ -14,4 +14,4 @@ struct b3BvhInfo int m_subTreeOffset; }; -#endif //B3_BVH_INFO_H \ No newline at end of file +#endif //B3_BVH_INFO_H diff --git a/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.cpp b/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.cpp index 3490cafdee..b991dce63a 100644 --- a/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.cpp +++ b/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.cpp @@ -117,4 +117,4 @@ void b3PrefixScanCL::executeHost(b3AlignedObjectArray& src, b3Alig { *sum = dst[n - 1]; } -} \ No newline at end of file +} diff --git a/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanFloat4CL.cpp b/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanFloat4CL.cpp index 3b497c300d..651e515f65 100644 --- a/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanFloat4CL.cpp +++ b/src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanFloat4CL.cpp @@ -117,4 +117,4 @@ void b3PrefixScanFloat4CL::executeHost(b3AlignedObjectArray& src, b3A { *sum = dst[n - 1]; } -} \ No newline at end of file +} diff --git a/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp b/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp index 70b7674b31..d07acb25ab 100644 --- a/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp +++ b/src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp @@ -376,4 +376,4 @@ void b3GpuRaycast::castRays(const b3AlignedObjectArray& rays, b3Align B3_PROFILE("raycast copyToHost"); m_data->m_gpuHitResults->copyToHost(hitResults); } -} \ No newline at end of file +} diff --git a/src/Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipeline.h b/src/Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipeline.h index 0e5c6fec12..e7506673b5 100644 --- a/src/Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipeline.h +++ b/src/Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipeline.h @@ -67,4 +67,4 @@ class b3GpuRigidBodyPipeline int getNumBodies() const; }; -#endif //B3_GPU_RIGIDBODY_PIPELINE_H \ No newline at end of file +#endif //B3_GPU_RIGIDBODY_PIPELINE_H diff --git a/src/BulletCollision/CollisionShapes/btCollisionShape.cpp b/src/BulletCollision/CollisionShapes/btCollisionShape.cpp index 0b3640a65b..d3abfb94fe 100644 --- a/src/BulletCollision/CollisionShapes/btCollisionShape.cpp +++ b/src/BulletCollision/CollisionShapes/btCollisionShape.cpp @@ -116,4 +116,4 @@ void btCollisionShape::serializeSingleShape(btSerializer* serializer) const btChunk* chunk = serializer->allocate(len, 1); const char* structType = serialize(chunk->m_oldPtr, serializer); serializer->finalizeChunk(chunk, structType, BT_SHAPE_CODE, (void*)this); -} \ No newline at end of file +} diff --git a/src/BulletCollision/CollisionShapes/btConeShape.cpp b/src/BulletCollision/CollisionShapes/btConeShape.cpp index 64a6f272ca..b6c9876f21 100644 --- a/src/BulletCollision/CollisionShapes/btConeShape.cpp +++ b/src/BulletCollision/CollisionShapes/btConeShape.cpp @@ -139,4 +139,4 @@ void btConeShape::setLocalScaling(const btVector3& scaling) m_radius *= (scaling[r1] / m_localScaling[r1] + scaling[r2] / m_localScaling[r2]) / 2; m_sinAngle = (m_radius / btSqrt(m_radius * m_radius + m_height * m_height)); btConvexInternalShape::setLocalScaling(scaling); -} \ No newline at end of file +} diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.cpp b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.cpp index 3497d0c9c7..562fbce783 100644 --- a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.cpp +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.cpp @@ -789,4 +789,4 @@ void btReducedDeformableBody::disableReducedModes(const bool rigid_only) bool btReducedDeformableBody::isReducedModesOFF() const { return m_rigidOnly; -} \ No newline at end of file +} diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h index 8968fb0cb9..5a1143f9fd 100644 --- a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBody.h @@ -254,4 +254,4 @@ class btReducedDeformableBody : public btSoftBody #endif }; -#endif // BT_REDUCED_SOFT_BODY_H \ No newline at end of file +#endif // BT_REDUCED_SOFT_BODY_H diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h index 2b259a931f..40552a8818 100644 --- a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodyHelpers.h @@ -22,4 +22,4 @@ struct btReducedDeformableBodyHelpers }; -#endif // BT_REDUCED_SOFT_BODY_HELPERS_H \ No newline at end of file +#endif // BT_REDUCED_SOFT_BODY_HELPERS_H diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.cpp b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.cpp index 3e1c6cc14e..e334986779 100644 --- a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.cpp +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.cpp @@ -322,4 +322,4 @@ void btReducedDeformableBodySolver::deformableBodyInternalWriteBack() rsb->applyInternalVelocityChanges(); } m_ascendOrder = true; -} \ No newline at end of file +} diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h index 04c171f315..a3e966c2b3 100644 --- a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableBodySolver.h @@ -58,4 +58,4 @@ class btReducedDeformableBodySolver : public btDeformableBodySolver }; -#endif // BT_REDUCED_DEFORMABLE_BODY_DYNAMICS_WORLD_H \ No newline at end of file +#endif // BT_REDUCED_DEFORMABLE_BODY_DYNAMICS_WORLD_H diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp index e94ff4c3b1..e8c8ea597f 100644 --- a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.cpp @@ -576,4 +576,4 @@ btVector3 btReducedDeformableFaceRigidContactConstraint::getDv(const btSoftBody: void btReducedDeformableFaceRigidContactConstraint::applyImpulse(const btVector3& /*impulse*/) { // -} \ No newline at end of file +} diff --git a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.h b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.h index cb88d7461a..91adeef189 100644 --- a/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.h +++ b/src/BulletSoftBody/BulletReducedDeformableBody/btReducedDeformableContactConstraint.h @@ -191,4 +191,4 @@ class btReducedDeformableFaceRigidContactConstraint : public btReducedDeformable // this calls reduced deformable body's applyFullSpaceImpulse virtual void applyImpulse(const btVector3& impulse); -}; \ No newline at end of file +}; diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index 027e2c3598..f1658a292b 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -590,4 +590,4 @@ void btDeformableBodySolver::applyTransforms(btScalar timeStep) } psb->interpolateRenderMesh(); } -} \ No newline at end of file +} diff --git a/test/BulletDynamics/test_btKinematicCharacterController.cpp b/test/BulletDynamics/test_btKinematicCharacterController.cpp index e06dbf3213..9fde9e5929 100644 --- a/test/BulletDynamics/test_btKinematicCharacterController.cpp +++ b/test/BulletDynamics/test_btKinematicCharacterController.cpp @@ -23,4 +23,4 @@ int main(int argc, char** argv) { ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); -} \ No newline at end of file +} From fafb5e576d65acb541c8dc98ac3c7484ba637591 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 02:35:22 +0100 Subject: [PATCH 39/57] Compiler warnings - format specifier printf --- Extras/HACD/hacdHACD.cpp | 2 +- examples/InverseDynamics/InverseDynamicsExample.cpp | 4 ++-- src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Extras/HACD/hacdHACD.cpp b/Extras/HACD/hacdHACD.cpp index cd38a7018a..ae64518ebc 100644 --- a/Extras/HACD/hacdHACD.cpp +++ b/Extras/HACD/hacdHACD.cpp @@ -654,7 +654,7 @@ void HACD::Simplify() if (m_callBack) { char msg[1024]; - sprintf(msg, "\t CH \t %lu \t %lf \t %lf\n", static_cast(p), m_graph.m_vertices[v].m_concavity, m_graph.m_vertices[v].m_error); + sprintf(msg, "\t CH \t %lu \t %f \t %f\n", static_cast(p), m_graph.m_vertices[v].m_concavity, m_graph.m_vertices[v].m_error); (*m_callBack)(msg, 0.0, 0.0, m_nClusters); p++; } diff --git a/examples/InverseDynamics/InverseDynamicsExample.cpp b/examples/InverseDynamics/InverseDynamicsExample.cpp index 95ad3dbf7f..840f67f689 100644 --- a/examples/InverseDynamics/InverseDynamicsExample.cpp +++ b/examples/InverseDynamics/InverseDynamicsExample.cpp @@ -220,11 +220,11 @@ void InverseDynamicsExample::initPhysics() if (m_timeSeriesCanvas && m_guiHelper->getParameterInterface()) { - for (std::size_t dof = 0; dof < qd.size(); dof++) + for (unsigned int dof = 0; dof < qd.size(); dof++) { qd[dof] = 0; char tmp[25]; - sprintf(tmp, "q_desired[%zu]", dof); + sprintf(tmp, "q_desired[%u]", dof); qd_name[dof] = tmp; SliderParams slider(qd_name[dof].c_str(), &qd[dof]); slider.m_minVal = -3.14; diff --git a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.cpp b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.cpp index 618cae5c25..d343562591 100644 --- a/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.cpp +++ b/src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.cpp @@ -247,7 +247,7 @@ void b3GpuGridBroadphase::calculateOverlappingPairs(int maxPairs) printf("m_gpuPairs.size()=%d\n", sz); for (size_t i = 0; i < m_gpuPairs.size(); i++) { - printf("pair %zu = %d,%d\n", i, pairsCpu[i].x, pairsCpu[i].y); + printf("pair %u = %d,%d\n", (unsigned int)i, pairsCpu[i].x, pairsCpu[i].y); } printf("?!?\n"); From 60f62045956d5f7f5ae3fccff4cb0072ca4bee08 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 02:40:04 +0100 Subject: [PATCH 40/57] Compiler warnings - multiline comment - gtest --- test/gtest-1.7.0/include/gtest/gtest.h | 2 +- test/gtest-1.7.0/src/gtest.cc | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/test/gtest-1.7.0/include/gtest/gtest.h b/test/gtest-1.7.0/include/gtest/gtest.h index ef30ce95f9..3deb515242 100644 --- a/test/gtest-1.7.0/include/gtest/gtest.h +++ b/test/gtest-1.7.0/include/gtest/gtest.h @@ -1494,7 +1494,7 @@ AssertionResult CmpHelperEQ(const char* expected_expression, { #ifdef _MSC_VER #pragma warning(push) // Saves the current warning state. -#pragma warning(disable : 4389) // Temporarily disables warning on \ +#pragma warning(disable : 4389) // Temporarily disables warning on // signed/unsigned mismatch. #endif diff --git a/test/gtest-1.7.0/src/gtest.cc b/test/gtest-1.7.0/src/gtest.cc index e5f294f72d..b90a556cfd 100644 --- a/test/gtest-1.7.0/src/gtest.cc +++ b/test/gtest-1.7.0/src/gtest.cc @@ -3573,7 +3573,7 @@ std::string FormatEpochTimeInMillisAsIso8601(TimeInMillis ms) time_t seconds = static_cast(ms / 1000); #ifdef _MSC_VER #pragma warning(push) // Saves the current warning state. -#pragma warning(disable : 4996) // Temporarily disables warning 4996 \ +#pragma warning(disable : 4996) // Temporarily disables warning 4996 // (function or variable may be unsafe). const struct tm* const time_struct = localtime(&seconds); // NOLINT #pragma warning(pop) // Restores the warning state again. @@ -4428,7 +4428,7 @@ UnitTestImpl::UnitTestImpl(UnitTest* parent) : parent_(parent), #ifdef _MSC_VER #pragma warning(push) // Saves the current warning state. -#pragma warning(disable : 4355) // Temporarily disables warning 4355 \ +#pragma warning(disable : 4355) // Temporarily disables warning 4355 // (using this in initializer). default_global_test_part_result_reporter_(this), default_per_thread_test_part_result_reporter_(this), From 0bd1b90ef074d156cf943647bb677b9e20a91e52 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 02:40:25 +0100 Subject: [PATCH 41/57] Compiler warnings - type conversion - gtest --- test/gtest-1.7.0/include/gtest/gtest.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/gtest-1.7.0/include/gtest/gtest.h b/test/gtest-1.7.0/include/gtest/gtest.h index 3deb515242..4487d7ef7b 100644 --- a/test/gtest-1.7.0/include/gtest/gtest.h +++ b/test/gtest-1.7.0/include/gtest/gtest.h @@ -1498,7 +1498,7 @@ AssertionResult CmpHelperEQ(const char* expected_expression, // signed/unsigned mismatch. #endif - if (expected == actual) + if ((int)expected == actual) { return AssertionSuccess(); } From d28e36746929470831e9dcb7c33008f0871d7ee0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 21:43:20 +0100 Subject: [PATCH 42/57] Compiler warnings - unused parameter - stb_truetype --- examples/ThirdPartyLibs/stb_image/stb_truetype.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/ThirdPartyLibs/stb_image/stb_truetype.h b/examples/ThirdPartyLibs/stb_image/stb_truetype.h index 1510d4b589..fa8f9b28d4 100644 --- a/examples/ThirdPartyLibs/stb_image/stb_truetype.h +++ b/examples/ThirdPartyLibs/stb_image/stb_truetype.h @@ -2201,7 +2201,7 @@ static void stbtt__fill_active_edges_new(float *scanline, float *scanline_fill, } // directly AA rasterize edges w/o supersampling -static void stbtt__rasterize_sorted_edges(stbtt__bitmap *result, stbtt__edge *e, int n, int vsubsample, int off_x, int off_y, void *userdata) +static void stbtt__rasterize_sorted_edges(stbtt__bitmap *result, stbtt__edge *e, int n, int /*vsubsample*/, int off_x, int off_y, void *userdata) { stbtt__hheap hh = {}; stbtt__active_edge *active = NULL; From b09bb0151bf1f73d2b60d5f0e3e0a4ecff6a29fd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 12 Apr 2024 00:25:01 +0200 Subject: [PATCH 43/57] Compiler warnings - uninitialized members - stb_image --- examples/ThirdPartyLibs/stb_image/stb_image.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/ThirdPartyLibs/stb_image/stb_image.cpp b/examples/ThirdPartyLibs/stb_image/stb_image.cpp index 5f9d6a86d5..bbb8e0a3cc 100644 --- a/examples/ThirdPartyLibs/stb_image/stb_image.cpp +++ b/examples/ThirdPartyLibs/stb_image/stb_image.cpp @@ -4341,7 +4341,7 @@ static uint8 *stbi_gif_load_next(stbi *s, stbi_gif *g, int *comp, int req_comp) static stbi_uc *stbi_gif_load(stbi *s, int *x, int *y, int *comp, int req_comp) { uint8 *u = 0; - stbi_gif g = {0}; + stbi_gif g = {}; u = stbi_gif_load_next(s, &g, comp, req_comp); if (u == (void *)1) u = 0; // end of animated gif marker From 4661e2381fee2be04533db3716b669f44518c304 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 02:42:17 +0100 Subject: [PATCH 44/57] Compiler warnings - stb_truetype - refine macro for unused parameters --- examples/ThirdPartyLibs/imgui/stb_truetype.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/ThirdPartyLibs/imgui/stb_truetype.h b/examples/ThirdPartyLibs/imgui/stb_truetype.h index 2e8b093bb1..a84078b440 100644 --- a/examples/ThirdPartyLibs/imgui/stb_truetype.h +++ b/examples/ThirdPartyLibs/imgui/stb_truetype.h @@ -462,8 +462,8 @@ typedef char stbtt__check_size16[sizeof(stbtt_int16) == 2 ? 1 : -1]; // #define your own functions "STBTT_malloc" / "STBTT_free" to avoid malloc.h #ifndef STBTT_malloc #include -#define STBTT_malloc(x, u) ((void)(u), malloc(x)) -#define STBTT_free(x, u) ((void)(u), free(x)) +#define STBTT_malloc(x, u) ((void)(u); malloc(x)) +#define STBTT_free(x, u) ((void)(u); free(x)) #endif #ifndef STBTT_assert From edcb9a4a55732ab7300eadad9fded1e435b5fc2a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Thu, 11 Apr 2024 23:29:22 +0200 Subject: [PATCH 45/57] Compiler warnings - ignored loop variable (MSVC C4258) --- examples/SharedMemory/PhysicsServerCommandProcessor.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index ad89ddddc5..ad95eabbec 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -5011,9 +5011,9 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str btScalar* datafl = (btScalar*)heightfieldData; - for (int i = 0; i < width * height; i++) + for (int j = 0; j < width * height; j++) { - heightfieldDest[i] = datafl[i]; + heightfieldDest[j] = datafl[j]; } //update graphics From 901c1ac03bfebf2d504d30e0621529234908e704 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 23:40:23 +0100 Subject: [PATCH 46/57] Compiler warnings - documentation-unknown-command --- src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h | 2 +- src/LinearMath/btHashMap.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h b/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h index 3668cabcdc..dcda5f7e33 100644 --- a/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h +++ b/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h @@ -30,7 +30,7 @@ subject to the following restrictions: ///It is recommended to enable useQuantizedAabbCompression for better memory usage. ///It takes a triangle mesh as input, for example a btTriangleMesh or btTriangleIndexVertexArray. The btBvhTriangleMeshShape class allows for triangle mesh deformations by a refit or partialRefit method. ///Instead of building the bounding volume hierarchy acceleration structure, it is also possible to serialize (save) and deserialize (load) the structure from disk. -///See Demos\ConcaveDemo\ConcavePhysicsDemo.cpp for an example. +///See Demos/ConcaveDemo/ConcavePhysicsDemo.cpp for an example. ATTRIBUTE_ALIGNED16(class) btBvhTriangleMeshShape : public btTriangleMeshShape { diff --git a/src/LinearMath/btHashMap.h b/src/LinearMath/btHashMap.h index 528b12527f..7c0896660e 100644 --- a/src/LinearMath/btHashMap.h +++ b/src/LinearMath/btHashMap.h @@ -214,7 +214,7 @@ class btHashKey }; ///The btHashMap template class implements a generic and lightweight hashmap. -///A basic sample of how to use btHashMap is located in Demos\BasicDemo\main.cpp +///A basic sample of how to use btHashMap is located in Demos/BasicDemo/main.cpp template class btHashMap { From 5e77db933b2202a5348129492bdd7e3105365bf2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 20:38:28 +0100 Subject: [PATCH 47/57] Compiler error - M_PI undefined --- examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp | 3 +-- examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp | 4 ++-- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp b/examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp index a835f904e3..a8f78e5fcd 100644 --- a/examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp +++ b/examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp @@ -1,9 +1,8 @@ +#define _USE_MATH_DEFINES #include "MathUtil.h" #include -#define _USE_MATH_DEFINES #include - int cMathUtil::Clamp(int val, int min, int max) { return std::max(min, std::min(val, max)); diff --git a/examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp b/examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp index ec8919152b..738265b6f7 100644 --- a/examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp +++ b/examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp @@ -1,8 +1,8 @@ +#define _USE_MATH_DEFINES #include "RBDUtil.h" #include - -#define _USE_MATH_DEFINES #include "math.h" + void cRBDUtil::SolveInvDyna(const cRBDModel& model, const Eigen::VectorXd& acc, Eigen::VectorXd& out_tau) { const Eigen::MatrixXd& joint_mat = model.GetJointMat(); From 850590e682b64ff194b6574c23b4122afc74e34b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Thu, 11 Apr 2024 23:50:12 +0200 Subject: [PATCH 48/57] Compiler error - snprintf undefined --- .../PhysicsClientSharedMemory.cpp | 23 +++++++++++-------- 1 file changed, 14 insertions(+), 9 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.cpp b/examples/SharedMemory/PhysicsClientSharedMemory.cpp index 2919b2a0e2..0a23f89498 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsClientSharedMemory.cpp @@ -889,43 +889,48 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() char msg[1024]; #define customMin(a,b) (a < b ? a : b) #define currPos(buf) (buf + customMin(1000,strlen(buf))) + #if defined(_MSC_VER) + #define printfVariant _snprintf + #else + #define printfVariant snprintf + #endif { - snprintf(msg,1024, "Q=["); + printfVariant(msg,1024, "Q=["); for (int i = 0; i < numQ; i++) { if (i < numQ - 1) { - snprintf(currPos(msg),1024, "%f,", + printfVariant(currPos(msg),1024, "%f,", m_data->m_cachedState.m_actualStateQ[i]); } else { - snprintf(currPos(msg),1024, "%f", + printfVariant(currPos(msg),1024, "%f", m_data->m_cachedState.m_actualStateQ[i]); } } - snprintf(currPos(msg),1024, "]"); + printfVariant(currPos(msg),1024, "]"); } b3Printf(msg); - snprintf(currPos(msg),1024, "U=["); + printfVariant(currPos(msg),1024, "U=["); for (int i = 0; i < numU; i++) { if (i < numU - 1) { - snprintf(currPos(msg),1024, "%f,", + printfVariant(currPos(msg),1024, "%f,", m_data->m_cachedState.m_actualStateQdot[i]); } else { - snprintf(currPos(msg),1024, "%f", + printfVariant(currPos(msg),1024, "%f", m_data->m_cachedState.m_actualStateQdot[i]); } } - snprintf(currPos(msg),1024, "]"); - + printfVariant(currPos(msg),1024, "]"); + #undef printfVariant #undef customMin #undef currPos b3Printf(msg); From ddb96563e0b985eda713edf3376a45f70a79fa68 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 20:38:47 +0100 Subject: [PATCH 49/57] MinGW compatibility --- examples/RobotSimulator/CMakeLists.txt | 6 +++--- examples/StandaloneMain/hellovr_opengl_main.cpp | 2 +- examples/ThirdPartyLibs/clsocket/CMakeLists.txt | 2 +- examples/TwoJoint/CMakeLists.txt | 2 +- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/examples/RobotSimulator/CMakeLists.txt b/examples/RobotSimulator/CMakeLists.txt index c17481f8c7..9e4008ec88 100644 --- a/examples/RobotSimulator/CMakeLists.txt +++ b/examples/RobotSimulator/CMakeLists.txt @@ -75,7 +75,7 @@ TARGET_LINK_LIBRARIES(App_RobotSimulator BulletRobotics BulletExampleBrowserLib IF(WIN32) IF(BUILD_ENET OR BUILD_CLSOCKET) - TARGET_LINK_LIBRARIES(App_RobotSimulator ws2_32 Winmm) + TARGET_LINK_LIBRARIES(App_RobotSimulator ws2_32 winmm) ENDIF(BUILD_ENET OR BUILD_CLSOCKET) ENDIF(WIN32) @@ -106,7 +106,7 @@ TARGET_LINK_LIBRARIES(App_RobotSimulator_NoGUI BulletRobotics BulletFileLoader B IF(WIN32) IF(BUILD_ENET OR BUILD_CLSOCKET) - TARGET_LINK_LIBRARIES(App_RobotSimulator_NoGUI ws2_32 Winmm) + TARGET_LINK_LIBRARIES(App_RobotSimulator_NoGUI ws2_32 winmm) ENDIF(BUILD_ENET OR BUILD_CLSOCKET) ELSE() IF(APPLE) @@ -143,7 +143,7 @@ TARGET_LINK_LIBRARIES(App_HelloBulletRobotics BulletRobotics BulletFileLoader Bu IF(WIN32) IF(BUILD_ENET OR BUILD_CLSOCKET) - TARGET_LINK_LIBRARIES(App_HelloBulletRobotics ws2_32 Winmm) + TARGET_LINK_LIBRARIES(App_HelloBulletRobotics ws2_32 winmm) ENDIF(BUILD_ENET OR BUILD_CLSOCKET) ELSE() IF(NOT APPLE) diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index 29113ce19d..5174b9286b 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -55,7 +55,7 @@ static vr::VRControllerState_t sPrevStates[vr::k_unMaxTrackedDeviceCount] = {}; #include "unistd.h" #endif #ifdef _WIN32 -#include +#include #endif #ifdef __linux__ #define APIENTRY diff --git a/examples/ThirdPartyLibs/clsocket/CMakeLists.txt b/examples/ThirdPartyLibs/clsocket/CMakeLists.txt index bb9a4c1e14..602ae74971 100644 --- a/examples/ThirdPartyLibs/clsocket/CMakeLists.txt +++ b/examples/ThirdPartyLibs/clsocket/CMakeLists.txt @@ -33,7 +33,7 @@ if(UNIX) add_definitions(${OSDEF}) elseif(WIN32) add_definitions(-DWIN32) - SET(PROJECT_LIBS Ws2_32.lib) + SET(PROJECT_LIBS ws2_32.lib) if(MINGW) # Special MINGW stuff here elseif(MSVC) diff --git a/examples/TwoJoint/CMakeLists.txt b/examples/TwoJoint/CMakeLists.txt index 210f5ee3b3..bb62fd869e 100644 --- a/examples/TwoJoint/CMakeLists.txt +++ b/examples/TwoJoint/CMakeLists.txt @@ -177,7 +177,7 @@ SET_TARGET_PROPERTIES(App_TwoJoint PROPERTIES DEBUG_POSTFIX "_d") IF(WIN32) IF(BUILD_ENET OR BUILD_CLSOCKET) - TARGET_LINK_LIBRARIES(App_TwoJoint ws2_32 ) + TARGET_LINK_LIBRARIES(App_TwoJoint ws2_32 winmm) ENDIF(BUILD_ENET OR BUILD_CLSOCKET) ENDIF(WIN32) From e328adc76669e2884f7558d8230fa576a1d7fc44 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 16:10:59 +0100 Subject: [PATCH 50/57] inverse square root - float only - newer version of GIMPACT has this reworked a lot --- src/BulletCollision/Gimpact/gim_math.h | 30 +++++++++++++++----------- 1 file changed, 18 insertions(+), 12 deletions(-) diff --git a/src/BulletCollision/Gimpact/gim_math.h b/src/BulletCollision/Gimpact/gim_math.h index 3c4f821a72..007bb6cfe6 100644 --- a/src/BulletCollision/Gimpact/gim_math.h +++ b/src/BulletCollision/Gimpact/gim_math.h @@ -109,19 +109,25 @@ enum GIM_SCALAR_TYPES a = a - b; \ } -#define GIM_INV_SQRT(va, isva) \ +#define GIM_INV_SQRT(va, isva) \ { \ - if (va <= 0.0000001f) \ - { \ - isva = G_REAL_INFINITY; \ - } \ - else \ - { \ - GREAL _x = va * 0.5f; \ - GUINT _y = 0x5f3759df - (GIM_IR(va) >> 1); \ - isva = GIM_FR(_y); \ - isva = isva * (1.5f - (_x * isva * isva)); \ - } \ + const bool isFloat = sizeof(va)==sizeof(float); \ + if(!isFloat) \ + isva = 1.0 / sqrt(va); \ + else \ + { \ + if (va <= 0.0000001f) \ + { \ + isva = G_REAL_INFINITY; \ + } \ + else \ + { \ + GREAL _x = va * 0.5f; \ + GUINT _y = 0x5f3759df - (GIM_IR(va) >> 1); \ + isva = GIM_FR(_y); \ + isva = isva * (1.5f - (_x * isva * isva)); \ + } \ + }\ } #define GIM_SQRT(va, sva) \ From 8914bfda2c2f67a3be8b70880c50630618aa7c00 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 16:12:03 +0100 Subject: [PATCH 51/57] remove unnecessary overwrite of STBTT_malloc and _free --- examples/OpenGLWindow/fontstash.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/examples/OpenGLWindow/fontstash.cpp b/examples/OpenGLWindow/fontstash.cpp index 0881f02a0a..cf1a128bc3 100644 --- a/examples/OpenGLWindow/fontstash.cpp +++ b/examples/OpenGLWindow/fontstash.cpp @@ -33,8 +33,6 @@ #define ADDITIONAL_HEIGHT 2 #define STB_TRUETYPE_IMPLEMENTATION -#define STBTT_malloc(x, u) malloc(x) -#define STBTT_free(x, u) free(x) #include "stb_image/stb_truetype.h" #define HASH_LUT_SIZE 256 From 9deea03776d88189b3047a6c844a6ced808961cb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 03:28:57 +0100 Subject: [PATCH 52/57] clang suggested bugfix --- examples/MultiBody/Pendulum.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/MultiBody/Pendulum.cpp b/examples/MultiBody/Pendulum.cpp index 51690432d9..310bd8119f 100644 --- a/examples/MultiBody/Pendulum.cpp +++ b/examples/MultiBody/Pendulum.cpp @@ -184,7 +184,7 @@ TEST(BulletDynamicsTest, pendulum) DummyGUIHelper noGfx; Pendulum* setup = new Pendulum(&noGfx); setup->initPhysics(); - int numGoldValues = sizeof(sPendulumGold) / sizeof(float); + int numGoldValues = sizeof(sPendulumGold) / sizeof(btScalar); for (int i = 0; i < 2000; i++) { setup->stepSimulation(0.001); From 78fc47bbbce43f69fbca6f6e615a04c82532ee85 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 03:54:49 +0100 Subject: [PATCH 53/57] documentation fix --- src/LinearMath/btMatrix3x3.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/LinearMath/btMatrix3x3.h b/src/LinearMath/btMatrix3x3.h index d43d51ca2f..b0bf65c6ae 100644 --- a/src/LinearMath/btMatrix3x3.h +++ b/src/LinearMath/btMatrix3x3.h @@ -333,7 +333,7 @@ btMatrix3x3 #endif } - /**@brief Set the matrix to the identity */ + /**@brief Set the matrix to zero */ void setZero() { #if (defined(BT_USE_SSE_IN_API) && defined(BT_USE_SSE)) || defined(BT_USE_NEON) From 5bffd756a8e9ba14b71b0c7f66770759fa2c0d6b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Sat, 9 Mar 2024 23:02:13 +0100 Subject: [PATCH 54/57] include files removed for C++98 mode compilation with GCC --- examples/ReducedDeformableDemo/ConservationTest.cpp | 1 - examples/ThirdPartyLibs/openvr/samples/shared/compat.h | 1 - 2 files changed, 2 deletions(-) diff --git a/examples/ReducedDeformableDemo/ConservationTest.cpp b/examples/ReducedDeformableDemo/ConservationTest.cpp index 505f3d444d..3acf29a66c 100644 --- a/examples/ReducedDeformableDemo/ConservationTest.cpp +++ b/examples/ReducedDeformableDemo/ConservationTest.cpp @@ -22,7 +22,6 @@ #include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" #include "../CommonInterfaces/CommonParameterInterface.h" #include //printf debugging -#include #include "../CommonInterfaces/CommonDeformableBodyBase.h" #include "../Utils/b3ResourcePath.h" diff --git a/examples/ThirdPartyLibs/openvr/samples/shared/compat.h b/examples/ThirdPartyLibs/openvr/samples/shared/compat.h index d7ada5674e..0ace018660 100644 --- a/examples/ThirdPartyLibs/openvr/samples/shared/compat.h +++ b/examples/ThirdPartyLibs/openvr/samples/shared/compat.h @@ -8,7 +8,6 @@ // Handle non standard code. #ifndef _WIN32 -#include #include #define sprintf_s snprintf From 9fb78ecd8365a166a429777d1a4994ef879c0d01 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 8 Mar 2024 16:12:44 +0100 Subject: [PATCH 55/57] unsolved - variadic args in macros --- examples/ThirdPartyLibs/optionalX11/X11/Xfuncproto.h | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/examples/ThirdPartyLibs/optionalX11/X11/Xfuncproto.h b/examples/ThirdPartyLibs/optionalX11/X11/Xfuncproto.h index db6d41f4bf..f8eec049e3 100644 --- a/examples/ThirdPartyLibs/optionalX11/X11/Xfuncproto.h +++ b/examples/ThirdPartyLibs/optionalX11/X11/Xfuncproto.h @@ -132,11 +132,12 @@ in this Software without prior written authorization from The Open Group. /* requires xproto >= 7.0.22 - since this uses either gcc or C99 variable argument macros, must be only used inside #ifdef _X_NONNULL guards, as - many legacy X clients are compiled in C89 mode still. */ -#if defined(__GNUC__) && ((__GNUC__ * 100 + __GNUC_MINOR__) >= 303) -#define _X_NONNULL(args...) __attribute__((nonnull(args))) -#elif defined(__STDC_VERSION__) && (__STDC_VERSION__ - 0 >= 199901L) /* C99 */ + many legacy X clients are compiled in C89 mode still. + For C++ variadic macros were introduced in C++11 */ +#if (defined(__STDC_VERSION__) && (__STDC_VERSION__ - 0 >= 199901L)) || (defined(__cplusplus) && _cplusplus >= 201103L) /* C99 */ #define _X_NONNULL(...) /* */ +#elif defined(__GNUC__) && ((__GNUC__ * 100 + __GNUC_MINOR__) >= 303) +#define _X_NONNULL(args...) __attribute__((nonnull(args))) #endif /* requires xproto >= 7.0.22 */ From e3e1df53811106defb248c163cc504868e281f60 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 12 Apr 2024 02:05:53 +0200 Subject: [PATCH 56/57] CMake - compile settings more pedantic build --- CMakeLists.txt | 45 +++++++++++++++++++++++++++++++++++++++++++++ MinGW64.cmake | 35 +++++++++++++++++++++++++++++++++++ 2 files changed, 80 insertions(+) create mode 100644 MinGW64.cmake diff --git a/CMakeLists.txt b/CMakeLists.txt index a695b71726..0f3bca3421 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -4,6 +4,10 @@ cmake_policy(SET CMP0017 NEW) #this line has to appear before 'PROJECT' in order to be able to disable incremental linking SET(MSVC_INCREMENTAL_DEFAULT ON) +if(TOOLCHAIN_ROOT) + include(MinGW64.cmake) +endif() + PROJECT(BULLET_PHYSICS) FILE (STRINGS "VERSION" BULLET_VERSION) @@ -269,6 +273,47 @@ IF (BULLET2_USE_OPEN_MP_MULTITHREADING) ENDIF (MSVC) ENDIF (BULLET2_USE_OPEN_MP_MULTITHREADING) +set(CMAKE_CXX_STANDARD 98) +set(CMAKE_CXX_STANDARD_REQUIRED ON) +set(CMAKE_CXX_EXTENSIONS OFF) +IF(MSVC) + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /W4") + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /wd4127") # conditional expression is constant + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /wd4456") # hides previous local declaration + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /wd4457") # hides function parameter + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /wd4458") # hides class member + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /wd4459") # hides global declaration + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /wd4996") # tr1 namespace deprecated + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /wd4312") # int to pointer + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /wd4706") # assign within conditional expression + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /wd4512") # assignment operator could not be generated + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /wd4714") # __forceinline not inlined + if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER_EQUAL 19.10) # from MSVC 2017 + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /Zc:__cplusplus /permissive-") + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /std:c++14") # earliest c++ standard explicitly supported + endif() +ELSE() + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic -Werror") + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-int-to-void-pointer-cast") # hellovr, SimpleSocket + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-int-to-pointer-cast") # hellovr, stb_image + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-long-long") # C++98 has no long long + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-variadic-macros") # C++98 variadic macros + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-missing-field-initializers") # gtest, stb_image + IF(CMAKE_CXX_COMPILER_ID MATCHES "GNU") + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-maybe-uninitialized") # gtest + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-ignored-attributes") # b3Int64 cl_long + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-deprecated-copy") # GIMPACT + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-strict-aliasing") # GIMPACT, btSoftBody, OpenCL + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-stringop-overflow") # btAlignedObjectArray - placement new + ELSEIF(CMAKE_CXX_COMPILER_ID MATCHES "Clang") + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-zero-as-null-pointer-constant") + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-deprecated-copy-with-user-provided-copy") # GIMPACT + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-overloaded-virtual") # exampleBrowser OpenGLGuiHelper and btDeformable* + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-null-pointer-subtraction") # btSoftBody + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-invalid-offsetof") # hellovr + ENDIF() +ENDIF() + IF (BULLET2_USE_TBB_MULTITHREADING) SET (BULLET2_TBB_INCLUDE_DIR "not found" CACHE PATH "Directory for Intel TBB includes.") SET (BULLET2_TBB_LIB_DIR "not found" CACHE PATH "Directory for Intel TBB libraries.") diff --git a/MinGW64.cmake b/MinGW64.cmake new file mode 100644 index 0000000000..3f6447dc03 --- /dev/null +++ b/MinGW64.cmake @@ -0,0 +1,35 @@ +# source: https://gist.github.com/peterspackman/8cf73f7f12ba270aa8192d6911972fe8 + +# Sample toolchain file for building for Windows from an Ubuntu Linux system. +# +# Typical usage: +# *) install cross compiler: `sudo apt-get install mingw-w64` +# *) cd build +# *) cmake -DCMAKE_TOOLCHAIN_FILE=~/mingw-w64-x86_64.cmake .. +# This is free and unencumbered software released into the public domain. + +if(CMAKE_HOST_SYSTEM_NAME STREQUAL "Windows") + set(EXE_EXTENSION .exe) +else() + set(EXE_EXTENSION) +endif() +set(CMAKE_SYSTEM_NAME Windows) +set(TOOLCHAIN_PREFIX ${TOOLCHAIN_ROOT}x86_64-w64-mingw32) + +# cross compilers to use for C, C++ and Fortran +set(CMAKE_ASM_COMPILER ${TOOLCHAIN_PREFIX}-gcc${EXE_EXTENSION}) +set(CMAKE_C_COMPILER_AR ${TOOLCHAIN_PREFIX}-ar${EXE_EXTENSION}) +set(CMAKE_C_COMPILER_RANLIB ${TOOLCHAIN_PREFIX}-ranlib${EXE_EXTENSION}) +set(CMAKE_C_COMPILER ${TOOLCHAIN_PREFIX}-gcc${EXE_EXTENSION}) +set(CMAKE_CXX_COMPILER_AR ${TOOLCHAIN_PREFIX}-ar${EXE_EXTENSION}) +set(CMAKE_CXX_COMPILER_RANLIB ${TOOLCHAIN_PREFIX}-ranlib${EXE_EXTENSION}) +set(CMAKE_CXX_COMPILER ${TOOLCHAIN_PREFIX}-g++${EXE_EXTENSION}) +set(CMAKE_Fortran_COMPILER ${TOOLCHAIN_PREFIX}-gfortran${EXE_EXTENSION}) +set(CMAKE_RC_COMPILER ${TOOLCHAIN_PREFIX}-windres${EXE_EXTENSION}) +# target environment on the build host system +set(CMAKE_FIND_ROOT_PATH ${TOOLCHAIN_PREFIX}) + +# modify default behavior of FIND_XXX() commands +set(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER) +set(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY) +set(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY) From 757487eedb1368b87f25050682b116252d08e1e1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Max=20Seidenst=C3=BCcker?= Date: Fri, 12 Apr 2024 02:07:29 +0200 Subject: [PATCH 57/57] gitignore --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index baee1828b8..19dfbefc59 100644 --- a/.gitignore +++ b/.gitignore @@ -40,3 +40,4 @@ CTestTestFile.cmake .vscode/ .idea/ cmake-build-debug/ +build-*/