DriveWorks SDK Reference
3.5.78 Release
For Test and Development only

Egomotion.h
Go to the documentation of this file.
1 // This code contains NVIDIA Confidential Information and is disclosed
3 // under the Mutual Non-Disclosure Agreement.
4 //
5 // Notice
6 // ALL NVIDIA DESIGN SPECIFICATIONS AND CODE ("MATERIALS") ARE PROVIDED "AS IS" NVIDIA MAKES
7 // NO REPRESENTATIONS, WARRANTIES, EXPRESSED, IMPLIED, STATUTORY, OR OTHERWISE WITH RESPECT TO
8 // THE MATERIALS, AND EXPRESSLY DISCLAIMS ANY IMPLIED WARRANTIES OF NONINFRINGEMENT,
9 // MERCHANTABILITY, OR FITNESS FOR A PARTICULAR PURPOSE.
10 //
11 // NVIDIA Corporation assumes no responsibility for the consequences of use of such
12 // information or for any infringement of patents or other rights of third parties that may
13 // result from its use. No license is granted by implication or otherwise under any patent
14 // or patent rights of NVIDIA Corporation. No third party distribution is allowed unless
15 // expressly authorized by NVIDIA. Details are subject to change without notice.
16 // This code supersedes and replaces all information previously supplied.
17 // NVIDIA Corporation products are not authorized for use as critical
18 // components in life support devices or systems without express written approval of
19 // NVIDIA Corporation.
20 //
21 // Copyright (c) 2015-2020 NVIDIA Corporation. All rights reserved.
22 //
23 // NVIDIA Corporation and its licensors retain all intellectual property and proprietary
24 // rights in and to this software and related documentation and any modifications thereto.
25 // Any use, reproduction, disclosure or distribution of this software and related
26 // documentation without an express license agreement from NVIDIA Corporation is
27 // strictly prohibited.
28 //
30 
61 #ifndef DW_EGOMOTION_EGOMOTION_H_
62 #define DW_EGOMOTION_EGOMOTION_H_
63 
64 #include <dw/core/Config.h>
65 #include <dw/core/Exports.h>
66 #include <dw/core/Context.h>
67 #include <dw/core/Types.h>
68 
70 
71 #include <dw/sensors/imu/IMU.h>
72 
73 #include <dw/rig/Rig.h>
74 
75 #ifdef __cplusplus
76 extern "C" {
77 #endif
78 
79 typedef struct dwEgomotionObject* dwEgomotionHandle_t;
80 typedef struct dwEgomotionObject const* dwEgomotionConstHandle_t;
81 
83 typedef enum dwMotionModel {
120 
157 
158 } dwMotionModel;
159 
163 typedef enum {
164  DW_EGOMOTION_MEASURMENT_VELOCITY DW_DEPRECATED_ENUM("Use DW_EGOMOTION_MEASUREMENT_VELOCITY") = 0,
166  DW_EGOMOTION_MEASURMENT_STEERINGANGLE DW_DEPRECATED_ENUM("Use DW_EGOMOTION_MEASUREMENT_STEERINGANGLE") = 1,
168  DW_EGOMOTION_MEASURMENT_STEERINGWHEELANGLE DW_DEPRECATED_ENUM("Use DW_EGOMOTION_MEASUREMENT_STEERINGWHEELANGLE") = 2,
171 
192 
212 
220 
228 
232 typedef struct dwEgomotionLinearAccelFilterParams
233 {
235  dwEgomotionLinearAccelerationFilterMode mode;
236 
237  // Simple filter parameters (ignored for other modes)
244 
248 typedef struct
249 {
253 
277 
282 
284 
289 {
293 
297 
302 
306 
310 
313 
320 
322 
326 typedef struct dwEgomotionParameters
327 {
332 
339 
343 
345  dwMotionModel motionModel;
346 
351 
362 
365  uint32_t historySize;
366 
370  float32_t gyroscopeBias[3];
371 
378 
382 
389 
391 
395 typedef enum dwEgomotionDataField {
397 
401 
405 
409 
411 
416 typedef struct
417 {
419 
422 
423  float32_t linearVelocity[3];
424 
428  float32_t angularVelocity[3];
429 
430  float32_t linearAcceleration[3];
431 
432  int32_t validFlags;
434 
448 typedef struct
449 {
451 
452  float32_t linearVelocity[3];
453 
454  float32_t angularVelocity[3];
455 
456  float32_t linearAcceleration[3];
457 
459 
460  int64_t validFlags;
462 
466 typedef struct
467 {
471  bool valid;
473 
502  const char* imuSensorName, const char* canSensorName);
503 
520  uint32_t imuSensorIdx, uint32_t canSensorIdx);
521 
534 dwStatus dwEgomotion_initialize(dwEgomotionHandle_t* obj, const dwEgomotionParameters* params, dwContextHandle_t ctx);
535 
546 dwStatus dwEgomotion_reset(dwEgomotionHandle_t obj);
547 
559 dwStatus dwEgomotion_release(dwEgomotionHandle_t obj);
560 
583  float32_t measuredValue, dwTime_t timestamp,
584  dwEgomotionHandle_t obj);
585 
599 dwStatus dwEgomotion_addVehicleState(const dwVehicleIOState* state, dwEgomotionHandle_t obj);
600 
613 dwStatus dwEgomotion_updateVehicle(const dwVehicle* vehicle, dwEgomotionHandle_t obj);
614 
631 dwStatus dwEgomotion_addIMUMeasurement(const dwIMUFrame* imu, dwEgomotionHandle_t obj);
632 
646 dwStatus dwEgomotion_updateIMUExtrinsics(const dwTransformation3f* imuToRig, dwEgomotionHandle_t obj);
647 
677 dwStatus dwEgomotion_update(dwTime_t timestamp_us, dwEgomotionHandle_t obj);
678 
702  dwTime_t timestamp_us, dwEgomotionConstHandle_t obj);
703 
724  dwEgomotionRelativeUncertainty* uncertainty,
725  dwTime_t timestamp_a, dwTime_t timestamp_b,
726  dwEgomotionConstHandle_t obj);
727 
741 dwStatus dwEgomotion_getEstimationTimestamp(dwTime_t* timestamp, dwEgomotionConstHandle_t obj);
742 
754 dwStatus dwEgomotion_hasEstimation(bool* result, dwEgomotionConstHandle_t obj);
755 
768 dwStatus dwEgomotion_getEstimation(dwEgomotionResult* result, dwEgomotionConstHandle_t obj);
769 
784 dwStatus dwEgomotion_getUncertainty(dwEgomotionUncertainty* result, dwEgomotionConstHandle_t obj);
785 
797 dwStatus dwEgomotion_getHistorySize(size_t* num, dwEgomotionConstHandle_t obj);
798 
814  size_t index, dwEgomotionConstHandle_t obj);
815 
827 dwStatus dwEgomotion_getMotionModel(dwMotionModel* model, dwEgomotionConstHandle_t obj);
828 
829 //-----------------------------
830 // utility functions
831 
846  const dwTransformation3f* poseOld2New,
847  const dwTransformation3f* oldVehicle2World);
848 
869  float32_t* inverseSteeringR,
870  const dwIMUFrame* imuMeasurement,
871  dwEgomotionConstHandle_t obj);
872 
890  dwEgomotionHandle_t obj);
891 
909  dwEgomotionHandle_t obj);
910 
911 #ifdef __cplusplus
912 }
913 #endif
914 
915 #endif // DW_EGOMOTION_EGOMOTION_H_
DW_API_PUBLIC dwStatus dwEgomotion_getUncertainty(dwEgomotionUncertainty *result, dwEgomotionConstHandle_t obj)
Gets the latest state estimate uncertainties.
float32_t imuSamplingRateHz
If known this entry shall indicate expected sampling rate in [Hz] of the IMU sensor.
Definition: Egomotion.h:309
Suspension model type and parameters.
Definition: Egomotion.h:248
DW_API_PUBLIC dwStatus dwEgomotion_initParamsFromRig(dwEgomotionParameters *params, dwConstRigHandle_t rigConfiguration, const char *imuSensorName, const char *canSensorName)
Initialize egomotion parameters from a provided RigConfiguration.
NVIDIA DriveWorks API: Core Types
float float32_t
Specifies POD types.
Definition: Types.h:70
indicates validity of linearVelocity[0]
Definition: Egomotion.h:398
NVIDIA DriveWorks API: Rig Configuration
indicates validity of linearVelocity[2]
Definition: Egomotion.h:400
Fuses odometry model with IMU measurements to estimate motion of the vehicle.
Definition: Egomotion.h:156
indicates validity of linearAcceleration[1]
Definition: Egomotion.h:407
indicates validity of linearAcceleration[0]
Definition: Egomotion.h:406
dwEgomotionDataField
Defines flags that indicate validity of corresponding data in dwEgomotionResult and dwEgomotionUncert...
Definition: Egomotion.h:395
The state data.
Definition: VehicleIO.h:299
float32_t measurementNoiseStdevAcceleration
Standard deviation of measurement noise in acceleration [m/s^2].
Definition: Egomotion.h:242
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.
float32_t velocityFactor
CAN velocity correction factor which is read from can properties in rig file.
Definition: Egomotion.h:319
Models suspension as single-axis damped torsional spring.
Definition: Egomotion.h:226
bool valid
indicates whether uncertainty estimates are valid or not
Definition: Egomotion.h:471
DW_API_PUBLIC dwStatus dwEgomotion_addIMUMeasurement(const dwIMUFrame *imu, dwEgomotionHandle_t obj)
Adds an IMU frame to the egomotion module.
indicates validity of angularVelocity[0]
Definition: Egomotion.h:402
NVIDIA DriveWorks API: VehicleIO car controller
DW_API_PUBLIC dwStatus dwEgomotion_initParamsFromRigByIndex(dwEgomotionParameters *params, dwConstRigHandle_t rigConfiguration, uint32_t imuSensorIdx, uint32_t canSensorIdx)
Same as dwEgomotion_initParamsFromRig however uses sensor indices in rigConfiguration instead of thei...
indicates validity of angularVelocity[2]
Definition: Egomotion.h:404
Defines a single-precision quaternion.
Definition: Types.h:418
DW_API_PUBLIC dwStatus dwEgomotion_getEstimation(dwEgomotionResult *result, dwEgomotionConstHandle_t obj)
Gets the latest state estimate.
float32_t processNoiseStdevAcceleration
Square root of continuous time process noise covariance in acceleration [m/s^2 * 1/sqrt(s)].
Definition: Egomotion.h:240
dwEgomotionSpeedMeasurementType speedMeasurementType
Defines which velocity readings from dwVehicleIOState shall be used for egomotion estimation...
Definition: Egomotion.h:377
bool estimateInitialOrientation
When enabled, initial rotation will be estimated from accelerometer measurements. ...
Definition: Egomotion.h:350
DW_API_PUBLIC dwStatus dwEgomotion_addVehicleState(const dwVehicleIOState *state, dwEgomotionHandle_t obj)
Notifies the egomotion module of a changed vehicle state.
dwTime_t timeInterval
relative motion time interval [us]
Definition: Egomotion.h:470
int32_t validFlags
Bitwise combination of dwEgomotionDataField flags.
Definition: Egomotion.h:432
Holds egomotion uncertainty estimates for a relative motion estimate.
Definition: Egomotion.h:466
dwEgomotionLinearAccelerationFilterParams linearAccelerationFilterParameters
Linear acceleration filter parameters.
Definition: Egomotion.h:381
float32_t accNoiseDensityMicroG
Expected zero mean measurement noise of the linear accelerometer, also known as Noise Density [ug/sqr...
Definition: Egomotion.h:305
dwMatrix3f rotation
a 3x3 covariance of the rotation (order: roll, pitch, yaw) [rad]
Definition: Egomotion.h:468
NVIDIA DriveWorks API: Core Methods
float32_t measurementNoiseStdevSpeed
Standard deviation of measurement noise in speed [m/s].
Definition: Egomotion.h:241
float32_t lateralSlipCoefficient
Lateral slip coefficient [rad*s^2/m].
Definition: Egomotion.h:338
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.
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...
float32_t gyroBiasRange
If known this value in [rad/s] shall indicate standard deviation of the expected bias range of the gy...
Definition: Egomotion.h:301
dwEgomotionSuspensionParameters suspension
Suspension model parameters.
Definition: Egomotion.h:388
indicates validity of rotation,
Definition: Egomotion.h:396
Sensor measurement noise characteristics.
Definition: Egomotion.h:288
Specifies a 3D rigid transformation.
Definition: Types.h:462
DW_API_PUBLIC dwStatus dwEgomotion_update(dwTime_t timestamp_us, dwEgomotionHandle_t obj)
Runs the motion model estimation for a given timestamp.
dwMotionModel motionModel
Specifies the motion model to be used for pose estimation.
Definition: Egomotion.h:345
uint32_t historySize
Number of state estimates to keep in the history (if 0 specified default of 1000 is used)...
Definition: Egomotion.h:365
dwStatus
Status definition.
Definition: Status.h:178
float32_t accelerationFilterTimeConst
Time constant of the IMU acceleration measurements.
Definition: Egomotion.h:238
struct dwEgomotionObject * dwEgomotionHandle_t
Definition: Egomotion.h:79
Vehicle velocity [m/s].
Definition: Egomotion.h:165
DW_API_PUBLIC dwStatus dwEgomotion_release(dwEgomotionHandle_t obj)
Releases the egomotion module.
DW_API_PUBLIC dwStatus dwEgomotion_getHistorySize(size_t *num, dwEgomotionConstHandle_t obj)
Returns the number of elements currently stored in the history.
indicates validity of linearVelocity[1]
Definition: Egomotion.h:399
DW_API_PUBLIC dwStatus dwEgomotion_getEstimationTimestamp(dwTime_t *timestamp, dwEgomotionConstHandle_t obj)
Gets the timestamp of the latest state estimate.
int64_t dwTime_t
Specifies a timestamp unit, in microseconds.
Definition: Types.h:82
dwMotionModel
Defines the motion models.
Definition: Egomotion.h:83
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_API_PUBLIC dwStatus dwEgomotion_reset(dwEgomotionHandle_t obj)
Resets the state estimate and all history of the egomotion module.
Vehicle velocity [m/s].
Definition: Egomotion.h:164
no filtering of the output linear acceleration
Definition: Egomotion.h:217
float32_t torsionalSpringPitchDampingRatio
Level of damping relative to critical damping around the pitch axis of the vehicle [dimensionless]...
Definition: Egomotion.h:281
float32_t processNoiseStdevSpeed
Square root of continuous time process noise covariance in speed [m/s * 1/sqrt(s)].
Definition: Egomotion.h:239
dwTime_t timestamp
Timestamp of egomotion state estimate [us].
Definition: Egomotion.h:421
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...
dwEgomotionSuspensionModel model
Suspension model to use.
Definition: Egomotion.h:252
An IMU frame containing sensor readings from the IMU sensor.
Definition: IMU.h:104
struct dwEgomotionObject const * dwEgomotionConstHandle_t
Definition: Egomotion.h:80
dwTime_t velocityLatency
CAN velocity latency in microseconds which is read from can properties in rig file.
Definition: Egomotion.h:312
struct dwRigObject const * dwConstRigHandle_t
Definition: Rig.h:73
dwTransformation3f imu2rig
IMU extrinsics.
Definition: Egomotion.h:342
Defines a 3x3 matrix of floating point numbers.
Definition: Types.h:237
float32_t gyroNoiseDensityDeg
Expected zero mean measurement noise of the gyroscope, also known as Noise Density [deg/s/sqrt(Hz)] A...
Definition: Egomotion.h:292
bool automaticUpdate
Automatically update state estimation.
Definition: Egomotion.h:361
DW_API_PUBLIC dwStatus dwEgomotion_hasEstimation(bool *result, dwEgomotionConstHandle_t obj)
Check whether has state estimate.
dwEgomotionLinearAccelerationFilterMode
Defines egomotion linear acceleration filter mode.
Definition: Egomotion.h:216
Defines egomotion linear acceleration filter parameters.
Definition: Egomotion.h:232
DW_API_PUBLIC dwStatus dwEgomotion_getHistoryElement(const dwEgomotionResult **pose, const dwEgomotionUncertainty **uncertainty, size_t index, dwEgomotionConstHandle_t obj)
Returns an element from the motion history that is currently available.
DW_API_PUBLIC dwStatus dwEgomotion_steeringWheelAngleToSteeringAngle(float32_t *steeringAngle, float32_t steeringWheelAngle, dwEgomotionHandle_t obj)
Convert steering wheel angle to steering angle.
dwVehicle vehicle
Vehicle parameters to setup the model.
Definition: Egomotion.h:331
Holds egomotion uncertainty estimates.
Definition: Egomotion.h:448
Indicates that speeds are angular speeds [rad/s] measured at rear wheels.
Definition: Egomotion.h:210
Holds egomotion state estimate.
Definition: Egomotion.h:416
dwTime_t timestamp
Timestamp of egomotion uncertainty estimate [us].
Definition: Egomotion.h:458
struct dwContextObject * dwContextHandle_t
Context handle.
Definition: Context.h:80
dwMatrix3f translation
a 3x3 covariance of the translation (x,y,z) [m]
Definition: Egomotion.h:469
dwEgomotionSpeedMeasurementType
Defines speed measurement types.
Definition: Egomotion.h:175
dwEgomotionLinearAccelerationFilterMode mode
Linear acceleration filter mode. Default (0): no filtering.
Definition: Egomotion.h:235
No suspension model. Equivalent to perfectly rigid suspension.
Definition: Egomotion.h:225
DW_API_PUBLIC dwStatus dwEgomotion_getMotionModel(dwMotionModel *model, dwEgomotionConstHandle_t obj)
Returns the type of the motion model used.
DW_API_PUBLIC dwStatus dwEgomotion_initialize(dwEgomotionHandle_t *obj, const dwEgomotionParameters *params, dwContextHandle_t ctx)
Initializes the egomotion module.
Steering wheel angle [rad].
Definition: Egomotion.h:169
Holds initialization parameters for the Egomotion module.
Definition: Egomotion.h:326
NVIDIA DriveWorks API: Core Exports
Indicates that speed is linear speed [m/s] measured at front wheels (along steering direction)...
Definition: Egomotion.h:191
DW_API_PUBLIC dwStatus dwEgomotion_steeringAngleToSteeringWheelAngle(float32_t *steeringWheelAngle, float32_t steeringAngle, dwEgomotionHandle_t obj)
Convert steering angle to steering wheel angle.
float32_t gyroDriftRate
Expected gyroscope drift rate in [deg/s].
Definition: Egomotion.h:296
indicates validity of linearAcceleration[2]
Definition: Egomotion.h:408
simple low-pass filtering of the acceleration
Definition: Egomotion.h:218
dwMotionModelMeasurement
Defines motion measurements.
Definition: Egomotion.h:163
dwEgomotionSuspensionModel
Defines egomotion suspension model.
Definition: Egomotion.h:224
#define DW_API_PUBLIC
Definition: Exports.h:56
NVIDIA DriveWorks API: IMU
Given odometry information, estimates motion of the vehicle using a bicycle model.
Definition: Egomotion.h:119
dwQuaternionf rotation
Rotation represented as quaternion (x,y,z,w).
Definition: Egomotion.h:418
dwEgomotionSensorCharacteristics sensorParameters
Sensor parameters, containing information about sensor characteristics.
Definition: Egomotion.h:375
float32_t torsionalSpringPitchNaturalFrequency
Torsional spring model parameters.
Definition: Egomotion.h:276
DEPRECATED: Properties of a passenger car vehicle.
Definition: Vehicle.h:306
indicates validity of angularVelocity[1]
Definition: Egomotion.h:403
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_applyRelativeTransformation(dwTransformation3f *newVehicle2World, const dwTransformation3f *poseOld2New, const dwTransformation3f *oldVehicle2World)
Applies the estimated relative motion as returned by dwEgomotion_computeRelativeTransformation() to a...