59#ifndef DW_EGOMOTION_EGOMOTION_H_
60#define DW_EGOMOTION_EGOMOTION_H_
275typedef struct dwEgomotionLinearAccelFilterParams
386 DW_DEPRECATED(
"Deriving lateral slip coefficient from vehicle parameters, unless this parameter is non-zero.")
567 const char* imuSensorName,
const char* vehicleSensorName);
588 uint32_t imuSensorIdx, uint32_t vehicleSensorIdx);
NVIDIA DriveWorks API: IMU
NVIDIA DriveWorks API: Rig Configuration
NVIDIA DriveWorks API: VehicleIO car controller
NVIDIA DriveWorks API: Core Types
NVIDIA DriveWorks API: Core Methods
NVIDIA DriveWorks API: Core Exports
Non-safety critical RoV state.
Safety critical VIO state.
The vehicle IO state data.
struct dwContextObject * dwContextHandle_t
Context handle.
#define DW_DEPRECATED(msg)
dwStatus
Status definition.
float float32_t
Specifies POD types.
int64_t dwTime_t
Specifies a timestamp unit, in microseconds.
Defines a 3x3 matrix of floating point numbers by using only one array.
Defines a single-precision quaternion.
Defines a three-element floating-point vector.
float32_t gyroNoiseDensityDeg
Expected zero mean measurement noise of the gyroscope, also known as Noise Density [deg/s/sqrt(Hz)] A...
float32_t odometrySamplingRateHz
If known this entry shall indicate expected sampling rate in [Hz] of the odometry signals.
dwTime_t velocityLatency
CAN velocity latency in microseconds which is read from can properties in rig file.
float32_t gyroscopeBias[3]
Initial gyroscope biases, if known at initialization time.
dwMatrix3f rotation
Rotation covariance represented as euler angles (order: roll, pitch, yaw) in [rad^2].
float32_t torsionalSpringPitchNaturalFrequency
Torsional spring model parameters.
dwTransformation3f imu2rig
IMU extrinsics.
dwEgomotionSensorCharacteristics sensorParameters
Sensor parameters, containing information about sensor characteristics.
float32_t accNoiseDensityMicroG
Expected zero mean measurement noise of the linear accelerometer, also known as Noise Density [ug/sqr...
dwEgomotionSuspensionModel model
Suspension model to use.
dwMatrix3f rotation
a 3x3 covariance of the rotation (order: roll, pitch, yaw) [rad]
float32_t accelerationFilterTimeConst
Time constant of the IMU acceleration measurements.
dwEgomotionSpeedMeasurementType speedMeasurementType
Defines which velocity readings from dwVehicleIOState shall be used for egomotion estimation.
float32_t gyroDriftRate
Expected gyroscope drift rate in [deg/s].
float32_t torsionalSpringPitchDampingRatio
Level of damping relative to critical damping around the pitch axis of the vehicle [dimensionless].
bool estimateInitialOrientation
When enabled, initial rotation will be estimated from accelerometer measurements.
dwEgomotionSteeringMeasurementType steeringMeasurementType
Defines which steering readings from dwVehicleIOState shall be used for egomotion estimation.
uint32_t historySize
Number of state estimates to keep in the history (if 0 specified default of 1000 is used).
dwTime_t timestamp
Timestamp of egomotion state estimate [us].
int32_t validFlags
Bitwise combination of dwEgomotionDataField flags.
float32_t velocityFactor
CAN velocity correction factor which is read from can properties in rig file.
float32_t gyroBiasRange
If known this value in [rad/s] shall indicate standard deviation of the expected bias range of the gy...
float32_t imuSamplingRateHz
If known this entry shall indicate expected sampling rate in [Hz] of the IMU sensor.
bool automaticUpdate
Automatically update state estimation.
dwEgomotionSuspensionParameters suspension
Suspension model parameters.
dwMatrix3f translation
a 3x3 covariance of the translation (x,y,z) [m]
float32_t lateralSlipCoefficient
Lateral slip coefficient [rad*s^2/m].
dwEgomotionLinearAccelerationFilterParams linearAccelerationFilterParameters
Linear acceleration filter parameters.
dwEgomotionLinearAccelerationFilterMode mode
Linear acceleration filter mode. Default (0): no filtering.
float32_t measurementNoiseStdevAcceleration
Standard deviation of measurement noise in acceleration [m/s^2].
dwVehicle vehicle
Vehicle parameters to setup the model.
int64_t validFlags
Bitwise combination of dwEgomotionDataField flags.
float32_t measurementNoiseStdevSpeed
Standard deviation of measurement noise in speed [m/s].
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)].
bool valid
indicates whether uncertainty estimates are valid or not
dwMotionModel motionModel
Specifies the motion model to be used for pose estimation.
dwQuaternionf rotation
Rotation represented as quaternion (x,y,z,w).
dwTime_t timeInterval
relative motion time interval [us]
dwTime_t timestamp
Timestamp of egomotion uncertainty estimate [us].
dwMotionModelMeasurement
Defines motion measurements.
DW_API_PUBLIC dwStatus dwEgomotion_getEstimation(dwEgomotionResult *result, dwEgomotionConstHandle_t obj)
Gets the latest state estimate.
DW_API_PUBLIC dwStatus dwEgomotion_getMotionModel(dwMotionModel *model, dwEgomotionConstHandle_t obj)
Returns the type of the motion model used.
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...
DW_API_PUBLIC dwStatus dwEgomotion_getGyroscopeBias(dwVector3f *gyroBias, dwEgomotionConstHandle_t obj)
Get estimated gyroscope bias.
DW_API_PUBLIC dwStatus dwEgomotion_getUncertainty(dwEgomotionUncertainty *result, dwEgomotionConstHandle_t obj)
Gets the latest state estimate uncertainties.
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.
dwEgomotionDataField
Defines flags that indicate validity of corresponding data in dwEgomotionResult and dwEgomotionUncert...
DW_API_PUBLIC dwStatus dwEgomotion_hasEstimation(bool *result, dwEgomotionConstHandle_t obj)
Check whether has state estimate.
struct dwEgomotionObject const * dwEgomotionConstHandle_t
DW_API_PUBLIC dwStatus dwEgomotion_updateVehicle(const dwVehicle *vehicle, dwEgomotionHandle_t obj)
This method updates the egomotion module with an updated vehicle.
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.
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.
DW_API_PUBLIC dwStatus dwEgomotion_reset(dwEgomotionHandle_t obj)
Resets the state estimate and all history of the egomotion module.
DW_API_PUBLIC dwStatus dwEgomotion_steeringAngleToSteeringWheelAngle(float32_t *steeringWheelAngle, float32_t steeringAngle, dwEgomotionHandle_t obj)
Convert steering angle to steering wheel angle.
DW_API_PUBLIC dwStatus dwEgomotion_getHistorySize(size_t *num, dwEgomotionConstHandle_t obj)
Returns the number of elements currently stored in the history.
dwMotionModel
Defines the motion models.
DW_API_PUBLIC dwStatus dwEgomotion_getEstimationTimestamp(dwTime_t *timestamp, dwEgomotionConstHandle_t obj)
Gets the timestamp of the latest state estimate.
DW_API_PUBLIC dwStatus dwEgomotion_initialize(dwEgomotionHandle_t *obj, const dwEgomotionParameters *params, dwContextHandle_t ctx)
Initializes the egomotion module.
dwEgomotionSuspensionModel
Defines egomotion suspension model.
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 c...
dwEgomotionLinearAccelerationFilterMode
Defines egomotion linear acceleration filter mode.
DW_API_PUBLIC dwStatus dwEgomotion_steeringWheelAngleToSteeringAngle(float32_t *steeringAngle, float32_t steeringWheelAngle, dwEgomotionHandle_t obj)
Convert steering wheel angle to steering angle.
DW_API_PUBLIC dwStatus dwEgomotion_addVehicleState(const dwVehicleIOState *state, dwEgomotionHandle_t obj)
Notifies the egomotion module of a changed vehicle state.
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.
dwEgomotionSteeringMeasurementType
Defines steering measurement types.
DW_API_PUBLIC dwStatus dwEgomotion_initParamsFromRig(dwEgomotionParameters *params, dwConstRigHandle_t rigConfiguration, const char *imuSensorName, const char *vehicleSensorName)
Initialize egomotion parameters from a provided RigConfiguration.
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.
struct dwEgomotionObject * dwEgomotionHandle_t
DW_API_PUBLIC dwStatus dwEgomotion_release(dwEgomotionHandle_t obj)
Releases the egomotion module.
dwEgomotionSpeedMeasurementType
Defines speed measurement types.
DW_API_PUBLIC dwStatus dwEgomotion_update(dwTime_t timestamp_us, dwEgomotionHandle_t obj)
Runs the motion model estimation for a given timestamp.
DW_API_PUBLIC dwStatus dwEgomotion_addIMUMeasurement(const dwIMUFrame *imu, dwEgomotionHandle_t obj)
Adds an IMU frame to the egomotion module.
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 thei...
DW_API_PUBLIC dwStatus dwEgomotion_estimate(dwEgomotionResult *pose, dwEgomotionUncertainty *uncertainty, dwTime_t timestamp_us, dwEgomotionConstHandle_t obj)
Estimates the state for a given timestamp.
@ DW_EGOMOTION_MEASUREMENT_VELOCITY
Vehicle velocity [m/s].
@ DW_EGOMOTION_MEASUREMENT_STEERINGANGLE
Steering angle [rad].
@ DW_EGOMOTION_MEASUREMENT_STEERINGWHEELANGLE
Steering wheel angle [rad].
@ DW_EGOMOTION_LIN_VEL_X
indicates validity of linearVelocity[0]
@ DW_EGOMOTION_LIN_ACC_X
indicates validity of linearAcceleration[0]
@ DW_EGOMOTION_ANG_ACC_Z
indicates validity of angularAcceleration[2]
@ DW_EGOMOTION_ANG_ACC_Y
indicates validity of angularAcceleration[1]
@ DW_EGOMOTION_ROTATION
indicates validity of rotation,
@ DW_EGOMOTION_LIN_VEL_Y
indicates validity of linearVelocity[1]
@ DW_EGOMOTION_LIN_ACC_Z
indicates validity of linearAcceleration[2]
@ DW_EGOMOTION_ANG_ACC_X
indicates validity of angularAcceleration[0]
@ DW_EGOMOTION_LIN_ACC_Y
indicates validity of linearAcceleration[1]
@ DW_EGOMOTION_ANG_VEL_Y
indicates validity of angularVelocity[1]
@ DW_EGOMOTION_ANG_VEL_X
indicates validity of angularVelocity[0]
@ DW_EGOMOTION_LIN_VEL_Z
indicates validity of linearVelocity[2]
@ DW_EGOMOTION_ANG_VEL_Z
indicates validity of angularVelocity[2]
@ DW_EGOMOTION_ODOMETRY
Given odometry information, estimates motion of the vehicle using a bicycle model.
@ DW_EGOMOTION_IMU_ODOMETRY
Fuses odometry model with IMU measurements to estimate motion of the vehicle.
@ 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.
@ 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
@ DW_EGOMOTION_STEERING_WHEEL_ANGLE
@ DW_EGOMOTION_FRONT_STEERING
@ DW_EGOMOTION_REAR_WHEEL_SPEED
Indicates that speeds are angular speeds [rad/s] measured at rear wheels.
@ DW_EGOMOTION_FRONT_SPEED
Indicates that speed is linear speed [m/s] measured at front wheels (along steering direction).
@ DW_EGOMOTION_REAR_SPEED
Indicates that speed is linear speed [m/s] measured at rear axle center (along steering direction).
Defines egomotion linear acceleration filter parameters.
Holds initialization parameters for the Egomotion module.
Holds egomotion uncertainty estimates for a relative motion estimate.
Holds egomotion state estimate.
Sensor measurement noise characteristics.
Suspension model type and parameters.
Holds egomotion uncertainty estimates.
An IMU frame containing sensor readings from the IMU sensor.
struct dwRigObject const * dwConstRigHandle_t
DEPRECATED: Properties of a passenger car vehicle.