DriveWorks SDK Reference
5.14.77 Release
For Test and Development only

Egomotion Interface

Detailed Description

Provides vehicle egomotion functionality.

The egomotion module provides implementations of motion models with different sensor modalities. Starting from a simple Ackerman-based odometry-only model, to a full-fledged fusion of inertial sensor information.

This module provides access to a history of motion estimates with a predefined cadence and length. At any point of time an access into the history can be made to retrieve previous estimates. The access into the history is timestamp-based. If an access falls between two history entries it will be interpolated.

In addition to history-based access, all motion models support prediction of the motion into the future.

Modules

 API
 Defines additional related API.
 
 Global Egomotion Interface
 Provides global location and orientation estimation functionality.
 
 Producer/State API
 Defines producer/state related API.
 
 RadarDopplerMotion Interface
 Provides estimation of the speed and heading of the radar observing doppler based radar measurements.
 

Typedefs

typedef struct dwEgomotionObject const * dwEgomotionConstHandle_t
 Const Egomotion Handle. More...
 
typedef struct dwEgomotionObject * dwEgomotionHandle_t
 Egomotion Handle. More...
 

Functions

DW_API_PUBLIC dwStatus dwEgomotion_addIMUMeasurement (const dwIMUFrame *imu, dwEgomotionHandle_t obj)
 Adds an IMU frame to the egomotion module. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_addOdometry (dwMotionModelMeasurement measuredType, float32_t measuredValue, dwTime_t timestamp, dwEgomotionHandle_t obj)
 Notifies the egomotion module of a new odometry measurement. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_addVehicleIOState (dwVehicleIOSafetyState const *safeState, dwVehicleIONonSafetyState const *nonSafeState, dwVehicleIOActuationFeedback const *actuationFeedback, dwEgomotionHandle_t obj)
 Notifies the egomotion module of a changed vehicle state. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_addVehicleState (const dwVehicleIOState *state, dwEgomotionHandle_t obj)
 Notifies the egomotion module of a changed vehicle state. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_applyRelativeTransformation (dwTransformation3f *vehicleToWorldAtB, const dwTransformation3f *vehicleAToB, const dwTransformation3f *vehicleToWorldAtA)
 Applies the estimated relative motion as returned by dwEgomotion_computeRelativeTransformation to a given vehicle pose. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_computeBodyTransformation (dwTransformation3f *const transformationAToB, dwEgomotionRelativeUncertainty *const uncertainty, dwTime_t const timestamp, dwCoordinateSystem const coordinateSystemA, dwCoordinateSystem const coordinateSystemB, dwEgomotionConstHandle_t const obj)
 Compute the transformation between two coordinate systems at a specific timestamp and the uncertainty of this transform. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_computeRelativeTransformation (dwTransformation3f *poseAtoB, dwEgomotionRelativeUncertainty *uncertainty, dwTime_t timestamp_a, dwTime_t timestamp_b, dwEgomotionConstHandle_t obj)
 Computes the relative transformation between two timestamps and the uncertainty of this transform. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_computeSteeringAngleFromIMU (float32_t *steeringAngle, float32_t *inverseSteeringR, const dwIMUFrame *imuMeasurement, dwEgomotionConstHandle_t obj)
 Computes steering angle of the vehicle based on IMU measurement. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_estimate (dwEgomotionResult *pose, dwEgomotionUncertainty *uncertainty, dwTime_t timestamp_us, dwEgomotionConstHandle_t obj)
 Estimates the state for a given timestamp. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_getEstimation (dwEgomotionResult *result, dwEgomotionConstHandle_t obj)
 Gets the latest state estimate. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_getEstimationTimestamp (dwTime_t *timestamp, dwEgomotionConstHandle_t obj)
 Gets the timestamp of the latest state estimate. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_getGyroscopeBias (dwVector3f *gyroBias, dwEgomotionConstHandle_t obj)
 Get estimated gyroscope bias. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_getHistoryElement (dwEgomotionResult *pose, dwEgomotionUncertainty *uncertainty, size_t index, dwEgomotionConstHandle_t obj)
 Returns an element from the motion history that is currently available. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_getHistorySize (size_t *size, dwEgomotionConstHandle_t obj)
 Returns the number of elements currently stored in the history. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_getMotionModel (dwMotionModel *model, dwEgomotionConstHandle_t obj)
 Returns the type of the motion model used. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_getUncertainty (dwEgomotionUncertainty *result, dwEgomotionConstHandle_t obj)
 Gets the latest state estimate uncertainties. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_hasEstimation (bool *result, dwEgomotionConstHandle_t obj)
 Check whether estimation is available. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_initialize (dwEgomotionHandle_t *obj, const dwEgomotionParameters *params, dwContextHandle_t ctx)
 Initializes the egomotion module. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_initParamsFromRig (dwEgomotionParameters *params, dwConstRigHandle_t rigConfiguration, const char *imuSensorName, const char *vehicleSensorName)
 Initialize egomotion parameters from a provided RigConfiguration. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_initParamsFromRigByIndex (dwEgomotionParameters *params, dwConstRigHandle_t rigConfiguration, uint32_t imuSensorIdx, uint32_t vehicleSensorIdx)
 Same as dwEgomotion_initParamsFromRig however uses sensor indices in rigConfiguration instead of their names. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_release (dwEgomotionHandle_t obj)
 Releases the egomotion module. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_reset (dwEgomotionHandle_t obj)
 Resets the state estimate and all history of the egomotion module. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_steeringAngleToSteeringWheelAngle (float32_t *steeringWheelAngle, float32_t steeringAngle, dwEgomotionHandle_t obj)
 Convert steering angle to steering wheel angle. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_steeringWheelAngleToSteeringAngle (float32_t *steeringAngle, float32_t steeringWheelAngle, dwEgomotionHandle_t obj)
 Convert steering wheel angle to steering angle. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_update (dwTime_t timestamp_us, dwEgomotionHandle_t obj)
 Runs the motion model estimation for a given timestamp. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_updateIMUExtrinsics (const dwTransformation3f *imuToRig, dwEgomotionHandle_t obj)
 This method updates the IMU extrinsics to convert from the IMU coordinate system to the vehicle rig coordinate system. More...
 
