Przeglądaj źródła

Ability for sensors to detect collisions with sleeping bodies (#133)

Sensors can now be made Kinematic or Dynamic and when activated they will detect collisions with sleeping bodies too.
Jorrit Rouwe 3 lat temu
rodzic
commit
f1e8191199

+ 10 - 0
Docs/Architecture.md

@@ -171,6 +171,16 @@ will return a box of size 2x2x2 centered around the origin, so in order to get i
 
 Note that when you work with interface of [BroadPhaseQuery](@ref BroadPhaseQuery), [NarrowPhaseQuery](@ref NarrowPhaseQuery) or [TransformedShape](@ref TransformedShape) this transformation is done for you.
 
+## Sensors
+
+Sensors are normal rigid bodies that report contacts with other Dynamic or Kinematic bodies through the [ContactListener](@ref ContactListener) interface. Any detected penetrations will however not be resolved. Sensors can be used to implement triggers that detect when an object enters their area.
+
+The cheapest sensor has a Static motion type. This type of sensor will only detect active bodies entering their area. As soon as a body goes to sleep, the contact will be lost. Note that you can still move a Static sensor around using [BodyInterface::SetPosition](@ref BodyInterface::SetPosition).
+
+When you make a sensor Kinematic or Dynamic and activate it, it will also detect collisions with sleeping bodies, albeit with a higher run-time cost.
+
+To create a sensor, either set [BodyCreationSettings::mIsSensor](@ref BodyCreationSettings::mIsSensor) to true when constructing a body or set it after construction through [Body::SetIsSensor](@ref Body::SetIsSensor). A sensor can only use the discrete motion quality type at this moment.
+
 ## Constraints
 
 Bodies can be connected to each other using constraints ([Constraint](@ref Constraint)).

+ 2 - 2
Jolt/Physics/Body/Body.cpp

@@ -136,8 +136,8 @@ void Body::SetShapeInternal(const Shape *inShape, bool inUpdateMassProperties)
 
 Body::ECanSleep Body::UpdateSleepStateInternal(float inDeltaTime, float inMaxMovement, float inTimeBeforeSleep)
 {
-	// Check override
-	if (!mMotionProperties->mAllowSleeping)
+	// Check override & sensors will never go to sleep (they would stop detecting collisions with sleeping bodies)
+	if (!mMotionProperties->mAllowSleeping || IsSensor())
 		return ECanSleep::CannotSleep;
 
 	// Get the points to test

+ 7 - 4
Jolt/Physics/Body/Body.h

@@ -55,9 +55,12 @@ public:
 	/// Check if a body could be made kinematic or dynamic (if it was created dynamic or with mAllowDynamicOrKinematic set to true)
 	inline bool				CanBeKinematicOrDynamic() const									{ return mMotionProperties != nullptr; }
 
-	/// Change the body to a sensor or to a regular static body. A sensor will receive collision callbacks, but will not cause any collision responses and can be used as a trigger volume.
-	/// Note that Sensors need to be of motion type Static (they can be moved around using BodyInterface::SetPosition/SetPositionAndRotation).
-	inline void				SetIsSensor(bool inIsSensor)									{ JPH_ASSERT(!inIsSensor || mMotionProperties == nullptr, "A sensor needs to be Static"); if (inIsSensor) mFlags.fetch_or(uint8(JPH::Body::EFlags::IsSensor), JPH::memory_order_relaxed); else mFlags.fetch_and(uint8(~uint8(JPH::Body::EFlags::IsSensor)), JPH::memory_order_relaxed); }
+	/// Change the body to a sensor. A sensor will receive collision callbacks, but will not cause any collision responses and can be used as a trigger volume.
+	/// The cheapest sensor (in terms of CPU usage) is a sensor with motion type Static (they can be moved around using BodyInterface::SetPosition/SetPositionAndRotation).
+	/// These sensors will only detect collisions with active Dynamic or Kinematic bodies. As soon as a body go to sleep, the contact point with the sensor will be lost.
+	/// If you make a sensor Dynamic or Kinematic and activate them, the sensor will be able to detect collisions with sleeping bodies too. An active sensor will never go to sleep automatically.
+	/// When you make a Dynamic or Kinematic sensor, make sure it is in an ObjectLayer that does not collide with Static bodies or other sensors to avoid extra overhead in the broad phase.
+	inline void				SetIsSensor(bool inIsSensor)									{ if (inIsSensor) mFlags.fetch_or(uint8(JPH::Body::EFlags::IsSensor), JPH::memory_order_relaxed); else mFlags.fetch_and(uint8(~uint8(JPH::Body::EFlags::IsSensor)), JPH::memory_order_relaxed); }
 
 	/// Check if this body is a sensor.
 	inline bool				IsSensor() const												{ return (mFlags.load(memory_order_relaxed) & uint8(EFlags::IsSensor)) != 0; }
@@ -261,7 +264,7 @@ public:
 
 	///@}
 
-	static const uint32		cInactiveIndex = uint32(-1);									///< Constant indicating that body is not active
+	static constexpr uint32	cInactiveIndex = uint32(-1);									///< Constant indicating that body is not active
 
 private:
 	friend class BodyManager;

+ 4 - 0
Jolt/Physics/Body/Body.inl

@@ -35,6 +35,10 @@ inline bool Body::sFindCollidingPairsCanCollide(const Body &inBody1, const Body
 		&& !(inBody1.IsKinematic() && inBody2.IsSensor()))
 		return false;
 
+	// If both bodies are sensors, there's no collision
+	if (inBody1.IsSensor() && inBody2.IsSensor())
+		return false;
+
 	// Check that body 1 is active
 	uint32 body1_index_in_active_bodies = inBody1.GetIndexInActiveBodiesInternal();
 	JPH_ASSERT(!inBody1.IsStatic() && body1_index_in_active_bodies != Body::cInactiveIndex, "This function assumes that Body 1 is active");

+ 1 - 1
Jolt/Physics/Body/BodyCreationSettings.h

@@ -90,7 +90,7 @@ public:
 	///@name Simulation properties
 	EMotionType				mMotionType = EMotionType::Dynamic;								///< Motion type, determines if the object is static, dynamic or kinematic
 	bool					mAllowDynamicOrKinematic = false;								///< When this body is created as static, this setting tells the system to create a MotionProperties object so that the object can be switched to kinematic or dynamic
-	bool					mIsSensor = false;												///< If this body is a sensor. A sensor will receive collision callbacks, but will not cause any collision responses and can be used as a trigger volume.
+	bool					mIsSensor = false;												///< If this body is a sensor. A sensor will receive collision callbacks, but will not cause any collision responses and can be used as a trigger volume. See description at Body::SetIsSensor.
 	EMotionQuality			mMotionQuality = EMotionQuality::Discrete;						///< Motion quality, or how well it detects collisions when it has a high velocity
 	bool					mAllowSleeping = true;											///< If this body can go to sleep or not
 	float					mFriction = 0.2f;												///< Friction of the body (dimensionless number, usually between 0 and 1, 0 = no friction, 1 = friction force equals force that presses the two bodies together)

+ 3 - 2
Jolt/Physics/PhysicsSystem.cpp

@@ -1192,7 +1192,7 @@ void PhysicsSystem::ProcessBodyPair(ContactAllocator &ioContactAllocator, const
 	}
 
 	// If an actual contact is present we need to do some extra work
-	if (contact_found)
+	if (contact_found && !body1->IsSensor() && !body2->IsSensor())
 	{
 		// Wake up sleeping bodies
 		BodyID body_ids[2];
@@ -1421,7 +1421,8 @@ void PhysicsSystem::JobIntegrateVelocity(const PhysicsUpdateContext *ioContext,
 				break;
 
 			case EMotionQuality::LinearCast:
-				if (body.IsDynamic()) // Kinematic bodies cannot be stopped
+				if (body.IsDynamic() // Kinematic bodies cannot be stopped
+					&& !body.IsSensor()) // We don't support CCD sensors
 				{
 					// Determine inner radius (the smallest sphere that fits into the shape)
 					float inner_radius = body.GetShape()->GetInnerRadius();

+ 13 - 5
Samples/Layers.h

@@ -16,7 +16,8 @@ namespace Layers
 	static constexpr uint8 NON_MOVING = 4;
 	static constexpr uint8 MOVING = 5;
 	static constexpr uint8 DEBRIS = 6; // Example: Debris collides only with NON_MOVING
-	static constexpr uint8 NUM_LAYERS = 7;
+	static constexpr uint8 SENSOR = 7; // Sensors only collide with MOVING objects
+	static constexpr uint8 NUM_LAYERS = 8;
 };
 
 /// Function that determines if two object layers can collide
@@ -32,9 +33,11 @@ inline bool ObjectCanCollide(ObjectLayer inObject1, ObjectLayer inObject2)
 	case Layers::NON_MOVING:
 		return inObject2 == Layers::MOVING || inObject2 == Layers::DEBRIS;
 	case Layers::MOVING:
-		return inObject2 == Layers::NON_MOVING || inObject2 == Layers::MOVING;
+		return inObject2 == Layers::NON_MOVING || inObject2 == Layers::MOVING || inObject2 == Layers::SENSOR;
 	case Layers::DEBRIS:
 		return inObject2 == Layers::NON_MOVING;
+	case Layers::SENSOR:
+		return inObject2 == Layers::MOVING;
 	default:
 		JPH_ASSERT(false);
 		return false;
@@ -47,8 +50,9 @@ namespace BroadPhaseLayers
 	static constexpr BroadPhaseLayer NON_MOVING(0);
 	static constexpr BroadPhaseLayer MOVING(1);
 	static constexpr BroadPhaseLayer DEBRIS(2);
-	static constexpr BroadPhaseLayer UNUSED(3);
-	static constexpr uint NUM_LAYERS(4);
+	static constexpr BroadPhaseLayer SENSOR(3);
+	static constexpr BroadPhaseLayer UNUSED(4);
+	static constexpr uint NUM_LAYERS(5);
 };
 
 /// BroadPhaseLayerInterface implementation
@@ -65,6 +69,7 @@ public:
 		mObjectToBroadPhase[Layers::NON_MOVING] = BroadPhaseLayers::NON_MOVING;
 		mObjectToBroadPhase[Layers::MOVING] = BroadPhaseLayers::MOVING;
 		mObjectToBroadPhase[Layers::DEBRIS] = BroadPhaseLayers::DEBRIS;
+		mObjectToBroadPhase[Layers::SENSOR] = BroadPhaseLayers::SENSOR;
 	}
 
 	virtual uint					GetNumBroadPhaseLayers() const override
@@ -86,6 +91,7 @@ public:
 		case (BroadPhaseLayer::Type)BroadPhaseLayers::NON_MOVING:	return "NON_MOVING";
 		case (BroadPhaseLayer::Type)BroadPhaseLayers::MOVING:		return "MOVING";
 		case (BroadPhaseLayer::Type)BroadPhaseLayers::DEBRIS:		return "DEBRIS";
+		case (BroadPhaseLayer::Type)BroadPhaseLayers::SENSOR:		return "SENSOR";
 		case (BroadPhaseLayer::Type)BroadPhaseLayers::UNUSED:		return "UNUSED";
 		default:													JPH_ASSERT(false); return "INVALID";
 		}
@@ -104,9 +110,11 @@ inline bool BroadPhaseCanCollide(ObjectLayer inLayer1, BroadPhaseLayer inLayer2)
 	case Layers::NON_MOVING:
 		return inLayer2 == BroadPhaseLayers::MOVING;
 	case Layers::MOVING:
-		return inLayer2 == BroadPhaseLayers::NON_MOVING || inLayer2 == BroadPhaseLayers::MOVING;
+		return inLayer2 == BroadPhaseLayers::NON_MOVING || inLayer2 == BroadPhaseLayers::MOVING || inLayer2 == BroadPhaseLayers::SENSOR;
 	case Layers::DEBRIS:
 		return inLayer2 == BroadPhaseLayers::NON_MOVING;
+	case Layers::SENSOR:
+		return inLayer2 == BroadPhaseLayers::MOVING;
 	case Layers::UNUSED1:
 	case Layers::UNUSED2:
 	case Layers::UNUSED3:

+ 72 - 54
Samples/Tests/General/SensorTest.cpp

@@ -29,12 +29,26 @@ void SensorTest::Initialize()
 	// Floor
 	CreateFloor();
 
-	// Sensor
-	BodyCreationSettings sensor_settings(new SphereShape(10.0f), Vec3(0, 10, 0), Quat::sIdentity(), EMotionType::Static, Layers::NON_MOVING);
-	sensor_settings.mIsSensor = true;
-	Body &sensor = *mBodyInterface->CreateBody(sensor_settings);
-	mSensorID = sensor.GetID();
-	mBodyInterface->AddBody(mSensorID, EActivation::DontActivate);
+	{
+		// A static sensor that attrects dynamic bodies that enter its area
+		BodyCreationSettings sensor_settings(new SphereShape(10.0f), Vec3(0, 10, 0), Quat::sIdentity(), EMotionType::Static, Layers::SENSOR);
+		sensor_settings.mIsSensor = true;
+		mSensorID[StaticAttractor] = mBodyInterface->CreateAndAddBody(sensor_settings, EActivation::DontActivate);
+	}
+	
+	{
+		// A static sensor that only detects active bodies
+		BodyCreationSettings sensor_settings(new BoxShape(Vec3::sReplicate(5.0f)), Vec3(-10, 5, 0), Quat::sIdentity(), EMotionType::Static, Layers::SENSOR);
+		sensor_settings.mIsSensor = true;
+		mSensorID[StaticSensor] = mBodyInterface->CreateAndAddBody(sensor_settings, EActivation::DontActivate);
+	}
+
+	{
+		// A kinematic sensor that also detects sleeping bodies
+		BodyCreationSettings sensor_settings(new BoxShape(Vec3::sReplicate(5.0f)), Vec3(10, 5, 0), Quat::sIdentity(), EMotionType::Kinematic, Layers::SENSOR);
+		sensor_settings.mIsSensor = true;
+		mSensorID[KinematicSensor] = mBodyInterface->CreateAndAddBody(sensor_settings, EActivation::Activate);
+	}
 
 	// Dynamic bodies
 	for (int i = 0; i < 10; ++i)
@@ -64,7 +78,7 @@ void SensorTest::Initialize()
 	mRagdoll->AddToPhysicsSystem(EActivation::Activate);
 
 	// Create kinematic body
-	BodyCreationSettings kinematic_settings(new BoxShape(Vec3(0.25f, 0.5f, 1.0f)), Vec3(-15, 10, 0), Quat::sIdentity(), EMotionType::Kinematic, Layers::MOVING);
+	BodyCreationSettings kinematic_settings(new BoxShape(Vec3(0.25f, 0.5f, 1.0f)), Vec3(-20, 10, 0), Quat::sIdentity(), EMotionType::Kinematic, Layers::MOVING);
 	Body &kinematic = *mBodyInterface->CreateBody(kinematic_settings);
 	mKinematicBodyID = kinematic.GetID();
 	mBodyInterface->AddBody(kinematic.GetID(), EActivation::Activate);
@@ -76,12 +90,18 @@ void SensorTest::PrePhysicsUpdate(const PreUpdateParams &inParams)
 	mTime += inParams.mDeltaTime;
 
 	// Move kinematic body
-	Vec3 kinematic_pos = Vec3(-15.0f * cos(mTime), 10, 0);
+	Vec3 kinematic_pos = Vec3(-20.0f * cos(mTime), 10, 0);
 	mBodyInterface->MoveKinematic(mKinematicBodyID, kinematic_pos, Quat::sIdentity(), inParams.mDeltaTime);
 
-	// Draw if the kinematic body is in the sensor
-	if (mKinematicBodyInSensor)
-		mDebugRenderer->DrawWireBox(mBodyInterface->GetTransformedShape(mKinematicBodyID).GetWorldSpaceBounds(), Color::sRed);
+	// Draw if body is in sensor
+	Color sensor_color[] = { Color::sRed, Color::sGreen, Color::sBlue };
+	for (int sensor = 0; sensor < NumSensors; ++sensor)
+		for (const BodyAndCount &body_and_count : mBodiesInSensor[sensor])
+		{
+			AABox bounds = mBodyInterface->GetTransformedShape(body_and_count.mBodyID).GetWorldSpaceBounds();
+			bounds.ExpandBy(Vec3::sReplicate(0.01f * sensor));
+			mDebugRenderer->DrawWireBox(bounds, sensor_color[sensor]);
+		}
 
 	// Apply forces to dynamic bodies in sensor
 	lock_guard lock(mMutex);
@@ -90,12 +110,14 @@ void SensorTest::PrePhysicsUpdate(const PreUpdateParams &inParams)
 	float centrifugal_force = 10.0f;
 	Vec3 gravity = mPhysicsSystem->GetGravity();
 	
-	for (const BodyAndCount &body_and_count : mBodiesInSensor)
+	for (const BodyAndCount &body_and_count : mBodiesInSensor[StaticAttractor])
 	{
 		BodyLockWrite body_lock(mPhysicsSystem->GetBodyLockInterface(), body_and_count.mBodyID);
 		if (body_lock.Succeeded())
 		{
 			Body &body = body_lock.GetBody();
+			if (body.IsKinematic())
+				continue;
 
 			// Calculate centrifugal acceleration
 			Vec3 acceleration = center - body.GetPosition();
@@ -119,61 +141,57 @@ void SensorTest::PrePhysicsUpdate(const PreUpdateParams &inParams)
 
 void SensorTest::OnContactAdded(const Body &inBody1, const Body &inBody2, const ContactManifold &inManifold, ContactSettings &ioSettings)
 {
-	// Check which body is the sensor
-	BodyID body_id;
-	if (inBody1.GetID() == mSensorID)
-		body_id = inBody2.GetID();
-	else if (inBody2.GetID() == mSensorID)
-		body_id = inBody1.GetID();
-	else
-		return;
+	for (int sensor = 0; sensor < NumSensors; ++sensor)
+	{
+		BodyID sensor_id = mSensorID[sensor];
 
-	lock_guard lock(mMutex);
+		// Check which body is the sensor
+		BodyID body_id;
+		if (inBody1.GetID() == sensor_id)
+			body_id = inBody2.GetID();
+		else if (inBody2.GetID() == sensor_id)
+			body_id = inBody1.GetID();
+		else
+			continue;
+
+		lock_guard lock(mMutex);
 
-	if (body_id == mKinematicBodyID)
-	{
-		JPH_ASSERT(!mKinematicBodyInSensor);
-		mKinematicBodyInSensor = true;
-	}
-	else
-	{
 		// Add to list and make sure that the list remains sorted for determinism (contacts can be added from multiple threads)
 		BodyAndCount body_and_count { body_id, 1 };
-		BodiesInSensor::iterator b = lower_bound(mBodiesInSensor.begin(), mBodiesInSensor.end(), body_and_count);
-		if (b != mBodiesInSensor.end() && b->mBodyID == body_id)
+		BodiesInSensor &bodies_in_sensor = mBodiesInSensor[sensor];
+		BodiesInSensor::iterator b = lower_bound(bodies_in_sensor.begin(), bodies_in_sensor.end(), body_and_count);
+		if (b != bodies_in_sensor.end() && b->mBodyID == body_id)
 		{
 			// This is the right body, increment reference
 			b->mCount++;
 			return;
 		}
-		mBodiesInSensor.insert(b, body_and_count);
+		bodies_in_sensor.insert(b, body_and_count);
 	}
 }
 
 void SensorTest::OnContactRemoved(const SubShapeIDPair &inSubShapePair)
 {
-	// Check which body is the sensor
-	BodyID body_id;
-	if (inSubShapePair.GetBody1ID() == mSensorID)
-		body_id = inSubShapePair.GetBody2ID();
-	else if (inSubShapePair.GetBody2ID() == mSensorID)
-		body_id = inSubShapePair.GetBody1ID();
-	else
-		return;
+	for (int sensor = 0; sensor < NumSensors; ++sensor)
+	{
+		BodyID sensor_id = mSensorID[sensor];
 
-	lock_guard lock(mMutex);
+		// Check which body is the sensor
+		BodyID body_id;
+		if (inSubShapePair.GetBody1ID() == sensor_id)
+			body_id = inSubShapePair.GetBody2ID();
+		else if (inSubShapePair.GetBody2ID() == sensor_id)
+			body_id = inSubShapePair.GetBody1ID();
+		else
+			continue;
+
+		lock_guard lock(mMutex);
 
-	if (body_id == mKinematicBodyID)
-	{
-		JPH_ASSERT(mKinematicBodyInSensor);
-		mKinematicBodyInSensor = false;
-	}
-	else
-	{
 		// Remove from list
 		BodyAndCount body_and_count { body_id, 1 };
-		BodiesInSensor::iterator b = lower_bound(mBodiesInSensor.begin(), mBodiesInSensor.end(), body_and_count);
-		if (b != mBodiesInSensor.end() && b->mBodyID == body_id)
+		BodiesInSensor &bodies_in_sensor = mBodiesInSensor[sensor];
+		BodiesInSensor::iterator b = lower_bound(bodies_in_sensor.begin(), bodies_in_sensor.end(), body_and_count);
+		if (b != bodies_in_sensor.end() && b->mBodyID == body_id)
 		{
 			// This is the right body, increment reference
 			JPH_ASSERT(b->mCount > 0);
@@ -181,7 +199,7 @@ void SensorTest::OnContactRemoved(const SubShapeIDPair &inSubShapePair)
 
 			// When last reference remove from the list
 			if (b->mCount == 0)
-				mBodiesInSensor.erase(b);
+				bodies_in_sensor.erase(b);
 			return;
 		}
 		JPH_ASSERT(false, "Body pair not found");
@@ -191,13 +209,13 @@ void SensorTest::OnContactRemoved(const SubShapeIDPair &inSubShapePair)
 void SensorTest::SaveState(StateRecorder &inStream) const
 {
 	inStream.Write(mTime);
-	inStream.Write(mBodiesInSensor);
-	inStream.Write(mKinematicBodyInSensor);
+	for (const BodiesInSensor &b : mBodiesInSensor)
+		inStream.Write(b);
 }
 
 void SensorTest::RestoreState(StateRecorder &inStream)
 {
 	inStream.Read(mTime);
-	inStream.Read(mBodiesInSensor);
-	inStream.Read(mKinematicBodyInSensor);
+	for (BodiesInSensor &b : mBodiesInSensor)
+		inStream.Read(b);
 }

+ 10 - 4
Samples/Tests/General/SensorTest.h

@@ -35,7 +35,15 @@ public:
 private:
 	float				mTime = 0.0f;						// Total elapsed time
 
-	BodyID				mSensorID;							// Body ID of the sensor
+	enum
+	{
+		StaticAttractor,									// A static sensor that attrects dynamic bodies that enter its area
+		StaticSensor,										// A static sensor that only detects active bodies
+		KinematicSensor,									// A kinematic sensor that also detects sleeping bodies
+		NumSensors
+	};
+
+	BodyID				mSensorID[NumSensors];				// Body ID of the various sensors
 
 	Ref<Ragdoll>		mRagdoll;							// Ragdoll that is falling into the sensor
 
@@ -53,7 +61,5 @@ private:
 	};
 
 	using BodiesInSensor = vector<BodyAndCount>;
-	BodiesInSensor		mBodiesInSensor;					// Dynamic bodies that are currently inside the sensor
-
-	bool				mKinematicBodyInSensor = false;		// Keeps track if the kinematic body is in the sensor
+	BodiesInSensor		mBodiesInSensor[NumSensors];		// Dynamic bodies that are currently inside the sensor
 };

+ 97 - 0
UnitTests/Physics/SensorTests.cpp

@@ -84,4 +84,101 @@ TEST_SUITE("SensorTests")
 		c.Simulate(3.0f + c.GetDeltaTime());
 		CHECK(listener.Contains(EType::Remove, kinematic.GetID(), sensor_id));
 	}
+
+	TEST_CASE("TestDynamicSleepingVsStaticSensor")
+	{
+		PhysicsTestContext c;
+
+		// Register listener
+		LoggingContactListener listener;
+		c.GetSystem()->SetContactListener(&listener);
+
+		// Sensor
+		BodyCreationSettings sensor_settings(new BoxShape(Vec3::sReplicate(1)), Vec3::sZero(), Quat::sIdentity(), EMotionType::Static, Layers::NON_MOVING);
+		sensor_settings.mIsSensor = true;
+		Body &sensor = *c.GetBodyInterface().CreateBody(sensor_settings);
+		c.GetBodyInterface().AddBody(sensor.GetID(), EActivation::DontActivate);
+
+		// Floor
+		Body &floor = c.CreateFloor();
+
+		// Dynamic body on floor (make them penetrate)
+		Body &dynamic = c.CreateBox(Vec3(0, 0.5f - c.GetSystem()->GetPhysicsSettings().mMaxPenetrationDistance, 0), Quat::sIdentity(), EMotionType::Dynamic, EMotionQuality::Discrete, Layers::MOVING, Vec3::sReplicate(0.5f), EActivation::DontActivate);
+
+		// After a single step (because the object is sleeping) there should not be a contact
+		c.SimulateSingleStep();
+		CHECK(listener.GetEntryCount() == 0);
+
+		// Activate the body
+		c.GetBodyInterface().ActivateBody(dynamic.GetID());
+
+		// After a single step we should have detected the collision with the floor and the sensor
+		c.SimulateSingleStep();
+		CHECK(listener.GetEntryCount() == 4);
+		CHECK(listener.Contains(EType::Validate, floor.GetID(), dynamic.GetID()));
+		CHECK(listener.Contains(EType::Add, floor.GetID(), dynamic.GetID()));
+		CHECK(listener.Contains(EType::Validate, sensor.GetID(), dynamic.GetID()));
+		CHECK(listener.Contains(EType::Add, sensor.GetID(), dynamic.GetID()));
+		listener.Clear();
+
+		// After a second the body should have gone to sleep and the contacts should have been removed
+		c.Simulate(1.0f);
+		CHECK(!dynamic.IsActive());
+		CHECK(listener.Contains(EType::Remove, floor.GetID(), dynamic.GetID()));
+		CHECK(listener.Contains(EType::Remove, sensor.GetID(), dynamic.GetID()));
+	}
+
+	TEST_CASE("TestDynamicSleepingVsKinematicSensor")
+	{
+		PhysicsTestContext c;
+
+		// Register listener
+		LoggingContactListener listener;
+		c.GetSystem()->SetContactListener(&listener);
+
+		// Kinematic sensor that is active (so will keep detecting contacts with sleeping bodies)
+		BodyCreationSettings sensor_settings(new BoxShape(Vec3::sReplicate(1)), Vec3::sZero(), Quat::sIdentity(), EMotionType::Kinematic, Layers::NON_MOVING);
+		sensor_settings.mIsSensor = true;
+		Body &sensor = *c.GetBodyInterface().CreateBody(sensor_settings);
+		c.GetBodyInterface().AddBody(sensor.GetID(), EActivation::Activate);
+
+		// Floor
+		Body &floor = c.CreateFloor();
+
+		// Dynamic body on floor (make them penetrate)
+		Body &dynamic = c.CreateBox(Vec3(0, 0.5f - c.GetSystem()->GetPhysicsSettings().mMaxPenetrationDistance, 0), Quat::sIdentity(), EMotionType::Dynamic, EMotionQuality::Discrete, Layers::MOVING, Vec3::sReplicate(0.5f), EActivation::DontActivate);
+
+		// After a single step, there should be a contact with the sensor only (the sensor is active)
+		c.SimulateSingleStep();
+		CHECK(listener.GetEntryCount() == 2);
+		CHECK(listener.Contains(EType::Validate, sensor.GetID(), dynamic.GetID()));
+		CHECK(listener.Contains(EType::Add, sensor.GetID(), dynamic.GetID()));
+		listener.Clear();
+
+		// The sensor should be in its own island
+		CHECK(sensor.GetMotionProperties()->GetIslandIndexInternal() != Body::cInactiveIndex);
+		CHECK(dynamic.GetMotionProperties()->GetIslandIndexInternal() == Body::cInactiveIndex);
+
+		// Activate the body
+		c.GetBodyInterface().ActivateBody(dynamic.GetID());
+
+		// After a single step we should have detected collision with the floor and the collision with the sensor should have persisted
+		c.SimulateSingleStep();
+		CHECK(listener.GetEntryCount() == 3);
+		CHECK(listener.Contains(EType::Validate, floor.GetID(), dynamic.GetID()));
+		CHECK(listener.Contains(EType::Add, floor.GetID(), dynamic.GetID()));
+		CHECK(listener.Contains(EType::Persist, sensor.GetID(), dynamic.GetID()));
+		listener.Clear();
+
+		// The sensor should not be part of the same island as the dynamic body (they won't interact, so this is not needed)
+		CHECK(sensor.GetMotionProperties()->GetIslandIndexInternal() != Body::cInactiveIndex);
+		CHECK(dynamic.GetMotionProperties()->GetIslandIndexInternal() != Body::cInactiveIndex);
+		CHECK(sensor.GetMotionProperties()->GetIslandIndexInternal() != dynamic.GetMotionProperties()->GetIslandIndexInternal());
+
+		// After a second the body should have gone to sleep and the contacts with the floor should have been removed, but not with the sensor
+		c.Simulate(1.0f);
+		CHECK(!dynamic.IsActive());
+		CHECK(listener.Contains(EType::Remove, floor.GetID(), dynamic.GetID()));
+		CHECK(!listener.Contains(EType::Remove, sensor.GetID(), dynamic.GetID()));
+	}
 }