DriveWorks SDK Reference
5.4.5418 Release
For Test and Development only

Egomotion.h
Go to the documentation of this file.
1 //
3 // Notice
4 // ALL NVIDIA DESIGN SPECIFICATIONS AND CODE ("MATERIALS") ARE PROVIDED "AS IS" NVIDIA MAKES
5 // NO REPRESENTATIONS, WARRANTIES, EXPRESSED, IMPLIED, STATUTORY, OR OTHERWISE WITH RESPECT TO
6 // THE MATERIALS, AND EXPRESSLY DISCLAIMS ANY IMPLIED WARRANTIES OF NONINFRINGEMENT,
7 // MERCHANTABILITY, OR FITNESS FOR A PARTICULAR PURPOSE.
8 //
9 // NVIDIA CORPORATION & AFFILIATES assumes no responsibility for the consequences of use of such
10 // information or for any infringement of patents or other rights of third parties that may
11 // result from its use. No license is granted by implication or otherwise under any patent
12 // or patent rights of NVIDIA CORPORATION & AFFILIATES. No third party distribution is allowed unless
13 // expressly authorized by NVIDIA. Details are subject to change without notice.
14 // This code supersedes and replaces all information previously supplied.
15 // NVIDIA CORPORATION & AFFILIATES products are not authorized for use as critical
16 // components in life support devices or systems without express written approval of
17 // NVIDIA CORPORATION & AFFILIATES.
18 //
19 // SPDX-FileCopyrightText: Copyright (c) 2015-2021 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
20 // SPDX-License-Identifier: LicenseRef-NvidiaProprietary
21 //
22 // NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
23 // property and proprietary rights in and to this material, related
24 // documentation and any modifications thereto. Any use, reproduction,
25 // disclosure or distribution of this material and related documentation
26 // without an express license agreement from NVIDIA CORPORATION or
27 // its affiliates is 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 {
126 
172 
173 } dwMotionModel;
174 
178 typedef enum {
183 
206 
229 
247 
255 
263 
271 
275 typedef struct dwEgomotionLinearAccelFilterParams
276 {
278  dwEgomotionLinearAccelerationFilterMode mode;
279 
280  // Simple filter parameters (ignored for other modes)
287 
291 typedef struct
292 {
296 
320 
325 
327 
332 {
336 
340 
345 
349 
353 
358 
361 
368 
370 
374 typedef struct dwEgomotionParameters
375 {
380 
386  DW_DEPRECATED("Deriving lateral slip coefficient from vehicle parameters, unless this parameter is non-zero.")
387  float32_t lateralSlipCoefficient;
388 
392 
394  dwMotionModel motionModel;
395 
399  bool estimateInitialOrientation;
400 
410  bool automaticUpdate;
411 
414  uint32_t historySize;
415 
419  float32_t gyroscopeBias[3];
420 
425 
427  dwEgomotionSpeedMeasurementType speedMeasurementType;
428 
430  dwEgomotionSteeringMeasurementType steeringMeasurementType;
431 
434  dwEgomotionLinearAccelerationFilterParams linearAccelerationFilterParameters;
435 
442 
444 
448 typedef enum dwEgomotionDataField {
450 
454 
458 
462 
464 
469 //# sergen(generate)
470 typedef struct dwEgomotionResult
471 {
473 
476 
477  float32_t linearVelocity[3];
478 
482  float32_t angularVelocity[3];
483 
484  float32_t linearAcceleration[3];
485 
486  int32_t validFlags;
488 
502 typedef struct
503 {
505 
506  float32_t linearVelocity[3];
507 
508  float32_t angularVelocity[3];
509 
510  float32_t linearAcceleration[3];
511 
513 
514  int64_t validFlags;
516 
520 typedef struct
521 {
525  bool valid;
527 
559  const char* imuSensorName, const char* vehicleSensorName);
560 
580  uint32_t imuSensorIdx, uint32_t vehicleSensorIdx);
581 
594 dwStatus dwEgomotion_initialize(dwEgomotionHandle_t* obj, const dwEgomotionParameters* params, dwContextHandle_t ctx);
595 
606 dwStatus dwEgomotion_reset(dwEgomotionHandle_t obj);
607 
619 dwStatus dwEgomotion_release(dwEgomotionHandle_t obj);
620 
642 DW_DEPRECATED("Use dwEgomotion_addVehicleState instead.")
644  float32_t measuredValue, dwTime_t timestamp,
645  dwEgomotionHandle_t obj);
646 
661 dwStatus dwEgomotion_addVehicleState(const dwVehicleIOState* state, dwEgomotionHandle_t obj);
662 
679  dwVehicleIONonSafetyState const* nonSafeState,
680  dwVehicleIOActuationFeedback const* actuationFeedback,
681  dwEgomotionHandle_t obj);
682 
695 dwStatus dwEgomotion_updateVehicle(const dwVehicle* vehicle, dwEgomotionHandle_t obj);
696 
713 dwStatus dwEgomotion_addIMUMeasurement(const dwIMUFrame* imu, dwEgomotionHandle_t obj);
714 
728 dwStatus dwEgomotion_updateIMUExtrinsics(const dwTransformation3f* imuToRig, dwEgomotionHandle_t obj);
729 
759 DW_DEPRECATED("Deprecated, will be removed. Set dwEgomotionParameters.autoupdate to true instead.")
760 dwStatus dwEgomotion_update(dwTime_t timestamp_us, dwEgomotionHandle_t obj);
761 
785  dwTime_t timestamp_us, dwEgomotionConstHandle_t obj);
786 
807  dwEgomotionRelativeUncertainty* uncertainty,
808  dwTime_t timestamp_a, dwTime_t timestamp_b,
809  dwEgomotionConstHandle_t obj);
810 
824 dwStatus dwEgomotion_getEstimationTimestamp(dwTime_t* timestamp, dwEgomotionConstHandle_t obj);
825 
837 dwStatus dwEgomotion_hasEstimation(bool* result, dwEgomotionConstHandle_t obj);
838 
851 dwStatus dwEgomotion_getEstimation(dwEgomotionResult* result, dwEgomotionConstHandle_t obj);
852 
867 dwStatus dwEgomotion_getUncertainty(dwEgomotionUncertainty* result, dwEgomotionConstHandle_t obj);
868 
882 dwStatus dwEgomotion_getGyroscopeBias(dwVector3f* gyroBias, dwEgomotionConstHandle_t obj);
883 
895 dwStatus dwEgomotion_getHistorySize(size_t* num, dwEgomotionConstHandle_t obj);
896 
912  size_t index, dwEgomotionConstHandle_t obj);
913 
925 dwStatus dwEgomotion_getMotionModel(dwMotionModel* model, dwEgomotionConstHandle_t obj);
926 
927 //-----------------------------
928 // utility functions
929 
944  const dwTransformation3f* poseOld2New,
945  const dwTransformation3f* oldVehicle2World);
946 
967  float32_t* inverseSteeringR,
968  const dwIMUFrame* imuMeasurement,
969  dwEgomotionConstHandle_t obj);
970 
988  dwEgomotionHandle_t obj);
989 
1007  dwEgomotionHandle_t obj);
1008 
1009 #ifdef __cplusplus
1010 }
1011 #endif
1012 
1013 #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:352
DW_API_PUBLIC dwStatus dwEgomotion_getGyroscopeBias(dwVector3f *gyroBias, dwEgomotionConstHandle_t obj)
Get estimated gyroscope bias.
Suspension model type and parameters.
Definition: Egomotion.h:291
float float32_t
Specifies POD types.
Definition: Types.h:70
indicates validity of linearVelocity[0]
Definition: Egomotion.h:451
NVIDIA DriveWorks API: Rig Configuration
indicates validity of linearVelocity[2]
Definition: Egomotion.h:453
Fuses odometry model with IMU measurements to estimate motion of the vehicle.
Definition: Egomotion.h:171
indicates validity of linearAcceleration[1]
Definition: Egomotion.h:460
indicates validity of linearAcceleration[0]
Definition: Egomotion.h:459
dwEgomotionDataField
Defines flags that indicate validity of corresponding data in dwEgomotionResult and dwEgomotionUncert...
Definition: Egomotion.h:448
The vehicle IO state data.
float32_t measurementNoiseStdevAcceleration
Standard deviation of measurement noise in acceleration [m/s^2].
Definition: Egomotion.h:285
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:367
Models suspension as single-axis damped torsional spring.
Definition: Egomotion.h:269
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:525
DW_API_PUBLIC dwStatus dwEgomotion_addIMUMeasurement(const dwIMUFrame *imu, dwEgomotionHandle_t obj)
Adds an IMU frame to the egomotion module.
Defines a three-element floating-point vector.
Definition: Types.h:323
indicates validity of angularVelocity[0]
Definition: Egomotion.h:455
Non-safety critical RoV state.
NVIDIA DriveWorks API: VehicleIO car controller
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.
indicates validity of angularVelocity[2]
Definition: Egomotion.h:457
Defines a single-precision quaternion.
Definition: Types.h:423
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:283
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:524
int32_t validFlags
Bitwise combination of dwEgomotionDataField flags.
Definition: Egomotion.h:486
Holds egomotion uncertainty estimates for a relative motion estimate.
Definition: Egomotion.h:520
float32_t accNoiseDensityMicroG
Expected zero mean measurement noise of the linear accelerometer, also known as Noise Density [ug/sqr...
Definition: Egomotion.h:348
dwMatrix3f rotation
a 3x3 covariance of the rotation (order: roll, pitch, yaw) [rad]
Definition: Egomotion.h:522
float32_t measurementNoiseStdevSpeed
Standard deviation of measurement noise in speed [m/s].
Definition: Egomotion.h:284
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:344
dwEgomotionSteeringMeasurementType
Defines steering measurement types.
Definition: Egomotion.h:251
indicates validity of rotation,
Definition: Egomotion.h:449
Sensor measurement noise characteristics.
Definition: Egomotion.h:331
Specifies a 3D rigid transformation.
Definition: Types.h:467
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
Safety critical VIO state.
float32_t accelerationFilterTimeConst
Time constant of the IMU acceleration measurements.
Definition: Egomotion.h:281
struct dwEgomotionObject * dwEgomotionHandle_t
Definition: Egomotion.h:77
Vehicle velocity [m/s].
Definition: Egomotion.h:179
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:452
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:260
#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:324
float32_t processNoiseStdevSpeed
Square root of continuous time process noise covariance in speed [m/s * 1/sqrt(s)].
Definition: Egomotion.h:282
dwTime_t timestamp
Timestamp of egomotion state estimate [us].
Definition: Egomotion.h:475
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:295
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:360
struct dwRigObject const * dwConstRigHandle_t
Definition: Rig.h:71
Defines a 3x3 matrix of floating point numbers.
Definition: Types.h:240
float32_t gyroNoiseDensityDeg
Expected zero mean measurement noise of the gyroscope, also known as Noise Density [deg/s/sqrt(Hz)] A...
Definition: Egomotion.h:335
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:259
Defines egomotion linear acceleration filter parameters.
Definition: Egomotion.h:275
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:379
float32_t odometrySamplingRateHz
If known this entry shall indicate expected sampling rate in [Hz] of the odometry signals...
Definition: Egomotion.h:357
Holds egomotion uncertainty estimates.
Definition: Egomotion.h:502
Indicates that speeds are angular speeds [rad/s] measured at rear wheels.
Definition: Egomotion.h:228
Holds egomotion state estimate.
Definition: Egomotion.h:470
dwTime_t timestamp
Timestamp of egomotion uncertainty estimate [us].
Definition: Egomotion.h:512
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:523
NVIDIA DriveWorks API: Core Methods
dwEgomotionSpeedMeasurementType
Defines speed measurement types.
Definition: Egomotion.h:187
dwEgomotionLinearAccelerationFilterMode mode
Linear acceleration filter mode. Default (0): no filtering.
Definition: Egomotion.h:278
No suspension model. Equivalent to perfectly rigid suspension.
Definition: Egomotion.h:268
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:181
Holds initialization parameters for the Egomotion module.
Definition: Egomotion.h:374
Indicates that speed is linear speed [m/s] measured at front wheels (along steering direction)...
Definition: Egomotion.h:205
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:339
indicates validity of linearAcceleration[2]
Definition: Egomotion.h:461
simple low-pass filtering of the acceleration
Definition: Egomotion.h:261
dwMotionModelMeasurement
Defines motion measurements.
Definition: Egomotion.h:178
dwEgomotionSuspensionModel
Defines egomotion suspension model.
Definition: Egomotion.h:267
#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:125
dwQuaternionf rotation
Rotation represented as quaternion (x,y,z,w).
Definition: Egomotion.h:472
float32_t torsionalSpringPitchNaturalFrequency
Torsional spring model parameters.
Definition: Egomotion.h:319
DEPRECATED: Properties of a passenger car vehicle.
Definition: Vehicle.h:315
Indicates that speed is linear speed [m/s] measured at rear axle center (along steering direction)...
Definition: Egomotion.h:245
indicates validity of angularVelocity[1]
Definition: Egomotion.h:456
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...