NVIDIA DriveOS Linux NSR SDK API Reference

7.0.3.0 Release
Engine.h
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: Copyright (c) 2016-2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3  * SPDX-License-Identifier: LicenseRef-NvidiaProprietary
4  *
5  * NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
6  * property and proprietary rights in and to this material, related
7  * documentation and any modifications thereto. Any use, reproduction,
8  * disclosure or distribution of this material and related documentation
9  * without an express license agreement from NVIDIA CORPORATION or
10  * its affiliates is strictly prohibited.
11  */
12 
29 #ifndef DW_CALIBRATION_ENGINE_CALIBRATIONENGINE_H_
30 #define DW_CALIBRATION_ENGINE_CALIBRATIONENGINE_H_
31 
32 #include <dw/core/context/Context.h>
33 #include <dw/rig/Rig.h>
34 #include <dw/egomotion/base/Egomotion.h>
35 #include <dw/egomotion/radar/DopplerMotionEstimator.h>
36 #include <dw/imageprocessing/features/FeatureList.h>
37 
38 #include <dw/calibration/engine/common/CalibrationTypes.h>
39 #include <dw/calibration/engine/camera/CameraParams.h>
40 #include <dw/calibration/engine/imu/IMUParams.h>
41 #if !defined(DW_L2_BUILD) && !defined(DW_IS_SAFETY)
42 #include <dw/calibration/engine/vehicle/VehicleParams.h>
43 #include <dw/calibration/engine/lidar/LidarParams.h>
44 #include <dw/calibration/engine/stereo/StereoParams.h>
45 #endif
46 #include <dw/calibration/engine/radar/RadarParams.h>
47 
48 #ifdef __cplusplus
49 extern "C" {
50 #endif
51 
72  dwContextHandle_t context);
73 
116  uint32_t sensorIndex,
118  dwEgomotionConstHandle_t egomotion,
119  cudaStream_t stream,
121 
151  const uint32_t imuIndex,
152  const uint32_t canIndex,
155 
156 #if !defined(DW_L2_BUILD) && !defined(DW_IS_SAFETY)
157 
180  uint32_t lidarIndex,
181  uint32_t canIndex,
183  cudaStream_t stream,
185 #endif
186 
209  uint32_t radarIndex,
210  uint32_t canIndex,
213 
214 #if !defined(DW_L2_BUILD) && !defined(DW_IS_SAFETY)
215 
241  uint32_t vehicleSensorIndex,
242  uint32_t leftSensorIndex,
243  uint32_t rightSensorIndex,
245  cudaStream_t stream,
247 
271 DW_DEPRECATED("Vehicle Calibration has been deprecated and will be removed/replaced by the next major release")
273  uint32_t sensorIndex,
275  dwEgomotionConstHandle_t egoMotion,
276  const dwVehicle* vehicle,
278 #endif
279 
304 
324 
344 
361 
380 
399 
421 
443 
468 
492  uint32_t indexA, uint32_t indexB,
495 
524 
525 #if !defined(DW_L2_BUILD) && !defined(DW_IS_SAFETY)
526 
544 DW_DEPRECATED("Vehicle Calibration has been deprecated and will be removed/replaced by the next major release")
548 #endif
549 
575 dwStatus dwCalibrationEngine_addFeatureDetections(uint32_t featureCapacity,
576  uint32_t historyCapacity,
577  const uint32_t* d_featureCount,
578  const uint32_t* d_ages,
579  const dwVector2f* d_locationHistory,
580  const dwFeature2DStatus* d_featureStatuses,
581  uint32_t currentTimeIdx,
583  uint32_t sensorIndex,
585 
611  uint32_t sensorIndex,
613 
614 #if !defined(DW_L2_BUILD) && !defined(DW_IS_SAFETY)
615 
638  uint32_t pointCount,
640  uint32_t sensorIndex,
642 #endif
643 
644 #if !defined(DW_L2_BUILD) && !defined(DW_IS_SAFETY)
645 
669 dwStatus dwCalibrationEngine_addLidarPose(const dwTransformation3f* deltaPoseLidarTimeAToTimeB,
670  const dwTransformation3f* deltaPoseRigTimeAToTimeB,
671  dwTime_t timestampA,
672  dwTime_t timestampB,
673  uint32_t sensorIndex,
675 #endif
676 
696  uint32_t sensorIndex,
698 #if !defined(DW_L2_BUILD) && !defined(DW_IS_SAFETY)
699 
721  uint32_t leftSensorIndex,
722  uint32_t rightSensorIndex,
724 #endif
725 
747  uint32_t sensorIndex,
749 
771  uint32_t sensorIndex,
773 
774 #ifdef __cplusplus
775 }
776 #endif
777 
779 #endif // DW_CALIBRATION_ENGINE_CALIBRATIONENGINE_H_
dwVehicleWheels
dwVehicleWheels
Define index for each of the wheels on a 4 wheeled vehicle.
Definition: Vehicle.h:60
dwCalibrationLidarParams
Calibration parameters for calibrating a lidar sensor this should be added to the dwCalibrationParams...
Definition: LidarParams.h:35
dwCalibrationEngineHandle_t
struct dwCalibrationEngineObject * dwCalibrationEngineHandle_t
Handle representing the calibration engine interface.
Definition: CalibrationTypes.h:50
dwCalibrationEngine_startCalibration
DW_API_PUBLIC dwStatus dwCalibrationEngine_startCalibration(dwCalibrationRoutineHandle_t routine, dwCalibrationEngineHandle_t engine)
Starts a calibration routine associated with a calibration engine.
dwCalibrationEngine_getCalibrationStatus
DW_API_PUBLIC dwStatus dwCalibrationEngine_getCalibrationStatus(dwCalibrationStatus *status, dwConstCalibrationRoutineHandle_t routine, dwConstCalibrationEngineHandle_t engine)
Returns the current status of a calibration routine.
dwVector4f
Defines a four-element single-precision floating point vector.
Definition: MatrixTypes.h:96
dwVehicleSteeringProperties
Steering parameter calibration data.
Definition: VehicleParamsTypes_1.h:27
dwConstRigHandle_t
struct dwRigObject const * dwConstRigHandle_t
Handle representing the const Rig interface.
Definition: Rig.h:58
dwCalibrationEngine_initializeCamera
DW_API_PUBLIC dwStatus dwCalibrationEngine_initializeCamera(dwCalibrationRoutineHandle_t *routine, uint32_t sensorIndex, const dwCalibrationCameraParams *params, dwEgomotionConstHandle_t egomotion, cudaStream_t stream, dwCalibrationEngineHandle_t engine)
Initializes a camera calibration routine designated by the sensor provided to the method.
dwVehicleIONonSafetyState
Non-safety critical RoV state.
Definition: VehicleIOValStructures.h:8792
dwCalibrationStatus
Defines the current status of an individual calibration.
Definition: CalibrationBaseTypes.h:153
dwCalibrationSignal
dwCalibrationSignal
Defines signal types supported by a calibration routine.
Definition: CalibrationBaseTypes.h:79
dwConstCalibrationRoutineHandle_t
struct dwCalibrationRoutineObject const * dwConstCalibrationRoutineHandle_t
Handle representing the const calibration routine interface.
Definition: CalibrationTypes.h:47
dwCalibrationCameraParams
Calibration parameters for calibrating a camera sensor.
Definition: CameraParams.h:72
timestamp
const WFDPipeline const WFDSource const WFDTransition const WFDRect *const const WFDuint64 timestamp
Definition: wfdext.h:61
dwConstCalibrationEngineHandle_t
struct dwCalibrationEngineObject const * dwConstCalibrationEngineHandle_t
Handle representing the const calibration engine interface.
Definition: CalibrationTypes.h:52
dwCalibrationEngine_initialize
DW_API_PUBLIC dwStatus dwCalibrationEngine_initialize(dwCalibrationEngineHandle_t *engine, dwConstRigHandle_t rig, dwContextHandle_t context)
Creates and initializes a Calibration Engine.
dwCalibrationEngine_dryrunRoutine
DW_API_PUBLIC dwStatus dwCalibrationEngine_dryrunRoutine(dwCalibrationRoutineHandle_t routine, dwCalibrationEngineHandle_t engine)
Dryrun the routine estimation GPU to record CUDAGraph.
dwCalibrationEngine_initializeStereo
DW_API_PUBLIC dwStatus dwCalibrationEngine_initializeStereo(dwCalibrationRoutineHandle_t *routine, uint32_t vehicleSensorIndex, uint32_t leftSensorIndex, uint32_t rightSensorIndex, const dwCalibrationStereoParams *params, cudaStream_t stream, dwCalibrationEngineHandle_t engine)
This method initializes a stereo camera pose calibration routine relative to the sensor index of the ...
dwCalibrationEngine_addLidarPose
DW_API_PUBLIC dwStatus dwCalibrationEngine_addLidarPose(const dwTransformation3f *deltaPoseLidarTimeAToTimeB, const dwTransformation3f *deltaPoseRigTimeAToTimeB, dwTime_t timestampA, dwTime_t timestampB, uint32_t sensorIndex, dwCalibrationEngineHandle_t engine)
Adds lidar delta-poses and ego-motion delta poses to the calibration engine.
dwCalibrationEngine_reset
DW_API_PUBLIC dwStatus dwCalibrationEngine_reset(dwCalibrationEngineHandle_t engine)
Resets the Calibration Engine module.
dwTime_t
int64_t dwTime_t
Specifies a timestamp unit, in microseconds.
Definition: BasicTypes.h:54
dwCalibrationEngine_initializeLidar
DW_API_PUBLIC dwStatus dwCalibrationEngine_initializeLidar(dwCalibrationRoutineHandle_t *routine, uint32_t lidarIndex, uint32_t canIndex, const dwCalibrationLidarParams *params, cudaStream_t stream, dwCalibrationEngineHandle_t engine)
Initializes a lidar calibration routine designated by the sensor provided to the method.
float32_t
float float32_t
Specifies POD types.
Definition: BasicTypes.h:41
dwCalibrationEngine_addVehicleIOActuationFeedback
DW_API_PUBLIC dwStatus dwCalibrationEngine_addVehicleIOActuationFeedback(dwVehicleIOActuationFeedback const *const vioActuationFeedback, uint32_t sensorIndex, dwCalibrationEngineHandle_t engine)
Adds dwVehicleIOActuationFeedback to calibration engine.
dwCalibrationEngine_addLidarPointCloud
DW_API_PUBLIC dwStatus dwCalibrationEngine_addLidarPointCloud(const dwVector4f *lidarPoints, uint32_t pointCount, dwTime_t timestamp, uint32_t sensorIndex, dwCalibrationEngineHandle_t engine)
Adds a lidar sweep to the calibration engine.
dwCalibrationEngine_initializeIMU
DW_API_PUBLIC dwStatus dwCalibrationEngine_initializeIMU(dwCalibrationRoutineHandle_t *routine, const uint32_t imuIndex, const uint32_t canIndex, const dwCalibrationIMUParams *params, dwCalibrationEngineHandle_t engine)
Initializes an IMU calibration routine designated by the sensor provided to the method.
dwIMUFrame
This structure contains one frame of data from a IMU sensor.
Definition: IMUTypes.h:396
dwCalibrationEngine_release
DW_API_PUBLIC dwStatus dwCalibrationEngine_release(dwCalibrationEngineHandle_t engine)
Releases the Calibration Engine module.
dwVehicle
DEPRECATED: Properties of a passenger car vehicle.
Definition: Vehicle.h:472
DW_DEPRECATED
#define DW_DEPRECATED(msg)
Definition: Exports.h:50
dwCalibrationEngine_addMatches
DW_API_PUBLIC dwStatus dwCalibrationEngine_addMatches(const dwFeatureHistoryArray *matches, dwTime_t timestamp, uint32_t leftSensorIndex, uint32_t rightSensorIndex, dwCalibrationEngineHandle_t engine)
Adds detected visual feature matches to the calibration engine.
dwCalibrationEngine_getSensorToSensorTransformation
DW_API_PUBLIC dwStatus dwCalibrationEngine_getSensorToSensorTransformation(dwTransformation3f *sensorToSensor, uint32_t indexA, uint32_t indexB, dwCalibrationRoutineHandle_t routine, dwCalibrationEngineHandle_t engine)
Returns the current sensor to sensor transformation of a calibration routine estimating this transfor...
dwCalibrationEngine_resetCalibration
DW_API_PUBLIC dwStatus dwCalibrationEngine_resetCalibration(dwCalibrationRoutineHandle_t routine, dwCalibrationEngineHandle_t engine)
Resets the calibration of a specific calibration routine associated with a calibration engine.
dwFeature2DStatus
dwFeature2DStatus
Defines the feature array used by detector and tracker.
Definition: FeatureList.h:52
dwCalibrationEngine_getVehicleSteeringProperties
DW_API_PUBLIC dwStatus dwCalibrationEngine_getVehicleSteeringProperties(dwVehicleSteeringProperties *steering, dwCalibrationRoutineHandle_t routine, dwCalibrationEngineHandle_t engine)
Get vehicle parameter calibration result.
dwContextHandle_t
struct dwContextObject * dwContextHandle_t
Context handle.
Definition: Context.h:74
dwRadarDopplerMotion
Defines the radar motion.
Definition: DopplerMotionEstimatorTypes.h:41
dwCalibrationVehicleParams
Vehicle steering calibration-related parameters.
Definition: VehicleParams.h:34
dwVehicleIOActuationFeedback
Feedback from actuation.
Definition: VehicleIOValStructures.h:7205
dwStatus
dwStatus
Status definition.
Definition: ErrorDefs.h:27
dwCalibrationRadarParams
Calibration parameters for calibrating a radar sensor this should be added to the dwCalibrationParams...
Definition: RadarParams.h:53
dwFeatureHistoryArray
Holds pointers to the data exposed by a feature2d list.
Definition: FeatureList.h:105
dwTransformation3f
Specifies a 3D rigid transformation.
Definition: MatrixTypes.h:226
dwCalibrationEngine_initializeVehicle
DW_API_PUBLIC dwStatus dwCalibrationEngine_initializeVehicle(dwCalibrationRoutineHandle_t *routine, uint32_t sensorIndex, const dwCalibrationVehicleParams *params, dwEgomotionConstHandle_t egoMotion, const dwVehicle *vehicle, dwCalibrationEngineHandle_t engine)
Initialize vehicle parameter calibration.
params
DW_API_PUBLIC dwPointCloudRangeImageCreatorParams const *const params
Definition: PointCloudRangeImageCreator.h:292
dwCalibrationEngine_addFeatureDetections
DW_API_PUBLIC dwStatus dwCalibrationEngine_addFeatureDetections(uint32_t featureCapacity, uint32_t historyCapacity, const uint32_t *d_featureCount, const uint32_t *d_ages, const dwVector2f *d_locationHistory, const dwFeature2DStatus *d_featureStatuses, uint32_t currentTimeIdx, dwTime_t timestamp, uint32_t sensorIndex, dwCalibrationEngineHandle_t engine)
Adds detected visual features to the calibration engine.
dwCalibrationEngine_addRadarDopplerMotion
DW_API_PUBLIC dwStatus dwCalibrationEngine_addRadarDopplerMotion(dwRadarDopplerMotion const *const radarMotion, uint32_t sensorIndex, dwCalibrationEngineHandle_t engine)
Adds Radar Doppler motion to the calibration engine.
DW_API_PUBLIC
#define DW_API_PUBLIC
Definition: Exports.h:38
dwCalibrationIMUParams
Calibration parameters for calibrating a IMU sensor this should be added to the dwCalibrationParams p...
Definition: IMUParams.h:34
dwCalibrationEngine_stopCalibration
DW_API_PUBLIC dwStatus dwCalibrationEngine_stopCalibration(dwCalibrationRoutineHandle_t routine, dwCalibrationEngineHandle_t engine)
Stops a calibration routine associated with a calibration engine.
dwCalibrationEngine_addIMUFrame
DW_API_PUBLIC dwStatus dwCalibrationEngine_addIMUFrame(const dwIMUFrame *imuFrame, uint32_t sensorIndex, dwCalibrationEngineHandle_t engine)
Adds an IMU frame from an IMU sensor to the calibration engine.
dwEgomotionConstHandle_t
struct dwEgomotionObject const * dwEgomotionConstHandle_t
Const Egomotion Handle.
Definition: Egomotion.h:72
dwCalibrationEngine_addVehicleIONonSafetyState
DW_API_PUBLIC dwStatus dwCalibrationEngine_addVehicleIONonSafetyState(dwVehicleIONonSafetyState const *const vioNonSafetyState, uint32_t sensorIndex, dwCalibrationEngineHandle_t engine)
Adds dwVehicleIONonSafetyState to calibration engine.
dwCalibrationRoutineHandle_t
struct dwCalibrationRoutineObject * dwCalibrationRoutineHandle_t
Handle representing the calibration routine interface.
Definition: CalibrationTypes.h:45
dwCalibrationEngine_initializeRadar
DW_API_PUBLIC dwStatus dwCalibrationEngine_initializeRadar(dwCalibrationRoutineHandle_t *routine, uint32_t radarIndex, uint32_t canIndex, const dwCalibrationRadarParams *params, dwCalibrationEngineHandle_t engine)
Initializes a radar calibration routine designated by the sensor provided to the method.
dwCalibrationEngine_getVehicleWheelRadius
DW_API_PUBLIC dwStatus dwCalibrationEngine_getVehicleWheelRadius(float32_t *radius, dwVehicleWheels wheel, dwCalibrationRoutineHandle_t routine, dwCalibrationEngineHandle_t engine)
Get currently estimated wheel radius of a vehicle.
dwCalibrationEngine_getSupportedSignals
DW_API_PUBLIC dwStatus dwCalibrationEngine_getSupportedSignals(dwCalibrationSignal *signals, dwCalibrationRoutineHandle_t routine, dwCalibrationEngineHandle_t engine)
Query a calibration routine for the calibration type and enabled calibration signal components.
dwCalibrationEngine_getSensorToRigTransformation
DW_API_PUBLIC dwStatus dwCalibrationEngine_getSensorToRigTransformation(dwTransformation3f *sensorToRig, dwCalibrationRoutineHandle_t routine, dwCalibrationEngineHandle_t engine)
Returns the current sensor to rig transformation of a calibration routine estimating this transformat...
dwCalibrationStereoParams
Calibration parameters for calibrating a stereo sensor.
Definition: StereoParams.h:36
dwVector2f
Defines a two-element single-precision floating-point vector.
Definition: MatrixTypes.h:30