DriveWorks SDK Reference
4.0.0 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-2021 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 
59 #ifndef DW_EGOMOTION_EGOMOTION_H_
60 #define DW_EGOMOTION_EGOMOTION_H_
61 
62 #include <dw/core/Config.h>
63 #include <dw/core/base/Exports.h>
65 #include <dw/core/base/Types.h>
66 
68 
69 #include <dw/sensors/imu/IMU.h>
70 
71 #include <dw/rig/Rig.h>
72 
73 #ifdef __cplusplus
74 extern "C" {
75 #endif
76 
77 typedef struct dwEgomotionObject* dwEgomotionHandle_t;
78 typedef struct dwEgomotionObject const* dwEgomotionConstHandle_t;
79 
81 typedef enum dwMotionModel {
119 
159 
160 } dwMotionModel;
161 
165 typedef enum {
170 
191 
212 
228 
236 
244 
252 
256 typedef struct dwEgomotionLinearAccelFilterParams
257 {
259  dwEgomotionLinearAccelerationFilterMode mode;
260 
261  // Simple filter parameters (ignored for other modes)
268 
272 typedef struct
273 {
277 
301 
306 
308 
313 {
317 
321 
326 
330 
334 
337 
344 
346 
350 typedef struct dwEgomotionParameters
351 {
356 
362  DW_DEPRECATED("Deriving lateral slip coefficient from vehicle parameters, unless this parameter is non-zero.")
363  float32_t lateralSlipCoefficient;
364 
368 
370  dwMotionModel motionModel;
371 
375  bool estimateInitialOrientation;
376 
386  bool automaticUpdate;
387 
390  uint32_t historySize;
391 
395  float32_t gyroscopeBias[3];
396 
401 
403  dwEgomotionSpeedMeasurementType speedMeasurementType;
404 
406  dwEgomotionSteeringMeasurementType steeringMeasurementType;
407 
410  dwEgomotionLinearAccelerationFilterParams linearAccelerationFilterParameters;
411 
418 
420 
424 typedef enum dwEgomotionDataField {
426 
430 
434 
438 
440 
445 typedef struct
446 {
448 
451 
452  float32_t linearVelocity[3];
453 
457  float32_t angularVelocity[3];
458 
459  float32_t linearAcceleration[3];
460 
461  int32_t validFlags;
463 
477 typedef struct
478 {
480 
481  float32_t linearVelocity[3];
482 
483  float32_t angularVelocity[3];
484 
485  float32_t linearAcceleration[3];
486 
488 
489  int64_t validFlags;
491 
495 typedef struct
496 {
500  bool valid;
502 
534  const char* imuSensorName, const char* vehicleSensorName);
535 
555  uint32_t imuSensorIdx, uint32_t vehicleSensorIdx);
556 
569 dwStatus dwEgomotion_initialize(dwEgomotionHandle_t* obj, const dwEgomotionParameters* params, dwContextHandle_t ctx);
570 
581 dwStatus dwEgomotion_reset(dwEgomotionHandle_t obj);
582 
594 dwStatus dwEgomotion_release(dwEgomotionHandle_t obj);
595 
617 DW_DEPRECATED("Use dwEgomotion_addVehicleState instead.")
619  float32_t measuredValue, dwTime_t timestamp,
620  dwEgomotionHandle_t obj);
621 
635 dwStatus dwEgomotion_addVehicleState(const dwVehicleIOState* state, dwEgomotionHandle_t obj);
636 
649 dwStatus dwEgomotion_updateVehicle(const dwVehicle* vehicle, dwEgomotionHandle_t obj);
650 
667 dwStatus dwEgomotion_addIMUMeasurement(const dwIMUFrame* imu, dwEgomotionHandle_t obj);
668 
682 dwStatus dwEgomotion_updateIMUExtrinsics(const dwTransformation3f* imuToRig, dwEgomotionHandle_t obj);
683 
713 DW_DEPRECATED("Deprecated, will be removed. Set dwEgomotionParameters.autoupdate to true instead.")
714 dwStatus dwEgomotion_update(dwTime_t timestamp_us, dwEgomotionHandle_t obj);
715 
739  dwTime_t timestamp_us, dwEgomotionConstHandle_t obj);
740 
761  dwEgomotionRelativeUncertainty* uncertainty,
762  dwTime_t timestamp_a, dwTime_t timestamp_b,
763  dwEgomotionConstHandle_t obj);
764 
778 dwStatus dwEgomotion_getEstimationTimestamp(dwTime_t* timestamp, dwEgomotionConstHandle_t obj);
779 
791 dwStatus dwEgomotion_hasEstimation(bool* result, dwEgomotionConstHandle_t obj);
792 
805 dwStatus dwEgomotion_getEstimation(dwEgomotionResult* result, dwEgomotionConstHandle_t obj);
806 
821 dwStatus dwEgomotion_getUncertainty(dwEgomotionUncertainty* result, dwEgomotionConstHandle_t obj);
822 
834 dwStatus dwEgomotion_getHistorySize(size_t* num, dwEgomotionConstHandle_t obj);
835 
851  size_t index, dwEgomotionConstHandle_t obj);
852 
864 dwStatus dwEgomotion_getMotionModel(dwMotionModel* model, dwEgomotionConstHandle_t obj);
865 
866 //-----------------------------
867 // utility functions
868 
883  const dwTransformation3f* poseOld2New,
884  const dwTransformation3f* oldVehicle2World);
885 
906  float32_t* inverseSteeringR,
907  const dwIMUFrame* imuMeasurement,
908  dwEgomotionConstHandle_t obj);
909 
927  dwEgomotionHandle_t obj);
928 
946  dwEgomotionHandle_t obj);
947 
948 #ifdef __cplusplus
949 }
950 #endif
951 
952 #endif // DW_EGOMOTION_EGOMOTION_H_
NVIDIA DriveWorks API: Core Types
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:333
Suspension model type and parameters.
Definition: Egomotion.h:272
float float32_t
Specifies POD types.
Definition: Types.h:70
indicates validity of linearVelocity[0]
Definition: Egomotion.h:427
NVIDIA DriveWorks API: Rig Configuration
indicates validity of linearVelocity[2]
Definition: Egomotion.h:429
Fuses odometry model with IMU measurements to estimate motion of the vehicle.
Definition: Egomotion.h:158
indicates validity of linearAcceleration[1]
Definition: Egomotion.h:436
indicates validity of linearAcceleration[0]
Definition: Egomotion.h:435
dwEgomotionDataField
Defines flags that indicate validity of corresponding data in dwEgomotionResult and dwEgomotionUncert...
Definition: Egomotion.h:424
The state data.
Definition: VehicleIO.h:435
float32_t measurementNoiseStdevAcceleration
Standard deviation of measurement noise in acceleration [m/s^2].
Definition: Egomotion.h:266
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:343
Models suspension as single-axis damped torsional spring.
Definition: Egomotion.h:250
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.
bool valid
indicates whether uncertainty estimates are valid or not
Definition: Egomotion.h:500
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:431
NVIDIA DriveWorks API: VehicleIO car controller
indicates validity of angularVelocity[2]
Definition: Egomotion.h:433
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:264
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:499
int32_t validFlags
Bitwise combination of dwEgomotionDataField flags.
Definition: Egomotion.h:461
Holds egomotion uncertainty estimates for a relative motion estimate.
Definition: Egomotion.h:495
float32_t accNoiseDensityMicroG
Expected zero mean measurement noise of the linear accelerometer, also known as Noise Density [ug/sqr...
Definition: Egomotion.h:329
dwMatrix3f rotation
a 3x3 covariance of the rotation (order: roll, pitch, yaw) [rad]
Definition: Egomotion.h:497
float32_t measurementNoiseStdevSpeed
Standard deviation of measurement noise in speed [m/s].
Definition: Egomotion.h:265
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:325
dwEgomotionSteeringMeasurementType
Defines steering measurement types.
Definition: Egomotion.h:232
indicates validity of rotation,
Definition: Egomotion.h:425
Sensor measurement noise characteristics.
Definition: Egomotion.h:312
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.
dwStatus
Status definition.
Definition: Status.h:180
float32_t accelerationFilterTimeConst
Time constant of the IMU acceleration measurements.
Definition: Egomotion.h:262
struct dwEgomotionObject * dwEgomotionHandle_t
Definition: Egomotion.h:77
Vehicle velocity [m/s].
Definition: Egomotion.h:166
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:428
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:81
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.
no filtering of the output linear acceleration
Definition: Egomotion.h:241
#define DW_DEPRECATED(msg)
Definition: Exports.h:66
float32_t torsionalSpringPitchDampingRatio
Level of damping relative to critical damping around the pitch axis of the vehicle [dimensionless]...
Definition: Egomotion.h:305
float32_t processNoiseStdevSpeed
Square root of continuous time process noise covariance in speed [m/s * 1/sqrt(s)].
Definition: Egomotion.h:263
dwTime_t timestamp
Timestamp of egomotion state estimate [us].
Definition: Egomotion.h:450
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:276
An IMU frame containing sensor readings from the IMU sensor.
Definition: IMU.h:102
struct dwEgomotionObject const * dwEgomotionConstHandle_t
Definition: Egomotion.h:78
dwTime_t velocityLatency
CAN velocity latency in microseconds which is read from can properties in rig file.
Definition: Egomotion.h:336
struct dwRigObject const * dwConstRigHandle_t
Definition: Rig.h:71
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:316
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_hasEstimation(bool *result, dwEgomotionConstHandle_t obj)
Check whether has state estimate.
dwEgomotionLinearAccelerationFilterMode
Defines egomotion linear acceleration filter mode.
Definition: Egomotion.h:240
Defines egomotion linear acceleration filter parameters.
Definition: Egomotion.h:256
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:355
Holds egomotion uncertainty estimates.
Definition: Egomotion.h:477
Indicates that speeds are angular speeds [rad/s] measured at rear wheels.
Definition: Egomotion.h:211
Holds egomotion state estimate.
Definition: Egomotion.h:445
dwTime_t timestamp
Timestamp of egomotion uncertainty estimate [us].
Definition: Egomotion.h:487
struct dwContextObject * dwContextHandle_t
Context handle.
Definition: Context.h:79
dwMatrix3f translation
a 3x3 covariance of the translation (x,y,z) [m]
Definition: Egomotion.h:498
NVIDIA DriveWorks API: Core Methods
dwEgomotionSpeedMeasurementType
Defines speed measurement types.
Definition: Egomotion.h:174
dwEgomotionLinearAccelerationFilterMode mode
Linear acceleration filter mode. Default (0): no filtering.
Definition: Egomotion.h:259
No suspension model. Equivalent to perfectly rigid suspension.
Definition: Egomotion.h:249
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:168
Holds initialization parameters for the Egomotion module.
Definition: Egomotion.h:350
Indicates that speed is linear speed [m/s] measured at front wheels (along steering direction)...
Definition: Egomotion.h:190
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_initParamsFromRig(dwEgomotionParameters *params, dwConstRigHandle_t rigConfiguration, const char *imuSensorName, const char *vehicleSensorName)
Initialize egomotion parameters from a provided RigConfiguration.
float32_t gyroDriftRate
Expected gyroscope drift rate in [deg/s].
Definition: Egomotion.h:320
indicates validity of linearAcceleration[2]
Definition: Egomotion.h:437
simple low-pass filtering of the acceleration
Definition: Egomotion.h:242
dwMotionModelMeasurement
Defines motion measurements.
Definition: Egomotion.h:165
dwEgomotionSuspensionModel
Defines egomotion suspension model.
Definition: Egomotion.h:248
#define DW_API_PUBLIC
Definition: Exports.h:54
NVIDIA DriveWorks API: IMU
Given odometry information, estimates motion of the vehicle using a bicycle model.
Definition: Egomotion.h:118
dwQuaternionf rotation
Rotation represented as quaternion (x,y,z,w).
Definition: Egomotion.h:447
float32_t torsionalSpringPitchNaturalFrequency
Torsional spring model parameters.
Definition: Egomotion.h:300
DEPRECATED: Properties of a passenger car vehicle.
Definition: Vehicle.h:306
Indicates that speed is linear speed [m/s] measured at rear axle center (along steering direction)...
Definition: Egomotion.h:226
indicates validity of angularVelocity[1]
Definition: Egomotion.h:432
DW_API_PUBLIC dwStatus dwEgomotion_updateVehicle(const dwVehicle *vehicle, dwEgomotionHandle_t obj)
This method updates the egomotion module with an updated vehicle.
NVIDIA DriveWorks API: Core Exports
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...