DriveWorks SDK Reference
5.14.77 Release
For Test and Development only

EgomotionTypes.h File Reference

Go to the source code of this file.

Data Structures

struct  dwEgomotionLinearAccelerationFilterParams
 Defines egomotion linear acceleration filter parameters. More...
 
struct  dwEgomotionParameters
 Holds initialization parameters for the Egomotion module. More...
 
struct  dwEgomotionRelativeUncertainty
 Holds egomotion uncertainty estimates for a relative motion estimate. More...
 
struct  dwEgomotionResult
 Holds egomotion state estimate. More...
 
struct  dwEgomotionSensorCharacteristics
 Sensor measurement noise characteristics. More...
 
struct  dwEgomotionSuspensionParameters
 Suspension model type and parameters. More...
 
struct  dwEgomotionUncertainty
 Holds egomotion uncertainty estimates. More...
 

Enumerations

enum  dwEgomotionDataField {
  DW_EGOMOTION_ROTATION = 1 << 0 ,
  DW_EGOMOTION_LIN_VEL_X = 1 << 1 ,
  DW_EGOMOTION_LIN_VEL_Y = 1 << 2 ,
  DW_EGOMOTION_LIN_VEL_Z = 1 << 3 ,
  DW_EGOMOTION_ANG_VEL_X = 1 << 4 ,
  DW_EGOMOTION_ANG_VEL_Y = 1 << 5 ,
  DW_EGOMOTION_ANG_VEL_Z = 1 << 6 ,
  DW_EGOMOTION_LIN_ACC_X = 1 << 7 ,
  DW_EGOMOTION_LIN_ACC_Y = 1 << 8 ,
  DW_EGOMOTION_LIN_ACC_Z = 1 << 9 ,
  DW_EGOMOTION_ANG_ACC_X = 1 << 10 ,
  DW_EGOMOTION_ANG_ACC_Y = 1 << 11 ,
  DW_EGOMOTION_ANG_ACC_Z = 1 << 12
}
 Defines flags that indicate validity of corresponding data in dwEgomotionResult and dwEgomotionUncertainty. More...
 
enum  dwEgomotionLinearAccelerationFilterMode {
  DW_EGOMOTION_ACC_FILTER_NO_FILTERING = 0 ,
  DW_EGOMOTION_ACC_FILTER_SIMPLE = 1
}
 Defines egomotion linear acceleration filter mode. More...
 
enum  dwEgomotionSpeedMeasurementType {
  DW_EGOMOTION_FRONT_SPEED = 0 ,
  DW_EGOMOTION_REAR_WHEEL_SPEED = 1 ,
  DW_EGOMOTION_REAR_SPEED = 2
}
 Defines speed measurement types. More...
 
enum  dwEgomotionSteeringMeasurementType {
  DW_EGOMOTION_FRONT_STEERING = 0 ,
  DW_EGOMOTION_STEERING_WHEEL_ANGLE = 1
}
 Defines steering measurement types. More...
 
enum  dwEgomotionSuspensionModel {
  DW_EGOMOTION_SUSPENSION_RIGID_MODEL = 0 ,
  DW_EGOMOTION_SUSPENSION_TORSIONAL_SPRING_MODEL = 1
}
 Defines egomotion suspension model. More...
 
enum  dwMotionModel {
  DW_EGOMOTION_ODOMETRY = 1 << 0 ,
  DW_EGOMOTION_IMU_ODOMETRY = (1 << 2) - 1
}
 Defines the motion models. More...
 
enum  dwMotionModelMeasurement {
  DW_EGOMOTION_MEASUREMENT_VELOCITY = 0 ,
  DW_EGOMOTION_MEASUREMENT_STEERINGANGLE = 1 ,
  DW_EGOMOTION_MEASUREMENT_STEERINGWHEELANGLE = 2
}
 Defines motion measurements. More...
 

Data Structure Documentation

◆ dwEgomotionLinearAccelerationFilterParams

struct dwEgomotionLinearAccelerationFilterParams
Data Fields
float32_t accelerationFilterTimeConst Simple filter parameters (ignored for other modes)

Time constant of the IMU acceleration measurements