DW_API_PUBLIC dwStatus dwEgomotion_updateVehicle (const dwVehicle *vehicle, dwEgomotionHandle_t obj)
 This method updates the egomotion module with an updated vehicle. More...
 

Typedef Documentation

◆ dwEgomotionConstHandle_t

typedef struct dwEgomotionObject const* dwEgomotionConstHandle_t

Const Egomotion Handle.

Alias for pointer to const egomotion instance.

Definition at line 88 of file Egomotion.h.

◆ dwEgomotionHandle_t

typedef struct dwEgomotionObject* dwEgomotionHandle_t

Egomotion Handle.

Alias for pointer to egomotion instance.

Definition at line 83 of file Egomotion.h.

Function Documentation

◆ dwEgomotion_addIMUMeasurement()

DW_API_PUBLIC dwStatus dwEgomotion_addIMUMeasurement ( const dwIMUFrame imu,
dwEgomotionHandle_t  obj 
)

Adds an IMU frame to the egomotion module.

The IMU frame shall contain either linear acceleration or angular velocity measurements for X, Y and Z axes or both at once; the frame will be discarded otherwise.

Egomotion might generate a new estimate on addition of IMU frame, see dwEgomotionParameters::automaticUpdate.

Parameters
[in]imuIMU measurement.
[in]objEgomotion handle.
Returns
DW_INVALID_ARGUMENT - if timestamp is not greater than last measurement timestamp, or given frame is invalid.
DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_NOT_SUPPORTED - if the given measurement is not supported by the egomotion model.
DW_SUCCESS - if the IMU data has been passed to egomotion successfully.

◆ dwEgomotion_addOdometry()

DW_API_PUBLIC dwStatus dwEgomotion_addOdometry ( dwMotionModelMeasurement  measuredType,
float32_t  measuredValue,
dwTime_t  timestamp,
dwEgomotionHandle_t  obj 
)

Notifies the egomotion module of a new odometry measurement.

The following odometry measurements are required:

  • DW_EGOMOTION_MEASUREMENT_VELOCITY and
  • DW_EGOMOTION_MEASUREMENT_STEERINGANGLE or DW_EGOMOTION_MEASUREMENT_STEERINGWHEELANGLE
Note
measurement timestamp must be strictly increasing; i.e. take place after the previous measurement timestamp.
Parameters
[in]measuredTypeType of measurement. For example: velocity, steering angle.
[in]measuredValueValue that was measured. For example: 3.6 m/s, 0.1 rad.
[in]timestampTimestamp for the measurement.
[in]objEgomotion handle.
Returns
DW_INVALID_ARGUMENT - if timestamp is not greater than last measurement timestamp, measuredType is not valid, or measuredValue is not finite.
DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_NOT_SUPPORTED - if odometry measurements are not supported by the egomotion model or if egomotion speedMeasurementType is not DW_EGOMOTION_FRONT_SPEED.
DW_SUCCESS - if data was added succesfully.
Note
When velocity is passed to this module, it is assumed the velocity is measured on front wheels in the steering direction. See dwEgomotionSpeedMeasurementType::DW_EGOMOTION_FRONT_SPEED

◆ dwEgomotion_addVehicleIOState()

DW_API_PUBLIC dwStatus dwEgomotion_addVehicleIOState ( dwVehicleIOSafetyState const *  safeState,
dwVehicleIONonSafetyState const *  nonSafeState,
dwVehicleIOActuationFeedback const *  actuationFeedback,
dwEgomotionHandle_t  obj 
)

Notifies the egomotion module of a changed vehicle state.

In case relevant new information is contained in this state then it gets consumed, otherwise state is ignored.

Signals consumed depend on the selected egomotion motion model,

See also
dwMotionModel.

When using DW_EGOMOTION_ODOMETRY, the following valid signals in at least one of the structs dwVehicleIOSafetyState, dwVehicleIONonSafetyState or dwVehicleIOActuationFeedback are required:

When using DW_EGOMOTION_IMU_ODOMETRY, the following valid signals in at least one of the structs dwVehicleIOSafetyState, dwVehicleIONonSafetyState or dwVehicleIOActuationFeedback are required:

Parameters
[in]safeStateNew dwVehicleIOSafetyState which contains potentially new information for egomotion consumption
[in]nonSafeStateNew dwVehicleIONonSafetyState which contains potentially new information for egomotion consumption
[in]actuationFeedbackNew dwVehicleIOActuationFeedback which contains potentially new information for egomotion consumption
[in]objEgomotion handle.
Returns
DW_INVALID_HANDLE - if provided, the egomotion handle is invalid.
DW_NOT_SUPPORTED - if underlying egomotion handle does not support vehicle state.
DW_SUCCESS - if vehicle state has been passed to egomotion successfully.

◆ dwEgomotion_addVehicleState()

DW_API_PUBLIC dwStatus dwEgomotion_addVehicleState ( const dwVehicleIOState state,
dwEgomotionHandle_t  obj 
)

Notifies the egomotion module of a changed vehicle state.

In case relevant new information is contained in this state then it gets consumed, otherwise state is ignored.

Signals consumed depend on the selected egomotion motion model,

See also
dwMotionModel.

When using DW_EGOMOTION_ODOMETRY:

When using DW_EGOMOTION_IMU_ODOMETRY:

Parameters
[in]stateNew VehicleIOState which contains potentially new information for egomotion consumption
[in]objEgomotion handle.
Returns
DW_INVALID_HANDLE - if provided, the egomotion handle is invalid.
DW_NOT_SUPPORTED - if underlying egomotion handle does not support vehicle state.
DW_SUCCESS - if vehicleIOState has been consumed successfully.
Note
Deprecation warning: This method has been replaced with dwEgomotion_addVehicleIOState, and will be removed in next major release.

◆ dwEgomotion_applyRelativeTransformation()

DW_API_PUBLIC dwStatus dwEgomotion_applyRelativeTransformation ( dwTransformation3f vehicleToWorldAtB,
const dwTransformation3f vehicleAToB,
const dwTransformation3f vehicleToWorldAtA 
)

Applies the estimated relative motion as returned by dwEgomotion_computeRelativeTransformation to a given vehicle pose.

Parameters
[out]vehicleToWorldAtBTransformation to be filled with pose of the vehicle in world at time B.
[in]vehicleAToBTransformation providing motion of vehicle from time A to time B.
[in]vehicleToWorldAtATransformation providing pose of the vehicle in world at time A.
Returns
DW_INVALID_ARGUMENT - if any of the given arguments is nullptr
DW_SUCCESS - if the call was successful.

◆ dwEgomotion_computeBodyTransformation()

DW_API_PUBLIC dwStatus dwEgomotion_computeBodyTransformation ( dwTransformation3f *const  transformationAToB,
dwEgomotionRelativeUncertainty *const  uncertainty,
dwTime_t const  timestamp,
dwCoordinateSystem const  coordinateSystemA,
dwCoordinateSystem const  coordinateSystemB,
dwEgomotionConstHandle_t const  obj 
)

Compute the transformation between two coordinate systems at a specific timestamp and the uncertainty of this transform.

Parameters
[out]transformationAToBTransformation mapping a point in coordinate system A to a point in coordinate system B.
[out]uncertaintyStructure to be filled with uncertainty of transformation (optional, ignored if nullptr provided).
[in]timestampTimestamp for which to get transformation.
[in]coordinateSystemACoordinate system A.
[in]coordinateSystemBCoordinate system B.
[in]objEgomotion handle.
Note
uncertainty estimates are not supported at this time are left unpopulated.
Returns
DW_NOT_AVAILABLE - if there is currently not enough data available to make a prediction, requested timestamp is too far into the past or egomotion modality doesn't provide an estimate for the selected coordinate systems.
DW_NOT_SUPPORTED - if any coordinate system is not supported by any egomotion.
DW_INVALID_ARGUMENT - if any required argument is invalid.
DW_INVALID_HANDLE - if the provided egomotion handle invalid.
DW_SUCCESS

◆ dwEgomotion_computeRelativeTransformation()

DW_API_PUBLIC dwStatus dwEgomotion_computeRelativeTransformation ( dwTransformation3f poseAtoB,
dwEgomotionRelativeUncertainty uncertainty,
dwTime_t  timestamp_a,
dwTime_t  timestamp_b,
dwEgomotionConstHandle_t  obj 
)

Computes the relative transformation between two timestamps and the uncertainty of this transform.

Parameters
[out]poseAtoBTransform to be filled with transformation mapping a point at time a to a point at time b.
[out]uncertaintyStructure to be filled with uncertainty of transformation (optional, ignored if nullptr provided).
[in]timestamp_aTimestamp corresponding to beginning of transformation.
[in]timestamp_bTimestamp corresponding to end of transformation.
[in]objEgomotion handle.
Note
validity of uncertainty estimates is indicated by dwEgomotionRelativeUncertainty::valid
uncertainty estimates are currently only supported by DW_IMU_ODOMETRY motion model.
Returns
DW_INVALID_ARGUMENT - if any required argument is invalid.
DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_NOT_AVAILABLE - if there is currently not enough data available to make a prediction or requested timestamps are outside of available range (
See also
dwEgomotion_estimate).
DW_SUCCESS - if the computation was successful.

◆ dwEgomotion_computeSteeringAngleFromIMU()

DW_API_PUBLIC dwStatus dwEgomotion_computeSteeringAngleFromIMU ( float32_t steeringAngle,
float32_t inverseSteeringR,
const dwIMUFrame imuMeasurement,
dwEgomotionConstHandle_t  obj 
)

Computes steering angle of the vehicle based on IMU measurement.

The computation will take the yaw rate measurement from the IMU and combine it with currently estimated speed and wheel base. Speed used for estimation will be the reported by dwEgomotion_getEstimation.

Parameters
[out]steeringAngleSteering angle to be set to estimation from imu yaw rate (can be null, in which case it will not be set).
[out]inverseSteeringRInverse radius to be set to arc driven by the vehicle. (can be null, in which case it will not be filled).
[in]imuMeasurementIMU measurement with IMU measured in vehicle coordinate system.
[in]objEgomotion handle.
Returns
DW_INVALID_ARGUMENT - if any of the provided pointer arguments is nullptr DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_NOT_AVAILABLE - if there is currently no estimation available
DW_SUCCESS - if the call was successful.
Note
Depending on the underlying model the estimation might differ. Default implementation is to output steering angle and inverse radius as derived using bicycle model.

◆ dwEgomotion_estimate()

DW_API_PUBLIC dwStatus dwEgomotion_estimate ( dwEgomotionResult pose,
dwEgomotionUncertainty uncertainty,
dwTime_t  timestamp_us,
dwEgomotionConstHandle_t  obj 
)

Estimates the state for a given timestamp.

This method does not modify internal state and can only be used to extrapolate motion into the future or interpolate motion between estimates the past.

Parameters
[out]poseStructure to be filled with estimate state.
[out]uncertaintyStructure to be filled with uncertainties. Can be nullptr if not used.
[in]timestamp_usTimestamp to estimate state for.
[in]objEgomotion handle.
Returns
DW_NOT_AVAILABLE - if there is currently not enough data available to provide an estimate, or requested timestamp is too far from available estimates.
DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_SUCCESS - if the desired state has been provided successfully.
Note
Interpolation into the past can only happen within the available history range.
Interpolation interval is limited to 5 seconds, if interval between two successive poses is larger, the function will return DW_NOT_AVAILABLE.
Extrapolation into the future is limited to 2.5 seconds and the function will return DW_NOT_AVAILABLE if the extrapolation interval is larger.

◆ dwEgomotion_getEstimation()

DW_API_PUBLIC dwStatus dwEgomotion_getEstimation ( dwEgomotionResult result,
dwEgomotionConstHandle_t  obj 
)

Gets the latest state estimate.

Parameters
[out]resultStructure to be filled with latest state estimate.
[in]objEgomotion handle.
Returns
DW_INVALID_ARGUMENT - if the provided pointer is nullptr.
DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_NOT_AVAILABLE - if there is currently no estimation available.
DW_SUCCESS - if the estimation has been provided successfully.

◆ dwEgomotion_getEstimationTimestamp()

DW_API_PUBLIC dwStatus dwEgomotion_getEstimationTimestamp ( dwTime_t timestamp,
dwEgomotionConstHandle_t  obj 
)

Gets the timestamp of the latest state estimate.

The timestamp will be updated after each egomotion filter update.

Parameters
[out]timestampTimestamp to be set with latest available state estimate timestamp.
[in]objEgomotion handle.
Returns
DW_INVALID_ARGUMENT - if the provided timestamp pointer is nullptr.
DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_NOT_AVAILABLE - if there is currently no estimation available.
DW_SUCCESS - if the timestamp has been provided successfully

◆ dwEgomotion_getGyroscopeBias()

DW_API_PUBLIC dwStatus dwEgomotion_getGyroscopeBias ( dwVector3f gyroBias,
dwEgomotionConstHandle_t  obj 
)

Get estimated gyroscope bias.

