Vehicle2

Classes

Macros

Functions

Namespaces

Structs

Functions

inline void PxCloseVehicleExtension()

Shut down the PhysX Vehicle library.

This function should be called to cleanly shut down the PhysX Vehicle library before application exit.

Note

This function is required to be called to release foundation usage.

inline bool PxInitVehicleExtension(physx::PxFoundation &foundation)

Initialize the PhysX Vehicle library.

This should be called before calling any functions or methods in extensions which may require allocation.

Note

This function does not need to be called before creating a PxDefaultAllocator object.

Parameters

foundation – a PxFoundation object

bool PxVehicleAccelerationIntentCompute(const PxVehicleAxleDescription &poweredVehicleAxleDesc, const PxVehicleArrayData<const PxVehicleWheelActuationState> &poweredVehicleActuationStates)

Compute the intention to accelerate by inspecting the actuation states of the wheels of a powered vehicle.

Parameters
  • poweredVehicleAxleDesc[in] describes the axles and wheels of a powered vehicle in a jointed ensemble of vehicles.

  • poweredVehicleActuationStates[in] describes the drive state of each wheel of the powered vehicle.

void PxVehicleAckermannSteerUpdate(const PxReal steer, const PxVehicleSteerCommandResponseParams &steerResponseParmas, const PxVehicleSizedArrayData<const PxVehicleAckermannParams> &ackermannParams, PxVehicleArrayData<PxReal> &steerResponseStates)

Account for Ackermann correction by modifying the per wheel steer response multipliers to engineer an asymmetric steer response across axles.

Parameters
  • steer[in] is the input steer command value.

  • steerResponseParmas[in] describes the maximum response and a response multiplier per axle.

  • ackermannParams[in] is an array that describes the wheels affected by Ackerman steer correction.

  • steerResponseStates[inout] contains the corrected per wheel steer response multipliers that take account of Ackermann steer correction.

void PxVehicleAntiRollForceUpdate(const PxVehicleArrayData<const PxVehicleSuspensionParams> &suspensionParams, const PxVehicleSizedArrayData<const PxVehicleAntiRollForceParams> &antiRollParams, const PxVehicleArrayData<const PxVehicleSuspensionState> &suspensionStates, const PxVehicleArrayData<const PxVehicleSuspensionComplianceState> &complianceStates, const PxVehicleRigidBodyState &rigidBodyState, PxVehicleAntiRollTorque &antiRollTorque)

Compute the accumulated anti-roll torque to apply to the vehicle’s rigid body.

Note

suspensionParams must contain an entry for each wheel index referenced by antiRollParams.

Note

suspensionStates must contain an entry for each wheel index referenced by antiRollParams.

Note

complianceStates must contain an entry for each wheel index referenced by antiRollParams.

Note

antiRollTorque is expressed in the world frame.

Parameters
  • suspensionParams[in] The suspension parameters for each wheel.

  • antiRollParams[in] describes the wheel pairs connected by anti-roll bars and the strength of each anti-roll bar.

  • suspensionStates[in] The suspension states for each wheel.

  • complianceStates[in] The suspension compliance states for each wheel.

  • rigidBodyState[in] describes the pose and momentum of the vehicle’s rigid body in the world frame.

  • antiRollTorque[in] is the accumulated anti-roll torque that is computed by iterating over all anti-roll bars describes in antiRollParams.

void PxVehicleAutoBoxUpdate(const PxVehicleEngineParams &engineParams, const PxVehicleGearboxParams &gearboxParams, const PxVehicleAutoboxParams &autoboxParams, const PxVehicleEngineState &engineState, const PxVehicleGearboxState &gearboxState, const PxReal dt, PxU32 &targetGearCommand, PxVehicleAutoboxState &autoboxState, PxReal &throttle)

Note

The autobox will not begin a gear change if a gear change is already ongoing.

Note

The autobox will not begin a gear change until a threshold time has lapsed since the last automated gear change.

Note

A gear change is considered as ongoing for as long as PxVehicleGearboxState::currentGear is different from PxVehicleGearboxState::targetGear.

Note

The autobox will not shift down from 1st gear or up from reverse gear.

Note

The autobox shifts in single gear increments or decrements.

Note

The autobox instantiates a gear change by setting PxVehicleCommandState::targetGear to be different from from PxVehicleGearboxState::currentGear

Parameters
  • engineParams[in] specifies the engine configuration.

  • gearboxParams[in] specifies the gear ratios and the time required to complete a gear change.

  • autoboxParams[in] specifies the conditions for switching gear.

  • engineState[in] contains the current angular speed of the engine.

  • gearboxState[in] describes the current and target gear.

  • dt[in] is the time that has lapsed since the last call to PxVehicleAutoBoxUpdate.

  • targetGearCommand[inout] specifies the desired target gear for the gearbox. If set to PxVehicleEngineDriveTransmissionCommandState::eAUTOMATIC_GEAR, the value will get overwritten with a target gear chosen by the autobox.

  • autoboxState[out] specifies the time that has lapsed since the last automated gear change and contains a record of any ongoing automated gear change.

  • throttle[out] A throttle command value in [0, 1] that will be set to 0 if a gear change is initiated or is ongoing.

inline void PxVehicleBrakeCommandResponseUpdate(const PxReal *brakeCommands, const PxU32 nbBrakeCommands, const PxReal longitudinalSpeed, const PxU32 wheelId, const PxVehicleSizedArrayData<const PxVehicleBrakeCommandResponseParams> &brakeResponseParams, PxReal &brakeResponseState)

Compute the brake torque response to an array of brake commands.

Note

commands.brakes[i] and brakeResponseParams[i] are treated as pairs of brake command and brake command response.

Parameters
  • brakeCommands[in] is the array of input brake commands to be applied to the vehicle.

  • nbBrakeCommands[in] is the number of input brake commands to be applied to the vehicle.

  • longitudinalSpeed[in] is the longitudinal speed of the vehicle.

  • wheelId[in] specifies the wheel that is to have its brake response computed.

  • brakeResponseParams[in] specifies the per wheel brake torque response to each brake command as a nonlinear function of brake command and longitudinal speed.

  • brakeResponseState[out] is the brake torque response to the input brake command.

void PxVehicleClutchCommandResponseLinearUpdate(const PxReal clutchCommand, const PxVehicleClutchCommandResponseParams &clutchResponseParams, PxVehicleClutchCommandResponseState &clutchResponse)

Propagate the input clutch command to the clutch response state.

Parameters
  • clutchCommand[in] specifies the state of the clutch pedal.

  • clutchResponseParams[in] specifies how the clutch responds to the input clutch command.

  • clutchResponse[out] specifies the response of the clutch to the input clutch command.

inline PxReal PxVehicleClutchStrengthCompute(const PxVehicleClutchCommandResponseState &clutchResponseState, const PxVehicleGearboxParams &gearboxParams, const PxVehicleGearboxState &gearboxState)

Compute the coupling strength of the clutch.

Note

If the gear is in neutral the clutch is fully disengaged and the clutch strength is 0.

Note

A clutch response state of 0.0 denotes a fully engaged clutch with maximum strength.

Note

A clutch response state of 1.0 denotes a fully disengaged clutch with a strength of 0.0.

Parameters
  • clutchResponseState[in] describes the response of the clutch to the input clutch command.

  • gearboxParams[in] holds the index of neutral gear.

  • gearboxState[in] describes the current gear.

inline PxQuat PxVehicleComputeRotation(const PxVehicleFrame &frame, const PxReal roll, const PxReal pitch, const PxReal yaw)
inline PxF32 PxVehicleComputeSign(const PxReal f)
bool PxVehicleComputeSprungMasses(const PxU32 nbSprungMasses, const PxVec3 *sprungMassCoordinates, const PxReal totalMass, const PxVehicleAxes::Enum gravityDirection, PxReal *sprungMasses)

Compute the sprung masses of the suspension springs given (i) the number of sprung masses, (ii) coordinates of the sprung masses in the rigid body frame, (iii) the center of mass offset of the rigid body, (iv) the total mass of the rigid body, and (v) the direction of gravity.

Parameters
  • nbSprungMasses[in] is the number of sprung masses of the vehicle. This value corresponds to the number of wheels on the vehicle.

  • sprungMassCoordinates[in] are the coordinates of the sprung masses in the rigid body frame. The array sprungMassCoordinates must be of length nbSprungMasses or greater.

  • totalMass[in] is the total mass of all the sprung masses.

  • gravityDirection[in] describes the direction of gravitational acceleration.

  • sprungMasses[out] are the masses to set in the associated suspension data with PxVehicleSuspensionData::mSprungMass. The sprungMasses array must be of length nbSprungMasses or greater. Each element in the sprungMasses array corresponds to the suspension located at the same array element in sprungMassCoordinates. The center of mass of the masses in sprungMasses with the coordinates in sprungMassCoordinates satisfy the specified centerOfMass.

Returns

True if the sprung masses were successfully computed, false if the sprung masses were not successfully computed.

inline PxVec3 PxVehicleComputeSuspensionDirection(const PxVehicleSuspensionParams &suspensionParams, const PxTransform &rigidBodyPose)

Compute suspension travel direction in the world frame.

Note

The suspension travel direction is used to perform queries against the road geometry.

Parameters
  • suspensionParams[in] is a description of the suspension frame.

  • rigidBodyPose[in] is the current pose of the vehicle’s rigid body.

Returns

The return value is the suspension travel direction in the world frame.

inline void PxVehicleComputeSuspensionRaycast(const PxVehicleFrame &frame, const PxVehicleWheelParams &wheelParams, const PxVehicleSuspensionParams &suspensionParams, const PxF32 steerAngle, const PxTransform &rigidBodyPose, PxVec3 &start, PxVec3 &dir, PxReal &dist)

Compute the start point, direction and length of a suspension scene raycast.

Note

start, dir and dist together describe a raycast that begins at the top of wheel at maximum compression and ends at the bottom of wheel at maximum droop.

Parameters
  • frame[in] is a description of the longitudinal, lateral and vertical axes.

  • wheelParams[in] describes the radius and halfwidth of the wheel.

  • suspensionParams[in] describes the suspension frame and the maximum suspension travel.

  • steerAngle[in] is the yaw angle of the wheel in radians.

  • rigidBodyPose[in] is the pose of the rigid body in the world frame.

  • start[out] is the starting point of the raycast in the world frame.

  • dir[out] is the direction of the raycast in the world frame.

  • dist[out] is the length of the raycast.

inline void PxVehicleComputeSuspensionSweep(const PxVehicleFrame &frame, const PxVehicleSuspensionParams &suspensionParams, const PxReal steerAngle, const PxTransform &rigidBodyPose, PxTransform &start, PxVec3 &dir, PxReal &dist)

Compute the start pose, direction and length of a suspension scene sweep.

Note

start, dir and dist together describe a sweep that begins with the wheel placed at maximum compression and ends at the maximum droop pose.

Parameters
  • frame[in] is a description of the longitudinal, lateral and vertical axes.

  • suspensionParams[in] describes the suspension frame and the maximum suspension travel.

  • steerAngle[in] is the yaw angle of the wheel in radians.

  • rigidBodyPose[in] is the pose of the rigid body in the world frame.

  • start[out] is the start pose of the sweep in the world frame.

  • dir[out] is the direction of the sweep in the world frame.

  • dist[out] is the length of the sweep.

inline PxVec3 PxVehicleComputeTranslation(const PxVehicleFrame &frame, const PxReal lng, const PxReal lat, const PxReal vrt)
inline PxQuat PxVehicleComputeWheelLocalOrientation(const PxVehicleFrame &frame, const PxVehicleSuspensionParams &suspensionParams, const PxReal camberAngle, const PxReal toeAngle, const PxReal steerAngle, const PxReal rotationAngle)

Compute the quaternion of a wheel in the rigid body frame.

Parameters
  • frame[in] describes the longitudinal and lateral axes of the vehicle.

  • suspensionParams[in] describes the suspension and wheel frames.

  • camberAngle[in] is the camber angle in radian sinduced by suspension compliance.

  • toeAngle[in] is the toe angle in radians induced by suspension compliance.

  • steerAngle[in] is the steer angle in radians applied to the wheel.

  • rotationAngle[in] is the angle around the wheel’s lateral axis.

Returns

The quaterion of the wheel in the rigid body frame.

inline PxTransform PxVehicleComputeWheelLocalPose(const PxVehicleFrame &frame, const PxVehicleSuspensionParams &suspensionParams, const PxVehicleSuspensionState &suspensionState, const PxVehicleSuspensionComplianceState &suspensionComplianceState, const PxReal steerAngle, const PxVehicleWheelRigidBody1dState &wheelState)

Compute the pose of the wheel in the rigid body frame.

Parameters
  • frame[in] describes the longitudinal and lateral axes of the vehicle.

  • suspensionParams[in] describes the suspension and wheel frames.

  • suspensionState[in] is the compression state of the suspenson.

  • suspensionComplianceState[in] is the camber and toe angles induced by suspension compliance.

  • steerAngle[in] is the steer angle in radians applied to the wheel.

  • wheelState[in] is angle around the wheel’s lateral axis.

Returns

The pose of the wheel in the rigid body frame.

inline PxTransform PxVehicleComputeWheelLocalPose(const PxVehicleFrame &frame, const PxVehicleSuspensionParams &suspensionParams, const PxVehicleSuspensionState &suspensionState, const PxReal camberAngle, const PxReal toeAngle, const PxReal steerAngle, const PxReal rotationAngle)

