Skip to content

Commit

Permalink
Browse files Browse the repository at this point in the history
  • Loading branch information
JulioJerez committed Jan 4, 2025
2 parents 5c177f1 + 0ec05d1 commit 549d51f
Show file tree
Hide file tree
Showing 8 changed files with 38 additions and 65 deletions.
Binary file modified newton-4.00/applications/media/buggy_sk.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file modified newton-4.00/applications/media/truck.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file modified newton-4.00/applications/media/tyre.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
5 changes: 2 additions & 3 deletions newton-4.00/applications/ndSandbox/demos/ndBasicVehicle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -251,6 +251,8 @@ class ndBasicMultiBodyVehicle : public ndVehicleCommon
,m_fr_tire(nullptr)
,m_fl_tire(nullptr)
{
SetNotifyCallback(new ndVehicleCommonNotify(this));

ndDemoEntity* const vehicleEntityDummyRoot = LoadMeshModel(scene, desc.m_name);

ndDemoEntity* const vehicleEntity = vehicleEntityDummyRoot->GetFirstChild();
Expand Down Expand Up @@ -322,7 +324,6 @@ class ndBasicMultiBodyVehicle : public ndVehicleCommon
}
}


// 4- add a motor
ndMultiBodyVehicleMotor* const motor = AddMotor(m_configuration.m_motorMass, m_configuration.m_motorRadius);
motor->SetMaxRpm(m_configuration.m_engine.GetRedLineRadPerSec() * dRadPerSecToRpm);
Expand Down Expand Up @@ -391,8 +392,6 @@ class ndBasicMultiBodyVehicle : public ndVehicleCommon
//
//m_engineRpmSound->SetLoop(true);
//m_skipMarks->SetLoop(true);

SetNotifyCallback(new ndVehicleCommonNotify(this));
}

~ndBasicMultiBodyVehicle()
Expand Down
82 changes: 34 additions & 48 deletions newton-4.00/applications/ndSandbox/demos/ndHeavyVehicle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -212,30 +212,24 @@ class ndHeavyMultiBodyVehicle : public ndVehicleCommon
:ndVehicleCommon(desc)
,m_vehicleUI(vehicleUI)
{
ndAssert(0);
#if 0
ndDemoEntity* const vehicleEntity = LoadMeshModel(scene, desc.m_name);
SetNotifyCallback(new ndVehicleCommonNotify(this));
ndDemoEntity* const vehicleEntityRoot = LoadMeshModel(scene, desc.m_name);
ndDemoEntity* const vehicleEntity = vehicleEntityRoot->GetFirstChild();

vehicleEntity->ResetMatrix(vehicleEntity->CalculateGlobalMatrix() * matrix);

ndPhysicsWorld* const world = scene->GetWorld();

// create the vehicle chassis as a normal rigid body
ndBodyKinematic* const chassis = CreateChassis(scene, vehicleEntity, m_configuration.m_chassisMass);
chassis->SetAngularDamping(ndVector(m_configuration.m_chassisAngularDrag));
//ndBodyKinematic* const chassis = CreateChassis(scene, vehicleEntity, m_configuration.m_chassisMass);
ndSharedPtr<ndBody> chassisBody (CreateChassis(scene, vehicleEntity, m_configuration.m_chassisMass));
AddChassis(chassisBody);
m_chassis->SetAngularDamping(ndVector(m_configuration.m_chassisAngularDrag));

// lower vehicle com;
ndVector com(chassis->GetCentreOfMass());
ndVector com(m_chassis->GetCentreOfMass());
com += m_localFrame.m_up.Scale(m_configuration.m_comDisplacement.m_y);
com += m_localFrame.m_front.Scale(m_configuration.m_comDisplacement.m_x);
com += m_localFrame.m_right.Scale(m_configuration.m_comDisplacement.m_z);
chassis->SetCentreOfMass(com);

// 1- add chassis to the vehicle mode
SetChassis(chassis);
ndSharedPtr<ndBody> bodyPtr(chassis);
world->AddBody(bodyPtr);
#endif
m_chassis->SetCentreOfMass(com);
}