Parameters
[out]gyroBiasVector to be filled with gyroscope biases.
[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 gyroscope bias estimation has accepted a value

◆ dwEgomotion_getHistoryElement()

DW_API_PUBLIC dwStatus dwEgomotion_getHistoryElement ( dwEgomotionResult pose,
dwEgomotionUncertainty uncertainty,
size_t  index,
dwEgomotionConstHandle_t  obj 
)

Returns an element from the motion history that is currently available.

Parameters
[out]poseStructure to be filled with state estimate at the requested index in history (can be null, in which case it will not be filled).
[out]uncertaintyStructure to be filled with uncertainty at the requested index in history (can be null, in which case it will not be filled).
[in]indexIndex into the history, in the range [0; dwEgomotion_getHistorySize ), with 0 being latest estimate and last element pointing to oldest estimate.
[in]objEgomotion handle.
Returns
DW_INVALID_HANDLE - if the egomotion handle is invalid
DW_INVALID_ARGUMENT - if the index is outside of available history
DW_SUCCESS- if the call was successful.

◆ dwEgomotion_getHistorySize()

DW_API_PUBLIC dwStatus dwEgomotion_getHistorySize ( size_t *  size,
dwEgomotionConstHandle_t  obj 
)

Returns the number of elements currently stored in the history.

Note
the history size is always lower than or equal to the history capacity, which is set at initialization.
Parameters
[out]sizeInteger to be set with the number of elements in the history.
[in]objEgomotion handle.
Returns
DW_INVALID_ARGUMENT - if the provided pointer is nullptr.
DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_SUCCESS - if the call was successful.

◆ dwEgomotion_getMotionModel()

DW_API_PUBLIC dwStatus dwEgomotion_getMotionModel ( dwMotionModel model,
dwEgomotionConstHandle_t  obj 
)

Returns the type of the motion model used.

Parameters
[out]modeldwMotionModel to be set with the motion model type used by instance specified by the handle.
[in]objEgomotion handle.
Returns
DW_INVALID_ARGUMENT - if the provided pointer is nullptr.
DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_SUCCESS if the call was successful.

◆ dwEgomotion_getUncertainty()

DW_API_PUBLIC dwStatus dwEgomotion_getUncertainty ( dwEgomotionUncertainty result,
dwEgomotionConstHandle_t  obj 
)

Gets the latest state estimate uncertainties.

Parameters
[out]resultStructure to be filled with latest uncertainties.
[in]objEgomotion handle.
Returns
DW_INVALID_ARGUMENT - if the provided pointer is nullptr.
DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_NOT_AVAILABLE - if there is currently no estimation available.
DW_SUCCESS - if the uncertainty has been provided successfully.
Note
Not all values do have valid uncertainties. Check dwEgomotionUncertainty.validFlags.

◆ dwEgomotion_hasEstimation()

DW_API_PUBLIC dwStatus dwEgomotion_hasEstimation ( bool *  result,
dwEgomotionConstHandle_t  obj 
)

Check whether estimation is available.

Parameters
[out]resultBoolean to be set with estimation availablity.
[in]objEgomotion handle.
Returns
DW_INVALID_ARGUMENT - if the provided pointer is nullptr.
DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_SUCCESS - if the operation was successful.

◆ dwEgomotion_initialize()

DW_API_PUBLIC dwStatus dwEgomotion_initialize ( dwEgomotionHandle_t obj,
const dwEgomotionParameters params,
dwContextHandle_t  ctx 
)

Initializes the egomotion module.

Configuration of the module is provided by the params argument. Default parameters can be obtained from the dwEgomotion_initParamsFromRig function.

Parameters
[out]objHandle to be set with pointer to 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 module has been initialized successfully.

◆ dwEgomotion_initParamsFromRig()

DW_API_PUBLIC dwStatus dwEgomotion_initParamsFromRig ( dwEgomotionParameters params,
dwConstRigHandle_t  rigConfiguration,
const char *  imuSensorName,
const char *  vehicleSensorName 
)

Initialize egomotion parameters from a provided RigConfiguration.

This will read out vehicle as well as all relevant sensor parameters and apply them on top of default egomotion parameters.

Parameters
[out]paramsStructure to be filled out with vehicle and sensor parameters.
[in]rigConfigurationHandle to a rig configuration to retrieve parameters from.
[in]imuSensorNamename of the IMU sensor to be used (optional, can be null).
[in]vehicleSensorNamename of the vehicle sensor to be used (optional, can be null).
Returns
DW_INVALID_ARGUMENT - if provided params pointer or rig handle are invalid
DW_FILE_INVALID - if provided sensor could not be found in the rig config
DW_SUCCESS - if parameters have been initialized successfully.
Note
Clears any existing parameters set in params.
If a sensor name is null, no sensor specific parameters will be extracted from the configuration for this sensor.
Sets motionModel based on available sensor if passed in as 0; DW_EGOMOTION_IMU_ODOMETRY if IMU sensor is present, DW_EGOMOTION_ODOMETRY otherwise.
Following parameters are extracted from the rig configuration: CAN sensor:

◆ dwEgomotion_initParamsFromRigByIndex()

DW_API_PUBLIC dwStatus dwEgomotion_initParamsFromRigByIndex ( dwEgomotionParameters params,
dwConstRigHandle_t  rigConfiguration,
uint32_t  imuSensorIdx,
uint32_t  vehicleSensorIdx 
)

Same as dwEgomotion_initParamsFromRig however uses sensor indices in rigConfiguration instead of their names.

Parameters
[out]paramsStructure to be filled out with vehicle and sensor parameters.
[in]rigConfigurationHandle to a rig configuration to retrieve parameters from
[in]imuSensorIdxIndex of the IMU sensor to be retrieved (optional, can be (uint32_t)-1)
[in]vehicleSensorIdxIndex of the vehicle sensor to be retrieved (optional, can be (uint32_t)-1)
Note
Clears any existing parameters set in params.
Sets motionModel based on available sensor if passed in as 0; DW_EGOMOTION_IMU_ODOMETRY if IMU sensor is present, DW_EGOMOTION_ODOMETRY otherwise.
Returns
DW_INVALID_ARGUMENT - if provided params pointer or rig handle are invalid
DW_FILE_INVALID - if provided sensor could not be found in the rig config
DW_SUCCESS - if parameters have been initialized successfully.

◆ dwEgomotion_release()

DW_API_PUBLIC dwStatus dwEgomotion_release ( dwEgomotionHandle_t  obj)

Releases the egomotion module.

Note
This method renders the handle unusable.
Parameters
[in]objEgomotion handle to be released.
Returns
DW_INVALID_HANDLE - if the provided egomotion handle is invalid.
DW_SUCCESS - if the egomotion module has been released successfully.

◆ dwEgomotion_reset()

DW_API_PUBLIC dwStatus dwEgomotion_reset ( dwEgomotionHandle_t  obj)

Resets the state estimate and all history of the egomotion module.

All consecutive motion estimates will be relative to the (new) origin.

Parameters
[in]objEgomotion handle to be reset.
Returns
DW_INVALID_HANDLE - if the provided egomotion handle is invalid.
DW_SUCCESS - if the state and history have been reset successfully.

◆ dwEgomotion_steeringAngleToSteeringWheelAngle()

DW_API_PUBLIC dwStatus dwEgomotion_steeringAngleToSteeringWheelAngle ( float32_t steeringWheelAngle,
float32_t  steeringAngle,
dwEgomotionHandle_t  obj 
)

Convert steering angle to steering wheel angle.

Parameters
[out]steeringWheelAnglePointer to steering wheel angle to be set, in radians.
[in]steeringAngleSteering angle, in radians.
[in]objSpecifies the egomotion module handle.
Returns
DW_INVALID_ARGUMENT - if any of the provided pointer arguments is nullptr.
DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_NOT_SUPPORTED - if underlying egomotion handle does not support steering angle to steering wheel angle conversion. The egomotion model has to be DW_EGOMOTION_ODOMETRY or DW_EGOMOTION_IMU_ODOMETRY.
DW_SUCCESS - if the call was successful.

◆ dwEgomotion_steeringWheelAngleToSteeringAngle()

DW_API_PUBLIC dwStatus dwEgomotion_steeringWheelAngleToSteeringAngle ( float32_t steeringAngle,
float32_t  steeringWheelAngle,
dwEgomotionHandle_t  obj 
)

Convert steering wheel angle to steering angle.

Parameters
[out]steeringAnglePointer to steering angle to be set, in radians.
[in]steeringWheelAngleSteering wheel angle, in radians.
[in]objSpecifies the egomotion module handle.
Returns
DW_INVALID_ARGUMENT - if any of the provided pointer arguments is nullptr.
DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_NOT_SUPPORTED - if underlying egomotion handle does not support steering wheel angle to steering angle conversion. The egomotion model has to be DW_EGOMOTION_ODOMETRY or DW_EGOMOTION_IMU_ODOMETRY.
DW_SUCCESS - if the call was successful.

◆ dwEgomotion_update()

DW_API_PUBLIC dwStatus dwEgomotion_update ( dwTime_t  timestamp_us,
dwEgomotionHandle_t  obj 
)

Runs the motion model estimation for a given timestamp.

The internal state is modified. The motion model advances to the given timestamp. To retrieve the result of the estimation, use dwEgomotion_getEstimation.

This method allows the user to update the egomotion filter when required, for a specific timestamp, using all sensor data available up to this timestamp.

When the automatic update period is active (automaticUpdate in dwEgomotionParameters is set), dwEgomotion_update will not update the filter state and throw a DW_NOT_SUPPORTED exception instead.

Parameters
[in]timestamp_usTimestamp for which to estimate vehicle state.
[in]objEgomotion handle.
Returns
DW_INVALID_ARGUMENT - if given timestamp is not greater than last update timestamp.
DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_NOT_SUPPORTED - if the automatic estimation update period is active (i.e. non-zero).
DW_NOT_READY - if pre-conditions required for estimation are not (yet) met.
DW_SUCCESS - update was executed successfully.
Note
The provided timestamp must be larger than the previous timestamp used when calling dwEgomotion_estimate.
A full set of new sensor measurements should be added before calling this method; otherwise the state estimate might be based on older, extrapolated sensor measurements.
Updating internal state does not guarantee that a motion estimation is available, i.e. there might be not enough data to provide an estimate. Use dwEgomotion_getEstimation and/or dwEgomotion_computeRelativeTransformation to query estimation if it is available.

◆ dwEgomotion_updateIMUExtrinsics()

DW_API_PUBLIC dwStatus dwEgomotion_updateIMUExtrinsics ( const dwTransformation3f imuToRig,
dwEgomotionHandle_t  obj 
)

This method updates the IMU extrinsics to convert from the IMU coordinate system to the vehicle rig coordinate system.

Parameters
[in]imuToRigTransformation from the IMU coordinate system to the vehicle rig coordinate system.
[in]objEgomotion handle.
Returns
DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_INVALID_ARGUMENT - if provided imuToRig is nullptr.
DW_NOT_SUPPORTED - if given egomotion instance does not support change of this parameter.
DW_SUCCESS - if the update was successful.

◆ dwEgomotion_updateVehicle()

DW_API_PUBLIC dwStatus dwEgomotion_updateVehicle ( const dwVehicle vehicle,
dwEgomotionHandle_t  obj 
)

This method updates the egomotion module with an updated vehicle.

Parameters
[in]vehicleUpdated vehicle which may contain updated vehicle parameters.
[in]objEgomotion handle.
Returns
DW_INVALID_HANDLE - if the given egomotion handle is invalid.
DW_INVALID_ARGUMENT - if provided vehicle is nullptr.
DW_NOT_SUPPORTED - if given egomotion instance does not support change of this parameter.
DW_SUCCESS - if the vehicle has been updated successfully.