Compute the pose of the wheel in the rigid body frame.

Parameters
  • frame[in] describes the longitudinal and lateral axes of the vehicle.

  • suspensionParams[in] describes the suspension and wheel frames.

  • suspensionState[in] is the compression state of the suspenson.

  • camberAngle[in] is the camber angle in radian induced by suspension compliance.

  • toeAngle[in] is the toe angle in radians induced by suspension compliance.

  • steerAngle[in] is the steer angle in radians applied to the wheel.

  • rotationAngle[in] is the angle around the wheel’s lateral axis.

Returns

The pose of the wheel in the rigid body frame.

inline PxQuat PxVehicleComputeWheelOrientation(const PxVehicleFrame &frame, const PxVehicleSuspensionParams &suspensionParams, const PxReal camberAngle, const PxReal toeAngle, const PxReal steerAngle, const PxQuat &rigidBodyOrientation, const PxReal rotationAngle)

Compute the quaternion of a wheel in the world frame.

Parameters
  • frame[in] describes the longitudinal and lateral axes of the vehicle.

  • suspensionParams[in] describes the suspension and wheel frames.

  • camberAngle[in] is the camber angle in radian induced by suspension compliance.

  • toeAngle[in] is the toe angle in radians induced by suspension compliance.

  • steerAngle[in] is the steer angle in radians applied to the wheel.

  • rigidBodyOrientation[in] is the quaterion of the rigid body in the world frame.

  • rotationAngle[in] is the angle around the wheel’s lateral axis.

Returns

The quaterion of the wheel in the world frame.

inline PxTransform PxVehicleComputeWheelPose(const PxVehicleFrame &frame, const PxVehicleSuspensionParams &suspensionParams, const PxVehicleSuspensionState &suspensionState, const PxReal camberAngle, const PxReal toeAngle, const PxReal steerAngle, const PxTransform &rigidBodyPose, const PxReal rotationAngle)

Compute the pose of the wheel in the world frame.

Parameters
  • frame[in] describes the longitudinal and lateral axes of the vehicle.

  • suspensionParams[in] describes the suspension and wheel frames.

  • suspensionState[in] is the compression state of the suspenson.

  • camberAngle[in] is the camber angle in radian induced by suspension compliance.

  • toeAngle[in] is the toe angle in radians induced by suspension compliance.

  • steerAngle[in] is the steer angle in radians applied to the wheel.

  • rigidBodyPose[in] is the pose of the rigid body in the world frame.

  • rotationAngle[in] is the angle around the wheel’s lateral axis.

Returns

The pose of the wheel in the world frame.

inline PxTransform PxVehicleComputeWheelPose(const PxVehicleFrame &frame, const PxVehicleSuspensionParams &suspensionParams, const PxVehicleSuspensionState &suspensionState, const PxVehicleSuspensionComplianceState &suspensionComplianceState, const PxReal steerAngle, const PxTransform &rigidBodyPose, const PxVehicleWheelRigidBody1dState &wheelState)

Compute the pose of the wheel in the world frame.

Parameters
  • frame[in] describes the longitudinal and lateral axes of the vehicle.

  • suspensionParams[in] describes the suspension and wheel frames.

  • suspensionState[in] is the compression state of the suspenson.

  • suspensionComplianceState[in] is the camber and toe angles induced by suspension compliance.

  • steerAngle[in] is the steer angle in radians applied to the wheel.

  • rigidBodyPose[in] is the pose of the rigid body in the world frame.

  • wheelState[in] is angle around the wheel’s lateral axis.

Returns

The pose of the wheel in the world frame.

inline PxTransform PxVehicleComputeWheelPoseForSuspensionQuery(const PxVehicleFrame &frame, const PxVehicleSuspensionParams &suspensionParams, const PxReal steerAngle, const PxTransform &rigidBodyPose)

Compute the start pose of a suspension query.

Parameters
  • frame[in] is a description of the longitudinal, lateral and vertical axes.

  • suspensionParams[in] is a description of the suspension frame.

  • steerAngle[in] is the yaw angle of the wheel in radians.

  • rigidBodyPose[in] is the pose of the rigid body in the world frame.

void PxVehicleConstraintsCreate(const PxVehicleAxleDescription &axleDescription, PxPhysics &physics, PxRigidBody &physxActor, PxVehiclePhysXConstraints &vehicleConstraints)

Instantiate the PhysX custom constraints.

Custom constraints will resolve excess suspension compression and velocity constraints that serve as a replacement low speed tire model.

Parameters
  • axleDescription[in] describes the axles of the vehicle and the wheels on each axle.

  • physics[in] is a PxPhysics instance.

  • physxActor[in] is the vehicle’s PhysX representation as a PxRigidBody

  • vehicleConstraints[in] is a wrapper class that holds pointers to PhysX objects required to implement the custom constraint.

void PxVehicleConstraintsDestroy(PxVehiclePhysXConstraints &vehicleConstraints)

Destroy the PhysX custom constraints.

Parameters

vehicleConstraints[inout] describes the PhysX custom constraints to be released.

void PxVehicleConstraintsDirtyStateUpdate(PxVehiclePhysXConstraints &vehicleConstraints)

To ensure the constraints are processed by the PhysX scene they are marked as dirty prior to each simulate step.

Parameters

vehicleConstraints[in] is a wrapper class that holds pointers to PhysX objects required to implement the custom constraint.

void PxVehicleDifferentialStateUpdate(const PxVehicleAxleDescription &axleDescription, const PxVehicleFourWheelDriveDifferentialParams &diffParams, const PxVehicleArrayData<const PxVehicleWheelRigidBody1dState> &wheelStates, const PxReal dt, PxVehicleDifferentialState &diffState, PxVehicleWheelConstraintGroupState &wheelConstraintGroupState)

Compute the fraction of available torque to be delivered to each wheel and gather a list of all wheels connected to the differential.

Additionally, add wheel constraints for wheel pairs whose rotational speed ratio exceeds the corresponding differential bias.

Parameters
  • axleDescription[in] is a decription of the axles of the vehicle and the wheels on each axle.

  • diffParams[in] describe the division of available drive torque and the biases of the limited slip differential.

  • wheelStates[in] describes the rotational speeds of each wheel.

  • dt[in] is the simulation time that has passes since the last call to PxVehicleDifferentialStateUpdate()

  • diffState[out] contains the fraction of available drive torque to be delivered to each wheel.

  • wheelConstraintGroupState[out] describes the groups of wheels that have exceeded their corresponding differential biases.

void PxVehicleDifferentialStateUpdate(const PxVehicleAxleDescription &axleDescription, const PxVehicleMultiWheelDriveDifferentialParams &diffParams, PxVehicleDifferentialState &diffState)

Compute the fraction of available torque to be delivered to each wheel and gather a list of all wheels connected to the differential.

Parameters
  • axleDescription[in] is a decription of the axles of the vehicle and the wheels on each axle.

  • diffParams[in] specifies the operation of a differential that can be connected to any combination of wheels.

  • diffState[out] contains the fraction of available drive torque to be delivered to each wheel connected to the differential.

void PxVehicleDifferentialStateUpdate(const PxVehicleFourWheelDriveDifferentialLegacyParams &diffParams, const PxVehicleArrayData<const PxVehicleWheelRigidBody1dState> &wheelStates, PxVehicleDifferentialState &diffState)

Compute the fraction of available torque to be delivered to each wheel and gather a list of all wheels connected to the differential.

Deprecated:

Note

If the handbrake is on then torque is only delivered to the wheels specified as the front wheels of the differential.

Parameters
  • diffParams[in] specifies the operation of a differential that can be connected to up to four wheels.

  • wheelStates[in] describes the angular speed of each wheel

  • diffState[out] contains the fraction of available drive torque to be delivered to each wheel.

void PxVehicleDifferentialStateUpdate(const PxVehicleAxleDescription &axleDescription, const PxVehicleArrayData<const PxVehicleWheelParams> &wheelParams, const PxVehicleTankDriveDifferentialParams &diffParams, const PxReal thrustCommand0, PxReal thrustCommand1, PxVehicleDifferentialState &diffState, PxVehicleWheelConstraintGroupState &wheelConstraintGroupState)

Compute the fraction of available torque to be delivered to each wheel and gather a list of all wheels connected to the differential.

Parameters
  • axleDescription[in] is a decription of the axles of the vehicle and the wheels on each axle.

  • wheelParams[in] is an array that describes the wheel radius of each wheel.

  • diffParams[in] specifies the operation of a tank differential.

  • thrustCommand0[in] is the state of one of the two thrust controllers.

  • thrustCommand1[in] is the state of one of the two thrust controllers.

  • diffState[out] contains the fraction of available drive torque to be delivered to each wheel connected to the differential.

  • wheelConstraintGroupState[out] describes the groups of wheels connected by sharing a tank track.

void PxVehicleDirectDriveActuationStateUpdate(const PxReal brakeTorque, const PxReal driveTorque, PxVehicleWheelActuationState &actuationState)

Determine the actuation state of a wheel given the brake torque, handbrake torque and drive torque applied to it.

Parameters
  • brakeTorque[in] is the brake torque to be applied to the wheel.

  • driveTorque[in] is the drive torque to be applied to the wheel.

  • actuationState[out] contains a binary record of whether brake or drive torque is applied to the wheel.

void PxVehicleDirectDriveThrottleCommandResponseUpdate(const PxReal throttle, const PxVehicleDirectDriveTransmissionCommandState &transmissionCommands, const PxReal longitudinalSpeed, const PxU32 wheelId, const PxVehicleDirectDriveThrottleCommandResponseParams &throttleResponseParams, PxReal &throttleResponseState)

Compute the drive torque response to a throttle command.

Parameters
  • throttle[in] is the throttle command.

  • transmissionCommands[in] is the gearing command to apply to the direct drive tranmission.

  • longitudinalSpeed[in] is the longitudinal speed of the vehicle’s rigid body.

  • wheelId[in] specifies the wheel that is to have its throttle response computed.

  • throttleResponseParams[in] specifies the per wheel drive torque response to the throttle command as a nonlinear function of throttle command and longitudinal speed.

  • throttleResponseState[out] is the drive torque response to the input throttle command.

void PxVehicleDirectDriveUpdate(const PxVehicleWheelParams &wheelParams, const PxVehicleWheelActuationState &actuationState, const PxReal brakeTorque, const PxReal driveTorque, const PxVehicleTireForce &tireForce, const PxF32 dt, PxVehicleWheelRigidBody1dState &wheelRigidBody1dState)

Forward integrate the angular speed of a wheel given the brake and drive torque applied to it.

Parameters
  • wheelParams[in] specifies the moment of inertia of the wheel.

  • actuationState[in] is a binary record of whether brake and drive torque are to be applied to the wheel.

  • brakeTorque[in] is the brake torque to be applied to the wheel.

  • driveTorque[in] is the drive torque to be applied to the wheel.

  • tireForce[in] specifies the torque to apply to the wheel as a response to the longitudinal tire force.

  • dt[in] is the timestep of the forward integration.

  • wheelRigidBody1dState[out] describes the angular speed of the wheel.

inline PxReal PxVehicleEngineDampingRateCompute(const PxVehicleEngineParams &engineParams, const PxVehicleGearboxParams &gearboxParams, const PxVehicleGearboxState &gearboxState, const PxVehicleClutchCommandResponseState &clutchResponseState, const PxVehicleEngineDriveThrottleCommandResponseState &throttleResponseState)

Compute the damping rate of the engine.

Note

Engines typically have different damping rates with clutch engaged and disengaged.

Note

Engines typically have different damping rates at different throttle pedal values.

Note

In neutral gear the clutch is considered to be fully disengaged.

Parameters
  • engineParams[in] describes various damping rates of the engine in different operational states.

  • gearboxParams[in] holds the index of neutral gear.

  • gearboxState[in] describes the current gear.

  • clutchResponseState[in] is the response of the clutch to the clutch command.

  • throttleResponseState[in] is the response of the throttle to the throttle command.

void PxVehicleEngineDriveActuationStateUpdate(const PxVehicleAxleDescription &axleDescription, const PxVehicleGearboxParams &gearboxParams, const PxVehicleArrayData<const PxReal> &brakeResponseStates, const PxVehicleEngineDriveThrottleCommandResponseState &throttleResponseState, const PxVehicleGearboxState &gearboxState, const PxVehicleDifferentialState &diffState, const PxVehicleClutchCommandResponseState &clutchResponseState, PxVehicleArrayData<PxVehicleWheelActuationState> &actuationStates)

Determine the actuation state of all wheels on a vehicle.

Note

Drive torque is not applied to a wheel if a) the gearbox is in neutral b) the differential delivers no torque to the wheel c) no throttle is applied to the engine c) the clutch is fully disengaged.

Parameters
  • axleDescription[in] is a decription of the axles of the vehicle and the wheels on each axle.

  • gearboxParams[in] specifies the index of the neutral gear of the gearbox.

  • brakeResponseStates[in] specifies the response of each wheel to the input brake command.

  • throttleResponseState[in] specifies the response of the engine to the input throttle command.

  • gearboxState[in] specifies the current gear.

  • diffState[in] specifies the fraction of available drive torque to be delivered to each wheel.

  • clutchResponseState[in] specifies the response of the clutch to the input throttle command.

  • actuationStates[out] is an array of binary records determining whether brake and drive torque are to be applied to each wheel.

