NVIDIA DriveOS Linux NSR SDK API Reference

7.0.3.0 Release
Egomotion2.h File Reference

Go to the source code of this file.

Data Structures

struct  dwEgomotionMeasurementParameters
 Egomotion measurement parameters. More...
 
struct  dwEgomotionVMOParameters
 Vehicle motion observer parameters. More...
 
struct  dwEgomotionWheelObserverParameters
 Wheel observer parameters. More...
 
struct  dwEgomotionVehicleMovingDirectionDetectorParameters
 Vehicle moving direction detection parameters. More...
 
struct  dwEgomotionIMUIntrinsics
 IMU intrinsic parameters. More...
 
struct  dwEgomotionSuspensionProperties
 Suspension properties. More...
 
struct  dwEgomotionParameters2
 Egomotion parameters. More...
 

Typedefs

typedef enum dwEgomotionMeasurementTypes dwEgomotionMeasurementTypes
 Measurements used by egomotion. More...
 
typedef enum dwEgomotionGroundSpeedMeasurementTypes dwEgomotionGroundSpeedMeasurementTypes
 Ground speed measurement types. More...
 
typedef enum dwEgomotionDirectionMode dwEgomotionDirectionMode
 Vehicle direction detection modes. More...
 
typedef struct dwEgomotionMeasurementParameters dwEgomotionMeasurementParameters
 Egomotion measurement parameters. More...
 
typedef struct dwEgomotionVMOParameters dwEgomotionVMOParameters
 Vehicle motion observer parameters. More...
 
typedef struct dwEgomotionWheelObserverParameters dwEgomotionWheelObserverParameters
 Wheel observer parameters. More...
 
typedef struct dwEgomotionVehicleMovingDirectionDetectorParameters dwEgomotionVehicleMovingDirectionDetectorParameters
 Vehicle moving direction detection parameters. More...
 
typedef struct dwEgomotionIMUIntrinsics dwEgomotionIMUIntrinsics
 IMU intrinsic parameters. More...
 
typedef struct dwEgomotionSuspensionProperties dwEgomotionSuspensionProperties
 Suspension properties. More...
 
typedef struct dwEgomotionParameters2 dwEgomotionParameters2
 Egomotion parameters. More...
 

Enumerations

enum  dwEgomotionMeasurementTypes {
  DW_EGOMOTION_MEASUREMENT_STEERING = 0,
  DW_EGOMOTION_MEASUREMENT_SUSPENSION = 1,
  DW_EGOMOTION_MEASUREMENT_ANGULAR_ACCELERATION = 2,
  DW_EGOMOTION_MEASUREMENT_PROPER_ACCELERATION = 3,
  DW_EGOMOTION_MEASUREMENT_ANGULAR_VELOCITY = 4,
  DW_EGOMOTION_MEASUREMENT_LINEAR_GROUND_SPEED = 5,
  DW_EGOMOTION_MEASUREMENT_LINEAR_BODY_SPEED = 6,
  DW_EGOMOTION_MEASUREMENT_WHEEL_TICKS = 7,
  DW_EGOMOTION_MEASUREMENT_WHEEL_SPEEDS = 8,
  DW_EGOMOTION_MEASUREMENT_TRAILER_ANGLE = 9,
  DW_EGOMOTION_MEASUREMENT_TYPES_COUNT
}
 Measurements used by egomotion. More...
 
enum  dwEgomotionGroundSpeedMeasurementTypes {
  DW_EGOMOTION_GROUND_SPEED_FROM_WHEEL_SPEEDS_REAR_AXLE = 0,
  DW_EGOMOTION_GROUND_SPEED_FROM_WHEEL_SPEEDS_BOTH_AXLES = 1,
  DW_EGOMOTION_GROUND_SPEED_FROM_WHEEL_TICKS_AND_SPEEDS_REAR_AXLE = 2,
  DW_EGOMOTION_GROUND_SPEED_FROM_WHEEL_TICKS_AND_SPEEDS_BOTH_AXLES = 3,
  DW_EGOMOTION_GROUND_SPEED_FROM_LINEAR_SPEED = 4,
  DW_EGOMOTION_GROUND_SPEED_COUNT
}
 Ground speed measurement types. More...
 
