NVIDIA DriveOS Linux NSR SDK API Reference

7.0.3.0 Release
Vehicle.h
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: Copyright (c) 2022-2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3  * SPDX-License-Identifier: LicenseRef-NvidiaProprietary
4  *
5  * NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
6  * property and proprietary rights in and to this material, related
7  * documentation and any modifications thereto. Any use, reproduction,
8  * disclosure or distribution of this material and related documentation
9  * without an express license agreement from NVIDIA CORPORATION or
10  * its affiliates is strictly prohibited.
11  */
12 #ifndef DW_RIG_VEHICLE_H_
13 #define DW_RIG_VEHICLE_H_
14 // Generated by dwProto from vehicle.proto DO NOT EDIT BY HAND!
15 // See //3rdparty/shared/dwproto/README.md for more information
16 
31 #include <dw/pbwire/BasicTypes.h>
32 
33 #include <dw/core/base/Exports.h>
34 
35 #include <dw/core/base/MatrixTypes.h>
36 
37 #ifdef __cplusplus
38 extern "C" {
39 #endif
40 
41 #define DW_VEHICLE_STEER_MAP_POLY_DEGREE 5U
42 // coverity[misra_c_2012_rule_5_4_violation] Deviation Record: AV-NDAS-SWSADR-000
43 #define DW_VEHICLE_STEER_MAP_POLY_DEGREE_PLUS_ONE (DW_VEHICLE_STEER_MAP_POLY_DEGREE + 1U)
44 #define DW_VEHICLE_MAX_NUM_TRAILERS 1U
45 #define DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE 15U
46 #define DW_VEHICLE_NUM_CONTOUR_POINTS 200U
47 
49 // coverity[misra_c_2012_rule_2_4_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
50 // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
51 typedef enum dwVehicleTrailerType {
55 
58 // coverity[misra_c_2012_rule_2_4_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
59 // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
60 typedef enum dwVehicleWheels {
65 
69 
72 // coverity[misra_c_2012_rule_2_4_violation] Deviation Record: AV-NDAS-SWSADR-003
73 // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
75 {
78 
81 
85 
88 
94 
99 
104 
109 
113 
117 
121  // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
123 
125 // coverity[misra_c_2012_rule_2_4_violation] Deviation Record: AV-NDAS-SWSADR-003
126 // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
128 {
133 
136 
140 
144 
147 
152 
157  // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
159 
161 // coverity[misra_c_2012_rule_2_4_violation] Deviation Record: AV-NDAS-SWSADR-003
162 // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
163 typedef struct dwVehicleTorqueLUT
164 {
167 
170 
175 
178 
181  // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
183 
185 // coverity[misra_c_2012_rule_2_4_violation] Deviation Record: AV-NDAS-SWSADR-003
186 // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
188 {
191 
195 
198  DW_DEPRECATED("throttleActuatorTimeConstant is deprecated, please use accelerationTimeConstant_s instead.")
200 
203  DW_DEPRECATED("throttleActuatorTimeDelay is deprecated, please use accelerationTimeDelay_s instead.")
205 
208  DW_DEPRECATED("brakeActuatorTimeConstant is deprecated, please use decelerationTimeConstant_s instead.")
210 
213  DW_DEPRECATED("brakeActuatorTimeDelay is deprecated, please use decelerationTimeDelay_s instead.")
215 
218  DW_DEPRECATED("driveByWireTimeConstant is deprecated, please use frontWheelAngleTimeConstant_s instead.")
220 
223  DW_DEPRECATED("driveByWireTimeDelay is deprecated, please use frontWheelAngleTimeDelay_s instead.")
225 
230 
233  DW_DEPRECATED("driveByWireDampingRatio is deprecated")
235 
238  DW_DEPRECATED("driveByWireSecondOrder is deprecated")
240 
243 
248 
252 
256 
260 
264 
268 
272 
276 
280 
284 
288  // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
290 
292 // coverity[misra_c_2012_rule_2_4_violation] Deviation Record: AV-NDAS-SWSADR-003
293 // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
295 {
297  int32_t ticksPerTurn;
298 
300  int32_t ticksCountMin;
301 
303  int32_t ticksCountMax;
304 
308 
312  // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
314 
316 // coverity[misra_c_2012_rule_2_4_violation] Deviation Record: AV-NDAS-SWSADR-003
317 // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
319 {
323 
329 
334 
339  // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
341 
343 // coverity[misra_c_2012_rule_2_4_violation] Deviation Record: AV-NDAS-SWSADR-003
344 // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
346 {
349 
352 
355 
358 
361  // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
363 
365 // coverity[misra_c_2012_rule_2_4_violation] Deviation Record: AV-NDAS-SWSADR-003
366 // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
368 {
373 
377  // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
379 
381 // coverity[misra_c_2012_rule_2_4_violation] Deviation Record: AV-NDAS-SWSADR-003
382 // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
383 typedef struct dwVehicleCabin
384 {
387  // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
389 
391 // coverity[misra_c_2012_rule_2_4_violation] Deviation Record: AV-NDAS-SWSADR-003
392 // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
393 typedef struct dwVehicleTrailer
394 {
397 
400 
406 
409 
412  // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
414 
416 // coverity[misra_c_2012_rule_2_4_violation] Deviation Record: AV-NDAS-SWSADR-003
417 // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
418 typedef struct dwGenericVehicle
419 {
422 
425 
431 
434 
437 
440 
443 
447 
449  bool hasCabin;
450 
454  uint32_t numTrailers;
455 
460 
465  // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
467 
470 // coverity[misra_c_2012_rule_2_4_violation] Deviation Record: AV-NDAS-SWSADR-003
471 // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
472 typedef struct dwVehicle
473 {
492 
494  DW_DEPRECATED("Will be removed, unused")
495  float32_t aerodynamicDragCoeff;
496 
498  DW_DEPRECATED("Will be removed, unused")
499  float32_t frontalArea;
500  float32_t centerOfMassToFrontAxle;
501  float32_t centerOfMassHeight;
502 
504  DW_DEPRECATED("Will be removed, unused")
505  float32_t aeroHeight;
506 
508  DW_DEPRECATED("Will be removed, unused")
509  float32_t rollingResistanceCoeff;
510 
512  DW_DEPRECATED("Will be removed, unused")
513  float32_t maxEnginePower;
518 
523 
528  float32_t frontSteeringOffset;
529  // coverity[misra_c_2012_rule_2_3_violation] Deviation Record: AV-NDAS-DWPROTO-SWSADR-006
530 } dwVehicle;
531 
532 #ifdef __cplusplus
533 }
534 #endif
535 
539 #endif // DW_RIG_VEHICLE_H_
dwVehicleAxleProperties::track
float32_t track
Width of the axle, measured between center line of wheels [m].
Definition: Vehicle.h:135
dwVehicleActuationProperties::maxSteeringWheelAngle
float32_t maxSteeringWheelAngle
Maximum steering wheel angle [rad].
Definition: Vehicle.h:242
dwVehicleWheels
dwVehicleWheels
Define index for each of the wheels on a 4 wheeled vehicle.
Definition: Vehicle.h:60
dwVehicleWheelEncoderProperties::ticksCountMax
int32_t ticksCountMax
Number above which counter rolls over. [-].
Definition: Vehicle.h:303
DW_VEHICLE_WHEEL_FRONT_LEFT
@ DW_VEHICLE_WHEEL_FRONT_LEFT
Definition: Vehicle.h:61
dwVehicleCabin
struct dwVehicleCabin dwVehicleCabin
Vehicle cabin description.
dwVehicleActuationProperties::rearWheelAngleTimeConstant_s
float32_t rearWheelAngleTimeConstant_s
Time constant for first order + time delay system for rear wheel angle.
Definition: Vehicle.h:283
dwVehicleArticulationProperties::trailingVehicleHingePosition
dwVector3f trailingVehicleHingePosition
Position of trailing vehicle hinge attach point in trailer coordinate system (DW_COORDINATE_SYSTEM_VE...
Definition: Vehicle.h:376
dwVehicle::steeringCoefficient
float32_t steeringCoefficient
Steering coefficient for trivial linear mapping between steering wheel and steering angle,...
Definition: Vehicle.h:483
dwVehicleActuationProperties
Vehicle actuation properties.
Definition: Vehicle.h:187
dwVehicleActuationProperties::throttleActuatorTimeConstant
float32_t throttleActuatorTimeConstant
Time constant for first order + time delay throttle system [s].
Definition: Vehicle.h:199
dwVehicleWheelEncoderProperties
struct dwVehicleWheelEncoderProperties dwVehicleWheelEncoderProperties
Wheel encoder parameters.
dwGenericVehicle::suspension
dwVehicleSuspensionProperties suspension
Vehicle suspension properties.
Definition: Vehicle.h:439
dwVehicleTorqueLUT
struct dwVehicleTorqueLUT dwVehicleTorqueLUT
Throttle and brake state (input) to longitudinal force (output) lookup tables.
dwVehicleDynamicsProperties::sideSlipAngleGradient
float32_t sideSlipAngleGradient
Side slip angle gradient relating lateral acceleration to side slip angle.
Definition: Vehicle.h:322
dwVehicleSuspensionProperties::rearAxleToRoadLevelCurbMass
dwTransformation3f rearAxleToRoadLevelCurbMass
Transformation of the ISO23150 vehicle rear-axle coordinate system to the ISO23150 vehicle road-level...
Definition: Vehicle.h:360
dwGenericVehicle::body
dwVehicleBodyProperties body
Properties of the base body (passenger car body, truck tractor chassis)
Definition: Vehicle.h:421
dwVehicleCabin
Vehicle cabin description.
Definition: Vehicle.h:383
dwVehicleTrailer::axleFront
dwVehicleAxleProperties axleFront
Properties of the front (steering) axle [m].
Definition: Vehicle.h:399
dwVehicleActuationProperties::curvatureTimeDelay_s
float32_t curvatureTimeDelay_s
Time delay for first order + time delay curvature steering interface.
Definition: Vehicle.h:271
dwVehicleSuspensionProperties::pitchAngleGradientAccel
float32_t pitchAngleGradientAccel
Suspension pitch angle gradient during acceleration. [deg s^2 / m].
Definition: Vehicle.h:351
dwVehicleAxleProperties::position
float32_t position
Position of axle midpoint along X-axis in corresponding vehicle coordinate system (DW_COORDINATE_SYST...
Definition: Vehicle.h:132
dwVehicleActuationProperties::throttleActuatorTimeDelay
float32_t throttleActuatorTimeDelay
Time delay for first order + time delay throttle system [s].
Definition: Vehicle.h:204
dwVehicleCabin::body
dwVehicleBodyProperties body
Properties of the cabin body.
Definition: Vehicle.h:386
DW_VEHICLE_NUM_CONTOUR_POINTS
#define DW_VEHICLE_NUM_CONTOUR_POINTS
Definition: Vehicle.h:46
dwVehicleActuationProperties::driveByWireTimeDelay
float32_t driveByWireTimeDelay
Time delay for first order + time delay drive-by-wire / steer-by-wire [s].
Definition: Vehicle.h:224
dwVehicleBodyProperties
Physical properties of a vehicle body.
Definition: Vehicle.h:74
dwVehicleActuationProperties::frontWheelAngleTimeConstant_s
float32_t frontWheelAngleTimeConstant_s
Time constant for first order + time delay system for front wheel angle.
Definition: Vehicle.h:275
dwGenericVehicle::axleFront
dwVehicleAxleProperties axleFront
Properties of the front (steering) axle [m].
Definition: Vehicle.h:424
DW_VEHICLE_STEER_MAP_POLY_DEGREE_PLUS_ONE
#define DW_VEHICLE_STEER_MAP_POLY_DEGREE_PLUS_ONE
Definition: Vehicle.h:43
dwVehicleWheelEncoderProperties
Wheel encoder parameters.
Definition: Vehicle.h:294
dwVehicle::widthWithMirrors
float32_t widthWithMirrors
Width of the vehicle including side mirrors.
Definition: Vehicle.h:477
dwVehicleBodyProperties::inertia
dwVector3f inertia
Principal moments of inertia with respect to center of mass [kg m^2].
Definition: Vehicle.h:103
dwVehicle::inertia3D
dwVector3f inertia3D
vehicle inertia around each axis, w.r.t.
Definition: Vehicle.h:485
DW_VEHICLE_TRAILER_TYPE_SEMI
@ DW_VEHICLE_TRAILER_TYPE_SEMI
Trailer that has both front and rear axles.
Definition: Vehicle.h:53
dwVehicle::axlebaseRear
float32_t axlebaseRear
Width of the rear axle.
Definition: Vehicle.h:480
dwVehicleActuationProperties::driveByWireDampingRatio
float32_t driveByWireDampingRatio
Damping ratio for second order + time delay drive-by-wire / steer-by-wire [unitless].
Definition: Vehicle.h:234
dwVehicleBodyProperties::widthWithoutMirrors
float32_t widthWithoutMirrors
Width of the body without any side-mirrors, if applicable, otherwise same as width.
Definition: Vehicle.h:84
dwVehicleSuspensionProperties::rollAngleGradient
float32_t rollAngleGradient
Suspension roll angle gradient. [deg s^2 / m].
Definition: Vehicle.h:348
DW_VEHICLE_WHEEL_REAR_LEFT
@ DW_VEHICLE_WHEEL_REAR_LEFT
Definition: Vehicle.h:63
dwVehicleTorqueLUT::brakePedalInput
float32_t brakePedalInput[DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE]
1-d array of range of brake pedal values (Brake Look-up Table Input)
Definition: Vehicle.h:177
dwVehicleDynamicsProperties
Dynamics properties.
Definition: Vehicle.h:318
dwVehicleActuationProperties::accelerationTimeConstant_s
float32_t accelerationTimeConstant_s
Time constant for first order + time delay acceleration system.
Definition: Vehicle.h:251
dwVehicleWheelEncoderProperties::ticksCountInvalid
int32_t ticksCountInvalid
Invalid tick count, optional value provided by vehicle in case of error, must be outside of [ticksCou...
Definition: Vehicle.h:307
DW_VEHICLE_TRAILER_TYPE_FULL
@ DW_VEHICLE_TRAILER_TYPE_FULL
Definition: Vehicle.h:52
dwVehicleBodyProperties::rearAxleToBPillar
float32_t rearAxleToBPillar
Distance from rear axle to B pillar [m].
Definition: Vehicle.h:116
dwGenericVehicle
struct dwGenericVehicle dwGenericVehicle
Vehicle description.
dwVehicleActuationProperties::frontWheelAngleTimeDelay_s
float32_t frontWheelAngleTimeDelay_s
Time delay for first order + time delay system for front wheel angle.
Definition: Vehicle.h:279
dwVehicleSuspensionProperties
struct dwVehicleSuspensionProperties dwVehicleSuspensionProperties
Suspension properties.
DW_VEHICLE_WHEEL_REAR_RIGHT
@ DW_VEHICLE_WHEEL_REAR_RIGHT
Definition: Vehicle.h:64
dwVehicleWheelEncoderProperties::ticksPerTurn
int32_t ticksPerTurn
Ticks per wheel turn. [-].
Definition: Vehicle.h:297
dwVehicle::bumperRear
float32_t bumperRear
Distance rear axle to rear bumper.
Definition: Vehicle.h:481
dwVehicleBodyProperties::boundingBoxPosition
dwVector3f boundingBoxPosition
Position of bounding box origin in body coordinate system [m].
Definition: Vehicle.h:93
dwVehicleBodyProperties::rearAxleToAPillar
float32_t rearAxleToAPillar
Distance from rear axle to A pillar [m].
Definition: Vehicle.h:112
float32_t
float float32_t
Specifies POD types.
Definition: BasicTypes.h:41
dwVector3f
Defines a three-element floating-point vector.
Definition: MatrixTypes.h:74
dwVehicleActuationProperties::isDriveByWireSecondOrder
bool isDriveByWireSecondOrder
Indicates whether the drive-by-wire / steer-by-wire is second-order or not.
Definition: Vehicle.h:239
dwVehicle::bumperFront
float32_t bumperFront
Distance front axle to front bumper.
Definition: Vehicle.h:482
dwVehicleTorqueLUT::throttlePedalInput
float32_t throttlePedalInput[DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE]
1-d array of range of throttle pedal values (Throttle Look-up Table Input)
Definition: Vehicle.h:166
dwVehicleActuationProperties::driveByWireTimeConstant
float32_t driveByWireTimeConstant
Time constant for first order + time delay drive-by-wire / steer-by-wire [s].
Definition: Vehicle.h:219
dwVehicle::centerOfMassToRearAxle
float32_t centerOfMassToRearAxle
Distance between vehicle's CoM (center-of-mass) and center of the rear axle.
Definition: Vehicle.h:489
dwVehicle::driveByWireTimeConstant
float32_t driveByWireTimeConstant
Drive-by-wire (steer-by-wire) time constant.
Definition: Vehicle.h:491
dwVehicleDynamicsProperties
struct dwVehicleDynamicsProperties dwVehicleDynamicsProperties
Dynamics properties.
dwVehicle::mass
float32_t mass
vehicle mass [kg].
Definition: Vehicle.h:484
dwVehicleTrailer
Vehicle trailer description.
Definition: Vehicle.h:393
dwVehicle::wheelbase
float32_t wheelbase
Distance between the centers of the front and rear wheels.
Definition: Vehicle.h:478
dwVehicleBodyProperties
struct dwVehicleBodyProperties dwVehicleBodyProperties
Physical properties of a vehicle body.
DW_VEHICLE_WHEEL_FRONT_RIGHT
@ DW_VEHICLE_WHEEL_FRONT_RIGHT
Definition: Vehicle.h:62
dwVehicleSuspensionProperties::rearAxleToRoadLevelDesignMass
dwTransformation3f rearAxleToRoadLevelDesignMass
Transformation of the ISO23150 vehicle rear-axle coordinate system to the ISO23150 vehicle road-level...
Definition: Vehicle.h:357
dwVehicleArticulationProperties
Properties of an articulation linking two vehicle units.
Definition: Vehicle.h:367
dwVehicleActuationProperties::rearWheelAngleTimeDelay_s
float32_t rearWheelAngleTimeDelay_s
Time delay for first order + time delay system for rear wheel angle.
Definition: Vehicle.h:287
dwVehicleActuationProperties::brakeActuatorTimeDelay
float32_t brakeActuatorTimeDelay
Time delay for first order + time delay brake system [s].
Definition: Vehicle.h:214
dwVehicleAxleProperties::wheelRadiusRight
float32_t wheelRadiusRight
Radius of right wheel, when facing towards the forward direction of the vehicle [m].
Definition: Vehicle.h:143
dwVehicle
DEPRECATED: Properties of a passenger car vehicle.
Definition: Vehicle.h:472
dwVehicleTrailerType
dwVehicleTrailerType
Supported trailer types.
Definition: Vehicle.h:51
dwVehicle::frontCorneringStiffness
float32_t frontCorneringStiffness
front wheel cornering stiffness.
Definition: Vehicle.h:487
dwVehicleBodyProperties::height
float32_t height
Height of the bounding box (vertical dimension, along Z) [m].
Definition: Vehicle.h:87
DW_DEPRECATED
#define DW_DEPRECATED(msg)
Definition: Exports.h:50
dwVehicleTrailer::axleRear
dwVehicleAxleProperties axleRear
Properties of the rear axle group [m].
Definition: Vehicle.h:405
dwVehicleTorqueLUT::throttleSpeedInput
float32_t throttleSpeedInput[DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE]
1-d array of range of vehicle linear speed values (Throttle Look-up Table Input) [m/s]
Definition: Vehicle.h:169
dwGenericVehicle::axleRear
dwVehicleAxleProperties axleRear
Properties of the rear axle group [m].
Definition: Vehicle.h:430
dwVehicle::axlebaseFront
float32_t axlebaseFront
Width of the front axle.
Definition: Vehicle.h:479
dwVehicleDynamicsProperties::lowSpeedRearSideSlipGradientForward
float32_t lowSpeedRearSideSlipGradientForward
Low speed rear side slip gradient forward relating front steering angle to rear side slip angle.
Definition: Vehicle.h:333
dwVehicleTorqueLUT
Throttle and brake state (input) to longitudinal force (output) lookup tables.
Definition: Vehicle.h:163
dwGenericVehicle::hasCabin
bool hasCabin
Indicates presence of a cabin.
Definition: Vehicle.h:449
dwVehicleAxleProperties
Properties of an axle and its wheels.
Definition: Vehicle.h:127
dwVehicleArticulationProperties::leadingVehicleHingePosition
dwVector3f leadingVehicleHingePosition
Position of leading vehicle hinge attach point in leading vehicle coordinate system (DW_COORDINATE_SY...
Definition: Vehicle.h:372
dwGenericVehicle::wheelEncoder
dwVehicleWheelEncoderProperties wheelEncoder
Wheel encoder properties.
Definition: Vehicle.h:442
dwVehicleBodyProperties::width
float32_t width
Width of the bounding box (lateral dimension, along Y) [m].
Definition: Vehicle.h:80
dwVehicle::width
float32_t width
Width of the vehicle, without side mirrors.
Definition: Vehicle.h:476
dwVehicleTrailer::body
dwVehicleBodyProperties body
Properties of the trailer body.
Definition: Vehicle.h:396
dwVehicleWheelEncoderProperties::speedQuantization
float32_t speedQuantization
Wheel speed quantization.
Definition: Vehicle.h:311
dwGenericVehicle
Vehicle description.
Definition: Vehicle.h:418
dwVehicleWheelEncoderProperties::ticksCountMin
int32_t ticksCountMin
Number below which counter rolls under. [-].
Definition: Vehicle.h:300
dwVehicle::driveByWireTimeDelay
float32_t driveByWireTimeDelay
Drive-by-wire (steer-by-wire) time delay.
Definition: Vehicle.h:490
dwGenericVehicle::numTrailers
uint32_t numTrailers
Stores the occupied/valid length of trailers.
Definition: Vehicle.h:454
dwVehicleBodyProperties::mass
float32_t mass
Mass [kg].
Definition: Vehicle.h:108
dwVehicleTorqueLUT::throttleTorqueOutput
float32_t throttleTorqueOutput[DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE][DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE]
2-d torque table, mapping a given throttle pedal position at a given speed to a torque value (Throttl...
Definition: Vehicle.h:174
dwVehicleActuationProperties::steeringWheelToSteeringMap
float32_t steeringWheelToSteeringMap[DW_VEHICLE_STEER_MAP_POLY_DEGREE_PLUS_ONE]
Polynomial relating steering wheel angle [rad] to steering angle [rad].
Definition: Vehicle.h:247
dwVehicleArticulationProperties
struct dwVehicleArticulationProperties dwVehicleArticulationProperties
Properties of an articulation linking two vehicle units.
dwVehicleAxleProperties::nominalWheelRadiusLeft
float32_t nominalWheelRadiusLeft
Nominal value of radius of left wheel, when facing towards the forward direction of the vehicle.
Definition: Vehicle.h:151
dwVehicleActuationProperties::brakeActuatorTimeConstant
float32_t brakeActuatorTimeConstant
Time constant for first order + time delay brake system [s].
Definition: Vehicle.h:209
dwVehicleAxleProperties::wheelRadiusLeft
float32_t wheelRadiusLeft
Radius of left wheel, when facing towards the forward direction of the vehicle [m].
Definition: Vehicle.h:139
dwVehicleAxleProperties::nominalWheelRadiusRight
float32_t nominalWheelRadiusRight
Nominal value of radius of right wheel, when facing towards the forward direction of the vehicle.
Definition: Vehicle.h:156
dwVehicleActuationProperties::decelerationTimeDelay_s
float32_t decelerationTimeDelay_s
Time delay for first order + time delay deceleration system.
Definition: Vehicle.h:263
dwVehicle::length
float32_t length
Length of the vehicle.
Definition: Vehicle.h:475
dwVehicleTorqueLUT::brakeTorqueOutput
float32_t brakeTorqueOutput[DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE]
1-d torque Table, mapping a given brake pedal position to a torque value (Brake Look-up Table Output)
Definition: Vehicle.h:180
dwTransformation3f
Specifies a 3D rigid transformation.
Definition: MatrixTypes.h:226
dwVehicle::height
float32_t height
Height of the vehicle.
Definition: Vehicle.h:474
dwVehicleTrailer
struct dwVehicleTrailer dwVehicleTrailer
Vehicle trailer description.
dwVehicleBodyProperties::centerOfMass
dwVector3f centerOfMass
Position of center of mass in body coordinate system [m].
Definition: Vehicle.h:98
dwVehicle::effectiveMass
float32_t effectiveMass
effective mass due to vehicle rotational inertia (wheel rotation, engine, and other parts of the CVT ...
Definition: Vehicle.h:486
dwVehicleDynamicsProperties::lowSpeedRearSideSlipGradientBackward
float32_t lowSpeedRearSideSlipGradientBackward
Low speed rear side slip gradient backward relating front steering angle to rear side slip angle.
Definition: Vehicle.h:338
dwVehicleAxleProperties
struct dwVehicleAxleProperties dwVehicleAxleProperties
Properties of an axle and its wheels.
dwVehicleActuationProperties::driveByWireNaturalFrequency
float32_t driveByWireNaturalFrequency
Natural frequency for second order + time delay drive-by-wire / steer-by-wire [hz].
Definition: Vehicle.h:229
dwVehicleActuationProperties::curvatureTimeConstant_s
float32_t curvatureTimeConstant_s
Time constant for first order + time delay curvature steering interface.
Definition: Vehicle.h:267
dwVehicle::rearCorneringStiffness
float32_t rearCorneringStiffness
rear wheel cornering stiffness.
Definition: Vehicle.h:488
DW_VEHICLE_NUM_WHEELS
@ DW_VEHICLE_NUM_WHEELS
Number of wheels describing the vehicle.
Definition: Vehicle.h:67
dwVehicleBodyProperties::rearAxleToCPillar
float32_t rearAxleToCPillar
Distance from rear axle to C pillar [m].
Definition: Vehicle.h:120
dwVehicleDynamicsProperties::understeerAngleGradient
float32_t understeerAngleGradient
Understeer angle gradient relating lateral acceleration to steering angle deviation.
Definition: Vehicle.h:328
dwVehicleActuationProperties::effectiveMass
float32_t effectiveMass
Effective mass due to rotational inertia (wheel, engine, and other parts of the CVT drivetrain) [kg].
Definition: Vehicle.h:194
dwGenericVehicle::cabin
dwVehicleCabin cabin
Properties of an optional floating cabin attached to the base body.
Definition: Vehicle.h:446
dwVehicleActuationProperties::torqueLUT
dwVehicleTorqueLUT torqueLUT
Torque lookup tables.
Definition: Vehicle.h:190
dwVehicleSuspensionProperties::pitchAngleGradientBrake
float32_t pitchAngleGradientBrake
Suspension pitch angle gradient during braking. [deg s^2 / m].
Definition: Vehicle.h:354
dwVehicleTrailer::articulation
dwVehicleArticulationProperties articulation
Articulation linking trailer to leading vehicle unit.
Definition: Vehicle.h:411
DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE
#define DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE
Definition: Vehicle.h:45
dwGenericVehicle::dynamics
dwVehicleDynamicsProperties dynamics
Vehicle dynamics properties.
Definition: Vehicle.h:436
dwVehicleTrailer::type
dwVehicleTrailerType type
Trailer type, either full or semi, indicates presence of front axle.
Definition: Vehicle.h:408
dwVehicleSuspensionProperties
Suspension properties.
Definition: Vehicle.h:345
dwVehicleAxleProperties::corneringStiffness
float32_t corneringStiffness
Cornering stiffness for a single tire [N/rad].
Definition: Vehicle.h:146
dwGenericVehicle::actuation
dwVehicleActuationProperties actuation
Vehicle actuation properties.
Definition: Vehicle.h:433
dwVehicleActuationProperties::decelerationTimeConstant_s
float32_t decelerationTimeConstant_s
Time constant for first order + time delay deceleration system.
Definition: Vehicle.h:259
DW_VEHICLE_MAX_NUM_TRAILERS
#define DW_VEHICLE_MAX_NUM_TRAILERS
Definition: Vehicle.h:44
dwVehicleBodyProperties::length
float32_t length
Length of the bounding box (longitudinal dimension, along X) [m].
Definition: Vehicle.h:77
dwVehicleActuationProperties::accelerationTimeDelay_s
float32_t accelerationTimeDelay_s
Time delay for first order + time delay acceleration system.
Definition: Vehicle.h:255