void PxVehicleEngineDriveThrottleCommandResponseLinearUpdate(const PxVehicleCommandState &commands, PxVehicleEngineDriveThrottleCommandResponseState &throttleResponse)

Propagate the input throttle command to the throttle response state.

Parameters
  • commands[in] specifies the state of the throttle pedal.

  • throttleResponse[out] specifies how the clutch responds to the input throttle command.

inline PxReal PxVehicleEngineDriveTorqueCompute(const PxVehicleEngineParams &engineParams, const PxVehicleEngineState &engineState, const PxVehicleEngineDriveThrottleCommandResponseState &throttleCommandResponseState)

Compute the drive torque to deliver to the engine.

Parameters
  • engineParams[in] describes the profile of maximum available torque across the full range of engine rotational speed.

  • engineState[in] describes the engine rotational speed.

  • throttleCommandResponseState[in] describes the engine’s response to input throttle command.

void PxVehicleEngineDrivetrainUpdate(const PxVehicleAxleDescription &axleDescription, const PxVehicleArrayData<const PxVehicleWheelParams> &wheelParams, const PxVehicleEngineParams &engineParams, const PxVehicleClutchParams &clutchParams, const PxVehicleGearboxParams &gearboxParams, const PxVehicleArrayData<const PxReal> &brakeResponseStates, const PxVehicleArrayData<const PxVehicleWheelActuationState> &actuationStates, const PxVehicleArrayData<const PxVehicleTireForce> &tireForces, const PxVehicleGearboxState &gearboxState, const PxVehicleEngineDriveThrottleCommandResponseState &throttleResponse, const PxVehicleClutchCommandResponseState &clutchResponse, const PxVehicleDifferentialState &diffState, const PxVehicleWheelConstraintGroupState *constraintGroupState, const PxReal dt, PxVehicleArrayData<PxVehicleWheelRigidBody1dState> &wheelRigidbody1dStates, PxVehicleEngineState &engineState, PxVehicleClutchSlipState &clutchState)

Forward integrate the angular speed of the vehicle’s wheels and engine, given the state of clutch, differential and gearbox.

Note

If constraintGroupState is NULL then it is assumed that there are no wheels subject to rotational speed constraints.

Parameters
  • axleDescription[in] is a decription of the axles of the vehicle and the wheels on each axle.

  • wheelParams[in] specifies the moment of inertia of each wheel.

  • engineParams[in] specifies the torque curve of the engine and its moment of inertia.

  • clutchParams[in] specifies the maximum clutch strength that happens when the clutch is fully engaged.

  • gearboxParams[in] specifies the gearing ratios of the gearbox.

  • brakeResponseStates[in] describes the per wheel response to the input brake command.

  • actuationStates[in] is a binary record of whether brake or drive torque is applied to each wheel.

  • tireForces[in] describes the torque to apply to each wheel as a response to the longitudinal tire force.

  • gearboxState[in] describes the current gear.

  • throttleResponse[in] describes the engine response to the input throttle pedal.

  • clutchResponse[in] describes the clutch response to the input clutch pedal.

  • diffState[in] describes the fraction of available drive torque to be delivered to each wheel.

  • constraintGroupState[in] describes groups of wheels with rotational speed constrained to the same value.

  • dt[in] is the time that has lapsed since the last call to PxVehicleEngineDrivetrainUpdate

  • wheelRigidbody1dStates[out] describes the angular speed of each wheel.

  • engineState[out] describes the angular speed of the engine.

  • clutchState[out] describes the clutch slip.

void PxVehicleGearCommandResponseUpdate(const PxU32 targetGearCommand, const PxVehicleGearboxParams &gearboxParams, PxVehicleGearboxState &gearboxState)

Propagate input gear commands to the gearbox state.

Note

Any ongoing gear change must complete before starting another.

Note

A gear change is considered as ongoing for as long as PxVehicleGearboxState::currentGear is different from PxVehicleGearboxState::targetGear.

Note

The gearbox remains in neutral for the duration of the gear change.

Note

A gear change begins if PxVehicleCommandState::targetGear is different from PxVehicleGearboxState::currentGear.

Parameters
  • targetGearCommand[in] specifies the target gear for the gearbox.

  • gearboxParams[in] specifies the number of gears and the index of neutral gear.

  • gearboxState[out] contains a record of the current and target gear.

inline PxReal PxVehicleGearRatioCompute(const PxVehicleGearboxParams &gearboxParams, const PxVehicleGearboxState &gearboxState)

Compute the gear ratio delivered by the gearbox in the current gear.

Note

The gear ratio is the product of the gear ratio of the current gear and the final gear ratio of the gearbox.

Parameters
  • gearboxParams[in] describes the gear ratio of each gear and the final ratio.

  • gearboxState[in] describes the current gear.

void PxVehicleGearboxUpdate(const PxVehicleGearboxParams &gearboxParams, const PxF32 dt, PxVehicleGearboxState &gearboxState)

Update the current gear of the gearbox.

If a gear change is ongoing then complete the gear change if a threshold time has passed since the beginning of the gear change.

Note

A gear change is considered as ongoing for as long as PxVehicleGearboxState::currentGear is different from PxVehicleGearboxState::targetGear.

Parameters
  • gearboxParams[in] describes the time required to complete a gear change.

  • dt[in] is the time that has lapsed since the last call to PxVehicleGearboxUpdate.

  • gearboxState[out] is the gearbox state to be updated.

inline bool PxVehicleIsWheelOnGround(const PxVehicleSuspensionState &suspState)

Check if the suspension could place the wheel on the ground or not.

Parameters

suspState[in] The state of the suspension to check.

Returns

True if the wheel connects to the ground, else false.

void PxVehicleLegacyDifferentialTorqueRatiosCompute(const PxVehicleFourWheelDriveDifferentialLegacyParams &diffParams, const PxVehicleArrayData<const PxVehicleWheelRigidBody1dState> &wheelOmegas, const PxU32 nbWheels, PxReal *diffTorqueRatios)

Compute the fraction of available torque that is delivered to each wheel through the differential.

Deprecated:

Note

Any wheel on an axle connected to the diff could receive a non-zero ratio, depending on the way the differential couples to the wheels.

Note

Any wheel not on an axle connected to the diff will have a zero value.

Note

The sum of all the ratios adds to 1.0.

Note

Slipping wheels driven by the differential will typically receive less torque than non-slipping wheels in the event that the differential has a limited slip configuration.

Parameters
  • diffParams[in] describes the wheels coupled to the differential and the operation of the torque split at the differential.

  • wheelOmegas[in] describes the rotational speeds of the wheels. Is expected to have nbWheels entries.

  • nbWheels[in] The number of wheels. Can be larger than the number of wheels connected to the differential.

  • diffTorqueRatios[out] describes the fraction of available torque delivered to each wheel. The buffer needs to be sized to be able to hold at least nbWheels entries.

void PxVehicleLegacyDifferentialWheelSpeedContributionsCompute(const PxVehicleFourWheelDriveDifferentialLegacyParams &diffParams, const PxU32 nbWheels, PxReal *diffAveWheelSpeedContributions)

Compute the contribution that each wheel makes to the averaged wheel speed at the clutch plate connected to the wheels driven by the differential.

Deprecated:

Note

Any wheel on an axle connected to the differential could have a non-zero value, depending on the way the differential couples to the wheels.

Note

Any wheel on an axle not connected to the differential will have a zero contribution to the averaged wheel speed.

Parameters
  • diffParams[in] describes the wheels coupled to the differential and the operation of the torque split at the differential.

  • nbWheels[in] The number of wheels. Can be larger than the number of wheels connected to the differential.

  • diffAveWheelSpeedContributions[out] describes the contribution that each wheel makes to the averaged wheel speed at the clutch. The buffer needs to be sized to be able to hold at least nbWheels entries.

inline PxReal PxVehicleLinearResponseCompute(const PxReal command, const PxU32 wheelId, const PxVehicleCommandResponseParams &responseParams)

Compute the linear response to a command.

Parameters
  • command[in] is a normalised command value.

  • wheelId[in] specifies the wheel that is to respond to the command.

  • responseParams[in] specifies the wheel responses for all wheels on a vehicle.

Returns

The linear response of the specified wheel to the command.

PxReal PxVehicleNonLinearResponseCompute(const PxReal command, const PxReal longitudinalSpeed, const PxU32 wheelId, const PxVehicleCommandResponseParams &responseParams)

Compute the non-linear response to a command.

Note

responseParams is used to compute an interpolated normalized response to the combination of command and longitudinalSpeed. The interpolated normalized response is then used in place of the command as input to PxVehicleComputeLinearResponse().

Parameters
  • command[in] is a normalised command value.

  • longitudinalSpeed[in] is the longitudional speed of the vehicle.

  • wheelId[in] specifies the wheel that is to respond to the command.

  • responseParams[in] specifies the wheel responses for all wheels on a vehicle.

void PxVehiclePhysXActorConfigure(const PxVehiclePhysXRigidActorParams &rigidActorParams, const PxTransform &rigidActorCmassLocalPose, PxRigidBody &rigidBody)

Configure an actor so that it is ready for vehicle simulation.

Parameters
  • rigidActorParams[in] describes the mass and moment of inertia of the rigid body.

  • rigidActorCmassLocalPose[in] specifies the mapping between actor and rigid body frame.

  • rigidBody[out] is the body to be prepared for simulation.

void PxVehiclePhysXActorCreate(const PxVehicleFrame &vehicleFrame, const PxVehiclePhysXRigidActorParams &rigidActorParams, const PxTransform &rigidActorCmassLocalPose, const PxVehiclePhysXRigidActorShapeParams &rigidActorShapeParams, const PxVehiclePhysXWheelParams &wheelParams, const PxVehiclePhysXWheelShapeParams &wheelShapeParams, PxPhysics &physics, const PxCookingParams &params, PxVehiclePhysXActor &vehiclePhysXActor)

Create a PxRigidDynamic instance, instantiate it with desired properties and populate it with PxShape instances.

Note

This is an alternative to PxVehiclePhysXArticulationLinkCreate.

Note

PxVehiclePhysXActorCreate primarily serves as an illustration of the instantiation of the PhysX class instances required to simulate a vehicle with a PxRigidDynamic.

Parameters
  • vehicleFrame[in] describes the frame of the vehicle.

  • rigidActorParams[in] describes the mass and moment of inertia of the rigid body.

  • rigidActorCmassLocalPose[in] specifies the mapping between actor and rigid body frame.

  • rigidActorShapeParams[in] describes the collision geometry associated with the rigid body.

  • wheelParams[in] describes the radius and half-width of the wheels.

  • wheelShapeParams[in] describes the PxMaterial and PxShapeFlags to apply to the wheel shapes.

  • physics[in] is a PxPhysics instance.

  • params[in] is a PxCookingParams instance

  • vehiclePhysXActor[in] is a record of the PxRigidDynamic and PxShape instances instantiated.

void PxVehiclePhysXActorDestroy(PxVehiclePhysXActor &vehiclePhysXActor)

Release the PxRigidDynamic, PxArticulationReducedCoordinate, PxArticulationLink and PxShape instances instantiated by PxVehiclePhysXActorCreate or PxVehiclePhysXArticulationLinkCreate.

Parameters

vehiclePhysXActor[in] is a description of the PhysX instances to be released.

void PxVehiclePhysXArticulationLinkCreate(const PxVehicleFrame &vehicleFrame, const PxVehiclePhysXRigidActorParams &rigidActorParams, const PxTransform &rigidActorCmassLocalPose, const PxVehiclePhysXRigidActorShapeParams &rigidActorShapeParams, const PxVehiclePhysXWheelParams &wheelParams, const PxVehiclePhysXWheelShapeParams &wheelShapeParams, PxPhysics &physics, const PxCookingParams &params, PxVehiclePhysXActor &vehiclePhysXActor)

Create a PxArticulationReducedCoordinate and a single PxArticulationLink, instantiate the PxArticulationLink with desired properties and populate it with PxShape instances.

Note

This is an alternative to PxVehiclePhysXActorCreate.

Note

PxVehiclePhysXArticulationLinkCreate primarily serves as an illustration of the instantiation of the PhysX class instances required to simulate a vehicle as part of an articulated ensemble.

Parameters
  • vehicleFrame[in] describes the frame of the vehicle.

  • rigidActorParams[in] describes the mass and moment of inertia of the rigid body.

  • rigidActorCmassLocalPose[in] specifies the mapping between actor and rigid body frame.

  • rigidActorShapeParams[in] describes the collision geometry associated with the rigid body.

  • wheelParams[in] describes the radius and half-width of the wheels.

  • wheelShapeParams[in] describes the PxMaterial and PxShapeFlags to apply to the wheel shapes.

  • physics[in] is a PxPhysics instance.

  • params[in] is a PxCookingParams instance

  • vehiclePhysXActor[in] is a record of the PxArticulationReducedCoordinate, PxArticulationLink and PxShape instances instantiated.

void PxVehiclePhysXConstraintStatesUpdate(const PxVehicleSuspensionParams &suspensionParams, const PxVehiclePhysXSuspensionLimitConstraintParams &suspensionLimitParams, const PxVehicleSuspensionState &suspensionState, const PxVehicleSuspensionComplianceState &suspensionComplianceState, const PxVec3 &groundPlaneNormal, const PxReal tireStickyDampingLong, const PxReal tireStickyDampingLat, const PxVehicleTireDirectionState &tireDirectionState, const PxVehicleTireStickyState &tireStickyState, const PxVehicleRigidBodyState &rigidBodyState, PxVehiclePhysXConstraintState &constraintState)

