Vehicle applyEngineForce doesn't works

Post Reply
kcjsend2
Posts: 15
Joined: Wed Jun 30, 2021 9:10 am

Vehicle applyEngineForce doesn't works

Post by kcjsend2 »

hi.

When I make a second vehicle and try to use it, the vehicle won't move.

We have confirmed that the applyEngineForce is properly called, and the steering also moves properly, but the vehicle operates as if the EngineForce is zero.

The strangest thing is that there is no problem when I first make the vehicle I want to operate, but only when I make another vehicle after the first time.

The following is the code for making and control a vehicle.

Code: Select all


XMFLOAT3 pos = { 500.0f, 30.0f, 500.0f };
BuildCarObjects(pos, 4, false, cmdList, physics, 1, true);
pos.z += 40.0f;
BuildCarObjects(pos, 4, true, cmdList, physics, 0);
	
	
void InGameScene::BuildCarObjects(
	XMFLOAT3& position,
	char color,
	bool isPlayer,
	ID3D12GraphicsCommandList* cmdList, 
	const std::shared_ptr<BulletWrapper>& physics,
	UINT netID, bool latencyTest)
{
	auto carObj = make_shared<PhysicsPlayer>(netID);
	carObj->SetPosition(position);

	if (mMeshList[MeshType::Car].empty())
		mMeshList[MeshType::Car] = carObj->LoadModel(mDevice.Get(), cmdList, L"Models\\Car_Body.obj");
	else
		carObj->SetMeshes(mMeshList[MeshType::Car]);

	carObj->SetDiffuse("Car_Texture", mColorMap[(int)color]);
	for (int i = 0; i < 4; ++i)
	{
		auto wheelObj = make_shared<WheelObject>();

		if (i % 2 == 0)
		{
			if (mMeshList[MeshType::Wheel_L].empty())
				mMeshList[MeshType::Wheel_L] = wheelObj->LoadModel(mDevice.Get(), cmdList, L"Models\\Car_Wheel_L.obj");
			else
				wheelObj->SetMeshes(mMeshList[MeshType::Wheel_L]);
		}
		else
		{
			if (mMeshList[MeshType::Wheel_R].empty())
				mMeshList[MeshType::Wheel_R] = wheelObj->LoadModel(mDevice.Get(), cmdList, L"Models\\Car_Wheel_R.obj");
			else
				wheelObj->SetMeshes(mMeshList[MeshType::Wheel_R]);
		}

		carObj->SetWheel(wheelObj.get(), i);
		mPipelines[Layer::Color]->AppendObject(wheelObj);
	}
	carObj->BuildRigidBody(physics); //Actually make Vehicle Object
	carObj->BuildDsvRtvView(mDevice.Get());
	if (isPlayer) mPlayer = carObj.get();
	if (latencyTest) mFakePlayer = carObj.get();
	mPipelines[Layer::Color]->AppendObject(carObj);
	mPlayerObjects[netID] = std::move(carObj);
}

void PhysicsPlayer::BuildRigidBody(std::shared_ptr<BulletWrapper> physics)
{
	auto dynamicsWorld = physics->GetDynamicsWorld();

	mOOBB.Extents = { 10.0f, 4.0f, 14.0f };

	XMFLOAT3 vehicleExtents = mOOBB.Extents;
	XMFLOAT3 wheelExtents = mWheel[0]->GetBoundingBox().Extents;

	btCollisionShape* chassisShape = new btBoxShape(btVector3(vehicleExtents.x, vehicleExtents.y, vehicleExtents.z));

	btTransform btCarTransform;
	btCarTransform.setIdentity();
	btCarTransform.setOrigin(btVector3(mPosition.x, mPosition.y, mPosition.z));

	mBtRigidBody = physics->CreateRigidBody(1000.0f, btCarTransform, chassisShape);

	mVehicleRayCaster = std::make_shared<btDefaultVehicleRaycaster>(dynamicsWorld.get());
	mVehicle = std::make_shared<btRaycastVehicle>(mTuning, mBtRigidBody, mVehicleRayCaster.get());

	mBtRigidBody->setActivationState(DISABLE_DEACTIVATION);
	dynamicsWorld->addAction(mVehicle.get());

	mVehicle->setCoordinateSystem(0, 1, 2);

	btVector3 wheelDirectionCS0(0, -1, 0);
	btVector3 wheelAxleCS(-1, 0, 0);

	float wheelWidth = wheelExtents.x;
	float wheelRadius = wheelExtents.z;
	float wheelFriction = 26.0f;
	float suspensionStiffness = 20.f;
	float suspensionDamping = 2.3f;
	float suspensionCompression = 4.4f;
	float rollInfluence = 0.01f;  //1.0f;

	bool isFrontWheel = true;
	float connectionHeight = -0.9f;

	btVector3 connectionPointCS0(vehicleExtents.x - 2.5f, connectionHeight, vehicleExtents.z - 2.8f);
	mVehicle->addWheel(connectionPointCS0, wheelDirectionCS0, wheelAxleCS, 0.6, wheelRadius, mTuning, isFrontWheel);

	connectionPointCS0 = btVector3(-vehicleExtents.x + 2.5f, connectionHeight, vehicleExtents.z - 2.8f);
	mVehicle->addWheel(connectionPointCS0, wheelDirectionCS0, wheelAxleCS, 0.6, wheelRadius, mTuning, isFrontWheel);

	isFrontWheel = false;

	connectionPointCS0 = btVector3(vehicleExtents.x - 2.3f, connectionHeight, -vehicleExtents.z + 2.6f);
	mVehicle->addWheel(connectionPointCS0, wheelDirectionCS0, wheelAxleCS, 0.6, wheelRadius, mTuning, isFrontWheel);

	connectionPointCS0 = btVector3(-vehicleExtents.x + 2.3f, connectionHeight, -vehicleExtents.z + 2.6f);
	mVehicle->addWheel(connectionPointCS0, wheelDirectionCS0, wheelAxleCS, 0.6, wheelRadius, mTuning, isFrontWheel);

	for (int i = 0; i < mVehicle->getNumWheels(); i++)
	{
		btWheelInfo& wheel = mVehicle->getWheelInfo(i);
		wheel.m_suspensionStiffness = suspensionStiffness;
		wheel.m_wheelsDampingRelaxation = suspensionDamping;
		wheel.m_wheelsDampingCompression = suspensionCompression;
		wheel.m_frictionSlip = wheelFriction;
		wheel.m_rollInfluence = rollInfluence;
	}
}