~ndHeavyMultiBodyVehicle()
Expand Down Expand Up @@ -303,8 +297,6 @@ class ndHeavyMultiBodyVehicle : public ndVehicleCommon

void SetCamera(ndDemoEntityManager* const manager, ndFloat32)
{
ndAssert(0);
#if 0
ndDemoCamera* const camera = manager->GetCamera();
ndDemoEntity* const chassisEntity = (ndDemoEntity*)m_chassis->GetNotifyCallback()->GetUserData();
ndMatrix camMatrix(camera->GetNextMatrix());
Expand All @@ -316,7 +308,6 @@ class ndHeavyMultiBodyVehicle : public ndVehicleCommon
camOrigin -= frontDir.Scale(10.0f);

camera->SetNextMatrix(camMatrix, camOrigin);
#endif
}

protected:
Expand Down Expand Up @@ -750,45 +741,42 @@ class ndBigRigVehicle : public ndHeavyMultiBodyVehicle
// this function will create the tire as a normal rigid body
// and attach them to the chassis with the tire joints

ndAssert(0);
#if 0
ndWorld* const world = scene->GetWorld();
//ndWorld* const world = scene->GetWorld();
ndBodyKinematic* const chassis = m_chassis;

ndVehicleDectriptor::ndTireDefinition f0_tireConfiguration(m_configuration.m_frontTire);
ndVehicleDectriptor::ndTireDefinition f1_tireConfiguration(m_configuration.m_frontTire);
ndBodyKinematic* const fl_tire_body = CreateTireBody(scene, chassis, f0_tireConfiguration, "fl_tire");
ndBodyKinematic* const fr_tire_body = CreateTireBody(scene, chassis, f1_tireConfiguration, "fr_tire");
ndSharedPtr<ndBody> fl_tire_body (CreateTireBody(scene, chassis, f0_tireConfiguration, "fl_tire"));
ndSharedPtr<ndBody> fr_tire_body (CreateTireBody(scene, chassis, f1_tireConfiguration, "fr_tire"));
AddTire(f0_tireConfiguration, fr_tire_body);
AddTire(f0_tireConfiguration, fl_tire_body);

ndVehicleDectriptor::ndTireDefinition r0_tireConfiguration(m_configuration.m_rearTire);
ndVehicleDectriptor::ndTireDefinition r1_tireConfiguration(m_configuration.m_rearTire);
ndVehicleDectriptor::ndTireDefinition r2_tireConfiguration(m_configuration.m_rearTire);
ndVehicleDectriptor::ndTireDefinition r3_tireConfiguration(m_configuration.m_rearTire);
ndBodyKinematic* const rl_tire0_body = CreateTireBody(scene, chassis, r0_tireConfiguration, "rl_midle_tire");
ndBodyKinematic* const rr_tire0_body = CreateTireBody(scene, chassis, r1_tireConfiguration, "rr_midle_tire");
ndBodyKinematic* const rl_tire1_body = CreateTireBody(scene, chassis, r2_tireConfiguration, "rl_tire");
ndBodyKinematic* const rr_tire1_body = CreateTireBody(scene, chassis, r3_tireConfiguration, "rr_tire");
ndSharedPtr<ndBody> rl_tire0_body (CreateTireBody(scene, chassis, r0_tireConfiguration, "rl_midle_tire"));
ndSharedPtr<ndBody> rr_tire0_body (CreateTireBody(scene, chassis, r1_tireConfiguration, "rr_midle_tire"));
ndSharedPtr<ndBody> rl_tire1_body (CreateTireBody(scene, chassis, r2_tireConfiguration, "rl_tire"));
ndSharedPtr<ndBody> rr_tire1_body (CreateTireBody(scene, chassis, r3_tireConfiguration, "rr_tire"));