float32_t measurementNoiseStdevAcceleration Standard deviation of measurement noise in acceleration [m/s^2].
float32_t measurementNoiseStdevSpeed Standard deviation of measurement noise in speed [m/s].
dwEgomotionLinearAccelerationFilterMode mode Linear acceleration filter mode. Default (0): no filtering.
float32_t processNoiseStdevAcceleration Square root of continuous time process noise covariance in acceleration [m/s^2 * 1/sqrt(s)].
float32_t processNoiseStdevSpeed Square root of continuous time process noise covariance in speed [m/s * 1/sqrt(s)].

◆ dwEgomotionParameters

struct dwEgomotionParameters
Data Fields
bool 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 sensor measurements. The exact update timestamp is dependent on the sensor type and motion model implementation.

Note
when the automatic update is active, dwEgomotion_update will not update the filter state and throw a DW_NOT_SUPPORTED exception instead.
bool estimateInitialOrientation When enabled, initial rotation will be estimated from accelerometer measurements.

When disabled, initial rotation is assumed to be identity, i.e. vehicle standing on flat, horizontal ground.

Note
only available for DW_EGOMOTION_IMU_ODOMETRY motion model. Ignored when DW_EGOMOTION_ODOMETRY is used.
float32_t gyroscopeBias[3] Initial gyroscope biases, if known at initialization time.

Gyroscope biases are estimated internally at run-time, however it can be beneficial if the filter is initialized with already known biases. If unknown, leave biases zero-initialized.

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

Also known as the capacity of the history. Any call to dwEgomotion_update, or automatic update, adds an estimate into the history.

dwTransformation3f imu2rig IMU extrinsics.

Transformation from the IMU coordinate system to the vehicle rig coordinate system.

Note
the quality of the estimated motion is highly depended on the accuracy of the extrinsics.
float32_t lateralSlipCoefficient Lateral slip coefficient [rad*s^2/m].

Used in linear function mapping lateral acceleration [m/s^2] to slip angle [rad], such that slipAngle = lateralSlipCoefficient * lateralAcceleration. If 0, default slip coefficient of -2.83e-3 [rad*s^2/m] is used.

Note
only available for DW_EGOMOTION_IMU_ODOMETRY motion model. Ignored when DW_EGOMOTION_ODOMETRY is used.
Deprecated:
Deriving lateral slip coefficient from vehicle parameters, unless this parameter is non-zero.
dwEgomotionLinearAccelerationFilterParams linearAccelerationFilterParameters Linear acceleration filter parameters.
Note
only available for DW_EGOMOTION_IMU_ODOMETRY motion model. Ignored when other motion models are used.
dwMotionModel motionModel Specifies the motion model to be used for pose estimation.
dwEgomotionSensorCharacteristics sensorParameters Sensor parameters, containing information about sensor characteristics.

If the struct is zero initialized, default assumptions about sensor parameters are made.

See also
dwEgomotionSensorCharacteristics
dwEgomotionSpeedMeasurementType speedMeasurementType Defines which velocity readings from dwVehicleIOState shall be used for egomotion estimation.
dwEgomotionSteeringMeasurementType steeringMeasurementType Defines which steering readings from dwVehicleIOState shall be used for egomotion estimation.
dwEgomotionSuspensionParameters suspension Suspension model parameters.

The model is used internally to compensate for vehicle body rotation due to acceleration and resulting rotational suspension effects. If the struct is zero initialized, suspension will not be modeled and accounted for.

Note
only available for DW_EGOMOTION_IMU_ODOMETRY motion model. Ignored when other motion models are used.
dwVehicle vehicle Vehicle parameters to setup the model.
Note
The validity of the parameters will be verified at initialization time and an error will be returned back if vehicle parameters are found to be not plausible.

◆ dwEgomotionRelativeUncertainty

struct dwEgomotionRelativeUncertainty
Data Fields
dwMatrix3f rotation a 3x3 covariance of the rotation (order: roll, pitch, yaw) [rad]
dwTime_t timeInterval relative motion time interval [us]
dwMatrix3f translation a 3x3 covariance of the translation (x,y,z) [m]
bool valid indicates whether uncertainty estimates are valid or not

◆ dwEgomotionResult