//control vehicle


void PhysicsPlayer::OnPreciseKeyInput(float Elapsed)
{
	mCurrentSpeed = mVehicle->getCurrentSpeedKmHour();
	
	mEngineForce = 0.0f;
	if (mBoosterLeft > 0.0f)
	{
		mMaxSpeed = 1500.0f;
		mBoosterLeft -= Elapsed;
	}
	
	if(mBoosterLeft < 0.0f)
	{
		mMaxSpeed = 1000.0f;
		mBoosterLeft = 0.0f;
	}

	if (mVehicleSteering > 0)
	{
		mVehicleSteering -= mSteeringIncrement * Elapsed;
		if (mVehicleSteering < 0)
		{
			mVehicleSteering = 0;
		}
	}

	else if (mVehicleSteering < 0)
	{
		mVehicleSteering += mSteeringIncrement * Elapsed;
		if (mVehicleSteering > 0)
		{
			mVehicleSteering = 0;
		}
	}

	if (GetAsyncKeyState(VK_LEFT) & 0x8000)
	{
		mVehicleSteering -= mSteeringIncrement * 2 * Elapsed;
		if (mVehicleSteering < -mSteeringClamp)
			mVehicleSteering = -mSteeringClamp;
	}
	if (GetAsyncKeyState(VK_RIGHT) & 0x8000)
	{
		mVehicleSteering += mSteeringIncrement * 2 * Elapsed;
		if (mVehicleSteering > mSteeringClamp)
			mVehicleSteering = mSteeringClamp;
	}
	if (GetAsyncKeyState(VK_UP) & 0x8000)
	{
		if (mCurrentSpeed < 0.0f)
			mEngineForce = mMaxEngineForce * 1.5f;
		else if (mMaxSpeed > mCurrentSpeed)
			mEngineForce = mMaxEngineForce;
		else
			mEngineForce = 0.0f;
	}
	if (GetAsyncKeyState(VK_DOWN) & 0x8000)
	{
		if (mCurrentSpeed > 0.0f)
			mEngineForce = -mMaxEngineForce * 1.5f;
		else if (-mMaxSpeed < mCurrentSpeed)
			mEngineForce = -mMaxEngineForce;
		else
			mEngineForce = 0.0f;
	}
	if (GetAsyncKeyState('Z') & 0x8000)
	{
		if (mBoosterLeft == 0.0f)
			mBoosterLeft = mBoosterTime;
	}
	if (GetAsyncKeyState(VK_SHIFT) & 0x8000)
	{
		for (int i = 2; i < 4; ++i)
		{
			mVehicle->getWheelInfo(i).m_frictionSlip = 4.0f;
		}
	}
	else
	{
		for (int i = 0; i < 4; ++i)
		{
			mVehicle->getWheelInfo(i).m_frictionSlip = 25.0f;
		}
	}
	
	if (mBoosterLeft && mMaxSpeed < mCurrentSpeed)
		mEngineForce = mBoosterEngineForce;

	OutputDebugStringA("Update engineforce\n");
	for (int i = 0; i < 2; ++i)
	{
		mVehicle->applyEngineForce(mEngineForce, i);
	}
	
	int wheelIndex = 0;
	mVehicle->setSteeringValue(mVehicleSteering, wheelIndex);
	wheelIndex = 1;
	mVehicle->setSteeringValue(mVehicleSteering, wheelIndex);
}

Post Reply