enum  dwEgomotionDirectionMode {
  DW_EGOMOTION_DIRECTION_FROM_SPEED_SIGN = 0,
  DW_EGOMOTION_DIRECTION_FROM_WHEEL_DIR_AND_GEAR = 1,
  DW_EGOMOTION_DIRECTION_FROM_SPEED_SIGN_AND_GEAR = 2,
  DW_EGOMOTION_DIRECTION_COUNT
}
 Vehicle direction detection modes. More...
 

Functions

DW_API_PUBLIC dwStatus dwEgomotion2_initParamsFromRig (dwEgomotionParameters2 *params, dwConstRigHandle_t rigConfiguration, char const *imu1Name, char const *imu2Name, char const *imu3Name)
 Initializes the egomotion parameters to sane defaults given vehicle configuration. More...
 
DW_API_PUBLIC dwStatus dwEgomotion2_initDefaultParams (dwEgomotionParameters2 *params)
 Initializes the egomotion parameters to sane defaults applicable to most vehicles. More...
 
DW_API_PUBLIC dwStatus dwEgomotion2_initParamsFromRigByIndex (dwEgomotionParameters2 *params, dwConstRigHandle_t rigConfiguration, uint32_t const imu1Index, uint32_t const imu2Index, uint32_t const imu3Index)
 Initializes the egomotion parameters to sane defaults given vehicle configuration. More...
 
DW_API_PUBLIC dwStatus dwEgomotion2_initialize (dwEgomotionHandle_t *const obj, dwEgomotionParameters2 const *params, dwContextHandle_t const ctx)
 Initializes the egomotion 2.0 module. More...
 
DW_API_PUBLIC dwStatus dwEgomotion2_initializeState (dwEgomotionStateHandle_t *state, size_t const historySize, dwContextHandle_t ctx)
 Initializes an instance of the egomotion 2.0 state history. More...
 
DW_API_PUBLIC dwStatus dwEgomotion2_getAccelerometerBias (dwVector3f *accBias, dwEgomotionConstHandle_t obj)
 Get estimated accelerometer bias of the BASE IMU. More...
 
DW_API_PUBLIC dwStatus dwEgomotion2_getAccelerometerBiasByIndex (dwVector3f *accBias, uint32_t const sensorIndex, dwEgomotionConstHandle_t obj)
 Get estimated accelerometer bias of a specific IMU. More...
 

Typedef Documentation

◆ dwEgomotionDirectionMode

Vehicle direction detection modes.

Egomotion can estimate the vehicle moving direction from different sources depending on vehicle platform capabilities.

Select DW_EGOMOTION_DIRECTION_FROM_SPEED_SIGN if the wheel tick increments and wheel speeds are signed, indicating forward and reverse driving unambiguously.

Select DW_EGOMOTION_DIRECTION_FROM_WHEEL_DIR_AND_GEAR if the wheel tick increments and wheel speeds are unsigned, such that forward and reverse driving cannot be distinguished from these signals alone.

Select DW_EGOMOTION_DIRECTION_FROM_SPEED_SIGN_AND_GEAR if the wheel tick increments and wheel speeds are signed with ambiguous region around 0 to be resolved based on target gear and current gear signals. dwEgomotionVehicleMovingDirectionDetectorParameters::ticksAmbiguousSpeedThreshold

The default configuration for production platforms is DW_EGOMOTION_DIRECTION_FROM_WHEEL_DIR_AND_GEAR.

◆ dwEgomotionGroundSpeedMeasurementTypes

Ground speed measurement types.

Egomotion can estimate vehicle ground speed from different sources depending on vehicle platform capabilities.

The default configuration for production platforms is DW_EGOMOTION_GROUND_SPEED_FROM_WHEEL_TICKS_AND_SPEEDS_BOTH_AXLES.

◆ dwEgomotionIMUIntrinsics

IMU intrinsic parameters.

◆ dwEgomotionMeasurementParameters

Egomotion measurement parameters.

◆ dwEgomotionMeasurementTypes

Measurements used by egomotion.

◆ dwEgomotionParameters2

Egomotion parameters.

All parameters are required unless otherwise noted.

◆ dwEgomotionSuspensionProperties

◆ dwEgomotionVehicleMovingDirectionDetectorParameters

