NVIDIA DriveOS Linux NSR SDK API Reference

7.0.3.0 Release
dwEgomotionParameters2 Struct Reference

Detailed Description

Egomotion parameters.

All parameters are required unless otherwise noted.

Definition at line 324 of file Egomotion2.h.

Collaboration diagram for dwEgomotionParameters2:

Data Fields

dwGenericVehicle vehicle
 Vehicle parameters. More...
 
dwEgomotionMeasurementParameters measurements
 Measurement parameters. More...
 
dwTransformation3f imuExtrinsics [DW_EGOMOTION_IMU_COUNT_MAX]
 IMU extrinsics, transformation from IMU coordinate frame to vehicle rig coordinate frame. Order must match the imuSensorIndices. More...
 
dwEgomotionIMUIntrinsics imuIntrinsics [DW_EGOMOTION_IMU_COUNT_MAX]
 IMU intrinsics. Leave 0 initialized if unknown. Order must match the imuSensorIndices. More...
 
size_t imuCount
 Number of IMUs used simultaneously, in range [1, DW_EGOMOTION_IMU_COUNT_MAX]. More...
 
uint32_t imuSensorIndices [DW_EGOMOTION_IMU_COUNT_MAX]
 Sensor Ids of used IMU sensors. Order must match for all IMU parameter specification arrays. More...
 
dwEgomotionSuspensionProperties suspension
 Suspension parameters. More...
 
size_t stateHistorySize
 Number of state estimates to keep in the history (if 0 specified default of 1000 is used). More...
 
dwEgomotionGroundSpeedMeasurementTypes groundSpeedType
 Indicates the source for ground speed. More...
 
dwEgomotionWheelObserverParameters wheelObserver
 Wheel observer parameters. More...
 
dwEgomotionVehicleMovingDirectionDetectorParameters vehicleMovingDirectionDetector
 Vehicle moving direction detector parameters. More...
 
dwEgomotionVMOParameters vehicleMotionObserver
 Vehicle motion observer parameters. More...
 
dwEgomotionErrorHandlingParameters errorHandling
 Error handling parameters. More...
 
dwEgomotionIMUAccBiasEstimatorParameters accBiasEstimator
 IMU accelerometer bias estimator parameters. More...
 
dwEgomotionIMUGyroBiasEstimatorParameters gyroBiasEstimator
 IMU gyroscope bias estimator parameters. More...
 
bool automaticUpdate
 Automatically update state estimation. More...
 
bool enableSuspensionSensorsUsage
 Enable usage of suspension sensor signals. More...
 

Field Documentation

◆ accBiasEstimator

dwEgomotionIMUAccBiasEstimatorParameters dwEgomotionParameters2::accBiasEstimator

IMU accelerometer bias estimator parameters.

Definition at line 368 of file Egomotion2.h.

◆ automaticUpdate

bool dwEgomotionParameters2::automaticUpdate

Automatically update state estimation.

In general to update motion estimation, a call to dwEgomotion_update is required. When automaticUpdate is set, the motion estimation update is triggered by the addition of new IMU data.

Note
when the automatic update is active, dwEgomotion_update will not update the filter state and throw a DW_NOT_SUPPORTED exception instead.

Definition at line 378 of file Egomotion2.h.

◆ enableSuspensionSensorsUsage

bool dwEgomotionParameters2::enableSuspensionSensorsUsage

Enable usage of suspension sensor signals.

Definition at line 381 of file Egomotion2.h.

◆ errorHandling

dwEgomotionErrorHandlingParameters dwEgomotionParameters2::errorHandling

Error handling parameters.

Definition at line 365 of file Egomotion2.h.

◆ groundSpeedType

dwEgomotionGroundSpeedMeasurementTypes dwEgomotionParameters2::groundSpeedType

Indicates the source for ground speed.

Definition at line 351 of file Egomotion2.h.

◆ gyroBiasEstimator

dwEgomotionIMUGyroBiasEstimatorParameters dwEgomotionParameters2::gyroBiasEstimator

IMU gyroscope bias estimator parameters.

Definition at line 371 of file Egomotion2.h.

◆ imuCount

size_t dwEgomotionParameters2::imuCount

Number of IMUs used simultaneously, in range [1, DW_EGOMOTION_IMU_COUNT_MAX].

Definition at line 339 of file Egomotion2.h.

◆ imuExtrinsics

dwTransformation3f dwEgomotionParameters2::imuExtrinsics[DW_EGOMOTION_IMU_COUNT_MAX]

IMU extrinsics, transformation from IMU coordinate frame to vehicle rig coordinate frame. Order must match the imuSensorIndices.

Definition at line 333 of file Egomotion2.h.

◆ imuIntrinsics

dwEgomotionIMUIntrinsics dwEgomotionParameters2::imuIntrinsics[DW_EGOMOTION_IMU_COUNT_MAX]

IMU intrinsics. Leave 0 initialized if unknown. Order must match the imuSensorIndices.

Definition at line 336 of file Egomotion2.h.

◆ imuSensorIndices

uint32_t dwEgomotionParameters2::imuSensorIndices[DW_EGOMOTION_IMU_COUNT_MAX]

Sensor Ids of used IMU sensors. Order must match for all IMU parameter specification arrays.

Definition at line 342 of file Egomotion2.h.

◆ measurements

dwEgomotionMeasurementParameters dwEgomotionParameters2::measurements

Measurement parameters.

Definition at line 330 of file Egomotion2.h.

◆ stateHistorySize

size_t dwEgomotionParameters2::stateHistorySize

Number of state estimates to keep in the history (if 0 specified default of 1000 is used).

Definition at line 348 of file Egomotion2.h.

◆ suspension

dwEgomotionSuspensionProperties dwEgomotionParameters2::suspension

Suspension parameters.

Definition at line 345 of file Egomotion2.h.

◆ vehicle

dwGenericVehicle dwEgomotionParameters2::vehicle

Vehicle parameters.

Definition at line 327 of file Egomotion2.h.

◆ vehicleMotionObserver

dwEgomotionVMOParameters dwEgomotionParameters2::vehicleMotionObserver

Vehicle motion observer parameters.

Definition at line 362 of file Egomotion2.h.

◆ vehicleMovingDirectionDetector

dwEgomotionVehicleMovingDirectionDetectorParameters dwEgomotionParameters2::vehicleMovingDirectionDetector

Vehicle moving direction detector parameters.

Unused if

Parameters
groundSpeedTypeis FROM_LINEAR_SPEED.

Definition at line 359 of file Egomotion2.h.

◆ wheelObserver

dwEgomotionWheelObserverParameters dwEgomotionParameters2::wheelObserver

Wheel observer parameters.

Unused if

Parameters
groundSpeedTypeis not FROM_WHEEL_TICKS_AND_SPEEDS.

Definition at line 355 of file Egomotion2.h.


The documentation for this struct was generated from the following file: