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. 
|  | 
| 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... 
 | 
|  | 
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
- 
  
  
- 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.
 
 
 
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_us | Timestamp for which to estimate vehicle state. |  | [in] | obj | Egomotion 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.