struct dwEgomotionResult
Data Fields
float32_t angularAcceleration[3] Angular acceleration measured in body frame in [rad/s^2].
float32_t angularVelocity[3] Rotation speed in body frame measured in [rad/s].
float32_t linearAcceleration[3] Linear acceleration measured in body frame in [m/s^2].
float32_t linearVelocity[3] Linear velocity in body frame measured in [m/s] at the origin. For motion models capable of estimating slip angle imposed lateral velocity, y component will be populated.
Note
this represents instanteneous linear velocity
dwQuaternionf rotation Rotation represented as quaternion (x,y,z,w). Valid when DW_EGOMOTION_ROTATION is set.
dwTime_t timestamp Timestamp of egomotion state estimate [us].
int32_t validFlags Bitwise combination of dwEgomotionDataField flags.

◆ dwEgomotionSensorCharacteristics

struct dwEgomotionSensorCharacteristics
Data Fields
float32_t accNoiseDensityMicroG Expected zero mean measurement noise of the linear accelerometer, also known as Noise Density [ug/sqrt(Hz)] A default value of 100 micro-g per sqrt(Hz) will be assumed if no parameter, i.e.

0 or nan, passed

float32_t gyroBiasRange If known this value in [rad/s] shall indicate standard deviation of the expected bias range of the gyroscope sensor.

Usually temperature controlled/calibrated gyroscopes vary around the mean by few tens of a radian. If 0 is given, it will be assumed the standard deviation around the bias mean is about +-0.05 [rad/s], ~ +- 3deg/s

float32_t gyroDriftRate Expected gyroscope drift rate in [deg/s].

A default value of 0.025 [deg/s] will be assumed if no parameter, i.e. 0 or nan, passed

float32_t gyroNoiseDensityDeg Expected zero mean measurement noise of the gyroscope, also known as Noise Density [deg/s/sqrt(Hz)] A default value of 0.015 [deg/s/sqrt(Hz)] will be assumed if no parameter, i.e.

0 or nan, passed

float32_t imuSamplingRateHz If known this entry shall indicate expected sampling rate in [Hz] of the IMU sensor.

A default value of 100Hz is used if no parameter passed

float32_t odometrySamplingRateHz If known this entry shall indicate expected sampling rate in [Hz] of the odometry signals.

This is used for detection of delays or missing vehicle signals (valid range: [33%, 300%] of below value). A default value of 50Hz is used if no parameter passed (valid range: [16.7Hz, 150Hz])

float32_t velocityFactor CAN velocity correction factor which is read from can properties in rig file.

When dwEgomotionParameters::speedMeasurementType == DW_EGOMOTION_FRONT_SPEED or DW_EGOMOTION_REAR_SPEED then received speed measurements are multiplied by this factor to obtain (approximately) true vehicle speed, e.g. due to non-nominal wheel diameters.

Note
A default value of 1 is assumed if no parameter is passed
dwTime_t velocityLatency CAN velocity latency in microseconds which is read from can properties in rig file.

◆ dwEgomotionSuspensionParameters

struct dwEgomotionSuspensionParameters
Data Fields
dwEgomotionSuspensionModel model Suspension model to use.

If left zero-intialized, a rigid suspension system is assumed (i.e. no suspension modeling).

float32_t torsionalSpringPitchDampingRatio Level of damping relative to critical damping around the pitch axis of the vehicle [dimensionless].

Typical passenger car suspension systems have a damping ratio in the range of [0.2, 0.6]. Default value is 0.6 if left zero-initialized.

float32_t torsionalSpringPitchNaturalFrequency Torsional spring model parameters.

Used if model == DW_EGOMOTION_SUSPENSION_TORSIONAL_SPRING_MODEL. If left zero-initizialized, a default set of parameters will be used.

These model parameters are suitable for a simple damped torsional spring model with external driving torque resulting from vehicle linear accelerations, described by the following ODE: \( I \ddot{\theta} + C \dot{\theta} + k \theta = \tau \)

where:

  • \( \theta \) suspension angle [rad]
  • I vehicle inertia around y axis [kg m^2]
  • C angular damping constant [J s rad^-1]
  • k torsion spring constant [N m rad^-1]
  • \( \tau \) driving torque [N m], function of linear acceleration, vehicle mass and height of center of mass.
Note
if selected, this model requires accurate vehicle mass, inertia and height of center of mass in the dwVehicle struct provided as part of the dwEgomotionParameters.

Frequency at which the suspension system tends to oscillate around the pitch axis of the vehicle in the absence of an external driving force or damping [Hz]. Typical passenger car suspension systems have a natural frequency in the range of [0.5, 1.5] Hz. Default value is 1.25Hz if left zero-initialized.

