Loading [MathJax]/extensions/tex2jax.js
  • <xmp id="om0om">
  • <table id="om0om"><noscript id="om0om"></noscript></table>

  • DriveWorks SDK Reference
    5.6.215 Release
    For Test and Development only

    All Data Structures Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
    Egomotion.h
    Go to the documentation of this file.
    1
    2//
    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-2022 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>
    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
    74extern "C" {
    75#endif
    76
    77typedef struct dwEgomotionObject* dwEgomotionHandle_t;
    78typedef struct dwEgomotionObject const* dwEgomotionConstHandle_t;
    79
    81typedef enum dwMotionModel {
    126
    172
    174
    178typedef enum {
    183
    206
    229
    247
    255
    263
    271
    275typedef struct dwEgomotionLinearAccelFilterParams
    276{
    279
    280 // Simple filter parameters (ignored for other modes)
    287
    291typedef struct
    292{
    296
    320
    325
    327
    332{
    336
    340
    345
    349
    353
    358
    361
    368
    370
    375{
    380
    386 DW_DEPRECATED("Deriving lateral slip coefficient from vehicle parameters, unless this parameter is non-zero.")
    388
    392
    395
    400
    411
    414 uint32_t historySize;
    415
    420
    425
    428
    431
    435
    442
    444
    450
    454
    458
    462
    466
    468
    473//# sergen(generate)
    474typedef struct dwEgomotionResult
    475{
    478
    480
    481 float32_t linearVelocity[3];
    485
    486 float32_t angularVelocity[3];
    487
    488 float32_t linearAcceleration[3];
    489
    490 float32_t angularAcceleration[3];
    491
    492 int32_t validFlags;
    494
    508typedef struct
    509{
    511
    512 float32_t linearVelocity[3];
    513
    514 float32_t angularVelocity[3];
    515
    516 float32_t linearAcceleration[3];
    517
    518 float32_t angularAcceleration[3];
    519
    521
    522 int64_t validFlags;
    524
    528typedef struct
    529{
    533 bool valid;
    535
    567 const char* imuSensorName, const char* vehicleSensorName);
    568
    588 uint32_t imuSensorIdx, uint32_t vehicleSensorIdx);
    589
    603
    615
    628
    650DW_DEPRECATED("Use dwEgomotion_addVehicleState instead.")
    652 float32_t measuredValue, dwTime_t timestamp,
    654
    670
    687 dwVehicleIONonSafetyState const* nonSafeState,
    688 dwVehicleIOActuationFeedback const* actuationFeedback,
    690
    704
    722
    737
    767DW_DEPRECATED("Deprecated, will be removed. Set dwEgomotionParameters.autoupdate to true instead.")
    769
    793 dwTime_t timestamp_us, dwEgomotionConstHandle_t obj);
    794
    816 dwTime_t timestamp_a, dwTime_t timestamp_b,
    818
    833
    846
    860
    876
    891
    904
    920 size_t index, dwEgomotionConstHandle_t obj);
    921
    934
    935//-----------------------------
    936// utility functions
    937
    952 const dwTransformation3f* poseOld2New,
    953 const dwTransformation3f* oldVehicle2World);
    954
    975 float32_t* inverseSteeringR,
    976 const dwIMUFrame* imuMeasurement,
    978
    997
    1016
    1017#ifdef __cplusplus
    1018}
    1019#endif
    1021#endif // DW_EGOMOTION_EGOMOTION_H_
    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.
    Definition: Context.h:79
    #define DW_DEPRECATED(msg)
    Definition: Exports.h:66
    #define DW_API_PUBLIC
    Definition: Exports.h:54
    dwStatus
    Status definition.
    Definition: Status.h:170
    float float32_t
    Specifies POD types.
    Definition: Types.h:70
    int64_t dwTime_t
    Specifies a timestamp unit, in microseconds.
    Definition: Types.h:82
    Defines a 3x3 matrix of floating point numbers by using only one array.
    Definition: Types.h:261
    Defines a single-precision quaternion.
    Definition: Types.h:486
    Specifies a 3D rigid transformation.
    Definition: Types.h:536
    Defines a three-element floating-point vector.
    Definition: Types.h:355
    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
    float32_t odometrySamplingRateHz
    If known this entry shall indicate expected sampling rate in [Hz] of the odometry signals.
    Definition: Egomotion.h:357
    dwTime_t velocityLatency
    CAN velocity latency in microseconds which is read from can properties in rig file.
    Definition: Egomotion.h:360
    float32_t gyroscopeBias[3]
    Initial gyroscope biases, if known at initialization time.
    Definition: Egomotion.h:419
    dwMatrix3f rotation
    Rotation covariance represented as euler angles (order: roll, pitch, yaw) in [rad^2].
    Definition: Egomotion.h:510
    float32_t torsionalSpringPitchNaturalFrequency
    Torsional spring model parameters.
    Definition: Egomotion.h:319
    dwTransformation3f imu2rig
    IMU extrinsics.
    Definition: Egomotion.h:391
    dwEgomotionSensorCharacteristics sensorParameters
    Sensor parameters, containing information about sensor characteristics.
    Definition: Egomotion.h:424
    float32_t accNoiseDensityMicroG
    Expected zero mean measurement noise of the linear accelerometer, also known as Noise Density [ug/sqr...
    Definition: Egomotion.h:348
    dwEgomotionSuspensionModel model
    Suspension model to use.
    Definition: Egomotion.h:295
    dwMatrix3f rotation
    a 3x3 covariance of the rotation (order: roll, pitch, yaw) [rad]
    Definition: Egomotion.h:530
    float32_t accelerationFilterTimeConst
    Time constant of the IMU acceleration measurements.
    Definition: Egomotion.h:281
    dwEgomotionSpeedMeasurementType speedMeasurementType
    Defines which velocity readings from dwVehicleIOState shall be used for egomotion estimation.
    Definition: Egomotion.h:427
    float32_t gyroDriftRate
    Expected gyroscope drift rate in [deg/s].
    Definition: Egomotion.h:339
    float32_t torsionalSpringPitchDampingRatio
    Level of damping relative to critical damping around the pitch axis of the vehicle [dimensionless].
    Definition: Egomotion.h:324
    bool estimateInitialOrientation
    When enabled, initial rotation will be estimated from accelerometer measurements.
    Definition: Egomotion.h:399
    dwEgomotionSteeringMeasurementType steeringMeasurementType
    Defines which steering readings from dwVehicleIOState shall be used for egomotion estimation.
    Definition: Egomotion.h:430
    uint32_t historySize
    Number of state estimates to keep in the history (if 0 specified default of 1000 is used).
    Definition: Egomotion.h:414
    dwTime_t timestamp
    Timestamp of egomotion state estimate [us].
    Definition: Egomotion.h:479
    int32_t validFlags
    Bitwise combination of dwEgomotionDataField flags.
    Definition: Egomotion.h:492
    float32_t velocityFactor
    CAN velocity correction factor which is read from can properties in rig file.
    Definition: Egomotion.h:367
    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
    float32_t imuSamplingRateHz
    If known this entry shall indicate expected sampling rate in [Hz] of the IMU sensor.
    Definition: Egomotion.h:352
    bool automaticUpdate
    Automatically update state estimation.
    Definition: Egomotion.h:410
    dwEgomotionSuspensionParameters suspension
    Suspension model parameters.
    Definition: Egomotion.h:441
    dwMatrix3f translation
    a 3x3 covariance of the translation (x,y,z) [m]
    Definition: Egomotion.h:531
    float32_t lateralSlipCoefficient
    Lateral slip coefficient [rad*s^2/m].
    Definition: Egomotion.h:387
    dwEgomotionLinearAccelerationFilterParams linearAccelerationFilterParameters
    Linear acceleration filter parameters.
    Definition: Egomotion.h:434
    dwEgomotionLinearAccelerationFilterMode mode
    Linear acceleration filter mode. Default (0): no filtering.
    Definition: Egomotion.h:278
    float32_t measurementNoiseStdevAcceleration
    Standard deviation of measurement noise in acceleration [m/s^2].
    Definition: Egomotion.h:285
    dwVehicle vehicle
    Vehicle parameters to setup the model.
    Definition: Egomotion.h:379
    int64_t validFlags
    Bitwise combination of dwEgomotionDataField flags.
    Definition: Egomotion.h:522
    float32_t measurementNoiseStdevSpeed
    Standard deviation of measurement noise in speed [m/s].
    Definition: Egomotion.h:284
    float32_t processNoiseStdevAcceleration
    Square root of continuous time process noise covariance in acceleration [m/s^2 * 1/sqrt(s)].
    Definition: Egomotion.h:283
    float32_t processNoiseStdevSpeed
    Square root of continuous time process noise covariance in speed [m/s * 1/sqrt(s)].
    Definition: Egomotion.h:282
    bool valid
    indicates whether uncertainty estimates are valid or not
    Definition: Egomotion.h:533
    dwMotionModel motionModel
    Specifies the motion model to be used for pose estimation.
    Definition: Egomotion.h:394
    dwQuaternionf rotation
    Rotation represented as quaternion (x,y,z,w).
    Definition: Egomotion.h:476
    dwTime_t timeInterval
    relative motion time interval [us]
    Definition: Egomotion.h:532
    dwTime_t timestamp
    Timestamp of egomotion uncertainty estimate [us].
    Definition: Egomotion.h:520
    dwMotionModelMeasurement
    Defines motion measurements.
    Definition: Egomotion.h:178
    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...
    Definition: Egomotion.h:448
    DW_API_PUBLIC dwStatus dwEgomotion_hasEstimation(bool *result, dwEgomotionConstHandle_t obj)
    Check whether has state estimate.
    struct dwEgomotionObject const * dwEgomotionConstHandle_t
    Definition: Egomotion.h:78
    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.
    Definition: Egomotion.h:81
    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.
    Definition: Egomotion.h:267
    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.
    Definition: Egomotion.h:259
    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.
    Definition: Egomotion.h:251
    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
    Definition: Egomotion.h:77
    DW_API_PUBLIC dwStatus dwEgomotion_release(dwEgomotionHandle_t obj)
    Releases the egomotion module.
    dwEgomotionSpeedMeasurementType
    Defines speed measurement types.
    Definition: Egomotion.h:187
    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].
    Definition: Egomotion.h:179
    @ DW_EGOMOTION_MEASUREMENT_STEERINGANGLE
    Steering angle [rad].
    Definition: Egomotion.h:180
    @ DW_EGOMOTION_MEASUREMENT_STEERINGWHEELANGLE
    Steering wheel angle [rad].
    Definition: Egomotion.h:181
    @ DW_EGOMOTION_LIN_VEL_X
    indicates validity of linearVelocity[0]
    Definition: Egomotion.h:451
    @ DW_EGOMOTION_LIN_ACC_X
    indicates validity of linearAcceleration[0]
    Definition: Egomotion.h:459
    @ DW_EGOMOTION_ANG_ACC_Z
    indicates validity of angularAcceleration[2]
    Definition: Egomotion.h:465
    @ DW_EGOMOTION_ANG_ACC_Y
    indicates validity of angularAcceleration[1]
    Definition: Egomotion.h:464
    @ DW_EGOMOTION_ROTATION
    indicates validity of rotation,
    Definition: Egomotion.h:449
    @ DW_EGOMOTION_LIN_VEL_Y
    indicates validity of linearVelocity[1]
    Definition: Egomotion.h:452
    @ DW_EGOMOTION_LIN_ACC_Z
    indicates validity of linearAcceleration[2]
    Definition: Egomotion.h:461
    @ DW_EGOMOTION_ANG_ACC_X
    indicates validity of angularAcceleration[0]
    Definition: Egomotion.h:463
    @ DW_EGOMOTION_LIN_ACC_Y
    indicates validity of linearAcceleration[1]
    Definition: Egomotion.h:460
    @ DW_EGOMOTION_ANG_VEL_Y
    indicates validity of angularVelocity[1]
    Definition: Egomotion.h:456
    @ DW_EGOMOTION_ANG_VEL_X
    indicates validity of angularVelocity[0]
    Definition: Egomotion.h:455
    @ DW_EGOMOTION_LIN_VEL_Z
    indicates validity of linearVelocity[2]
    Definition: Egomotion.h:453
    @ DW_EGOMOTION_ANG_VEL_Z
    indicates validity of angularVelocity[2]
    Definition: Egomotion.h:457
    @ DW_EGOMOTION_ODOMETRY
    Given odometry information, estimates motion of the vehicle using a bicycle model.
    Definition: Egomotion.h:125
    @ DW_EGOMOTION_IMU_ODOMETRY
    Fuses odometry model with IMU measurements to estimate motion of the vehicle.
    Definition: Egomotion.h:171
    @ DW_EGOMOTION_SUSPENSION_RIGID_MODEL
    No suspension model. Equivalent to perfectly rigid suspension.
    Definition: Egomotion.h:268
    @ DW_EGOMOTION_SUSPENSION_TORSIONAL_SPRING_MODEL
    Models suspension as single-axis damped torsional spring.
    Definition: Egomotion.h:269
    @ DW_EGOMOTION_ACC_FILTER_NO_FILTERING
    no filtering of the output linear acceleration
    Definition: Egomotion.h:260
    @ DW_EGOMOTION_ACC_FILTER_SIMPLE
    simple low-pass filtering of the acceleration
    Definition: Egomotion.h:261
    @ DW_EGOMOTION_STEERING_WHEEL_ANGLE
    Definition: Egomotion.h:253
    @ DW_EGOMOTION_FRONT_STEERING
    Definition: Egomotion.h:252
    @ DW_EGOMOTION_REAR_WHEEL_SPEED
    Indicates that speeds are angular speeds [rad/s] measured at rear wheels.
    Definition: Egomotion.h:228
    @ DW_EGOMOTION_FRONT_SPEED
    Indicates that speed is linear speed [m/s] measured at front wheels (along steering direction).
    Definition: Egomotion.h:205
    @ DW_EGOMOTION_REAR_SPEED
    Indicates that speed is linear speed [m/s] measured at rear axle center (along steering direction).
    Definition: Egomotion.h:245
    Defines egomotion linear acceleration filter parameters.
    Definition: Egomotion.h:276
    Holds initialization parameters for the Egomotion module.
    Definition: Egomotion.h:375
    Holds egomotion uncertainty estimates for a relative motion estimate.
    Definition: Egomotion.h:529
    Holds egomotion state estimate.
    Definition: Egomotion.h:475
    Sensor measurement noise characteristics.
    Definition: Egomotion.h:332
    Suspension model type and parameters.
    Definition: Egomotion.h:292
    Holds egomotion uncertainty estimates.
    Definition: Egomotion.h:509
    An IMU frame containing sensor readings from the IMU sensor.
    Definition: IMU.h:103
    struct dwRigObject const * dwConstRigHandle_t
    Definition: Rig.h:71
    DEPRECATED: Properties of a passenger car vehicle.
    Definition: Vehicle.h:316
    人人超碰97caoporen国产