ndMultiBodyVehicleTireJoint* const rr_tire0 = AddTire(r0_tireConfiguration, rr_tire0_body);
ndMultiBodyVehicleTireJoint* const rl_tire0 = AddTire(r1_tireConfiguration, rl_tire0_body);
ndMultiBodyVehicleTireJoint* const rr_tire1 = AddTire(r2_tireConfiguration, rr_tire1_body);
ndMultiBodyVehicleTireJoint* const rl_tire1 = AddTire(r3_tireConfiguration, rl_tire1_body);

ndSharedPtr<ndBody> fl_tire_body_Ptr(fl_tire_body);
ndSharedPtr<ndBody> fr_tire_body_Ptr(fr_tire_body);
ndSharedPtr<ndBody> rl_tire0_body_Ptr(rl_tire0_body);
ndSharedPtr<ndBody> rr_tire0_body_Ptr(rr_tire0_body);
ndSharedPtr<ndBody> rl_tire1_body_Ptr(rl_tire1_body);
ndSharedPtr<ndBody> rr_tire1_body_Ptr(rr_tire1_body);

world->AddBody(fl_tire_body_Ptr);
world->AddBody(fr_tire_body_Ptr);
world->AddBody(rl_tire0_body_Ptr);
world->AddBody(rr_tire0_body_Ptr);
world->AddBody(rl_tire1_body_Ptr);
world->AddBody(rr_tire1_body_Ptr);
//ndSharedPtr<ndBody> fl_tire_body_Ptr(fl_tire_body);
//ndSharedPtr<ndBody> fr_tire_body_Ptr(fr_tire_body);
//ndSharedPtr<ndBody> rl_tire0_body_Ptr(rl_tire0_body);
//ndSharedPtr<ndBody> rr_tire0_body_Ptr(rr_tire0_body);
//ndSharedPtr<ndBody> rl_tire1_body_Ptr(rl_tire1_body);
//ndSharedPtr<ndBody> rr_tire1_body_Ptr(rr_tire1_body);
//world->AddBody(fl_tire_body_Ptr);
//world->AddBody(fr_tire_body_Ptr);
//world->AddBody(rl_tire0_body_Ptr);
//world->AddBody(rr_tire0_body_Ptr);
//world->AddBody(rl_tire1_body_Ptr);
//world->AddBody(rr_tire1_body_Ptr);

m_currentGear = sizeof(m_configuration.m_transmission.m_forwardRatios) / sizeof(m_configuration.m_transmission.m_forwardRatios[0]) + 1;

Expand All @@ -807,7 +795,6 @@ class ndBigRigVehicle : public ndHeavyMultiBodyVehicle

// set a soft or hard mode
SetVehicleSolverModel(m_configuration.m_useHardSolverMode ? true : false);
#endif
}

