DriveWorks SDK Reference
4.0.0 Release
For Test and Development only

Vehicle.h
Go to the documentation of this file.
1 // This code contains NVIDIA Confidential Information and is disclosed
3 // under the Mutual Non-Disclosure Agreement.
4 //
5 // Notice
6 // ALL NVIDIA DESIGN SPECIFICATIONS AND CODE ("MATERIALS") ARE PROVIDED "AS IS" NVIDIA MAKES
7 // NO REPRESENTATIONS, WARRANTIES, EXPRESSED, IMPLIED, STATUTORY, OR OTHERWISE WITH RESPECT TO
8 // THE MATERIALS, AND EXPRESSLY DISCLAIMS ANY IMPLIED WARRANTIES OF NONINFRINGEMENT,
9 // MERCHANTABILITY, OR FITNESS FOR A PARTICULAR PURPOSE.
10 //
11 // NVIDIA Corporation assumes no responsibility for the consequences of use of such
12 // information or for any infringement of patents or other rights of third parties that may
13 // result from its use. No license is granted by implication or otherwise under any patent
14 // or patent rights of NVIDIA Corporation. No third party distribution is allowed unless
15 // expressly authorized by NVIDIA. Details are subject to change without notice.
16 // This code supersedes and replaces all information previously supplied.
17 // NVIDIA Corporation products are not authorized for use as critical
18 // components in life support devices or systems without express written approval of
19 // NVIDIA Corporation.
20 //
21 // Copyright (c) 2020-2021 NVIDIA Corporation. All rights reserved.
22 //
23 // NVIDIA Corporation and its licensors retain all intellectual property and proprietary
24 // rights in and to this software and related documentation and any modifications thereto.
25 // Any use, reproduction, disclosure or distribution of this software and related
26 // documentation without an express license agreement from NVIDIA Corporation is
27 // strictly prohibited.
28 //
30 
45 #ifndef DW_RIG_VEHICLE_H_
46 #define DW_RIG_VEHICLE_H_
47 
48 #include <dw/core/base/Types.h>
49 
50 #ifdef __cplusplus
51 extern "C" {
52 #endif
53 
54 #define DW_VEHICLE_STEER_MAP_POLY_DEGREE 5U
55 #define DW_VEHICLE_MAX_NUM_TRAILERS 1U
56 
63 {
66 
69 
73 
76 
82 
87 
92 
97 
99 
104 {
109 
112 
116 
120 
123 
125 
126 #define DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE 15U
127 
131 typedef struct dwVehicleTorqueLUT
132 {
135 
138 
143 
146 
149 
151 
156 {
159 
163 
166 
169 
172 
175 
178 
181 
184 
188  float32_t steeringWheelToSteeringMap[DW_VEHICLE_STEER_MAP_POLY_DEGREE + 1U];
189 
191 
196 {
201 
205 
207 
211 typedef enum dwVehicleTrailerType {
215 
219 typedef struct dwVehicleCabin
220 {
223 
225 
226 /***
227  * Vehicle trailer description.
228  */
229 typedef struct dwVehicleTrailer
230 {
233 
236 
242 
245 
249 
253 typedef struct dwGenericVehicle
254 {
257 
260 
266 
269 
273 
275  bool hasCabin;
276 
280 
282  uint32_t numTrailers;
283 
285 
291 typedef enum {
296 
300 
306 typedef struct dwVehicle
307 {
333  DW_DEPRECATED("Will be removed, unused")
334  float32_t aerodynamicDragCoeff;
336  DW_DEPRECATED("Will be removed, unused")
337  float32_t frontalArea;
339  float32_t centerOfMassToFrontAxle;
340  float32_t centerOfMassHeight;
342  DW_DEPRECATED("Will be removed, unused")
343  float32_t aeroHeight;
345  DW_DEPRECATED("Will be removed, unused")
346  float32_t rollingResistanceCoeff;
348  DW_DEPRECATED("Will be removed, unused")
349  float32_t maxEnginePower;
351  float32_t throttleActuatorTimeConstant;
352  float32_t brakeActuatorTimeConstant;
354  dwVehicleTorqueLUT torqueLUT;
358  float32_t steeringWheelToSteeringMap[DW_VEHICLE_STEER_MAP_POLY_DEGREE + 1];
359  float32_t maxSteeringWheelAngle;
362  float32_t frontSteeringOffset;
363 } dwVehicle;
367 
368 #ifdef __cplusplus
369 }
370 #endif
371 
373 #endif // DW_RIG_VEHICLE_H_
NVIDIA DriveWorks API: Core Types
dwVehicleTorqueLUT torqueLUT
Torque lookup tables.
Definition: Vehicle.h:158
float32_t brakeActuatorTimeConstant
Time constant for first order + time delay brake system [s].
Definition: Vehicle.h:171
dwVehicleTrailerType type
Trailer type, either full or semi, indicates presence of front axle.
Definition: Vehicle.h:244
float32_t length
Length of the bounding box (longitudinal dimension, along X) [m].
Definition: Vehicle.h:65
float32_t corneringStiffness
Cornering stiffness for a single tire [N/rad].
Definition: Vehicle.h:122
float float32_t
Specifies POD types.
Definition: Types.h:70
Physical properties of a vehicle body.
Definition: Vehicle.h:62
dwVector3f boundingBoxPosition
Position of bounding box origin in body coordinate system [m].
Definition: Vehicle.h:81
float32_t maxSteeringWheelAngle
Maximum steering wheel angle [rad].
Definition: Vehicle.h:183
Defines a three-element floating-point vector.
Definition: Types.h:319
float32_t wheelbase
Definition: Vehicle.h:313
uint32_t numTrailers
Number of trailer units.
Definition: Vehicle.h:282
dwVector3f inertia
Principal moments of inertia with respect to center of mass [kg m^2].
Definition: Vehicle.h:91
dwVehicleAxleProperties axleRear
Properties of the rear axle group [m].
Definition: Vehicle.h:265
dwVehicleCabin cabin
Properties of an optional floating cabin attached to the base body.
Definition: Vehicle.h:272
Vehicle description.
Definition: Vehicle.h:253
dwVector3f inertia3D
Definition: Vehicle.h:322
float32_t width
Width of the bounding box (lateral dimension, along Y) [m].
Definition: Vehicle.h:68
float32_t track
Width of the axle, measured between center line of wheels [m].
Definition: Vehicle.h:111
Vehicle actuation properties.
Definition: Vehicle.h:155
float32_t effectiveMass
Definition: Vehicle.h:324
dwVehicleTrailerType
Supported trailer types.
Definition: Vehicle.h:211
float32_t bumperRear
Definition: Vehicle.h:316
float32_t frontCorneringStiffness
Definition: Vehicle.h:326
float32_t centerOfMassToRearAxle
Definition: Vehicle.h:328
bool hasCabin
Indicates presence of a cabin.
Definition: Vehicle.h:275
dwVehicleAxleProperties axleRear
Properties of the rear axle group [m].
Definition: Vehicle.h:241
dwVehicleActuationProperties actuation
Vehicle actuation properties.
Definition: Vehicle.h:268
dwVehicleBodyProperties body
Properties of the base body (passenger car body, truck tractor chassis)
Definition: Vehicle.h:256
dwVector3f leadingVehicleHingePosition
Position of leading vehicle hinge attach point in leading vehicle coordinate system (DW_COORDINATE_SY...
Definition: Vehicle.h:200
dwVehicleAxleProperties axleFront
Properties of the front (steering) axle [m].
Definition: Vehicle.h:235
float32_t driveByWireTimeDelay
Time delay for first order + time delay drive-by-wire / steer-by-wire [s].
Definition: Vehicle.h:180
float32_t height
Height of the bounding box (vertical dimension, along Z) [m].
Definition: Vehicle.h:75
#define DW_VEHICLE_MAX_NUM_TRAILERS
Definition: Vehicle.h:55
float32_t length
Definition: Vehicle.h:309
float32_t driveByWireTimeConstant
Definition: Vehicle.h:331
float32_t mass
Mass [kg].
Definition: Vehicle.h:96
float32_t driveByWireTimeDelay
Definition: Vehicle.h:330
#define DW_DEPRECATED(msg)
Definition: Exports.h:66
Trailer that has both front and rear axles.
Definition: Vehicle.h:213
float32_t axlebaseFront
Definition: Vehicle.h:314
dwVehicleBodyProperties body
Properties of the cabin body.
Definition: Vehicle.h:222
#define DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE
Definition: Vehicle.h:126
dwVector3f trailingVehicleHingePosition
Position of trailing vehicle hinge attach point in trailer coordinate system (DW_COORDINATE_SYSTEM_VE...
Definition: Vehicle.h:204
dwVehicleArticulationProperties articulation
Articulation linking trailer to leading vehicle unit.
Definition: Vehicle.h:247
float32_t bumperFront
Definition: Vehicle.h:317
dwVehicleWheels
Define index for each of the wheels on a 4 wheeled vehicle.
Definition: Vehicle.h:291
dwVehicleBodyProperties body
Properties of the trailer body.
Definition: Vehicle.h:232
#define DW_VEHICLE_STEER_MAP_POLY_DEGREE
Definition: Vehicle.h:54
Properties of an axle and its wheels.
Definition: Vehicle.h:103
Properties of an articulation linking two vehicle units.
Definition: Vehicle.h:195
dwVector3f centerOfMass
Position of center of mass in body coordinate system [m].
Definition: Vehicle.h:86
Number of wheels describing the vehicle.
Definition: Vehicle.h:298
float32_t rearCorneringStiffness
Definition: Vehicle.h:327
float32_t effectiveMass
Effective mass due to rotational inertia (wheel, engine, and other parts of the CVT drivetrain) [kg]...
Definition: Vehicle.h:162
float32_t steeringCoefficient
Definition: Vehicle.h:318
float32_t widthWithMirrors
Definition: Vehicle.h:311
float32_t brakeActuatorTimeDelay
Time delay for first order + time delay brake system [s].
Definition: Vehicle.h:174
float32_t mass
Definition: Vehicle.h:320
float32_t height
Definition: Vehicle.h:308
float32_t position
Position of axle midpoint along X-axis in corresponding vehicle coordinate system (DW_COORDINATE_SYST...
Definition: Vehicle.h:108
Vehicle cabin description.
Definition: Vehicle.h:219
float32_t driveByWireTimeConstant
Time constant for first order + time delay drive-by-wire / steer-by-wire [s].
Definition: Vehicle.h:177
float32_t throttleActuatorTimeDelay
Time delay for first order + time delay throttle system [s].
Definition: Vehicle.h:168
dwVehicleAxleProperties axleFront
Properties of the front (steering) axle [m].
Definition: Vehicle.h:259
float32_t wheelRadiusRight
Radius of right wheel, when facing towards the forward direction of the vehicle [m].
Definition: Vehicle.h:119
Throttle and brake state (input) to longitudinal force (output) lookup tables.
Definition: Vehicle.h:131
float32_t axlebaseRear
Definition: Vehicle.h:315
float32_t throttleActuatorTimeConstant
Time constant for first order + time delay throttle system [s].
Definition: Vehicle.h:165
float32_t width
Definition: Vehicle.h:310
float32_t wheelRadiusLeft
Radius of left wheel, when facing towards the forward direction of the vehicle [m].
Definition: Vehicle.h:115
DEPRECATED: Properties of a passenger car vehicle.
Definition: Vehicle.h:306
float32_t widthWithoutMirrors
Width of the body without any side-mirrors, if applicable, otherwise same as width.
Definition: Vehicle.h:72