- Welcome
- Getting Started With the NVIDIA DriveWorks SDK
- Modules
- Samples
- Tools
- Tutorials
- SDK Porting Guide
- DriveWorks API
- More
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.
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... | |
Modules | |
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 |
typedef struct dwEgomotionObject * | dwEgomotionHandle_t |
struct dwEgomotionLinearAccelerationFilterParams |
Data Fields | ||
---|---|---|
float32_t | accelerationFilterTimeConst | 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)]. |
struct dwEgomotionParameters |
Data Fields | ||
---|---|---|
bool | automaticUpdate |
Automatically update state estimation. In general to update motion estimation, a call to
|
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.
|
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). Any call to |
dwTransformation3f | imu2rig |
IMU extrinsics. Transformation from the IMU coordinate system to the vehicle rig coordinate system.
|
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.
|
dwEgomotionLinearAccelerationFilterParams | linearAccelerationFilterParameters |
Linear acceleration filter parameters.
|
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.
|
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.
|
dwVehicle | vehicle |
Vehicle parameters to setup the model.
|
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 |
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.
|
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. |
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
|
dwTime_t | velocityLatency | CAN velocity latency in microseconds which is read from can properties in rig file. |
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:
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. |
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. |
typedef struct dwEgomotionObject const* dwEgomotionConstHandle_t |
Definition at line 78 of file Egomotion.h.
typedef struct dwEgomotionObject* dwEgomotionHandle_t |
Definition at line 77 of file Egomotion.h.
enum dwEgomotionDataField |
Defines flags that indicate validity of corresponding data in dwEgomotionResult
and dwEgomotionUncertainty
.
Enumerator | |
---|---|
DW_EGOMOTION_ROTATION | indicates validity of rotation,
|
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 448 of file Egomotion.h.
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 259 of file Egomotion.h.
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.
Provide front speed measurement and steering angle with the dwEgomotion_addOdometry() API, or with the dwEgomotion_addVehicleState() API where the |
DW_EGOMOTION_REAR_WHEEL_SPEED | Indicates that speeds are angular speeds [rad/s] measured at rear wheels.
Provide rear wheel speed measurements with the dwEgomotion_addVehicleState() API where the |
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.
Provide rear speed measurement with the dwEgomotion_addVehicleState() API where the |
Definition at line 187 of file Egomotion.h.
Defines steering measurement types.
Enumerator | |
---|---|
DW_EGOMOTION_FRONT_STEERING |
|
DW_EGOMOTION_STEERING_WHEEL_ANGLE |
|
Definition at line 251 of file Egomotion.h.
Defines egomotion suspension model.
Definition at line 267 of file Egomotion.h.
enum 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:
The following odometry measurements are required for this model:
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:
The following odometry measurements are required for this model:
This model is capable of providing the following estimates:
Uncertainty estimates are provided for all state estimates listed above.
|
Definition at line 81 of file Egomotion.h.
Defines motion measurements.
Definition at line 178 of file Egomotion.h.
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.
[in] | imu | IMU measurement. |
[in] | obj | Egomotion handle. |
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.
[in] | measuredType | Type of measurement. For example: velocity, steering angle. |
[in] | measuredValue | Value that was measured. For example: 3.6 m/s, 0.1 rad. |
[in] | timestamp | Timestamp for the measurement. |
[in] | obj | Egomotion handle. |
timestamp
is not greater than last measurement timestamp, measuredType
is not valid, or measuredValue
is not finite. dwEgomotionSpeedMeasurementType::DW_EGOMOTION_FRONT_SPEED
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.
[in] | safeState | New dwVehicleIOSafetyState which contains potentially new information for egomotion consumption |
[in] | nonSafeState | New dwVehicleIONonSafetyState which contains potentially new information for egomotion consumption |
[in] | actuationFeedback | New dwVehicleIOActuationFeedback which contains potentially new information for egomotion consumption |
[in] | obj | Egomotion handle. |
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.
[in] | state | New VehicleIOState which contains potentially new information for egomotion consumption |
[in] | obj | Egomotion handle. |
DW_API_PUBLIC dwStatus dwEgomotion_applyRelativeTransformation | ( | dwTransformation3f * | newVehicle2World, |
const dwTransformation3f * | poseOld2New, | ||
const dwTransformation3f * | oldVehicle2World | ||
) |
Applies the estimated relative motion as returned by dwEgomotion_computeRelativeTransformation() to a given vehicle pose.
[out] | newVehicle2World | Transformation representing new pose of a vehicle after applying the relative motion. |
[in] | poseOld2New | Relative motion between two timestamps. |
[in] | oldVehicle2World | Current pose of a vehicle. |
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.
[out] | poseAtoB | Transformation mapping a point at time a to a point at time b . |
[out] | uncertainty | Rotational and translational uncertainty of transformation (optional, ignored if nullptr provided) |
[in] | timestamp_a | Timestamp corresponding to beginning of transformation. |
[in] | timestamp_b | Timestamp corresponding to end of transformation. |
[in] | obj | Egomotion handle. |
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()
.
[out] | steeringAngle | Steering angle estimated from imu yaw rate. This parameter is optional. |
[out] | inverseSteeringR | Inverse radius of the arc driven by the vehicle. This parameter is optional. |
[in] | imuMeasurement | Current IMU measurement with IMU measured in vehicle coordinate system |
[in] | obj | Egomotion handle. |
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.
[out] | pose | Struct where to store estimate state. |
[out] | uncertainty | Struct where to store estiamted state uncertainties. Can be nullptr if not used. |
[in] | timestamp_us | Timestamp to estimate state for. |
[in] | obj | Egomotion handle. |
DW_API_PUBLIC dwStatus dwEgomotion_getEstimation | ( | dwEgomotionResult * | result, |
dwEgomotionConstHandle_t | obj | ||
) |
Gets the latest state estimate.
[out] | result | A pointer to the dwEgomotionResult struct containing state estimate. |
[in] | obj | Egomotion handle. |
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.
[out] | timestamp | Pointer to be filled with timestamp in [usec] of latest available state estimate. |
[in] | obj | Egomotion handle. |
DW_API_PUBLIC dwStatus dwEgomotion_getGyroscopeBias | ( | dwVector3f * | gyroBias, |
dwEgomotionConstHandle_t | obj | ||
) |
Get estimated gyroscope bias.
[out] | gyroBias | Pointer to dwVector3f to be filled with gyroscope biases. |
[in] | obj | Egomotion handle. |
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.
[out] | pose | Return state estimate at the requested index in history (can be null if not interested in data). |
[out] | uncertainty | Return estimate uncertainty at the requested index in history (can be null if not interested in data). |
[in] | index | Index into the history, in the range [0; dwEgomotion_getHistorySize ), with 0 being latest estimate and last element pointing to oldest estimate. |
[in] | obj | Egomotion handle. |
DW_API_PUBLIC dwStatus dwEgomotion_getHistorySize | ( | size_t * | num, |
dwEgomotionConstHandle_t | obj | ||
) |
Returns the number of elements currently stored in the history.
[out] | num | A pointer to the number of elements in the history. |
[in] | obj | Egomotion handle. |
DW_API_PUBLIC dwStatus dwEgomotion_getMotionModel | ( | dwMotionModel * | model, |
dwEgomotionConstHandle_t | obj | ||
) |
Returns the type of the motion model used.
[out] | model | Type of the motion model which is used by the instance specified by the handle. |
[in] | obj | Egomotion handle. |
DW_API_PUBLIC dwStatus dwEgomotion_getUncertainty | ( | dwEgomotionUncertainty * | result, |
dwEgomotionConstHandle_t | obj | ||
) |
Gets the latest state estimate uncertainties.
[out] | result | A pointer to the dwEgomotionUncertainty struct containing estimated state uncertainties. |
[in] | obj | Egomotion handle. |
DW_API_PUBLIC dwStatus dwEgomotion_hasEstimation | ( | bool * | result, |
dwEgomotionConstHandle_t | obj | ||
) |
Check whether has state estimate.
[out] | result | A pointer to the bool . |
[in] | obj | Egomotion handle. |
DW_API_PUBLIC dwStatus dwEgomotion_initialize | ( | dwEgomotionHandle_t * | obj, |
const dwEgomotionParameters * | params, | ||
dwContextHandle_t | ctx | ||
) |
Initializes the egomotion module.
[out] | obj | A pointer to the egomotion handle for the created module. |
[in] | params | A pointer to the configuration parameters of the module. |
[in] | ctx | Specifies the handler to the context under which the Egomotion module is created. |
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.
[out] | params | Pointer to a parameter struct to be filled out with vehicle and sensor parameters |
[in] | rigConfiguration | Handle to a rig configuration to retrieve parameters from |
[in] | imuSensorName | name of the IMU sensor to be used (optional, can be null) |
[in] | vehicleSensorName | name of the vehicle sensor to be used (optional, can be null) |
params
.motionModel
based on available sensor if passed in as 0; DW_EGOMOTION_IMU_ODOMETRY if IMU sensor is present, DW_EGOMOTION_ODOMETRY otherwise.dwEgomotionParameters.sensorParameters.velocityLatency
dwEgomotionParameters.sensorParameters.velocityFactor
IMU sensor:dwEgomotionParameters.gyroscopeBias
dwEgomotionParameters.imu2rig
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.
[out] | params | Pointer to a parameter struct to be filled out with default data |
[in] | rigConfiguration | Handle to a rig configuration to retrieve parameters from |
[in] | imuSensorIdx | Index of the IMU sensor to be retrieved (optional, can be (uint32_t)-1) |
[in] | vehicleSensorIdx | Index of the vehicle sensor to be retrieved (optional, can be (uint32_t)-1) |
params
.motionModel
based on available sensor if passed in as 0; DW_EGOMOTION_IMU_ODOMETRY if IMU sensor is present, DW_EGOMOTION_ODOMETRY otherwise.DW_API_PUBLIC dwStatus dwEgomotion_release | ( | dwEgomotionHandle_t | obj | ) |
Releases the egomotion module.
[in] | obj | Egomotion handle to be released. |
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.
[in] | obj | Egomotion handle to be reset. |
DW_API_PUBLIC dwStatus dwEgomotion_steeringAngleToSteeringWheelAngle | ( | float32_t * | steeringWheelAngle, |
float32_t | steeringAngle, | ||
dwEgomotionHandle_t | obj | ||
) |
Convert steering angle to steering wheel angle.
[out] | steeringWheelAngle | steering wheel angle [radian] |
[in] | steeringAngle | steering angle [radian] |
[in] | obj | Specifies the egomotion module handle. |
DW_API_PUBLIC dwStatus dwEgomotion_steeringWheelAngleToSteeringAngle | ( | float32_t * | steeringAngle, |
float32_t | steeringWheelAngle, | ||
dwEgomotionHandle_t | obj | ||
) |
Convert steering wheel angle to steering angle.
[out] | steeringAngle | steering angle [radian] |
[in] | steeringWheelAngle | steering wheel angle [radian] |
[in] | obj | Specifies the egomotion module handle. |
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.
[in] | timestamp_us | Timestamp for which to estimate vehicle state. |
[in] | obj | Egomotion handle. |
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.
[in] | imuToRig | Transformation from the IMU coordinate system to the vehicle rig coordinate system. |
[in] | obj | Egomotion handle. |
DW_API_PUBLIC dwStatus dwEgomotion_updateVehicle | ( | const dwVehicle * | vehicle, |
dwEgomotionHandle_t | obj | ||
) |
This method updates the egomotion module with an updated vehicle.
[in] | vehicle | Updated vehicle which may contain updated vehicle parameters. |
[in] | obj | Egomotion handle. |