Read constraint data from the vehicle’s internal state for a single wheel and write it to a structure that will be read by the associated PxScene and used to impose the constraints during the next PxScene::simulate() step.

Note

Constraints include suspension constraints to account for suspension travel limit and sticky tire constraints that bring the vehicle to rest at low longitudinal and lateral speed.

Parameters
  • suspensionParams[in] describes the suspension frame.

  • suspensionLimitParams[in] describes the restitution value applied to any constraint triggered by the suspension travel limit.

  • suspensionState[in] describes the excess suspension compression beyond the suspension travel limit that will be resolved with a constraint.

  • suspensionComplianceState[in] describes the effect of suspension compliance on the effective application point of the suspension force.

  • groundPlaneNormal[in] The normal direction of the ground plane the wheel is driving on. A normalized vector is expected.

  • tireStickyDampingLong[in] The damping coefficient to use in the constraint to approach a zero target velocity along the longitudinal tire axis.

  • tireStickyDampingLat[in] Same concept as tireStickyDampingLong but for the lateral tire axis.

  • tireDirectionState[in] describes the longitudinal and lateral directions of the tire in the world frame.

  • tireStickyState[in] describes the low speed state of the tire in the longitudinal and lateral directions.

  • rigidBodyState[in] describes the pose of the rigid body.

  • constraintState[out] is the data structure that will be read by the associated PxScene in the next call to PxScene::simulate().

void PxVehiclePhysXRoadGeometryQueryUpdate(const PxVehicleWheelParams &wheelParams, const PxVehicleSuspensionParams &suspParams, const PxVehiclePhysXRoadGeometryQueryType::Enum queryType, PxQueryFilterCallback *filterCallback, const PxQueryFilterData &filterData, const PxVehiclePhysXMaterialFrictionParams &materialFrictionParams, const PxReal wheelYawAngle, const PxVehicleRigidBodyState &rigidBodyState, const PxScene &scene, const PxConvexMesh *unitCylinderSweepMesh, const PxVehicleFrame &frame, PxVehicleRoadGeometryState &roadGeomState, PxVehiclePhysXRoadGeometryQueryState *physxRoadGeometryState)

Compute the plane of the road geometry under a wheel and the tire friction of the contact.

Note

PxVehicleRoadGeometryState::hitState will have value false in the event that the there is no reachable road geometry under the wheel and true if there is reachable road geometry under the wheel. Road geometry is considered reachable if the suspension can elongate from its reference pose far enough to place wheel on the ground.

Parameters
  • wheelParams[in] describes the radius and halfwidth of the wheel.

  • suspParams[in] describes the frame of the suspension and wheel and the maximum suspension travel.

  • queryType[in] describes what type of PhysX scene query to use (see PxVehiclePhysXRoadGeometryQueryType). If PxVehiclePhysXRoadGeometryQueryType::eNONE is used, no work will be done.

  • filterCallback[in] describes the filter callback to use for the PhysX scene query. NULL is a valid input.

  • filterData[in] describes the filter data to use for the PhysX scene query.

  • materialFrictionParams[in] describes a mapping between PxMaterial and friction in order to compute a tire friction value.

  • wheelYawAngle[in] is the yaw angle (in radians) of the wheel.

  • rigidBodyState[in] describes the pose of the rigid body.

  • scene[in] is the PhysX scene that will be queried by the scene query.

  • unitCylinderSweepMesh[in] is a convex cylindrical mesh of unit radius and half-width to be used in the event that a sweep query is to be used.

  • frame[in] describes the lateral, longitudinal and vertical axes and is used to scale unitCylinderSweepMesh by the wheel’s radius and half-width.

  • roadGeomState[out] contains the plane and friction of the road geometry under the wheel.

  • physxRoadGeometryState[out] Optional buffer to store additional information about the query (like actor/shape that got hit etc.). Set to NULL if not needed.

void PxVehiclePhysxActorKeepAwakeCheck(const PxVehicleAxleDescription &axleDescription, const PxVehicleArrayData<const PxVehicleWheelParams> &wheelParams, const PxVehicleArrayData<const PxVehicleWheelRigidBody1dState> &wheelRigidBody1dStates, const PxReal wakeCounterThreshold, const PxReal wakeCounterResetValue, const PxVehicleGearboxState *gearState, const PxReal *throttle, PxRigidBody &physxActor)

Check if the physx actor has to be kept awake.

Certain criteria should keep the vehicle physx actor awake, for example, if the (mass normalized) rotational kinetic energy of the wheels is above a certain threshold or if a gear change is pending or if throttle is applied. This method will reset the wake counter of the physx actor to a specified value, if any of the mentioned criteria are met.

Note

The physx actor’s sleep threshold will be used as threshold to test against for the energy criteria.

Parameters
  • axleDescription[in] identifies the wheels on each axle.

  • wheelParams[in] describes the radius, mass etc. of the wheels.

  • wheelRigidBody1dStates[in] describes the angular speed of the wheels.

  • wakeCounterThreshold[in] Once the wake counter of the physx actor falls below this threshold, the method will start testing if the wake counter needs to be reset.

  • wakeCounterResetValue[in] The value to set the physx actor wake counter to, if any of the criteria to do so are met.

  • gearState[in] The gear state. Can be set to NULL if the vehicle does not have gears or if the mentioned behavior is not desired.

  • throttle[in] The throttle command state (see PxVehicleCommandState). Can be set to NULL if the vehicle is not controlled through PxVehicleCommandState or if the mentioned behavior is not desired.

  • physxActor[in] is the PxRigidBody instance associated with the vehicle.

bool PxVehiclePhysxActorSleepCheck(const PxVehicleAxleDescription &axleDescription, const PxRigidBody &physxActor, const PxVehicleEngineParams *engineParams, PxVehicleRigidBodyState &rigidBodyState, PxVehiclePhysXConstraints &physxConstraints, PxVehicleArrayData<PxVehicleWheelRigidBody1dState> &wheelRigidBody1dStates, PxVehicleEngineState *engineState)

Check if the physx actor is sleeping and clear certain vehicle states if it is.

Parameters
  • axleDescription[in] identifies the wheels on each axle.

  • physxActor[in] is the PxRigidBody instance associated with the vehicle.

  • engineParams[in] The engine parameters. Can be set to NULL if the vehicle does not have an engine. Must be specified, if engineState is specified.

  • rigidBodyState[inout] is the state of the rigid body used by the Vehicle SDK.

  • physxConstraints[inout] The state of the suspension limit and low speed tire constraints. If the vehicle actor is sleeping and constraints are active, they will be deactivated and marked as dirty.

  • wheelRigidBody1dStates[inout] describes the angular speed of the wheels.

  • engineState[out] The engine state. Can be set to NULL if the vehicle does not have an engine. If specified, then engineParams has to be specifed too. The engine rotation speed will get set to the idle rotation speed if the actor is sleeping.

Returns

True if the actor was sleeping, else false.

void PxVehiclePhysxActorWakeup(const PxVehicleCommandState &commands, const PxVehicleEngineDriveTransmissionCommandState *transmissionCommands, const PxVehicleGearboxParams *gearParams, const PxVehicleGearboxState *gearState, PxRigidBody &physxActor, PxVehiclePhysXSteerState &physxSteerState)

Wake up the physx actor if the actor is asleep and the commands signal an intent to change the state of the vehicle.

Note

If the steering has changed, the actor will be woken up.

Note

On exit from PxVehiclePhysxActorWakeup, physxSteerState.previousSteerCommand is assigned to the value of commands.steer so that the steer state may be propagated to the subsequent call to PxVehiclePhysxActorWakeup().

Note

If physxSteerState.previousSteerCommand has value PX_VEHICLE_UNSPECIFIED_STEER_STATE, the steering state is treated as though it has not changed.

Parameters
  • commands[in] are the brake, throttle and steer values that will drive the vehicle.

  • transmissionCommands[in] are the target gear and clutch values that will control the transmission. If the target gear is different from the current gearbox target gear, then the physx actor will get woken up. Can be set to NULL if the vehicle does not have a gearbox or if this is not a desired behavior. If specified, then gearParams and gearState has to be specifed too.

  • gearParams[in] The gearbox parameters. Can be set to NULL if the vehicle does not have a gearbox and transmissionCommands is NULL.

  • gearState[in] The state of the gearbox. Can be set to NULL if the vehicle does not have a gearbox and transmissionCommands is NULL.

  • physxActor[in] is the PxRigidBody instance associated with the vehicle.

  • physxSteerState[inout] and commands are compared to determine if the steering state has changed since the last call to PxVehiclePhysxActorWakeup().

