From eeb5b07f35c002b453a509e81734c8acf3e31b16 Mon Sep 17 00:00:00 2001 From: Daniel Chappuis Date: Wed, 29 Jul 2020 22:49:19 +0200 Subject: [PATCH] Remove rolling restistance constraint from contact solver. Angular damping has to be used instead --- CHANGELOG.md | 5 ++ .../collision/ContactManifold.h | 3 -- include/reactphysics3d/engine/Material.h | 33 +----------- include/reactphysics3d/engine/PhysicsWorld.h | 5 -- .../reactphysics3d/mathematics/Matrix3x3.h | 3 -- .../systems/ContactSolverSystem.h | 17 ------ src/body/CollisionBody.cpp | 2 +- src/body/RigidBody.cpp | 2 +- src/engine/Material.cpp | 5 +- src/mathematics/Matrix3x3.cpp | 24 --------- src/systems/CollisionDetectionSystem.cpp | 1 - src/systems/ContactSolverSystem.cpp | 54 ------------------- .../scenes/concavemesh/ConcaveMeshScene.cpp | 5 -- testbed/scenes/cubestack/CubeStackScene.cpp | 2 + .../scenes/heightfield/HeightFieldScene.cpp | 5 -- testbed/scenes/pile/PileScene.cpp | 5 -- 16 files changed, 12 insertions(+), 159 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 9fe03754..add9c854 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -14,8 +14,13 @@ do not hesitate to take a look at the user manual. ### Changed + - Rolling resistance constraint is not solved anymore in the solver. Angular damping needs to be used instead to simulate this. + ### Removed + - Method Material::getRollingResistance() has been removed (angular damping has to be used instead of rolling resistance) + - Method Material::setRollingResistance() has been removed (angular damping has to be used instead of rolling resistance) + ### Fixed - Issue with concave vs convex shape collision detection has been fixed diff --git a/include/reactphysics3d/collision/ContactManifold.h b/include/reactphysics3d/collision/ContactManifold.h index 3dfeb0df..b76906da 100644 --- a/include/reactphysics3d/collision/ContactManifold.h +++ b/include/reactphysics3d/collision/ContactManifold.h @@ -95,9 +95,6 @@ class ContactManifold { /// Twist friction constraint accumulated impulse decimal frictionTwistImpulse; - /// Accumulated rolling resistance impulse - Vector3 rollingResistanceImpulse; - /// True if the contact manifold has already been added into an island bool isAlreadyInIsland; diff --git a/include/reactphysics3d/engine/Material.h b/include/reactphysics3d/engine/Material.h index a8462c20..e15d2532 100644 --- a/include/reactphysics3d/engine/Material.h +++ b/include/reactphysics3d/engine/Material.h @@ -48,9 +48,6 @@ class Material { /// Square root of the friction coefficient decimal mFrictionCoefficientSqrt; - /// Rolling resistance factor (positive value) - decimal mRollingResistance; - /// Bounciness during collisions (between 0 and 1) where 1 is for a very bouncy body decimal mBounciness; @@ -60,7 +57,7 @@ class Material { // -------------------- Methods -------------------- // /// Constructor - Material(decimal frictionCoefficient, decimal rollingResistance, decimal bounciness, decimal massDensity = decimal(1.0)); + Material(decimal frictionCoefficient, decimal bounciness, decimal massDensity = decimal(1.0)); public : @@ -81,12 +78,6 @@ class Material { /// Return the square root friction coefficient decimal getFrictionCoefficientSqrt() const; - /// Return the rolling resistance factor - decimal getRollingResistance() const; - - /// Set the rolling resistance factor - void setRollingResistance(decimal rollingResistance); - /// Return the mass density of the collider decimal getMassDensity() const; @@ -146,27 +137,6 @@ RP3D_FORCE_INLINE decimal Material::getFrictionCoefficientSqrt() const { return mFrictionCoefficientSqrt; } -// Return the rolling resistance factor. If this value is larger than zero, -// it will be used to slow down the body when it is rolling -// against another body. -/** - * @return The rolling resistance factor (positive value) - */ -RP3D_FORCE_INLINE decimal Material::getRollingResistance() const { - return mRollingResistance; -} - -// Set the rolling resistance factor. If this value is larger than zero, -// it will be used to slow down the body when it is rolling -// against another body. -/** - * @param rollingResistance The rolling resistance factor - */ -RP3D_FORCE_INLINE void Material::setRollingResistance(decimal rollingResistance) { - assert(rollingResistance >= 0); - mRollingResistance = rollingResistance; -} - // Return the mass density of the collider RP3D_FORCE_INLINE decimal Material::getMassDensity() const { return mMassDensity; @@ -186,7 +156,6 @@ RP3D_FORCE_INLINE std::string Material::to_string() const { std::stringstream ss; ss << "frictionCoefficient=" << (mFrictionCoefficientSqrt * mFrictionCoefficientSqrt) << std::endl; - ss << "rollingResistance=" << mRollingResistance << std::endl; ss << "bounciness=" << mBounciness << std::endl; return ss.str(); diff --git a/include/reactphysics3d/engine/PhysicsWorld.h b/include/reactphysics3d/engine/PhysicsWorld.h index ea507ef8..e2618959 100644 --- a/include/reactphysics3d/engine/PhysicsWorld.h +++ b/include/reactphysics3d/engine/PhysicsWorld.h @@ -93,9 +93,6 @@ class PhysicsWorld { /// Velocity threshold for contact velocity restitution decimal restitutionVelocityThreshold; - /// Default rolling resistance - decimal defaultRollingRestistance; - /// True if the sleeping technique is enabled bool isSleepingEnabled; @@ -129,7 +126,6 @@ class PhysicsWorld { defaultFrictionCoefficient = decimal(0.3); defaultBounciness = decimal(0.5); restitutionVelocityThreshold = decimal(0.5); - defaultRollingRestistance = decimal(0.0); isSleepingEnabled = true; defaultVelocitySolverNbIterations = 10; defaultPositionSolverNbIterations = 5; @@ -152,7 +148,6 @@ class PhysicsWorld { ss << "defaultFrictionCoefficient=" << defaultFrictionCoefficient << std::endl; ss << "defaultBounciness=" << defaultBounciness << std::endl; ss << "restitutionVelocityThreshold=" << restitutionVelocityThreshold << std::endl; - ss << "defaultRollingRestistance=" << defaultRollingRestistance << std::endl; ss << "isSleepingEnabled=" << isSleepingEnabled << std::endl; ss << "defaultVelocitySolverNbIterations=" << defaultVelocitySolverNbIterations << std::endl; ss << "defaultPositionSolverNbIterations=" << defaultPositionSolverNbIterations << std::endl; diff --git a/include/reactphysics3d/mathematics/Matrix3x3.h b/include/reactphysics3d/mathematics/Matrix3x3.h index 6d14d993..575adfc4 100644 --- a/include/reactphysics3d/mathematics/Matrix3x3.h +++ b/include/reactphysics3d/mathematics/Matrix3x3.h @@ -95,9 +95,6 @@ class Matrix3x3 { /// Return the inverse matrix Matrix3x3 getInverse() const; - /// Return the inverse matrix - Matrix3x3 getInverseWithDeterminant(decimal determinant) const; - /// Return the matrix with absolute values Matrix3x3 getAbsoluteMatrix() const; diff --git a/include/reactphysics3d/systems/ContactSolverSystem.h b/include/reactphysics3d/systems/ContactSolverSystem.h index 11960b68..8c484328 100644 --- a/include/reactphysics3d/systems/ContactSolverSystem.h +++ b/include/reactphysics3d/systems/ContactSolverSystem.h @@ -199,9 +199,6 @@ class ContactSolverSystem { /// Mix friction coefficient for the two bodies decimal frictionCoefficient; - /// Rolling resistance factor between the two bodies - decimal rollingResistanceFactor; - // - Variables used when friction constraints are apply at the center of the manifold-// /// Average normal vector of the contact manifold @@ -240,9 +237,6 @@ class ContactSolverSystem { /// Matrix K for the twist friction constraint decimal inverseTwistFrictionMass; - /// Matrix K for the rolling resistance constraint - Matrix3x3 inverseRollingResistance; - /// First friction direction at contact manifold center Vector3 frictionVector1; @@ -264,9 +258,6 @@ class ContactSolverSystem { /// Twist friction impulse at contact manifold center decimal frictionTwistImpulse; - /// Rolling resistance impulse - Vector3 rollingResistanceImpulse; - /// Number of contact points int8 nbContacts; }; @@ -344,9 +335,6 @@ class ContactSolverSystem { /// Compute the mixed friction coefficient from the friction coefficient of each collider decimal computeMixedFrictionCoefficient(const Material &material1, const Material &material2) const; - /// Compute th mixed rolling resistance factor between two colliders - decimal computeMixedRollingResistance(const Material& material1, const Material& material2) const; - /// Compute the two unit orthogonal vectors "t1" and "t2" that span the tangential friction /// plane for a contact manifold. The two vectors have to be /// such that : t1 x t2 = contactNormal. @@ -424,11 +412,6 @@ RP3D_FORCE_INLINE decimal ContactSolverSystem::computeMixedFrictionCoefficient(c return material1.getFrictionCoefficientSqrt() * material2.getFrictionCoefficientSqrt(); } -// Compute th mixed rolling resistance factor between two colliders -RP3D_FORCE_INLINE decimal ContactSolverSystem::computeMixedRollingResistance(const Material& material1, const Material& material2) const { - return decimal(0.5f) * (material1.getRollingResistance() + material2.getRollingResistance()); -} - #ifdef IS_RP3D_PROFILING_ENABLED // Set the profiler diff --git a/src/body/CollisionBody.cpp b/src/body/CollisionBody.cpp index 5c9c9610..4f065264 100644 --- a/src/body/CollisionBody.cpp +++ b/src/body/CollisionBody.cpp @@ -89,7 +89,7 @@ Collider* CollisionBody::addCollider(CollisionShape* collisionShape, const Trans // TODO : Maybe this method can directly returns an AABB collisionShape->getLocalBounds(localBoundsMin, localBoundsMax); const Transform localToWorldTransform = mWorld.mTransformComponents.getTransform(mEntity) * transform; - Material material(mWorld.mConfig.defaultFrictionCoefficient, mWorld.mConfig.defaultRollingRestistance, mWorld.mConfig.defaultBounciness); + Material material(mWorld.mConfig.defaultFrictionCoefficient, mWorld.mConfig.defaultBounciness); ColliderComponents::ColliderComponent colliderComponent(mEntity, collider, AABB(localBoundsMin, localBoundsMax), transform, collisionShape, 0x0001, 0xFFFF, localToWorldTransform, material); bool isActive = mWorld.mCollisionBodyComponents.getIsActive(mEntity); diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index 4e884efc..8b08cac2 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -590,7 +590,7 @@ Collider* RigidBody::addCollider(CollisionShape* collisionShape, const Transform // TODO : Maybe this method can directly returns an AABB collisionShape->getLocalBounds(localBoundsMin, localBoundsMax); const Transform localToWorldTransform = mWorld.mTransformComponents.getTransform(mEntity) * transform; - Material material(mWorld.mConfig.defaultFrictionCoefficient, mWorld.mConfig.defaultRollingRestistance, mWorld.mConfig.defaultBounciness); + Material material(mWorld.mConfig.defaultFrictionCoefficient, mWorld.mConfig.defaultBounciness); ColliderComponents::ColliderComponent colliderComponent(mEntity, collider, AABB(localBoundsMin, localBoundsMax), transform, collisionShape, 0x0001, 0xFFFF, localToWorldTransform, material); bool isSleeping = mWorld.mRigidBodyComponents.getIsSleeping(mEntity); diff --git a/src/engine/Material.cpp b/src/engine/Material.cpp index 3c73b11e..dee9c015 100644 --- a/src/engine/Material.cpp +++ b/src/engine/Material.cpp @@ -29,8 +29,7 @@ using namespace reactphysics3d; // Constructor -Material::Material(decimal frictionCoefficient, decimal rollingResistance, decimal bounciness, decimal massDensity) - : mFrictionCoefficientSqrt(std::sqrt(frictionCoefficient)), - mRollingResistance(rollingResistance), mBounciness(bounciness), mMassDensity(massDensity) { +Material::Material(decimal frictionCoefficient, decimal bounciness, decimal massDensity) + : mFrictionCoefficientSqrt(std::sqrt(frictionCoefficient)), mBounciness(bounciness), mMassDensity(massDensity) { } diff --git a/src/mathematics/Matrix3x3.cpp b/src/mathematics/Matrix3x3.cpp index 16502f0d..18f96a1b 100644 --- a/src/mathematics/Matrix3x3.cpp +++ b/src/mathematics/Matrix3x3.cpp @@ -65,27 +65,3 @@ Matrix3x3 Matrix3x3::getInverse() const { // Return the inverse matrix return (invDeterminant * tempMatrix); } - -// Return the inverse matrix -Matrix3x3 Matrix3x3::getInverseWithDeterminant(decimal determinant) const { - - // Check if the determinant is equal to zero - assert(determinant != decimal(0.0)); - - decimal invDeterminant = decimal(1.0) / determinant; - - Matrix3x3 tempMatrix((mRows[1][1]*mRows[2][2]-mRows[2][1]*mRows[1][2]), - -(mRows[0][1]*mRows[2][2]-mRows[2][1]*mRows[0][2]), - (mRows[0][1]*mRows[1][2]-mRows[0][2]*mRows[1][1]), - -(mRows[1][0]*mRows[2][2]-mRows[2][0]*mRows[1][2]), - (mRows[0][0]*mRows[2][2]-mRows[2][0]*mRows[0][2]), - -(mRows[0][0]*mRows[1][2]-mRows[1][0]*mRows[0][2]), - (mRows[1][0]*mRows[2][1]-mRows[2][0]*mRows[1][1]), - -(mRows[0][0]*mRows[2][1]-mRows[2][0]*mRows[0][1]), - (mRows[0][0]*mRows[1][1]-mRows[0][1]*mRows[1][0])); - - // Return the inverse matrix - return (invDeterminant * tempMatrix); -} - - diff --git a/src/systems/CollisionDetectionSystem.cpp b/src/systems/CollisionDetectionSystem.cpp index 3eab8488..b7de88b0 100644 --- a/src/systems/CollisionDetectionSystem.cpp +++ b/src/systems/CollisionDetectionSystem.cpp @@ -903,7 +903,6 @@ void CollisionDetectionSystem::initContactsWithPreviousOnes() { currentContactManifold.frictionImpulse1 = previousContactManifold.frictionImpulse1; currentContactManifold.frictionImpulse2 = previousContactManifold.frictionImpulse2; currentContactManifold.frictionTwistImpulse = previousContactManifold.frictionTwistImpulse; - currentContactManifold.rollingResistanceImpulse = previousContactManifold.rollingResistanceImpulse; break; } diff --git a/src/systems/ContactSolverSystem.cpp b/src/systems/ContactSolverSystem.cpp index 0dbb6649..a3d4936d 100644 --- a/src/systems/ContactSolverSystem.cpp +++ b/src/systems/ContactSolverSystem.cpp @@ -153,7 +153,6 @@ void ContactSolverSystem::initializeForIsland(uint islandIndex) { mContactConstraints[mNbContactManifolds].massInverseBody2 = mRigidBodyComponents.mInverseMasses[rigidBodyIndex2]; mContactConstraints[mNbContactManifolds].nbContacts = externalManifold.nbContactPoints; mContactConstraints[mNbContactManifolds].frictionCoefficient = computeMixedFrictionCoefficient(mColliderComponents.mMaterials[collider1Index], mColliderComponents.mMaterials[collider2Index]); - mContactConstraints[mNbContactManifolds].rollingResistanceFactor = computeMixedRollingResistance(mColliderComponents.mMaterials[collider1Index], mColliderComponents.mMaterials[collider2Index]); mContactConstraints[mNbContactManifolds].externalContactManifold = &externalManifold; mContactConstraints[mNbContactManifolds].normal.setToZero(); mContactConstraints[mNbContactManifolds].frictionPointBody1.setToZero(); @@ -273,24 +272,6 @@ void ContactSolverSystem::initializeForIsland(uint islandIndex) { mContactConstraints[mNbContactManifolds].friction2Impulse = externalManifold.frictionImpulse2; mContactConstraints[mNbContactManifolds].frictionTwistImpulse = externalManifold.frictionTwistImpulse; - // Compute the inverse K matrix for the rolling resistance constraint - const bool isBody1DynamicType = mRigidBodyComponents.mBodyTypes[rigidBodyIndex1] == BodyType::DYNAMIC; - const bool isBody2DynamicType = mRigidBodyComponents.mBodyTypes[rigidBodyIndex2] == BodyType::DYNAMIC; - mContactConstraints[mNbContactManifolds].inverseRollingResistance.setToZero(); - if (mContactConstraints[mNbContactManifolds].rollingResistanceFactor > 0 && (isBody1DynamicType || isBody2DynamicType)) { - - mContactConstraints[mNbContactManifolds].inverseRollingResistance = mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody1 + mContactConstraints[mNbContactManifolds].inverseInertiaTensorBody2; - const decimal det = mContactConstraints[mNbContactManifolds].inverseRollingResistance.getDeterminant(); - - // If the matrix is not inversible - if (approxEqual(det, decimal(0.0))) { - mContactConstraints[mNbContactManifolds].inverseRollingResistance.setToZero(); - } - else { - mContactConstraints[mNbContactManifolds].inverseRollingResistance = mContactConstraints[mNbContactManifolds].inverseRollingResistance.getInverseWithDeterminant(det); - } - } - mContactConstraints[mNbContactManifolds].normal.normalize(); // deltaVFrictionPoint = v2 + w2.cross(mContactConstraints[mNbContactManifolds].r2Friction) - @@ -479,11 +460,6 @@ void ContactSolverSystem::warmStart() { // Update the velocities of the body 2 by applying the impulse P mRigidBodyComponents.mConstrainedAngularVelocities[rigidBody2Index] += mContactConstraints[c].inverseInertiaTensorBody2 * angularImpulseBody2; - // ------ Rolling resistance at the center of the contact manifold ------ // - - // Compute the impulse P = J^T * lambda - angularImpulseBody2 = mContactConstraints[c].rollingResistanceImpulse; - // Update the velocities of the body 1 by applying the impulse P mRigidBodyComponents.mConstrainedAngularVelocities[rigidBody1Index] -= mContactConstraints[c].inverseInertiaTensorBody1 * angularImpulseBody2; @@ -496,7 +472,6 @@ void ContactSolverSystem::warmStart() { mContactConstraints[c].friction1Impulse = 0.0; mContactConstraints[c].friction2Impulse = 0.0; mContactConstraints[c].frictionTwistImpulse = 0.0; - mContactConstraints[c].rollingResistanceImpulse.setToZero(); } } } @@ -781,34 +756,6 @@ void ContactSolverSystem::solve() { mRigidBodyComponents.mConstrainedAngularVelocities[rigidBody2Index].x += angularVelocity2.x; mRigidBodyComponents.mConstrainedAngularVelocities[rigidBody2Index].y += angularVelocity2.y; mRigidBodyComponents.mConstrainedAngularVelocities[rigidBody2Index].z += angularVelocity2.z; - - // --------- Rolling resistance constraint at the center of the contact manifold --------- // - - if (mContactConstraints[c].rollingResistanceFactor > 0) { - - // Compute J*v - const Vector3 JvRolling = w2 - w1; - - // Compute the Lagrange multiplier lambda - Vector3 deltaLambdaRolling = mContactConstraints[c].inverseRollingResistance * (-JvRolling); - decimal rollingLimit = mContactConstraints[c].rollingResistanceFactor * sumPenetrationImpulse; - Vector3 lambdaTempRolling = mContactConstraints[c].rollingResistanceImpulse; - mContactConstraints[c].rollingResistanceImpulse = clamp(mContactConstraints[c].rollingResistanceImpulse + - deltaLambdaRolling, rollingLimit); - deltaLambdaRolling = mContactConstraints[c].rollingResistanceImpulse - lambdaTempRolling; - - // Update the velocities of the body 1 by applying the impulse P - angularVelocity1 = mContactConstraints[c].inverseInertiaTensorBody1 * deltaLambdaRolling; - mRigidBodyComponents.mConstrainedAngularVelocities[rigidBody1Index].x -= angularVelocity1.x; - mRigidBodyComponents.mConstrainedAngularVelocities[rigidBody1Index].y -= angularVelocity1.y; - mRigidBodyComponents.mConstrainedAngularVelocities[rigidBody1Index].z -= angularVelocity1.z; - - // Update the velocities of the body 2 by applying the impulse P - angularVelocity2 = mContactConstraints[c].inverseInertiaTensorBody2 * deltaLambdaRolling; - mRigidBodyComponents.mConstrainedAngularVelocities[rigidBody2Index].x += angularVelocity2.x; - mRigidBodyComponents.mConstrainedAngularVelocities[rigidBody2Index].y += angularVelocity2.y; - mRigidBodyComponents.mConstrainedAngularVelocities[rigidBody2Index].z += angularVelocity2.z; - } } } @@ -833,7 +780,6 @@ void ContactSolverSystem::storeImpulses() { mContactConstraints[c].externalContactManifold->frictionImpulse1 = mContactConstraints[c].friction1Impulse; mContactConstraints[c].externalContactManifold->frictionImpulse2 = mContactConstraints[c].friction2Impulse; mContactConstraints[c].externalContactManifold->frictionTwistImpulse = mContactConstraints[c].frictionTwistImpulse; - mContactConstraints[c].externalContactManifold->rollingResistanceImpulse = mContactConstraints[c].rollingResistanceImpulse; mContactConstraints[c].externalContactManifold->frictionVector1 = mContactConstraints[c].frictionVector1; mContactConstraints[c].externalContactManifold->frictionVector2 = mContactConstraints[c].frictionVector2; } diff --git a/testbed/scenes/concavemesh/ConcaveMeshScene.cpp b/testbed/scenes/concavemesh/ConcaveMeshScene.cpp index e08ef540..c0c1b3e0 100644 --- a/testbed/scenes/concavemesh/ConcaveMeshScene.cpp +++ b/testbed/scenes/concavemesh/ConcaveMeshScene.cpp @@ -108,9 +108,6 @@ ConcaveMeshScene::ConcaveMeshScene(const std::string& name, EngineSettings& sett // Create a sphere and a corresponding rigid in the physics world Sphere* sphere = new Sphere(true, SPHERE_RADIUS, mPhysicsCommon, mPhysicsWorld, meshFolderPath); - // Add some rolling resistance - sphere->getCollider()->getMaterial().setRollingResistance(rp3d::decimal(0.08)); - // Set the box color sphere->setColor(mObjectColorDemo); sphere->setSleepingColor(mSleepingColorDemo); @@ -131,8 +128,6 @@ ConcaveMeshScene::ConcaveMeshScene(const std::string& name, EngineSettings& sett Capsule* capsule = new Capsule(true, CAPSULE_RADIUS, CAPSULE_HEIGHT, mPhysicsCommon, mPhysicsWorld, meshFolderPath); - capsule->getCollider()->getMaterial().setRollingResistance(rp3d::decimal(0.08)); - // Set the box color capsule->setColor(mObjectColorDemo); capsule->setSleepingColor(mSleepingColorDemo); diff --git a/testbed/scenes/cubestack/CubeStackScene.cpp b/testbed/scenes/cubestack/CubeStackScene.cpp index b45f4977..40b2b66d 100644 --- a/testbed/scenes/cubestack/CubeStackScene.cpp +++ b/testbed/scenes/cubestack/CubeStackScene.cpp @@ -145,6 +145,8 @@ void CubeStackScene::reset() { 0); box->setTransform(rp3d::Transform(position, rp3d::Quaternion::identity())); + box->getRigidBody()->setLinearVelocity(rp3d::Vector3::zero()); + box->getRigidBody()->setAngularVelocity(rp3d::Vector3::zero()); index++; } diff --git a/testbed/scenes/heightfield/HeightFieldScene.cpp b/testbed/scenes/heightfield/HeightFieldScene.cpp index 53ac20c7..4620ca54 100644 --- a/testbed/scenes/heightfield/HeightFieldScene.cpp +++ b/testbed/scenes/heightfield/HeightFieldScene.cpp @@ -107,9 +107,6 @@ HeightFieldScene::HeightFieldScene(const std::string& name, EngineSettings& sett // Create a sphere and a corresponding rigid in the physics world Sphere* sphere = new Sphere(true, SPHERE_RADIUS, mPhysicsCommon, mPhysicsWorld, meshFolderPath); - // Add some rolling resistance - sphere->getCollider()->getMaterial().setRollingResistance(0.08f); - // Set the box color sphere->setColor(mObjectColorDemo); sphere->setSleepingColor(mSleepingColorDemo); @@ -129,8 +126,6 @@ HeightFieldScene::HeightFieldScene(const std::string& name, EngineSettings& sett // Create a cylinder and a corresponding rigid in the physics world Capsule* capsule = new Capsule(true, CAPSULE_RADIUS, CAPSULE_HEIGHT, mPhysicsCommon, mPhysicsWorld, meshFolderPath); - capsule->getCollider()->getMaterial().setRollingResistance(0.08f); - // Set the box color capsule->setColor(mObjectColorDemo); capsule->setSleepingColor(mSleepingColorDemo); diff --git a/testbed/scenes/pile/PileScene.cpp b/testbed/scenes/pile/PileScene.cpp index 6698bc6e..636fe087 100644 --- a/testbed/scenes/pile/PileScene.cpp +++ b/testbed/scenes/pile/PileScene.cpp @@ -105,9 +105,6 @@ PileScene::PileScene(const std::string& name, EngineSettings& settings) // Create a sphere and a corresponding rigid in the physics world Sphere* sphere = new Sphere(true, SPHERE_RADIUS, mPhysicsCommon, mPhysicsWorld, meshFolderPath); - // Add some rolling resistance - sphere->getCollider()->getMaterial().setRollingResistance(rp3d::decimal(0.08)); - // Set the box color sphere->setColor(mObjectColorDemo); sphere->setSleepingColor(mSleepingColorDemo); @@ -128,8 +125,6 @@ PileScene::PileScene(const std::string& name, EngineSettings& settings) Capsule* capsule = new Capsule(true, CAPSULE_RADIUS, CAPSULE_HEIGHT, mPhysicsCommon, mPhysicsWorld, meshFolderPath); - capsule->getCollider()->getMaterial().setRollingResistance(rp3d::decimal(0.08f)); - // Set the box color capsule->setColor(mObjectColorDemo); capsule->setSleepingColor(mSleepingColorDemo);