◆ dwEgomotionUncertainty

struct dwEgomotionUncertainty
Data Fields
float32_t angularAcceleration[3]
float32_t angularVelocity[3] Rotation speed std dev in body frame measured in [rad/s].
float32_t linearAcceleration[3] Linear acceleration std dev measured in body frame in [m/s^2].
float32_t linearVelocity[3] Linear velocity std dev in body frame measured in [m/s].
dwMatrix3f rotation Rotation covariance represented as euler angles (order: roll, pitch, yaw) in [rad^2].
dwTime_t timestamp Timestamp of egomotion uncertainty estimate [us].
int64_t validFlags Bitwise combination of dwEgomotionDataField flags.

Enumeration Type Documentation

◆ dwEgomotionDataField

Defines flags that indicate validity of corresponding data in dwEgomotionResult and dwEgomotionUncertainty.

Enumerator
DW_EGOMOTION_ROTATION 

indicates validity of rotation,

See also
limitations of selected dwMotionModel
DW_EGOMOTION_LIN_VEL_X 

indicates validity of linearVelocity[0]

DW_EGOMOTION_LIN_VEL_Y 

indicates validity of linearVelocity[1]

DW_EGOMOTION_LIN_VEL_Z 

indicates validity of linearVelocity[2]

DW_EGOMOTION_ANG_VEL_X 

indicates validity of angularVelocity[0]

DW_EGOMOTION_ANG_VEL_Y 

indicates validity of angularVelocity[1]

DW_EGOMOTION_ANG_VEL_Z 

indicates validity of angularVelocity[2]

DW_EGOMOTION_LIN_ACC_X 

indicates validity of linearAcceleration[0]

DW_EGOMOTION_LIN_ACC_Y 

indicates validity of linearAcceleration[1]

DW_EGOMOTION_LIN_ACC_Z 

indicates validity of linearAcceleration[2]

DW_EGOMOTION_ANG_ACC_X 

indicates validity of angularAcceleration[0]

DW_EGOMOTION_ANG_ACC_Y 

indicates validity of angularAcceleration[1]

DW_EGOMOTION_ANG_ACC_Z 

indicates validity of angularAcceleration[2]

Definition at line 192 of file EgomotionTypes.h.

◆ dwEgomotionLinearAccelerationFilterMode

Defines egomotion linear acceleration filter mode.

Enumerator
DW_EGOMOTION_ACC_FILTER_NO_FILTERING 

no filtering of the output linear acceleration

DW_EGOMOTION_ACC_FILTER_SIMPLE 

simple low-pass filtering of the acceleration

Definition at line 180 of file EgomotionTypes.h.

◆ dwEgomotionSpeedMeasurementType

Defines speed measurement types.

Enumerator
DW_EGOMOTION_FRONT_SPEED 

Indicates that speed is linear speed [m/s] measured at front wheels (along steering direction).

Steering angle [rad] is used internally to compute longitudinal speed.

  • Positive speed corresponds to a forward motion of the vehicle.
  • Positive steering angle corresponds to a left turn.
Note
: estimation quality is dependent on measurement accuracy, resolution and sampling rate. We recommend the following:
  • speed signal at >=50Hz sampling rate and resolution of 0.02 m/s or higher.
  • steering angle signal at >=50Hz sampling rate and resolution of 0.01 deg or higher.

Provide front speed measurement and steering angle with the dwEgomotion_addOdometry API, or with the dwEgomotion_addVehicleState API where the dwVehicleIOState struct contains speed, frontSteeringAngle, speedTimestamp and steeringTimestamp or with dwEgomotion_addVehicleIOState API where at least one of dwVehicleIOSafetyState, dwVehicleIONonSafetyState or dwVehicleIOActuationFeedback contain valid values of speed, frontSteeringAngle, speedTimestamp and frontSteeringTimestamp.

DW_EGOMOTION_REAR_WHEEL_SPEED 

Indicates that speeds are angular speeds [rad/s] measured at rear wheels.

  • Positive angular speeds correspond to a forward motion of the vehicle.