void ApplyInputs(ndWorld* const world, ndFloat32 timestep)
Expand All @@ -820,10 +807,10 @@ void ndHeavyVehicle (ndDemoEntityManager* const scene)
{
ndMatrix sceneLocation(ndGetIdentityMatrix());
//BuildFloorBox(scene, sceneLocation);
//BuildFlatPlane(scene, true);
BuildFlatPlane(scene, true);
//BuildGridPlane(scene, 120, 4.0f, 0.0f);
//BuildStaticMesh(scene, "track.fbx", true);
BuildCompoundScene(scene, sceneLocation);
//BuildCompoundScene(scene, sceneLocation);
//BuildStaticMesh(scene, "playerarena.fbx", true);
//BuildSplineTrack(scene, "playerarena.fbx", true);
//sceneLocation.m_posit.m_x = -200.0f;
Expand Down Expand Up @@ -858,8 +845,7 @@ void ndHeavyVehicle (ndDemoEntityManager* const scene)
ndSharedPtr<ndUIEntity> vehicleUIPtr(vehicleUI);
scene->Set2DDisplayRenderFunction(vehicleUIPtr);

ndAssert(0);
//ndSharedPtr<ndModel> vehicle0(new ndBigRigVehicle(scene, bigRigDesc, matrix, vehicleUI));
ndSharedPtr<ndModel> vehicle0(new ndBigRigVehicle(scene, bigRigDesc, matrix, vehicleUI));

matrix.m_posit.m_x += 6.0f;
matrix.m_posit.m_z += 6.0f;
Expand All @@ -868,12 +854,12 @@ void ndHeavyVehicle (ndDemoEntityManager* const scene)
matrix.m_posit.m_z -= 12.0f;
//ndSharedPtr<ndModel> vehicle2(new ndTractorVehicle(scene, tractorDesc, matrix, vehicleUI));

//world->AddModel(vehicle0);
world->AddModel(vehicle0);
//world->AddModel(vehicle1);
//world->AddModel(vehicle2);

//ndHeavyMultiBodyVehicle* const vehicle = (ndHeavyMultiBodyVehicle*)*vehicle0;
//vehicle->SetAsPlayer(scene);
ndHeavyMultiBodyVehicle* const vehicle = (ndHeavyMultiBodyVehicle*)*vehicle0;
vehicle->SetAsPlayer(scene);

matrix.m_posit.m_x += 25.0f;
matrix.m_posit.m_z += 6.0f;
Expand Down
4 changes: 2 additions & 2 deletions newton-4.00/applications/ndSandbox/ndDemoEntityManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,8 @@
//#define DEFAULT_SCENE 9 // static mesh collision
//#define DEFAULT_SCENE 10 // static user mesh collision
//#define DEFAULT_SCENE 11 // basic joints
#define DEFAULT_SCENE 12 // basic vehicle
//#define DEFAULT_SCENE 13 // heavy vehicle
//#define DEFAULT_SCENE 12 // basic vehicle
#define DEFAULT_SCENE 13 // heavy vehicle
//#define DEFAULT_SCENE 14 // background vehicle prop
//#define DEFAULT_SCENE 15 // basic player
//#define DEFAULT_SCENE 16 // rag doll
Expand Down
10 changes: 0 additions & 10 deletions newton-4.00/applications/ndSandbox/toolbox/ndVehicleCommon.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -338,16 +338,6 @@ bool ndVehicleCommon::IsPlayer() const
return m_isPlayer;
}

//void ndVehicleCommon::SetChassis(ndBodyKinematic* const chassis)
//{
// ndAssert(0);
// AddChassis(chassis);
// // assign chassis material id.
// ndShapeInstance& instanceShape = chassis->GetCollisionShape();
// instanceShape.m_shapeMaterial.m_userId = ndDemoContactCallback::m_modelPart;
// instanceShape.m_shapeMaterial.m_userParam[ndDemoContactCallback::m_modelPointer].m_ptrData = this;
//}

void ndVehicleCommon::CalculateTireDimensions(const char* const tireName, ndFloat32& width, ndFloat32& radius, ndDemoEntity* const vehEntity) const
{
// find the the tire visual mesh
Expand Down
2 changes: 0 additions & 2 deletions newton-4.00/applications/ndSandbox/toolbox/ndVehicleCommon.h
Original file line number Diff line number Diff line change
Expand Up @@ -208,8 +208,6 @@ class ndVehicleCommon : public ndMultiBodyVehicle
protected:
void Update(ndWorld* const world, ndFloat32 timestep);
void PostUpdate(ndWorld* const world, ndFloat32 timestep);

//void SetChassis(ndBodyKinematic* const chassis);
void CalculateTireDimensions(const char* const tireName, ndFloat32& width, ndFloat32& radius, ndDemoEntity* const vehEntity) const;
ndBodyKinematic* CreateTireBody(ndDemoEntityManager* const scene, ndBodyKinematic* const parentBody, ndVehicleDectriptor::ndTireDefinition& definition, const char* const tireName) const;

Expand Down

0 comments on commit 549d51f

Please sign in to comment.