Vehicle moving direction detection parameters.

Used to inform egomotion on the moving direction of the vehicle.

◆ dwEgomotionVMOParameters

Vehicle motion observer parameters.

◆ dwEgomotionWheelObserverParameters

Enumeration Type Documentation

◆ dwEgomotionDirectionMode

Vehicle direction detection modes.

Egomotion can estimate the vehicle moving direction from different sources depending on vehicle platform capabilities.

Select DW_EGOMOTION_DIRECTION_FROM_SPEED_SIGN if the wheel tick increments and wheel speeds are signed, indicating forward and reverse driving unambiguously.

Select DW_EGOMOTION_DIRECTION_FROM_WHEEL_DIR_AND_GEAR if the wheel tick increments and wheel speeds are unsigned, such that forward and reverse driving cannot be distinguished from these signals alone.

Select DW_EGOMOTION_DIRECTION_FROM_SPEED_SIGN_AND_GEAR if the wheel tick increments and wheel speeds are signed with ambiguous region around 0 to be resolved based on target gear and current gear signals. dwEgomotionVehicleMovingDirectionDetectorParameters::ticksAmbiguousSpeedThreshold

The default configuration for production platforms is DW_EGOMOTION_DIRECTION_FROM_WHEEL_DIR_AND_GEAR.

Enumerator
DW_EGOMOTION_DIRECTION_FROM_SPEED_SIGN 

Vehicle Moving Direction based on signed wheel encoder information.

DW_EGOMOTION_DIRECTION_FROM_WHEEL_DIR_AND_GEAR 

Vehicle Moving Direction based on unsigned wheel encoder, wheel direction and gear information.

DW_EGOMOTION_DIRECTION_FROM_SPEED_SIGN_AND_GEAR 

Vehicle Moving Direction based on signed wheel encoder and gear information.

DW_EGOMOTION_DIRECTION_COUNT 

Definition at line 117 of file Egomotion2.h.

◆ dwEgomotionGroundSpeedMeasurementTypes

Ground speed measurement types.

Egomotion can estimate vehicle ground speed from different sources depending on vehicle platform capabilities.

The default configuration for production platforms is DW_EGOMOTION_GROUND_SPEED_FROM_WHEEL_TICKS_AND_SPEEDS_BOTH_AXLES.

Enumerator
DW_EGOMOTION_GROUND_SPEED_FROM_WHEEL_SPEEDS_REAR_AXLE 

Ground speed from wheel speeds only rear axle (Wheel observer is disabled)

DW_EGOMOTION_GROUND_SPEED_FROM_WHEEL_SPEEDS_BOTH_AXLES 

Ground speed from wheel speeds only both axle (Wheel observer is disabled)

DW_EGOMOTION_GROUND_SPEED_FROM_WHEEL_TICKS_AND_SPEEDS_REAR_AXLE 

Ground speed from wheel ticks and speeds rear axle (Wheel observer is enabled)

DW_EGOMOTION_GROUND_SPEED_FROM_WHEEL_TICKS_AND_SPEEDS_BOTH_AXLES 

Ground speed from wheel ticks and speeds both axles (Wheel observer is enabled)

DW_EGOMOTION_GROUND_SPEED_FROM_LINEAR_SPEED 

Ground speed from signed vehicle linear speed at rear axle center (Wheel observer is disabled)

DW_EGOMOTION_GROUND_SPEED_COUNT 

Definition at line 84 of file Egomotion2.h.

◆ dwEgomotionMeasurementTypes

Measurements used by egomotion.

Enumerator
DW_EGOMOTION_MEASUREMENT_STEERING 
See also
dwVehicleIOState steering
DW_EGOMOTION_MEASUREMENT_SUSPENSION 
See also
dwVehicleIOState suspension
DW_EGOMOTION_MEASUREMENT_ANGULAR_ACCELERATION 

IMU angular acceleration [rad/s^2].

DW_EGOMOTION_MEASUREMENT_PROPER_ACCELERATION 
See also
dwIMUFrame acceleration
DW_EGOMOTION_MEASUREMENT_ANGULAR_VELOCITY 
See also
dwIMUFrame turnrate
DW_EGOMOTION_MEASUREMENT_LINEAR_GROUND_SPEED 
See also
dwVehicleIOState speeds
DW_EGOMOTION_MEASUREMENT_LINEAR_BODY_SPEED 

