Skip to content

Commit

Permalink
appling same method to heavy truck demo (wip)
Browse files Browse the repository at this point in the history
  • Loading branch information
JulioJerez committed Jan 4, 2025
1 parent 8fede7e commit 020b6cd
Show file tree
Hide file tree
Showing 6 changed files with 76 additions and 33 deletions.
41 changes: 36 additions & 5 deletions newton-4.00/applications/ndSandbox/demos/ndHeavyVehicle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -762,6 +762,36 @@ class ndBigRigVehicle : public ndHeavyMultiBodyVehicle
}
};


static ndDemoEntity* LoadVehicleMeshModel(ndDemoEntityManager* const scene, const char* const filename)
{
ndMeshLoader loader;
ndDemoEntity* const vehicleEntity = loader.LoadEntity(filename, scene);
scene->AddEntity(vehicleEntity);
return vehicleEntity;
}

static ndMultiBodyVehicle* CreateBigRig(ndDemoEntityManager* const scene, const ndVehicleDectriptor& desc, const ndMatrix& matrix, ndVehicleUI* const vehicleUI)
{
ndMultiBodyVehicle* const vehicle = new ndMultiBodyVehicle;

vehicle->SetNotifyCallback(ndSharedPtr<ndModelNotify>(new ndVehicleCommonNotify(desc, vehicle, vehicleUI)));
ndVehicleCommonNotify* const notifyCallback = (ndVehicleCommonNotify*)*vehicle->GetNotifyCallback();

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

ndDemoEntity* const vehicleEntity = vehicleEntityDummyRoot->GetFirstChild();
vehicleEntity->ResetMatrix(vehicleEntity->CalculateGlobalMatrix() * matrix);

// 1- add chassis to the vehicle mode
// create the vehicle chassis as a normal rigid body
const ndVehicleDectriptor& configuration = notifyCallback->m_desc;


vehicle->SetVehicleSolverModel(configuration.m_useHardSolverMode ? true : false);
return vehicle;
}

void ndHeavyVehicle (ndDemoEntityManager* const scene)
{
ndMatrix sceneLocation(ndGetIdentityMatrix());
Expand Down Expand Up @@ -805,20 +835,21 @@ void ndHeavyVehicle (ndDemoEntityManager* const scene)
scene->Set2DDisplayRenderFunction(vehicleUIPtr);

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

matrix.m_posit.m_x += 6.0f;
matrix.m_posit.m_z += 6.0f;
//ndSharedPtr<ndModel> vehicle1(new ndLav25Vehicle(scene, lav25Desc, matrix, vehicleUI));

matrix.m_posit.m_z -= 12.0f;
ndSharedPtr<ndModel> vehicle2(new ndTractorVehicle(scene, tractorDesc, matrix, vehicleUI));
//ndSharedPtr<ndModel> vehicle2(new ndTractorVehicle(scene, tractorDesc, matrix, vehicleUI));

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

ndHeavyMultiBodyVehicle* const vehicle = (ndHeavyMultiBodyVehicle*)*vehicle2;
vehicle->SetAsPlayer(scene);
ndVehicleCommonNotify* const notifyCallback = (ndVehicleCommonNotify*)*vehicle0->GetNotifyCallback();
notifyCallback->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
23 changes: 13 additions & 10 deletions newton-4.00/applications/ndSandbox/toolbox/ndVehicleCommon.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -949,19 +949,22 @@ void ndVehicleCommonNotify::Debug(ndConstraintDebugCallback& context) const
}
}

void ndVehicleCommonNotify::SetCamera(ndDemoEntityManager* const manager, ndFloat32 timestep)
void ndVehicleCommonNotify::SetCamera(ndDemoEntityManager* const manager, ndFloat32)
{
ndMultiBodyVehicle* const vehicle = (ndMultiBodyVehicle*)GetModel();

ndDemoCamera* const camera = manager->GetCamera();
ndDemoEntity* const chassisEntity = (ndDemoEntity*)vehicle->GetChassis()->GetNotifyCallback()->GetUserData();
ndMatrix camMatrix(camera->GetNextMatrix());
ndMatrix playerMatrix(chassisEntity->GetNextMatrix());
if (vehicle->GetRoot())
{
ndDemoCamera* const camera = manager->GetCamera();
ndDemoEntity* const chassisEntity = (ndDemoEntity*)vehicle->GetChassis()->GetNotifyCallback()->GetUserData();
ndMatrix camMatrix(camera->GetNextMatrix());
ndMatrix playerMatrix(chassisEntity->GetNextMatrix());

ndVector frontDir(camMatrix[0]);
ndVector camOrigin(0.0f);
camOrigin = playerMatrix.m_posit + ndVector(0.0f, 1.0f, 0.0f, 0.0f);
camOrigin -= frontDir.Scale(10.0f);
ndVector frontDir(camMatrix[0]);
ndVector camOrigin(0.0f);
camOrigin = playerMatrix.m_posit + ndVector(0.0f, 1.0f, 0.0f, 0.0f);
camOrigin -= frontDir.Scale(10.0f);

camera->SetNextMatrix(camMatrix, camOrigin);
camera->SetNextMatrix(camMatrix, camOrigin);
}
}
4 changes: 2 additions & 2 deletions newton-4.00/sdk/dCollision/ndMeshEffect.h
Original file line number Diff line number Diff line change
Expand Up @@ -574,7 +574,7 @@ class ndMeshEffect: public ndPolyhedra
D_COLLISION_API void Init();
D_COLLISION_API virtual void BeginFace();
D_COLLISION_API virtual bool EndFace();
ndFloat64 QuantizeCordinade(ndFloat64 val) const;
ndFloat64 QuantizeCoordinade(ndFloat64 val) const;

bool Sanity() const;
void PackPoints();
Expand Down Expand Up @@ -633,7 +633,7 @@ inline dInt32 ndMeshEffect::GetVertexLayer(dInt32 index) const
}
#endif

inline ndFloat64 ndMeshEffect::QuantizeCordinade(ndFloat64 x) const
inline ndFloat64 ndMeshEffect::QuantizeCoordinade(ndFloat64 x) const
{
ndInt32 exp;
ndFloat64 mantissa = frexp(x, &exp);
Expand Down
2 changes: 1 addition & 1 deletion newton-4.00/sdk/dCollision/ndMeshEffect1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2402,7 +2402,7 @@ void ndMeshEffect::BeginBuildFace()
void ndMeshEffect::AddPoint(ndFloat64 x, ndFloat64 y, ndFloat64 z)
{
m_attrib.m_pointChannel.PushBack(ndInt32(m_points.m_vertex.GetCount()));
const ndBigVector point(QuantizeCordinade(x), QuantizeCordinade(y), QuantizeCordinade(z), ndFloat64(0.0f));
const ndBigVector point(QuantizeCoordinade(x), QuantizeCoordinade(y), QuantizeCoordinade(z), ndFloat64(0.0f));
m_points.m_vertex.PushBack(point);
}

Expand Down
35 changes: 22 additions & 13 deletions newton-4.00/sdk/dNewton/dModels/dVehicle/ndMultiBodyVehicle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -338,17 +338,19 @@ void ndMultiBodyVehicle::AddChassis(const ndSharedPtr<ndBody>& chassis)

void ndMultiBodyVehicle::SetVehicleSolverModel(bool hardJoint)
{
ndAssert(m_chassis);
ndJointBilateralSolverModel openLoopMode = hardJoint ? m_jointkinematicOpenLoop : m_jointIterativeSoft;
for (ndNode* node = GetRoot()->GetFirstChild(); node; node = node->GetNext())
if (GetRoot())
{
ndJointBilateralConstraint* const joint = *node->m_joint;
const char* const className = joint->ClassName();
if (!strcmp(className, "ndMultiBodyVehicleTireJoint") ||
!strcmp(className, "ndMultiBodyVehicleDifferential") ||
!strcmp(className, "ndMultiBodyVehicleMotor"))
for (ndNode* node = GetRoot()->GetFirstChild(); node; node = node->GetNext())
{
joint->SetSolverModel(openLoopMode);
ndJointBilateralConstraint* const joint = *node->m_joint;
const char* const className = joint->ClassName();
if (!strcmp(className, "ndMultiBodyVehicleTireJoint") ||
!strcmp(className, "ndMultiBodyVehicleDifferential") ||
!strcmp(className, "ndMultiBodyVehicleMotor"))
{
joint->SetSolverModel(openLoopMode);
}
}
}

Expand Down Expand Up @@ -541,11 +543,13 @@ ndMultiBodyVehicleGearBox* ndMultiBodyVehicle::AddGearBox(ndMultiBodyVehicleDiff
bool ndMultiBodyVehicle::IsSleeping() const
{
bool sleeping = true;
for (ndNode* node = GetRoot()->GetFirstIterator(); sleeping && node; node = node->GetNextIterator())
if (GetRoot())
{
ndBodyDynamic* const body = node->m_body->GetAsBodyDynamic();
//active = active || (body->GetScene() ? true : false);
sleeping = sleeping && body->GetSleepState();
for (ndNode* node = GetRoot()->GetFirstIterator(); sleeping && node; node = node->GetNextIterator())
{
ndBodyDynamic* const body = node->m_body->GetAsBodyDynamic();
sleeping = sleeping && body->GetSleepState();
}
}
return sleeping;
}
Expand Down Expand Up @@ -980,7 +984,12 @@ void ndMultiBodyVehicle::PostUpdate(ndWorld* const, ndFloat32)

void ndMultiBodyVehicle::Debug(ndConstraintDebugCallback& context) const
{
// draw vehicle cordinade system;
if (!GetRoot())
{
return;
}

// draw vehicle coordinade system;
const ndBodyKinematic* const chassis = m_chassis;
ndAssert(chassis);
ndMatrix chassisMatrix(chassis->GetMatrix());
Expand Down

0 comments on commit 020b6cd

Please sign in to comment.