Note
This mode requires valid dwEgomotionParameters.dwVehicle.wheelRadius otherwise incorrect estimation of the longitudinal speed will be made.
It is expected that both rear wheel speed measurements are not far apart in time, otherwise degradation in estimation quality is expected.
: estimation quality is dependent on measurement accuracy, resolution and sampling rate. We recommend the following:
  • speed signal at >=50Hz sampling rate and resolution of 0.05 rad/s or higher.
: Egomotion supports steered rear axles.

Provide rear wheel speed measurements with the dwEgomotion_addVehicleState API where the dwVehicleIOState struct contains wheelSpeed and wheelSpeedTimestamp or with dwEgomotion_addVehicleIOState API where at least one of dwVehicleIOSafetyState, dwVehicleIONonSafetyState or dwVehicleIOActuationFeedback contain valid values of wheelSpeed and wheelTickTimestamp.

DW_EGOMOTION_REAR_SPEED 

Indicates that speed is linear speed [m/s] measured at rear axle center (along steering direction).

Rear steering angle [rad] given by dwVehicleIOState.rearWheelAngle is used internally to compute longitudinal speed.

  • Positive speed corresponds to a forward motion of the vehicle.
  • Positive steering angle corresponds to a lateral motion towards the left at the rear axle.
Note
: estimation quality is dependent on measurement accuracy, resolution and sampling rate. We recommend the following:
  • speed signal at >=50Hz sampling rate and resolution of 0.02 m/s or higher.

Provide rear speed measurement with the dwEgomotion_addVehicleState API where the dwVehicleIOState struct contains speed, rearWheelAngle and speedTimestamp or with dwEgomotion_addVehicleIOState API where at least one of dwVehicleIOSafetyState, dwVehicleIONonSafetyState or dwVehicleIOActuationFeedback contain valid values for speed, rearWheelAngle and speedTimestamp.

Definition at line 112 of file EgomotionTypes.h.

◆ dwEgomotionSteeringMeasurementType

Defines steering measurement types.

Enumerator
DW_EGOMOTION_FRONT_STEERING 
See also
dwVehicleIOState frontSteeringAngle
DW_EGOMOTION_STEERING_WHEEL_ANGLE 
See also
dwVehicleIOState steeringWheelAngle

Definition at line 174 of file EgomotionTypes.h.

◆ dwEgomotionSuspensionModel

Defines egomotion suspension model.

Enumerator
DW_EGOMOTION_SUSPENSION_RIGID_MODEL 

No suspension model. Equivalent to perfectly rigid suspension.

DW_EGOMOTION_SUSPENSION_TORSIONAL_SPRING_MODEL 

Models suspension as single-axis damped torsional spring.

Definition at line 186 of file EgomotionTypes.h.

◆ dwMotionModel

Defines the motion models.

Enumerator
DW_EGOMOTION_ODOMETRY 

Given odometry information, estimates motion of the vehicle using a bicycle model.

The following parameters are required for this model:

  • dwEgomotionParameters
    • vehicle
      • wheelbase, mass, inertia3D, frontCorneringStiffness, rearCorneringStiffness, centerOfMassToRearAxle, wheelRadius (1), steeringWheelToSteeringMap (2), maxSteeringWheelAngle (2), frontSteeringOffset (2)
    • speedMeasurementType

This model is capable of providing the following estimates:

Uncertainty estimates are not supported at this time.

DW_EGOMOTION_IMU_ODOMETRY 

Fuses odometry model with IMU measurements to estimate motion of the vehicle.

The following parameters are required for this model:

  • dwEgomotionParameters
    • vehicle
      • wheelRadius (1), steeringWheelToSteeringMap (2), maxSteeringWheelAngle (2), wheelbase (3, 4), mass (3, 4), centerOfMassHeight (3), inertia3D (3), centerOfMassToFrontAxle (4) rearCorneringStiffness (4)
    • imu2rig
    • speedMeasurementType

This model is capable of providing the following estimates:

Uncertainty estimates are provided for all state estimates listed above.

Definition at line 46 of file EgomotionTypes.h.

◆ dwMotionModelMeasurement

Defines motion measurements.

Enumerator
DW_EGOMOTION_MEASUREMENT_VELOCITY 

Vehicle velocity [m/s].

DW_EGOMOTION_MEASUREMENT_STEERINGANGLE 

Steering angle [rad].

DW_EGOMOTION_MEASUREMENT_STEERINGWHEELANGLE 

Steering wheel angle [rad].

Definition at line 105 of file EgomotionTypes.h.