Linear body speed [m/s].

DW_EGOMOTION_MEASUREMENT_WHEEL_TICKS 
DW_EGOMOTION_MEASUREMENT_WHEEL_SPEEDS 
See also
dwVehicleIOState wheelTicks
DW_EGOMOTION_MEASUREMENT_TRAILER_ANGLE 
See also
dwVehicleIOState wheelSpeeds
DW_EGOMOTION_MEASUREMENT_TYPES_COUNT 
See also
dwVehicleIOState articulationAngle

Definition at line 61 of file Egomotion2.h.

Function Documentation

◆ dwEgomotion2_getAccelerometerBias()

DW_API_PUBLIC dwStatus dwEgomotion2_getAccelerometerBias ( dwVector3f accBias,
dwEgomotionConstHandle_t  obj 
)

Get estimated accelerometer bias of the BASE IMU.

See also
dwEgomotionIMUIdentifier.
Parameters
[in,out]accBiasPointer to dwVector3f to be filled with accelerometer biases [m/s^2].
[in]objEgomotion handle.
Returns
DW_INVALID_ARGUMENT - if the provided egomotion handle is invalid.
DW_NOT_SUPPORTED - if the given egomotion handle does not support the request
DW_NOT_READY - if the online estimation is not ready yet but an initial bias guess is available
DW_NOT_AVAILABLE - if the online estimation is not ready yet and no initial bias guess is available
DW_SUCCESS - if online accelerometer bias estimation has accepted a value
API Group
  • Init: Yes
  • Runtime: Yes
  • De-Init: Yes

◆ dwEgomotion2_getAccelerometerBiasByIndex()

DW_API_PUBLIC dwStatus dwEgomotion2_getAccelerometerBiasByIndex ( dwVector3f accBias,
uint32_t const  sensorIndex,
dwEgomotionConstHandle_t  obj 
)

Get estimated accelerometer bias of a specific IMU.

Parameters
[in,out]accBiasPointer to dwVector3f to be filled with accelerometer biases [m/s^2].
[in]sensorIndexIdentifier of IMU to get bias for
[in]objEgomotion handle.
Returns
DW_INVALID_ARGUMENT - if the provided egomotion handle is invalid or the sensorIndex is not in use.
DW_NOT_SUPPORTED - if the given egomotion handle does not support the request
DW_NOT_READY - if the online estimation is not ready yet but an initial bias guess is available
DW_NOT_AVAILABLE - if the online estimation is not ready yet and no initial bias guess is available
DW_SUCCESS - if online accelerometer bias estimation has accepted a value
API Group
  • Init: Yes
  • Runtime: Yes
  • De-Init: Yes

◆ dwEgomotion2_initDefaultParams()

DW_API_PUBLIC dwStatus dwEgomotion2_initDefaultParams ( dwEgomotionParameters2 params)

Initializes the egomotion parameters to sane defaults applicable to most vehicles.

This API does not set the required vehicle-specific parameters which must be provided separately.

See also dwEgomotion2_initParamsFromRig

Parameters
[in,out]paramsA pointer to the egomotion parameters to be filled out.
Returns
DW_INVALID_ARGUMENT - if provided arguments are invalid.
DW_SUCCESS - if the egomotion parameters have been set successfully.
API Group
  • Init: Yes
  • Runtime: No
  • De-Init: No

◆ dwEgomotion2_initialize()

DW_API_PUBLIC dwStatus dwEgomotion2_initialize ( dwEgomotionHandle_t *const  obj,
dwEgomotionParameters2 const *  params,
dwContextHandle_t const  ctx 
)

Initializes the egomotion 2.0 module.

Instantiates the subfunctions composing the overall module and allocates memory for their operation. Configuration of the module is provided by the params argument. Default parameters can be obtained from the dwEgomotion2_initParamsFromRig function.

Parameters
[in,out]objA pointer to the egomotion handle to be set for the created module.
[in]paramsA pointer to the configuration parameters of the module.
[in]ctxSpecifies the handler to the context under which the Egomotion module is created.
Returns
DW_INVALID_ARGUMENT - if provided egomotion handle or parameters are invalid.
DW_INVALID_HANDLE - if the provided DriveWorks context handle is invalid.
DW_SUCCESS - if the initialization is successful.
API Group
  • Init: Yes
  • Runtime: No
  • De-Init: No