void PxVehiclePvdAntiRollsRegister(const PxVehicleSizedArrayData<const PxVehicleAntiRollForceParams> &antiRollForceParams, const PxVehicleAntiRollTorque *antiRollTorque, const PxVehiclePvdAttributeHandles &attributeHandles, PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Register object instances in omnipvd that will be used to reflect the antiroll bars of a vehicle instance.

Note

If antiRollForceParams is empty, the corresponding data will not be reflected in omnipvd.

Note

If antiRollTorque is NULL, the corresponding data will not be reflected in omnipvd.

Parameters
  • antiRollForceParams[in] is an array of antiroll parameters.

  • antiRollTorque[in] describes the instantaneous accumulated torque from all antiroll bas.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdAntiRollsWrite(const PxVehicleSizedArrayData<const PxVehicleAntiRollForceParams> &antiRollForceParams, const PxVehicleAntiRollTorque *antiRollTorque, const PxVehiclePvdAttributeHandles &attributeHandles, const PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Write antiroll data to omnipvd.

Note

If antiRollForceParams is empty but the corresponding argument was not empty, the corresponding data will not be updated in omnipvd.

Note

If antiRollTorque is NULL but the corresponding argument was not NULL, the corresponding data will not be updated in omnipvd.

Parameters
  • antiRollForceParams[in] is an array of antiroll parameters.

  • antiRollTorque[in] describes the instantaneous accumulated torque from all antiroll bas.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

PxVehiclePvdAttributeHandles *PxVehiclePvdAttributesCreate(PxAllocatorCallback &allocator, OmniPvdWriter &omniWriter)

Create the attribute handles necessary to reflect vehicles in omnipvd.

Parameters
  • allocator[in] is used to allocate the memory used to store the attribute handles.

  • omniWriter[in] is used to register the attribute handles with omnipvd.

void PxVehiclePvdAttributesRelease(PxAllocatorCallback &allocator, PxVehiclePvdAttributeHandles &attributeHandles)

Destory the attribute handles created by PxVehiclePvdAttributesCreate().

Parameters
void PxVehiclePvdCommandResponseRegister(const PxVehicleSizedArrayData<const PxVehicleBrakeCommandResponseParams> &brakeResponseParams, const PxVehicleSteerCommandResponseParams *steerResponseParams, const PxVehicleAckermannParams *ackermannParams, const PxVehicleArrayData<PxReal> &brakeResponseStates, const PxVehicleArrayData<PxReal> &steerResponseStates, const PxVehiclePvdAttributeHandles &attributeHandles, PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Register object instances in omnipvd that will be used to reflect the brake and steer command response parameters of a vehicle instance.

Note

If brakeResponseParams is empty, omnipvd will not reflect any brake command response parameters.

Note

If steerResponseParams is NULL, omnipvd will not reflect the steer command response parameters.

Note

If ackermannParams is NULL, omnipvd will not reflect any Ackermann steer correction parameters.

Note

If brakeResponseStates is empty, omnipvd will not reflect any brake command response state.

Note

If steerResponseStates is empty, omnipvd will not reflect any steer command response state.

Parameters
  • brakeResponseParams[in] is an array of brake command response parameters.

  • steerResponseParams[in] describes the steer command response parameters.

  • ackermannParams[in] defines the Ackermann steer correction.

  • brakeResponseStates[in] is an array of brake responses torqyes,

  • steerResponseStates[in] is an array of steer response angles.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdCommandResponseWrite(const PxVehicleAxleDescription &axleDesc, const PxVehicleSizedArrayData<const PxVehicleBrakeCommandResponseParams> &brakeResponseParams, const PxVehicleSteerCommandResponseParams *steerResponseParams, const PxVehicleAckermannParams *ackermannParams, const PxVehicleArrayData<PxReal> &brakeResponseStates, const PxVehicleArrayData<PxReal> &steerResponseStates, const PxVehiclePvdAttributeHandles &attributeHandles, const PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Write brake and steer command response parameters to omnipvd.

Note

If brakeResponseParams is empty but a non-empty array was used in PxVehiclePvdCommandResponseRegister(), the brake command response parameters will not be updated in omnipvd.

Note

If steerResponseParams is non-NULL but a NULL value was used in PxVehiclePvdCommandResponseRegister(), the steer command parameters will not be updated in omnipvd.

Note

If ackermannParams is non-NULL but a NULL value was used in PxVehiclePvdCommandResponseRegister(), the Ackermann steer correction parameters will not be updated in omnipvd.

Note

If brakeResponseStates is empty but a non-empty array was used in PxVehiclePvdCommandResponseRegister(), the brake response states will not be updated in omnipvd.

Note

If steerResponseStates is empty but a non-empty array was used in PxVehiclePvdCommandResponseRegister(), the steer response states will not be updated in omnipvd.

Note

omniWriter must be the same instance used in PxVehiclePvdCommandResponseRegister().

Parameters
  • axleDesc[in] is a description of the wheels and axles of a vehicle.

  • brakeResponseParams[in] is an array of brake command response parameters.

  • steerResponseParams[in] describes the steer command response parameters.

  • ackermannParams[in] defines the Ackermann steer correction.

  • brakeResponseStates[in] is an array of brake response torques.

  • steerResponseStates[in] is an array of steer response angles.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdDirectDrivetrainRegister(const PxVehicleCommandState *commandState, const PxVehicleDirectDriveTransmissionCommandState *transmissionCommandState, const PxVehicleDirectDriveThrottleCommandResponseParams *directDriveThrottleResponseParams, const PxVehicleArrayData<PxReal> &directDriveThrottleResponseState, const PxVehiclePvdAttributeHandles &attributeHandles, PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Register object instances in omnipvd that will be used to reflect the direct drivetrain of a vehicle instance.

Note

If commandState is NULL, the corresponding data will not be reflected in omnipvd.

Note

If transmissionCommandState is NULL, the corresponding data will not be reflected in omnipvd.

Note

If directDriveThrottleResponseParams is NULL, the corresponding data will not be reflected in omnipvd.

Note

If directDriveThrottleResponseState is empty, the corresponding data will not be reflected in omnipvd.

Parameters
  • commandState[in] describes the control values applied to the vehicle.

  • transmissionCommandState[in] describes the state of the direct drive transmission.

  • directDriveThrottleResponseParams[in] describes the vehicle’s torque response to a throttle command.

  • directDriveThrottleResponseState[in] is the instantaneous torque response of each wheel to a throttle command.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdDirectDrivetrainWrite(const PxVehicleAxleDescription &axleDesc, const PxVehicleCommandState *commandState, const PxVehicleDirectDriveTransmissionCommandState *transmissionCommandState, const PxVehicleDirectDriveThrottleCommandResponseParams *directDriveThrottleResponseParams, const PxVehicleArrayData<PxReal> &directDriveThrottleResponseState, const PxVehiclePvdAttributeHandles &attributeHandles, const PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Write direct drivetrain data to omnipvd.

Note

If commandState is NULL but the corresponding entry in PxVehiclePvdDirectDrivetrainRegister() was not NULL, the corresponding data will not be updated in omnipvd.

Note

If transmissionCommandState is NULL but the corresponding entry in PxVehiclePvdDirectDrivetrainRegister() was not NULL, the corresponding data will not be updated in omnipvd.

Note

If directDriveThrottleResponseParams is NULL but the corresponding entry in PxVehiclePvdDirectDrivetrainRegister() was not NULL, the corresponding data will not be updated in omnipvd.

Note

If directDriveThrottleResponseState is empty but the corresponding entry in PxVehiclePvdDirectDrivetrainRegister() was not empty, the corresponding data will not be updated in omnipvd.

Parameters
  • axleDesc[in] is a description of the wheels and axles of a vehicle.

  • commandState[in] describes the control values applied to the vehicle.

  • transmissionCommandState[in] describes the state of the direct drive transmission.

  • directDriveThrottleResponseParams[in] describes the vehicle’s torque response to a throttle command.

  • directDriveThrottleResponseState[in] is the instantaneous torque response of each wheel to a throttle command.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdEngineDrivetrainRegister(const PxVehicleCommandState *commandState, const PxVehicleEngineDriveTransmissionCommandState *engineDriveTransmissionCommandState, const PxVehicleTankDriveTransmissionCommandState *tankDriveTransmissionCommandState, const PxVehicleClutchCommandResponseParams *clutchResponseParams, const PxVehicleClutchParams *clutchParams, const PxVehicleEngineParams *engineParams, const PxVehicleGearboxParams *gearboxParams, const PxVehicleAutoboxParams *autoboxParams, const PxVehicleMultiWheelDriveDifferentialParams *multiWheelDiffParams, const PxVehicleFourWheelDriveDifferentialParams *fourWheelDiffPrams, const PxVehicleTankDriveDifferentialParams *tankDiffParams, const PxVehicleClutchCommandResponseState *clutchResponseState, const PxVehicleEngineDriveThrottleCommandResponseState *throttleResponseState, const PxVehicleEngineState *engineState, const PxVehicleGearboxState *gearboxState, const PxVehicleAutoboxState *autoboxState, const PxVehicleDifferentialState *diffState, const PxVehicleClutchSlipState *clutchSlipState, const PxVehiclePvdAttributeHandles &attributeHandles, PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Register object instances in omnipvd that will be used to reflect the engine drivetrain of a vehicle instance.

Note

If any pointer is NULL, the corresponding data will not be reflected in omnipvd.

Note

At most one of engineDriveTransmissionCommandState and tankDriveTransmissionCommandState is expected to be non-NULL.

Note

At most one of multiWheelDiffParams, fourWheelDiffParams and tankDiffParams is expected to be non-NULL.

Parameters
  • commandState[in] describes the control values applied to the vehicle.

  • engineDriveTransmissionCommandState[in] describes the state of the engine drive transmission.

  • tankDriveTransmissionCommandState[in] describes the state of the tank drive transmission.

  • clutchResponseParams[in] describes the vehicle’s response to a clutch command.

  • clutchParams[in] describes the vehicle’s clutch.

  • engineParams[in] describes the engine.

  • gearboxParams[in] describes the gearbox.

  • autoboxParams[in] describes the automatic gearbox.

  • multiWheelDiffParams[in] describes a multiwheel differential without limited slip compensation.

  • fourWheelDiffPrams[in] describes a differential that delivers torque to four drive wheels with limited slip compensation.

  • tankDiffParams[in] describes the operation of the tank differential.

  • clutchResponseState[in] is the instantaneous reponse of the clutch to a clutch command.

  • throttleResponseState[in] is the instantaneous response to a throttle command.

  • engineState[in] is the instantaneous state of the engine.

  • gearboxState[in] is the instantaneous state of the gearbox.

  • autoboxState[in] is the instantaneous state of the automatic gearbox.

  • diffState[in] is the instantaneous state of the differential.

  • clutchSlipState[in] is the instantaneous slip recorded at the clutch.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdEngineDrivetrainWrite(const PxVehicleCommandState *commandState, const PxVehicleEngineDriveTransmissionCommandState *engineDriveTransmissionCommandState, const PxVehicleTankDriveTransmissionCommandState *tankDriveTransmissionCommandState, const PxVehicleClutchCommandResponseParams *clutchResponseParams, const PxVehicleClutchParams *clutchParams, const PxVehicleEngineParams *engineParams, const PxVehicleGearboxParams *gearboxParams, const PxVehicleAutoboxParams *autoboxParams, const PxVehicleMultiWheelDriveDifferentialParams *multiWheelDiffParams, const PxVehicleFourWheelDriveDifferentialParams *fourWheelDiffParams, const PxVehicleTankDriveDifferentialParams *tankDiffParams, const PxVehicleClutchCommandResponseState *clutchResponseState, const PxVehicleEngineDriveThrottleCommandResponseState *throttleResponseState, const PxVehicleEngineState *engineState, const PxVehicleGearboxState *gearboxState, const PxVehicleAutoboxState *autoboxState, const PxVehicleDifferentialState *diffState, const PxVehicleClutchSlipState *clutchSlipState, const PxVehiclePvdAttributeHandles &attributeHandles, const PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Write engine drivetrain data of a vehicle instance to omnipvd.

Note

If any pointer is NULL and the corresponding argument in PxVehiclePvdEngineDrivetrainRegister() was not NULL, the corresponding data will not be reflected in omnipvd.

Note

At most one of engineDriveTransmissionCommandState and tankDriveTransmissionCommandState is expected to be non-NULL.

Note

At most one of multiWheelDiffParams, fourWheelDiffParams and tankDiffParams is expected to be non-NULL.

Parameters
  • commandState[in] describes the control values applied to the vehicle.

  • engineDriveTransmissionCommandState[in] describes the state of the engine drive transmission.

  • tankDriveTransmissionCommandState[in] describes the state of the tank drive transmission.

  • clutchResponseParams[in] describes the vehicle’s response to a clutch command.

  • clutchParams[in] describes the vehicle’s clutch.

  • engineParams[in] describes the engine.

  • gearboxParams[in] describes the gearbox.

  • autoboxParams[in] describes the automatic gearbox.

  • multiWheelDiffParams[in] describes a multiwheel differential without limited slip compensation.

  • fourWheelDiffParams[in] describes a differential that delivers torque to four drive wheels with limited slip compensation.

  • tankDiffParams[in] describes the operation of the tank differential.

  • clutchResponseState[in] is the instantaneous reponse of the clutch to a clutch command.

  • throttleResponseState[in] is the instantaneous response to a throttle command.

  • engineState[in] is the instantaneous state of the engine.

  • gearboxState[in] is the instantaneous state of the gearbox.

  • autoboxState[in] is the instantaneous state of the automatic gearbox.

  • diffState[in] is the instantaneous state of the differential.

  • clutchSlipState[in] is the instantaneous slip recorded at the clutch.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

PxVehiclePvdObjectHandles *PxVehiclePvdObjectCreate(const PxU32 nbWheels, const PxU32 nbAntirolls, const PxU32 maxNbPhysxMaterialFrictions, const PxU64 contextHandle, PxAllocatorCallback &allocator)

Create omnipvd objects that will be used to reflect an individual veicle in omnipvd.

Parameters
  • nbWheels[in] must be greater than or equal to the number of wheels on the vehicle.

  • nbAntirolls[in] must be greater than or equal to the number of antiroll bars on the vehicle.

  • maxNbPhysxMaterialFrictions[in] must be greater than or equal to the number of PxPhysXMaterialFriction instances associated with any wheel of the vehicle.

  • contextHandle[in] is typically used to associated vehicles with a particular scene or group.

  • allocator[in] is used to allocate the memory used to store handles to the created omnipvd objects.

void PxVehiclePvdObjectRelease(OmniPvdWriter &omniWriter, PxAllocatorCallback &allocator, PxVehiclePvdObjectHandles &objectHandles)

Destroy the PxVehiclePvdObjectHandles instance created by PxVehiclePvdObjectCreate().

Parameters
void PxVehiclePvdPhysXRigidActorRegister(const PxVehiclePhysXActor *physxActor, const PxVehiclePvdAttributeHandles &attributeHandles, PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Register the PxRigidActor instance that represents the vehicle’s rigid body in a PhysX scene.

Note

If physxActor is NULL, the corresponding data will not be reflected in omnipvd.

Parameters
  • physxActor[in] describes the PxRigidActor instance that is used to represent the vehicle’s rigid body in PhysX.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdPhysXRigidActorWrite(const PxVehiclePhysXActor *physxActor, const PxVehiclePvdAttributeHandles &attributeHandles, const PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Write the PxRigidActor instance to omnipvd.

Note

If physxActor is NULL and the corresponding argument in PxVehiclePvdPhysXRigidActorRegister was not NULL, the corresponding data will not be updated in omnipvd.

Parameters
  • physxActor[in] describes the PxRigidActor instance that is used to represent the vehicle’s rigid body in PhysX.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdPhysXSteerStateRegister(const PxVehiclePhysXSteerState *physxSteerState, const PxVehiclePvdAttributeHandles &attributeHandles, PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Register the PhysX related steer state class.

Note

If physxSteerState is NULL, the corresponding data will not be reflected in omnipvd.

Parameters
  • physxSteerState[in] describes the PxVehiclePhysXSteerState instance that holds steer related state information.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdPhysXSteerStateWrite(const PxVehiclePhysXSteerState *physxSteerState, const PxVehiclePvdAttributeHandles &attributeHandles, const PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Write the PxVehiclePhysXSteerState instance to omnipvd.

Note

If physxSteerState is NULL and the corresponding argument in PxVehiclePvdPhysXSteerStateRegister was not NULL, the corresponding data will not be updated in omnipvd.

Parameters
  • physxSteerState[in] describes the PxVehiclePhysXSteerState instance that holds steer related state information.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdPhysXWheelAttachmentRegister(const PxVehicleAxleDescription &axleDesc, const PxVehicleArrayData<const PxVehiclePhysXSuspensionLimitConstraintParams> &physxSuspLimitConstraintParams, const PxVehicleArrayData<const PxVehiclePhysXMaterialFrictionParams> &physxMaterialFrictionParams, const PxVehiclePhysXActor *physxActor, const PxVehiclePhysXRoadGeometryQueryParams *physxRoadGeometryQueryParams, const PxVehicleArrayData<const PxVehiclePhysXRoadGeometryQueryState> &physxRoadGeomState, const PxVehicleArrayData<const PxVehiclePhysXConstraintState> &physxConstraintStates, const PxVehiclePvdAttributeHandles &attributeHandles, PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Register per wheel attachment data that involves the vehicle’s integration with a PhysX scene.

Note

If any array is empty, the corresponding data will not be reflected in omnipvd.

Note

If physxActor is NULL, the corresponding data will not be reflected in omnipvd.

Note

If physxRoadGeometryQueryParams is NULL, the corresponding data will not be reflected in omnipvd.

Note

Each array must either be empty or contain an entry for each wheel present in axleDesc.

Parameters
  • axleDesc[in] is a description of the wheels and axles of a vehicle.

  • physxSuspLimitConstraintParams[in] describes the method used by PhysX to enforce suspension travel limits.

  • physxMaterialFrictionParams[in] describes the friction response of each wheel to a set of PxMaterial instances.

  • physxActor[in] describes the PxRigidActor and PxShape instances that are used to represent the vehicle’s rigid body and wheel shapes in PhysX.

  • physxRoadGeometryQueryParams[in] describes the physx scene query method used to place each wheel on the ground.

  • physxRoadGeomState[in] is an array of per wheel physx scene query results.

  • physxConstraintStates[in] is an array of constraints states used by PhysX to enforce sticky tire and suspension travel limit constraints.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdPhysXWheelAttachmentWrite(const PxVehicleAxleDescription &axleDesc, const PxVehicleArrayData<const PxVehiclePhysXSuspensionLimitConstraintParams> &physxSuspLimitConstraintParams, const PxVehicleArrayData<const PxVehiclePhysXMaterialFrictionParams> &physxMaterialFrictionParams, const PxVehiclePhysXActor *physxActor, const PxVehiclePhysXRoadGeometryQueryParams *physxRoadGeometryQueryParams, const PxVehicleArrayData<const PxVehiclePhysXRoadGeometryQueryState> &physxRoadGeomState, const PxVehicleArrayData<const PxVehiclePhysXConstraintState> &physxConstraintStates, const PxVehiclePvdAttributeHandles &attributeHandles, const PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Write to omnipvd the per wheel attachment data that involves the vehicle’s integration with a PhysX scene.

Note

If any array is empty but the corresponding array in PxVehiclePvdPhysXWheelAttachmentRegister() was not empty, the corresponding data will not be updated in omnipvd.

Note

If physxActor is NULL but the corresponding argument in PxVehiclePvdPhysXWheelAttachmentRegister was not NULL, the corresponding data will not be reflected in omnipvd.

Note

If physxRoadGeometryQueryParams is NULL but the corresponding argument in PxVehiclePvdPhysXWheelAttachmentRegister was not NULL, the corresponding data will not be reflected in omnipvd.

Note

Each array must either be empty or contain an entry for each wheel present in axleDesc.

Parameters
  • axleDesc[in] is a description of the wheels and axles of a vehicle.

  • physxSuspLimitConstraintParams[in] describes the method used by PhysX to enforce suspension travel limits.

  • physxMaterialFrictionParams[in] describes the friction response of each wheel to a set of PxMaterial instances.

  • physxActor[in] describes the PxShape instances that are used to represent the vehicle’s wheel shapes in PhysX.

  • physxRoadGeometryQueryParams[in] describes the physx scene query method used to place each wheel on the ground.

  • physxRoadGeomState[in] is an array of per wheel physx scene query results.

  • physxConstraintStates[in] is an array of constraints states used by PhysX to enforce sticky tire and suspension travel limit constraints.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdRigidBodyRegister(const PxVehicleRigidBodyParams *rbodyParams, const PxVehicleRigidBodyState *rbodyState, const PxVehiclePvdAttributeHandles &attributeHandles, PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Create object instances in omnipvd that will be used to reflect the parameters and state of the rigid body of a vehicle instance.

Handles to the created object instances will be stored in a PxVehiclePvdObjectHandles instance.

Note

If rbodyParams is NULL, omnipvd will not reflect rigid body parameters.

Note

If rbodyState is NULL, omnipvd will not reflect rigid body state.

Note

PxVehiclePvdRigidBodyRegister should be called once for each vehicle instance.

Parameters
  • rbodyParams[in] describes the parameters of the vehicle’s rigid body.

  • rbodyState[in] describes the state of the vehicle’s rigid body.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdRigidBodyWrite(const PxVehicleRigidBodyParams *rbodyParams, const PxVehicleRigidBodyState *rbodyState, const PxVehiclePvdAttributeHandles &attributeHandles, const PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Write the parameters and state of the rigid body of a vehicle instance to omnipvd.

Note

If rbodyParams is NULL but a non-NULL value was used in PxVehiclePvdRigidBodyRegister(), the rigid body parameters will not be updated in omnipvd.

Note

If rbodyState is NULL but a non-NULL value was used in PxVehiclePvdRigidBodyRegister(), the rigid body state will not be updated in omnipvd.

Note

omniWriter must be the same instance used in PxVehiclePvdRigidBodyRegister().

Parameters
  • rbodyParams[in] describes the parameters of the vehicle’s rigid body.

  • rbodyState[in] describes the state of the vehicle’s rigid body.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdSuspensionStateCalculationParamsRegister(const PxVehicleSuspensionStateCalculationParams *suspStateCalcParams, const PxVehiclePvdAttributeHandles &attributeHandles, PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Register object instances in omnipvd that will be used to reflect the suspension state calculation parameters of a vehicle instance.

Note

If suspStateCalcParams is NULL, omnipvd will not reflect the suspension state calculation parameters.

Parameters
  • suspStateCalcParams[in] describes parameters used to calculate suspension state.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdSuspensionStateCalculationParamsWrite(const PxVehicleSuspensionStateCalculationParams *suspStateCalcParams, const PxVehiclePvdAttributeHandles &attributeHandles, const PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Write the parameters and state of the rigid body of a vehicle instance to omnipvd.

Note

If suspStateCalcParams is NULL but a non-NULL value was used in void PxVehiclePvdSuspensionStateCalculationParamsRegister(), the suspension state calculation parameters will not be updated in omnipvd.

Note

omniWriter must be the same instance used in PxVehiclePvdSuspensionStateCalculationParamsRegister().

Parameters
  • suspStateCalcParams[in] describes parameters used to calculate suspension state.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdWheelAttachmentsRegister(const PxVehicleAxleDescription &axleDesc, const PxVehicleArrayData<const PxVehicleWheelParams> &wheelParams, const PxVehicleArrayData<const PxVehicleWheelActuationState> &wheelActuationStates, const PxVehicleArrayData<const PxVehicleWheelRigidBody1dState> &wheelRigidBody1dStates, const PxVehicleArrayData<const PxVehicleWheelLocalPose> &wheelLocalPoses, const PxVehicleArrayData<const PxVehicleRoadGeometryState> &roadGeometryStates, const PxVehicleArrayData<const PxVehicleSuspensionParams> &suspParams, const PxVehicleArrayData<const PxVehicleSuspensionComplianceParams> &suspCompParams, const PxVehicleArrayData<const PxVehicleSuspensionForceParams> &suspForceParams, const PxVehicleArrayData<const PxVehicleSuspensionState> &suspStates, const PxVehicleArrayData<const PxVehicleSuspensionComplianceState> &suspCompStates, const PxVehicleArrayData<const PxVehicleSuspensionForce> &suspForces, const PxVehicleArrayData<const PxVehicleTireForceParams> &tireForceParams, const PxVehicleArrayData<const PxVehicleTireDirectionState> &tireDirectionStates, const PxVehicleArrayData<const PxVehicleTireSpeedState> &tireSpeedStates, const PxVehicleArrayData<const PxVehicleTireSlipState> &tireSlipStates, const PxVehicleArrayData<const PxVehicleTireStickyState> &tireStickyStates, const PxVehicleArrayData<const PxVehicleTireGripState> &tireGripStates, const PxVehicleArrayData<const PxVehicleTireCamberAngleState> &tireCamberStates, const PxVehicleArrayData<const PxVehicleTireForce> &tireForces, const PxVehiclePvdAttributeHandles &attributeHandles, PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Register object instances in omnipvd that will be used to reflect wheel attachment data such as tires, suspensions and wheels.

Note

If any array is empty, the corresponding data will not be reflected in omnipvd.

Note

Each array must either be empty or contain an entry for each wheel present in axleDesc.

Parameters
  • axleDesc[in] is a description of the wheels and axles of a vehicle.

  • wheelParams[in] is an array of wheel parameters.

  • wheelActuationStates[in] is an array of wheel actuation states.

  • wheelRigidBody1dStates[in] is an array of wheel rigid body states.

  • wheelLocalPoses[in] is an array of wheel local poses.

  • roadGeometryStates[in] is an array of road geometry states.

  • suspParams[in] is an array of suspension parameters.

  • suspCompParams[in] is an array of suspension compliance parameters.

  • suspForceParams[in] is an array of suspension force parameters.

  • suspStates[in] is an array of suspension states.

  • suspCompStates[in] is an array of suspension compliance states.

  • suspForces[in] is an array of suspension forces.

  • tireForceParams[in] is an array of tire force parameters.

  • tireDirectionStates[in] is an array of tire direction states.

  • tireSpeedStates[in] is an array of tire speed states.

  • tireSlipStates[in] is an array of tire slip states.

  • tireStickyStates[in] is an array of tire sticky states.

  • tireGripStates[in] is an array of tire grip states.

  • tireCamberStates[in] is an array of tire camber states.

  • tireForces[in] is an array of tire forces.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehiclePvdWheelAttachmentsWrite(const PxVehicleAxleDescription &axleDesc, const PxVehicleArrayData<const PxVehicleWheelParams> &wheelParams, const PxVehicleArrayData<const PxVehicleWheelActuationState> &wheelActuationStates, const PxVehicleArrayData<const PxVehicleWheelRigidBody1dState> &wheelRigidBody1dStates, const PxVehicleArrayData<const PxVehicleWheelLocalPose> &wheelLocalPoses, const PxVehicleArrayData<const PxVehicleRoadGeometryState> &roadGeometryStates, const PxVehicleArrayData<const PxVehicleSuspensionParams> &suspParams, const PxVehicleArrayData<const PxVehicleSuspensionComplianceParams> &suspCompParams, const PxVehicleArrayData<const PxVehicleSuspensionForceParams> &suspForceParams, const PxVehicleArrayData<const PxVehicleSuspensionState> &suspStates, const PxVehicleArrayData<const PxVehicleSuspensionComplianceState> &suspCompStates, const PxVehicleArrayData<const PxVehicleSuspensionForce> &suspForces, const PxVehicleArrayData<const PxVehicleTireForceParams> &tireForceParams, const PxVehicleArrayData<const PxVehicleTireDirectionState> &tireDirectionStates, const PxVehicleArrayData<const PxVehicleTireSpeedState> &tireSpeedStates, const PxVehicleArrayData<const PxVehicleTireSlipState> &tireSlipStates, const PxVehicleArrayData<const PxVehicleTireStickyState> &tireStickyStates, const PxVehicleArrayData<const PxVehicleTireGripState> &tireGripStates, const PxVehicleArrayData<const PxVehicleTireCamberAngleState> &tireCamberStates, const PxVehicleArrayData<const PxVehicleTireForce> &tireForces, const PxVehiclePvdAttributeHandles &attributeHandles, const PxVehiclePvdObjectHandles &objectHandles, OmniPvdWriter &omniWriter)

Write wheel attachment data such as tire, suspension and wheel data to omnipvd.

Note

If any array is empty but the corresponding argument in PxVehiclePvdWheelAttachmentsRegister was not empty, the corresponding data will not be updated in omnipvd.

Note

Each array must either be empty or contain an entry for each wheel present in axleDesc.

Parameters
  • axleDesc[in] is a description of the wheels and axles of a vehicle.

  • wheelParams[in] is an array of wheel parameters.

  • wheelActuationStates[in] is an array of wheel actuation states.

  • wheelRigidBody1dStates[in] is an array of wheel rigid body states.

  • wheelLocalPoses[in] is an array of wheel local poses.

  • roadGeometryStates[in] is an array of road geometry states.

  • suspParams[in] is an array of suspension parameters.

  • suspCompParams[in] is an array of suspension compliance parameters.

  • suspForceParams[in] is an array of suspension force parameters.

  • suspStates[in] is an array of suspension states.

  • suspCompStates[in] is an array of suspension compliance states.

  • suspForces[in] is an array of suspension forces.

  • tireForceParams[in] is an array of tire force parameters.

  • tireDirectionStates[in] is an array of tire direction states.

  • tireSpeedStates[in] is an array of tire speed states.

  • tireSlipStates[in] is an array of tire slip states.

  • tireStickyStates[in] is an array of tire sticky states.

  • tireGripStates[in] is an array of tire grip states.

  • tireCamberStates[in] is an array of tire camber states.

  • tireForces[in] is an array of tire forces.

  • attributeHandles[in] contains a general description of vehicle parameters and states that will be reflected in omnipvd.

  • objectHandles[in] contains unique handles for the parameters and states of each vehicle instance.

  • omniWriter[in] is an OmniPvdWriter instance used to communicate state and parameter data to omnipvd.

void PxVehicleReadRigidBodyStateFromPhysXActor(const PxRigidBody &physxActor, PxVehicleRigidBodyState &rigidBodyState)

Read the rigid body state from a PhysX actor.

Parameters
  • physxActor[in] is a reference to a PhysX actor.

  • rigidBodyState[out] is the state of the rigid body used by the Vehicle SDK.

void PxVehicleRigidBodyUpdate(const PxVehicleAxleDescription &axleDescription, const PxVehicleRigidBodyParams &rigidBodyParams, const PxVehicleArrayData<const PxVehicleSuspensionForce> &suspensionForces, const PxVehicleArrayData<const PxVehicleTireForce> &tireForces, const PxVehicleAntiRollTorque *antiRollTorque, const PxReal dt, const PxVec3 &gravity, PxVehicleRigidBodyState &rigidBodyState)

Forward integrate rigid body state.

Note

The suspensionForces array must contain an entry for each wheel listed as an active wheel in axleDescription.

Note

The tireForces array must contain an entry for each wheel listed as an active wheel in axleDescription.

Note

If antiRollTorque is a null pointer then zero anti-roll torque will be applied to the rigid body.

Parameters
  • axleDescription[in] is a description of the axles of the vehicle and the wheels on each axle.

  • rigidBodyParams[in] is a description of rigid body mass and moment of inertia.

  • suspensionForces[in] is an array of suspension forces and torques in the world frame to be applied to the rigid body.

  • tireForces[in] is an array of tire forces and torques in the world frame to be applied to the rigid body.

  • antiRollTorque[in] is an optional pointer to a single PxVehicleAntiRollTorque instance that contains the accumulated anti-roll torque to apply to the rigid body.

  • dt[in] is the timestep of the forward integration.

  • gravity[in] is gravitational acceleration.

  • rigidBodyState[inout] is the rigid body state that is to be updated.

inline void PxVehicleShiftOrigin(const PxVehicleAxleDescription &axleDesc, const PxVec3 &shift, PxVehicleRigidBodyState &rigidBodyState, PxVehicleRoadGeometryState *roadGeometryStates, PxVehiclePhysXActor *physxActor = NULL, PxVehiclePhysXRoadGeometryQueryState *physxQueryStates = NULL)

Shift the origin of a vehicle by the specified vector.

Call this method to adjust the internal data structures of vehicles to reflect the shifted origin location (the shift vector will get subtracted from all world space spatial data).

Note

It is the user’s responsibility to keep track of the summed total origin shift and adjust all input/output to/from the vehicle accordingly.

Note

This call will not automatically shift the PhysX scene and its objects. PxScene::shiftOrigin() must be called seperately to keep the systems in sync.

Note

If there is no associated PxRigidActor then set physxActor to NULL.

Note

If there is an associated PxRigidActor and it is already in a PxScene then the complementary call to PxScene::shiftOrigin() will take care of shifting the associated PxRigidActor. This being the case, set physxActor to NULL. physxActor should be a non-NULL pointer only when there is an associated PxRigidActor and it is not part of a PxScene. This can occur if the associated PxRigidActor is updated using PhysX immediate mode.

Note

If scene queries are independent of PhysX geometry then set queryStates to NULL.

Parameters
  • axleDesc[in] is a description of the wheels on the vehicle.

  • shift[in] is the translation vector used to shift the origin.

  • rigidBodyState[in] stores the current position of the vehicle

  • roadGeometryStates[in] stores the hit plane under each wheel.

  • physxActor[in] stores the PxRigidActor that is the vehicle’s PhysX representation.

  • physxQueryStates[in] stores the hit point of the most recent execution of PxVehiclePhysXRoadGeometryQueryUpdate() for each wheel.

void PxVehicleSteerCommandResponseUpdate(const PxReal steer, const PxReal longitudinalSpeed, const PxU32 wheelId, const PxVehicleSteerCommandResponseParams &steerResponseParmas, PxReal &steerResponseState)

Compute the yaw angle response to a steer command.

Parameters
  • steer[in] is the input steer command value.

  • longitudinalSpeed[in] is the longitudinal speed of the vehicle.

  • wheelId[in] specifies the wheel to have its steer response computed.

  • steerResponseParmas[in] specifies the per wheel yaw angle response to the steer command as a nonlinear function of steer command and longitudinal speed.

  • steerResponseState[out] is the yaw angle response to the input steer command.

void PxVehicleSuspensionComplianceUpdate(const PxVehicleSuspensionParams &suspensionParams, const PxVehicleSuspensionComplianceParams &complianceParams, const PxVehicleSuspensionState &suspensionState, PxVehicleSuspensionComplianceState &complianceState)

Compute the toe, camber and force application points that are affected by suspension compression.

Parameters
  • suspensionParams[in] is a description of the suspension and wheel frames.

  • complianceParams[in] describes how toe, camber and force application points are affected by suspension compression.

  • suspensionState[in] describes the current suspension compression.

  • complianceState[in] is the computed toe, camber and force application points.

void PxVehicleSuspensionForceUpdate(const PxVehicleSuspensionParams &suspensionParams, const PxVehicleSuspensionForceParams &suspensionForceParams, const PxVehicleRoadGeometryState &roadGeometryState, const PxVehicleSuspensionState &suspensionState, const PxVehicleSuspensionComplianceState &complianceState, const PxVehicleRigidBodyState &rigidBodyState, const PxVec3 &gravity, const PxReal vehicleMass, PxVehicleSuspensionForce &suspensionForce)

Compute the suspension force and torque arising from suspension compression and speed.

Parameters
  • suspensionParams[in] is a description of the suspension and wheel frames.

  • suspensionForceParams[in] describes the conversion of suspension state to suspension force.

  • roadGeometryState[in] describes the plane under the wheel of the suspension.

  • suspensionState[in] is the current compression state of the suspension.

  • complianceState[in] is the current compliance state of the suspension.

  • rigidBodyState[in] describes the current pose of the rigid body.

  • gravity[in] is the gravitational acceleration.

  • vehicleMass[in] is the rigid body mass.

  • suspensionForce[out] is the force and torque to apply to the rigid body arising from the suspension state.

void PxVehicleSuspensionLegacyForceUpdate(const PxVehicleSuspensionParams &suspensionParams, const PxVehicleSuspensionForceLegacyParams &suspensionForceParams, const PxVehicleRoadGeometryState &roadGeometryState, const PxVehicleSuspensionState &suspensionState, const PxVehicleSuspensionComplianceState &complianceState, const PxVehicleRigidBodyState &rigidBodyState, const PxVec3 &gravity, PxVehicleSuspensionForce &suspensionForce)

Compute the suspension force and torque arising from suspension compression and speed.

Deprecated:

Note

PxVehicleSuspensionLegacyForceUpdate implements the legacy force computation of PhysX 5.0 and earlier.

Parameters
  • suspensionParams[in] is a description of the suspension and wheel frames.

  • suspensionForceParams[in] describes the conversion of suspension state to suspension force.

  • roadGeometryState[in] describes the plane under the wheel of the suspension.

  • suspensionState[in] is the current compression state of the suspension.

  • complianceState[in] is the current compliance state of the suspension.

  • rigidBodyState[in] describes the current pose of the rigid body.

  • gravity[in] is the gravitational acceleration.

  • suspensionForce[out] is the force and torque to apply to the rigid body arising from the suspension state.

void PxVehicleSuspensionStateUpdate(const PxVehicleWheelParams &wheelParams, const PxVehicleSuspensionParams &suspensionParams, const PxVehicleSuspensionStateCalculationParams &suspensionStateCalcParams, const PxReal suspensionStiffness, const PxReal suspensionDamping, const PxReal steerAngle, const PxVehicleRoadGeometryState &roadGeometryState, const PxVehicleRigidBodyState &rigidBodyState, const PxReal dt, const PxVehicleFrame &frame, const PxVec3 &gravity, PxVehicleSuspensionState &suspState)

Compute the suspension compression and compression speed for a single suspension.

Parameters
  • wheelParams[in] is a description of the radius and half-width of the wheel on the suspension.

  • suspensionParams[in] is a description of the suspension and wheel frames.

  • suspensionStateCalcParams[in] specifies whether to compute the suspension compression by either raycasting or sweeping against the plane of the road geometry under the wheel.

  • suspensionStiffness[in] is the stiffness of the suspension

  • suspensionDamping[in] is the damping rate of the suspension. or whether to apply a limit to the expansion speed so that the wheel may not reach the ground.

  • steerAngle[in] is the yaw angle (in radians) of the wheel.

  • roadGeometryState[in] describes the plane under the wheel.

  • rigidBodyState[in] describes the pose of the rigid body.

  • dt[in] is the simulation time that has lapsed since the last call to PxVehicleSuspensionStateUpdate

  • frame[in] describes the longitudinal, lateral and vertical axes of the vehicle.

  • gravity[in] is the gravitational acceleration that acts on the suspension sprung mass.

  • suspState[inout] is the compression (jounce) and compression speed of the suspension.

void PxVehicleTireCamberAnglesUpdate(const PxVehicleSuspensionParams &suspensionParams, const PxReal steerAngle, const PxVec3 &groundNormal, bool isWheelOnGround, const PxVehicleSuspensionComplianceState &complianceState, const PxVehicleRigidBodyState &rigidBodyState, const PxVehicleFrame &frame, PxVehicleTireCamberAngleState &tireCamberAngleState)

Compute the camber angle of the wheel.

Parameters
  • suspensionParams[in] describes the frame of the suspension and wheel.

  • steerAngle[in] is the steer angle in radians to be applied to the wheel.

  • groundNormal[in] describes the plane normal of the road geometry under the wheel.

  • isWheelOnGround[in] defines whether the wheel touches the road geometry.

  • complianceState[in] is a description of the camber and toe angle that arise from suspension compliance.

  • rigidBodyState[in] describes the current pose of the vehicle’s rigid body in the world frame.

  • frame[in] is a description of the vehicle’s lateral and longitudinal axes.

  • tireCamberAngleState[out] is the computed camber angle of the tire expressed in radians.

void PxVehicleTireDirsLegacyUpdate(const PxVehicleSuspensionParams &suspensionParams, const PxReal steerAngle, const PxVehicleRoadGeometryState &roadGeometryState, const PxVehicleRigidBodyState &rigidBodyState, const PxVehicleFrame &frame, PxVehicleTireDirectionState &tireDirectionState)

Compute the longitudinal and lateral tire directions in the ground plane.

Deprecated:

Note

PxVehicleTireDirsLegacyUpdate replicates the tire direction calculation of PhysX 5.0 and earlier.

Parameters
  • suspensionParams[in] describes the frame of the suspension and wheel.

  • steerAngle[in] is the steer angle in radians to be applied to the wheel.

  • roadGeometryState[in] describes the plane of the road geometry under the wheel

  • rigidBodyState[in] describes the current pose of the vehicle’s rigid body in the world frame.

  • frame[in] is a description of the vehicle’s lateral and longitudinal axes.

  • tireDirectionState[out] is the computed tire longitudinal and lateral directions in the world frame.

void PxVehicleTireDirsUpdate(const PxVehicleSuspensionParams &suspensionParams, const PxReal steerAngle, const PxVec3 &groundNormal, bool isWheelOnGround, const PxVehicleSuspensionComplianceState &complianceState, const PxVehicleRigidBodyState &rigidBodyState, const PxVehicleFrame &frame, PxVehicleTireDirectionState &tireDirectionState)

Compute the longitudinal and lateral tire directions in the ground plane.

Note

The difference between PxVehicleTireDirsUpdate and PxVehicleTireDirsLegacyUpdate is that PxVehicleTireDirsUpdate accounts for suspension compliance while PxVehicleTireDirsLegacyUpdate does not.

Parameters
  • suspensionParams[in] describes the frame of the suspension and wheel.

  • steerAngle[in] is the steer angle in radians to be applied to the wheel.

  • groundNormal[in] describes the plane normal of the road geometry under the wheel.

  • isWheelOnGround[in] defines whether the wheel touches the road geometry.

  • complianceState[in] is a description of the camber and toe angle that arise from suspension compliance.

  • rigidBodyState[in] describes the current pose of the vehicle’s rigid body in the world frame.

  • frame[in] is a description of the vehicle’s lateral and longitudinal axes.

  • tireDirectionState[out] is the computed tire longitudinal and lateral directions in the world frame.

void PxVehicleTireForcesUpdate(const PxVehicleWheelParams &wheelParams, const PxVehicleSuspensionParams &suspensionParams, const PxVehicleTireForceParams &tireForceParams, const PxVehicleSuspensionComplianceState &complianceState, const PxVehicleTireGripState &tireGripState, const PxVehicleTireDirectionState &tireDirectionState, const PxVehicleTireSlipState &tireSlipState, const PxVehicleTireCamberAngleState &tireCamberAngleState, const PxVehicleRigidBodyState &rigidBodyState, PxVehicleTireForce &tireForce)

Compute the longitudinal and lateral forces in the world frame that develop on the tire as a consequence of the tire’s slip angles, friction and load.

Parameters
  • wheelParams[in] describes the radius and half-width of the wheel.

  • suspensionParams[in] describes the frame of the suspension and wheel.

  • tireForceParams[in] describes the conversion of slip angle, friction and load to a force along the longitudinal and lateral directions of the tire.

  • complianceState[in] is a description of the camber and toe angle that arise from suspension compliance.

  • tireGripState[out] is the load and friction experienced by the tire.

  • tireDirectionState[in] is the tire’s longitudinal and lateral directions in the ground plane.

  • tireSlipState[in] is the longitudinal and lateral slip angles.

  • tireCamberAngleState[in] is the camber angle of the tire expressed in radians.

  • rigidBodyState[in] describes the current pose of the vehicle’s rigid body in the world frame.

  • tireForce[out] is the computed tire forces in the world frame.

void PxVehicleTireGripUpdate(const PxVehicleTireForceParams &tireForceParams, PxReal frictionCoefficient, bool isWheelOnGround, const PxVehicleSuspensionForce &suspensionForce, const PxVehicleTireSlipState &tireSlipState, PxVehicleTireGripState &tireGripState)

Compute the load and friction experienced by the tire.

Note

If the suspension cannot place the wheel on the ground the tire load and friction will be 0.0.

Parameters
  • tireForceParams[in] describes the tire’s friction response to longitudinal lip angle and its load response.

  • frictionCoefficient[in] describes the friction coefficient for the tire and road geometry pair.

  • isWheelOnGround[in] defines whether the wheel touches the road geometry.

  • suspensionForce[in] is the force that the suspension exerts on the sprung mass of the suspension.

  • tireSlipState[in] is the tire longitudinal and lateral slip angles.

  • tireGripState[out] is the computed load and friction experienced by the tire.

void PxVehicleTireSlipSpeedsUpdate(const PxVehicleWheelParams &wheelParams, const PxVehicleSuspensionParams &suspensionParams, const PxF32 steerAngle, const PxVehicleSuspensionState &suspensionStates, const PxVehicleTireDirectionState &tireDirectionState, const PxVehicleRigidBodyState &rigidBodyState, const PxVehicleRoadGeometryState &roadGeometryState, const PxVehicleFrame &frame, PxVehicleTireSpeedState &tireSpeedState)

Project the rigid body velocity at the tire contact point along the tire longitudinal directions.

Parameters
  • wheelParams[in] is a description of the wheel’s radius and half-width.

  • suspensionParams[in] describes the frame of the suspension and wheel.

  • steerAngle[in] is the steer angle in radians to be applied to the wheel.

  • suspensionStates[in] is the current suspension compression state.

  • tireDirectionState[in] is the tire’s longitudinal and lateral directions in the ground plane.

  • rigidBodyState[in] describes the current pose and velocity of the vehicle’s rigid body in the world frame.

  • roadGeometryState[in] describes the current velocity of the road geometry under each wheel.

  • frame[in] is a description of the vehicle’s lateral and longitudinal axes.

  • tireSpeedState[out] is the components of rigid body velocity at the tire contact point along the tire’s longitudinal and lateral axes.

void PxVehicleTireSlipsAccountingForStickyStatesUpdate(const PxVehicleTireStickyState &tireStickyState, PxVehicleTireSlipState &tireSlipState)

Set the tire longitudinal and lateral slip values to 0.0 in the event that the tire has entred tire sticky state.

This is necessary to avoid both tire models being simultaneously active and interfering with each other.

Note

This function should not be invoked if there is no subsequent component to implement the sticky tire model.

Parameters
  • tireStickyState[in] is a description of the sticky state of the tire in the longitudinal and lateral directions.

  • tireSlipState[out] is the updated lateral and longudinal slip with either set to 0.0 in the event that the correspoinding sticky state is active.

void PxVehicleTireSlipsLegacyUpdate(const PxVehicleWheelParams &wheelParams, const PxVehicleTireSlipParams &tireSlipParams, const PxVehicleWheelActuationState &actuationState, PxVehicleTireSpeedState &tireSpeedState, const PxVehicleWheelRigidBody1dState &wheelRigidBody1dState, PxVehicleTireSlipState &tireSlipState)

Compute a tire’s longitudinal and lateral slip angles.

Deprecated:

Note

Longitudinal slip angle has the following theoretical form: (wheelRotationSpeed*wheelRadius - longitudinalSpeed)/|longitudinalSpeed|

Note

Lateral slip angle has the following theoretical form: atan(lateralSpeed/|longitudinalSpeed|)

Note

The calculation of both longitudinal and lateral slip angles avoid a zero denominator using minimum values for the denominator set in tireSlipParams.

Parameters
  • wheelParams[in] describes the radius of the wheel.

  • tireSlipParams[in] describes how to manage small longitudinal speeds by setting minimum values on the denominator of the quotients used to calculate lateral and longitudinal slip.

  • actuationState[in] describes whether a wheel is to be driven by a drive torque or not.

  • tireSpeedState[in] is the component of rigid body velocity at the tire contact point projected along the tire’s longitudinal and lateral axes.

  • wheelRigidBody1dState[in] is the wheel rotation speed.

  • tireSlipState[out] is the computed tire longitudinal and lateral slips.

void PxVehicleTireSlipsUpdate(const PxVehicleWheelParams &wheelParams, const PxVehicleTireSlipParams &tireSlipParams, const PxVehicleWheelActuationState &actuationState, PxVehicleTireSpeedState &tireSpeedState, const PxVehicleWheelRigidBody1dState &wheelRigidBody1dState, PxVehicleTireSlipState &tireSlipState)

Compute a tire’s longitudinal and lateral slip angles.

Note

Longitudinal slip angle has the following theoretical form: (wheelRotationSpeed*wheelRadius - longitudinalSpeed)/|longitudinalSpeed|

Note

Lateral slip angle has the following theoretical form: atan(lateralSpeed/|longitudinalSpeed|)

Note

The calculation of both longitudinal and lateral slip angles avoid a zero denominator using minimum values for the denominator set in tireSlipParams.

Parameters
  • wheelParams[in] describes the radius of the wheel.

  • tireSlipParams[in] describes how to manage small longitudinal speeds by setting minimum values on the denominator of the quotients used to calculate lateral and longitudinal slip.

  • actuationState[in] describes whether a wheel is to be driven by a drive torque or not.

  • tireSpeedState[in] is the component of rigid body velocity at the tire contact point projected along the tire’s longitudinal and lateral axes.

  • wheelRigidBody1dState[in] is the wheel rotation speed.

  • tireSlipState[out] is the computed tire longitudinal and lateral slips.

void PxVehicleTireStickyStateReset(const bool poweredVehicleIntentionToAccelerate, const PxVehicleAxleDescription &unpoweredVehicleAxleDesc, PxVehicleArrayData<PxVehicleTireStickyState> &unpoweredVehicleStickyState)

Reset the sticky tire states of an unpowered vehicle if it is in a jointed ensemble of vehicles with at least one powered vehicle.

Note

If any wheel on the powered vehicle is to receive a drive torque, the sticky tire states of the towed vehicle will be reset to the deactivated state.

Note

poweredVehicleIntentionToAccelerate may be computed using PxVehicleAccelerationIntentCompute().

Parameters
  • poweredVehicleIntentionToAccelerate[in] describes the state of the powered vehicle in an ensemble of jointed vehicles.

  • unpoweredVehicleAxleDesc[in] describes the axles and wheels of an unpowered vehicle towed by a powered vehicle.

  • unpoweredVehicleStickyState[out] is the sticky state of the wheels of an unpowered vehicle towed by a powered vehicle.

void PxVehicleTireStickyStateUpdate(const PxVehicleAxleDescription &axleDescription, const PxVehicleWheelParams &wheelParams, const PxVehicleTireStickyParams &tireStickyParams, const PxVehicleArrayData<const PxVehicleWheelActuationState> &actuationStates, const PxVehicleTireGripState &tireGripState, const PxVehicleTireSpeedState &tireSpeedState, const PxVehicleWheelRigidBody1dState &wheelRigidBody1dState, const PxReal dt, PxVehicleTireStickyState &tireStickyState)

When a tire has been at a very low speed for a threshold time without application of drive torque, a secondary tire model is applied to bring the tire to rest using velocity constraints that asymptotically approach zero speed along the tire’s lateral and longitudinal directions.

This secondary tire model is referred to as the sticky tire model and the tire is considered to be in the sticky tire state when the speed and time conditions are satisfied. The purpose of PxVehicleTireStickyStateUpdate is to compute the target speeds of the sticky state and to record whether sticky state is active or not.

Note

The velocity constraints are maintained through integration with the PhysX scene using the function PxVehiclePhysXConstraintStatesUpdate. Alternative implementations independent of PhysX are possible.

Parameters
  • axleDescription[in] is the axles of the vehicle and the wheels on each axle.

  • wheelParams[in] describes the radius of the wheel

  • tireStickyParams[in] describe the threshold speeds and times for the lateral and longitudinal sticky states.

  • actuationStates[in] describes whether each wheel experiences a drive torque.

  • tireGripState[in] is the load and friction experienced by the tire.

  • tireSpeedState[in] is the component of rigid body velocity at the tire contact point projected along the tire’s longitudinal and lateral axes.

  • wheelRigidBody1dState[in] is the wheel rotation speed.

  • dt[in] is the simulation time that has lapsed since the last call to PxVehicleTireStickyStateUpdate

  • tireStickyState[out] is a description of the sticky state of the tire in the longitudinal and lateral directions.

inline PxVec3 PxVehicleTransformFrameToFrame(const PxVehicleFrame &srcFrame, const PxVehicleFrame &trgFrame, const PxVehicleScale &srcScale, const PxVehicleScale &trgScale, const PxVec3 &v)
inline PxVec3 PxVehicleTransformFrameToFrame(const PxVehicleFrame &srcFrame, const PxVehicleFrame &trgFrame, const PxVec3 &v)
inline PxTransform PxVehicleTransformFrameToFrame(const PxVehicleFrame &srcFrame, const PxVehicleFrame &trgFrame, const PxVehicleScale &srcScale, const PxVehicleScale &trgScale, const PxTransform &v)
PxConvexMesh *PxVehicleUnitCylinderSweepMeshCreate(const PxVehicleFrame &vehicleFrame, PxPhysics &physics, const PxCookingParams &params)

Create a cylindrical mesh with unit radius and half-width.

Parameters
  • vehicleFrame[in] is a description of the lateral and longitudinal axes.

  • physics[in] is a PxPhysics instance.

  • params[in] is a PxCookingParams instance

Returns

Return a PxConvexMesh instance that represents a convex hull with unit radius and half-width.

void PxVehicleUnitCylinderSweepMeshDestroy(PxConvexMesh *mesh)

Release the mesh created with PxVehicleUnitCylinderSweepMeshCreate.

Parameters

mesh[in] is a PxConvexMesh instance.

void PxVehicleWheelRotationAngleUpdate(const PxVehicleWheelParams &wheelParams, const PxVehicleWheelActuationState &actuationState, const PxVehicleSuspensionState &suspensionState, const PxVehicleTireSpeedState &tireSpeedState, const PxReal thresholdForwardSpeedForWheelAngleIntegration, const PxReal dt, PxVehicleWheelRigidBody1dState &wheelRigidBody1dState)

Forward integrate the rotation angle of a wheel.

Note

The rotation angle of the wheel plays no role in simulation but is important to compute the pose of the wheel for rendering.

Note

At low speeds and large timesteps, wheel rotation speed can become noisy due to singularities in the tire slip computations. At low speeds, therefore, the wheel speed used for integrating the angle is a blend of current angular speed and rolling angular speed if the wheel experiences neither brake nor drive torque and can be placed on the ground. The blended rotation speed gets stored in PxVehicleWheelRigidBody1dState::correctedRotationSpeed.

Parameters
  • wheelParams[in] describes the radius and half-width of the wheel

  • actuationState[in] describes whether the wheel has drive or brake torque applied to it.

  • suspensionState[in] describes whether the wheel touches the ground.

  • tireSpeedState[in] describes the components of rigid body velocity at the ground contact point along the tire’s lateral and longitudinal directions.

  • thresholdForwardSpeedForWheelAngleIntegration[in] Forward wheel speed below which the wheel rotation speed gets blended with the rolling speed (based on the forward wheel speed) which is then used to integrate the wheel rotation angle. At low forward wheel speed, the wheel rotation speed can get unstable (depending on the tire model used) and, for example, oscillate. If brake or throttle is applied, there will be no blending.

  • dt[in] is the simulation time that has lapsed since the last call to PxVehicleWheelRotationAngleUpdate

  • wheelRigidBody1dState[inout] describes the current angular speed and angle of the wheel.

void PxVehicleWriteRigidBodyStateToPhysXActor(const PxVehiclePhysXActorUpdateMode::Enum physxActorUpdateMode, const PxVehicleRigidBodyState &rigidBodyState, const PxReal dt, PxRigidBody &physXActor)

Write the rigid body state to a PhysX actor.

Parameters
  • physxActorUpdateMode[in] controls whether the PhysX actor is to be updated with instantaneous velocity changes or with accumulated accelerations to be applied in the next simulation step of the associated PxScene.

  • rigidBodyState[in] is the state of the rigid body.

  • dt[in] is the simulation time that has elapsed since the last call to PxVehicleWriteRigidBodyStateToPhysXActor().

  • physXActor[out] is a reference to the PhysX actor.

void PxVehicleWriteWheelLocalPoseToPhysXWheelShape(const PxTransform &wheelLocalPose, const PxTransform &wheelShapeLocalPose, PxShape *shape)

Update the local pose of a PxShape that is associated with a wheel.

Parameters
  • wheelLocalPose[in] describes the local pose of each wheel in the rigid body frame.

  • wheelShapeLocalPose[in] describes the local pose to apply to the PxShape instance in the wheel’s frame.

  • shape[in] is the target PxShape.

inline PxU32 vehicleConstraintSolverPrep(Px1DConstraint *constraints, PxVec3p &body0WorldOffset, PxU32 maxConstraints, PxConstraintInvMassScale&, const void *constantBlock, const PxTransform &bodyAToWorld, const PxTransform &bodyBToWorld, bool, PxVec3p &cA2w, PxVec3p &cB2w)
inline void visualiseVehicleConstraint(PxConstraintVisualizer &viz, const void *constantBlock, const PxTransform &body0Transform, const PxTransform &body1Transform, PxU32 flags)