◆ dwEgomotion2_initializeState()

DW_API_PUBLIC dwStatus dwEgomotion2_initializeState ( dwEgomotionStateHandle_t state,
size_t const  historySize,
dwContextHandle_t  ctx 
)

Initializes an instance of the egomotion 2.0 state history.

This empty state history instance can be used to deserialize from a binary representation of the state. After deserialization state can be queried with state API for it's content. The state can contain internally a history of up-to passed amount of elements.

Parameters
[out]stateHandle to be set with pointer to created empty state.
[in]historySizeState history size (maximum capacity). If left 0, a default size of 1000 is used.
[in]ctxHandle of the context.
Returns
DW_INVALID_ARGUMENT - if given state handle is null
DW_INVALID_HANDLE - if context handle is invalid
DW_SUCCESS - if the call was successful.
Note
Ownership of the state goes back to caller. The state has to be released with dwEgomotionState_release.
If passed historySize is smaller than the egomotion internal history capacity, any retrieval of the state with dwEgomotion_getState will fill out this state's only with as much data as can fit, dropping oldest entries. This in turn would mean that calls to dwEgomotionState_computeRelativeTransformation might not succeed if requested for timestamp outside of the covered history.
API Group
  • Init: Yes
  • Runtime: No
  • De-Init: No

◆ dwEgomotion2_initParamsFromRig()

DW_API_PUBLIC dwStatus dwEgomotion2_initParamsFromRig ( dwEgomotionParameters2 params,
dwConstRigHandle_t  rigConfiguration,
char const *  imu1Name,
char const *  imu2Name,
char const *  imu3Name 
)

Initializes the egomotion parameters to sane defaults given vehicle configuration.

This API is used to initialize parameters for egomotion 2.0.

Parameters
[in,out]paramsA pointer to the egomotion parameters to be filled out.
[in]rigConfigurationA pointer to the vehicle rig configuration.
[in]imu1NameName of first IMU sensor as it appears in rig configuration.
[in]imu2NameName of second IMU sensor as it appears in rig configuration. Optional, can be left null (1) (2).
[in]imu3NameName of third IMU sensor as it appears in rig configuration. Optional, can be left null (1).
Note
(1) will default to egomotion parameters section in rig configuration.
(2) cannot be skipped if imu3Name is specified.
Returns
DW_INVALID_ARGUMENT - if provided arguments are invalid.
DW_FILE_INVALID - if the provided rig is invalid.
DW_SUCCESS - if the egomotion parameters have been set successfully.
API Group
  • Init: Yes
  • Runtime: No
  • De-Init: No

◆ dwEgomotion2_initParamsFromRigByIndex()

DW_API_PUBLIC dwStatus dwEgomotion2_initParamsFromRigByIndex ( dwEgomotionParameters2 params,
dwConstRigHandle_t  rigConfiguration,
uint32_t const  imu1Index,
uint32_t const  imu2Index,
uint32_t const  imu3Index 
)

Initializes the egomotion parameters to sane defaults given vehicle configuration.

This API is used to initialize parameters for egomotion 2.0.

Parameters
[in,out]paramsA pointer to the egomotion parameters to be filled out.
[in]rigConfigurationA pointer to the vehicle rig configuration.
[in]imu1IndexIndex of first IMU sensor as it appears in rig configuration.
[in]imu2IndexIndex of second IMU sensor as it appears in rig configuration. Optional, can be set to UINT32_MAX (1) (2).
[in]imu3IndexIndex of third IMU sensor as it appears in rig configuration. Optional, can be set to UINT32_MAX (1).
Note
(1) will default to egomotion parameters section in rig configuration.
(2) cannot be skipped if imu3Index is specified.
Returns
DW_INVALID_ARGUMENT - if provided arguments are invalid.
DW_FILE_INVALID - if the provided rig is invalid.
DW_SUCCESS - if the egomotion parameters have been set successfully.
API Group
  • Init: Yes
  • Runtime: No
  • De-Init: No