DriveWorks SDK Reference
4.0.0 Release
For Test and Development only

Calibration Interface

Detailed Description

Defines the Calibration module for performing self-calibration of sensors and internal parameters.

Modules

 Calibration Types
 Fundamental types associated with Calibration.
 
 Camera Calibration
 Parameters for initializing a camera calibration.
 

Functions

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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
DW_API_PUBLIC dwStatus dwCalibrationEngine_addRadarDopplerMotion (const dwRadarDopplerMotion *radarMotion, uint32_t sensorIndex, dwCalibrationEngineHandle_t engine)
 Adds Radar scan to the calibration engine. More...
 
DW_API_PUBLIC dwStatus dwCalibrationEngine_addVehicleIOState (const dwVehicleIOState *vioState, uint32_t sensorIndex, dwCalibrationEngineHandle_t engine)
 Adds vehicle IO state to calibration engine. More...
 
DW_API_PUBLIC dwStatus dwCalibrationEngine_getCalibrationStatus (dwCalibrationStatus *status, dwCalibrationRoutineHandle_t routine, dwCalibrationEngineHandle_t engine)
 Returns the current status of a calibration routine. More...
 
DW_API_PUBLIC dwStatus dwCalibrationEngine_getOdometrySpeedFactor (float32_t *odometrySpeedFactor, dwCalibrationRoutineHandle_t routine, dwCalibrationEngineHandle_t engine)
 Returns odometry speed factor, mapping speed as reported by odometry to actual speed. More...
 
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 transformation. More...
 
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 transformation. More...
 
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. More...
 
DW_API_PUBLIC dwStatus dwCalibrationEngine_getVehicleSteeringProperties (dwVehicleSteeringProperties *steering, dwCalibrationRoutineHandle_t routine, dwCalibrationEngineHandle_t engine)
 Get vehicle parameter calibration result. More...
 
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. More...
 
DW_API_PUBLIC dwStatus dwCalibrationEngine_initialize (dwCalibrationEngineHandle_t *engine, dwRigHandle_t rig, dwContextHandle_t context)
 Creates and initializes a Calibration Engine. More...
 
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. More...
 
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. More...
 
DW_API_PUBLIC dwStatus dwCalibrationEngine_initializeLidar (dwCalibrationRoutineHandle_t *routine, uint32_t lidarIndex, uint32_t canIndex, const dwLidarProperties *lidarProperties, const dwCalibrationLidarParams *params, cudaStream_t stream, dwCalibrationEngineHandle_t engine)
 Initializes a lidar calibration routine designated by the sensor provided to the method. More...
 
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. More...
 
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 left camera. More...
 
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. More...
 
DW_API_PUBLIC dwStatus dwCalibrationEngine_release (dwCalibrationEngineHandle_t engine)
 Releases the Calibration Engine module. More...
 
DW_API_PUBLIC dwStatus dwCalibrationEngine_reset (dwCalibrationEngineHandle_t engine)
 Resets the Calibration Engine module. More...
 
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. More...
 
DW_API_PUBLIC dwStatus dwCalibrationEngine_startCalibration (dwCalibrationRoutineHandle_t routine, dwCalibrationEngineHandle_t engine)
 Starts a calibration routine associated with a calibration engine. More...
 
DW_API_PUBLIC dwStatus dwCalibrationEngine_stopCalibration (dwCalibrationRoutineHandle_t routine, dwCalibrationEngineHandle_t engine)
 Stops a calibration routine associated with a calibration engine. More...
 

Function Documentation

◆ 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.

The calibration engine will send these features to all routines that use features from this sensor.

Parameters
[in]featureCapacityMax number of features that can be stored in the list
[in]historyCapacityMax age of a feature
[in]d_featureCountNumber of valid features (GPU memory)
[in]d_agesAge of features (GPU memory)
[in]d_locationHistoryLocations of features (GPU memory), see features.h for details on memory layout
[in]d_featureStatusesStatuses of features (GPU memory), see FeatureList.h for details on possible values
[in]currentTimeIdxThe index for the current time in the locationHistory arrays
[in]timestampThe time stamp when the detections were created
[in]sensorIndexThe index of the sensor that created the detections
[in]engineSpecifies the calibration engine module we are checking against
Returns
DW_INVALID_ARGUMENT - if the d_featureCount, d_ages, or d_locationHistory pointer is invalid
DW_INVALID_HANDLE - if provided engine handle is invalid, i.e., null or of wrong type
DW_INTERNAL_ERROR - if an internal unrecoverable error was detected
DW_SUCCESS

◆ 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.

The calibration engine will send these measurements to all routines that use features from this sensor.

The IMU frame shall contain both linear acceleration and angular velocity measurements for X, Y and Z axes; the frame will be discarded otherwise.

Parameters
[in]imuFrameThe IMU data that was taken from the sensor
[in]sensorIndexThe index of the sensor that created the IMU data
[in]engineSpecifies the calibration engine module we are checking against
Note
only calibrations that require the IMU from this sensor as part of their calibration routine will process the imu readings
Returns
DW_INVALID_ARGUMENT - if the imuFrame pointer is invalid
DW_INVALID_HANDLE - if provided engine handle is invalid, i.e., null or of wrong type
DW_INTERNAL_ERROR - if an internal unrecoverable error was detected
DW_SUCCESS

◆ 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.

The calibration engine will send these measurements to all routines that use features from this sensor.

Parameters
[in]lidarPointsThe lidar data that were acquired from the sensor
[in]pointCountThe number of lidar points in the lidar sweep
[in]timestampThe time stamp when the lidar sweep was created
[in]sensorIndexThe index of the sensor that created the lidarPoints
[in]engineSpecifies the calibration engine module we are checking against.
Returns
DW_INVALID_ARGUMENT - if the lidarPoints pointer is invalid
DW_INVALID_HANDLE - if provided engine handle is invalid, i.e., null or of wrong type
DW_INTERNAL_ERROR - if an internal unrecoverable error was detected
DW_SUCCESS

◆ 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.

The calibration engine will send these measurements to all routines that use features from this sensor.

Parameters
[in]deltaPoseLidarTimeAToTimeBThe relative pose in lidar frame from time A to time B
[in]deltaPoseRigTimeAToTimeBThe relative pose in Rig frame from time A to time B (optional) If set to NULL, deltaPoseLidarTimeAToTimeB is used to approximate deltaPoseRigTimeAToTimeB for the algorithm.
[in]timestampAThe time stamp of time A
[in]timestampBThe time stamp of time B
[in]sensorIndexThe index of the sensor that created the lidarPoints
[in]engineSpecifies the calibration engine module we are checking against.
Returns
DW_INVALID_ARGUMENT - if the lidarPoints pointer is invalid
DW_INVALID_HANDLE - if provided engine handle is invalid, i.e., null or of wrong type
DW_INTERNAL_ERROR - if an internal unrecoverable error was detected
DW_SUCCESS

◆ 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.

The calibration engine will send these feature matches to all routines that use feature matches from this sensor.

Parameters
[in]matchesHistory of feature matches between two cameras
[in]timestampThe time stamp when the detections were created
[in]leftSensorIndexThe index of the left sensor that created the matches
[in]rightSensorIndexThe index of the right sensor that created the matches
[in]engineSpecifies the calibration engine module we are checking against
Returns
DW_INVALID_ARGUMENT - if matches are invalid
DW_INVALID_HANDLE - if provided engine handle is invalid
DW_INTERNAL_ERROR - if an internal unrecoverable error was detected
DW_SUCCESS

◆ dwCalibrationEngine_addRadarDopplerMotion()

DW_API_PUBLIC dwStatus dwCalibrationEngine_addRadarDopplerMotion ( const dwRadarDopplerMotion radarMotion,
uint32_t  sensorIndex,
dwCalibrationEngineHandle_t  engine 
)

Adds Radar scan to the calibration engine.

Parameters
[in]radarMotionThe radar motion that estimated by DopplerMotionEstimator
[in]sensorIndexThe index of the sensor that created the radarPoints
[in]engineSpecifies the calibration engine module we are checking against
Returns
DW_INVALID_ARGUMENT - if the radarPoints pointer is invalid
DW_INVALID_HANDLE - if provided engine handle is invalid, i.e., null or of wrong type
DW_INTERNAL_ERROR - if an internal unrecoverable error was detected
DW_SUCCESS

◆ dwCalibrationEngine_addVehicleIOState()

DW_API_PUBLIC dwStatus dwCalibrationEngine_addVehicleIOState ( const dwVehicleIOState vioState,
uint32_t  sensorIndex,
dwCalibrationEngineHandle_t  engine 
)

Adds vehicle IO state to calibration engine.

Parameters
[in]vioStatevehicle io state
[in]sensorIndexThe index of sensor corresponding to steering system
[in]engineSpecifies the calibration engine module we are checking against.
Returns
DW_INVALID_ARGUMENT - if the vioState pointer is invalid
DW_INVALID_HANDLE - if provided engine handle is invalid
DW_INTERNAL_ERROR - if an internal unrecoverable error was detected
DW_SUCCESS

◆ dwCalibrationEngine_getCalibrationStatus()

DW_API_PUBLIC dwStatus dwCalibrationEngine_getCalibrationStatus ( dwCalibrationStatus status,
dwCalibrationRoutineHandle_t  routine,
dwCalibrationEngineHandle_t  engine 
)

Returns the current status of a calibration routine.

Parameters
[out]statusA pointer to the returned status
[in]routineSpecifies the handle of the calibration routine to querry
[in]engineSpecifies the calibration engine module we are checking against
Returns
DW_INVALID_ARGUMENT - if the calibration routine is not managed by the calibration engine
DW_INVALID_HANDLE - if any of the provided handles is invalid, i.e., null or of wrong type
DW_SUCCESS

◆ dwCalibrationEngine_getOdometrySpeedFactor()

DW_API_PUBLIC dwStatus dwCalibrationEngine_getOdometrySpeedFactor ( float32_t odometrySpeedFactor,
dwCalibrationRoutineHandle_t  routine,
dwCalibrationEngineHandle_t  engine 
)

Returns odometry speed factor, mapping speed as reported by odometry to actual speed.

Odometry speed factor can be estimated using multiple data sources. Following variants are currently supported:

Parameters
[out]odometrySpeedFactorFactor to be applied on measured odometry speed to map to actual speed
[in]routineSpecifies the handle of the calibration routine to query
[in]engineA pointer to the the calibration engine handle that owns the sensor
Returns
DW_INVALID_ARGUMENT - if given odometrySpeedFactor is null
DW_INVALID_HANDLE - if any of the provided handles is invalid, i.e., null or of wrong type
DW_NOT_SUPPORTED - if calibration routine is not performing an odometry speed factor estimation
DW_SUCCESS
Note
Speed factor returned is considered invalid unless dwCalibrationEngine_getCalibrationStatus() returns DW_CALIBRATION_STATE_ACCEPTED for the passed calibration routine.
The speed factor currently is only calibrated when vehicle is driving straight, i.e., steering angle of the front wheel within +-3deg. For this purpose, egomotion's steering signal is used to identify straight driving sections.

◆ 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 transformation.

Parameters
[out]sensorToRigA pointer to the return transform. The transform represents the extrinsic transformation from the sensor to the rig coordinate system
[in]routineSpecifies the handle of the calibration routine to query
[in]engineSpecifies the calibration engine module we are checking against
Returns
DW_INVALID_HANDLE - if any of the provided handles is invalid, i.e., null or of wrong type
DW_INVALID_ARGUMENT - if the calibration routine is not managed by the calibration engine
DW_NOT_SUPPORTED - if the calibration routine is not estimating a sensorToRigTransformation
DW_SUCCESS

◆ 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 transformation.

Parameters
[out]sensorToSensorA pointer to the return transform. The transform represents the extrinsic transformation from sensor A to sensor B coordinate system
[in]routineSpecifies the handle of the calibration routine to query
[in]indexAindex of sensor A
[in]indexBindex of sensor B
[in]engineSpecifies the calibration engine module we are checking against
Returns
DW_INVALID_HANDLE - if any of the provided handles is invalid
DW_INVALID_ARGUMENT - if the calibration routine is not managed by the calibration engine or if the calibration routine is not estimating a sensorToSensorTransformation DW_NOT_AVAILABLE - if the sensors indices provided are not related to the calibration routine
DW_SUCCESS

◆ 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.

Parameters
[out]signalsBitflag indicating supported calibration type and enabled signal components (binary OR of dwCalibrationSignal)
[in]routineSpecifies the handle of the calibration routine to query
[in]engineSpecifies the calibration engine module we are checking against
Returns
DW_INVALID_HANDLE - if any of the provided handles is invalid, i.e., null or of wrong type
DW_INVALID_ARGUMENT - if the calibration routine is not managed by the calibration engine or supported is null
DW_SUCCESS

◆ dwCalibrationEngine_getVehicleSteeringProperties()

DW_API_PUBLIC dwStatus dwCalibrationEngine_getVehicleSteeringProperties ( dwVehicleSteeringProperties steering,
dwCalibrationRoutineHandle_t  routine,
dwCalibrationEngineHandle_t  engine 
)

Get vehicle parameter calibration result.

Parameters
[out]steeringA pointer to the calibration result of vehicle steering parameters
[in]routineSpecifies the handle of the vehicle calibration routine to query
[in]engineA pointer to the the calibration engine handle that owns the sensor.
Returns
DW_INVALID_HANDLE - if provided engine handle is invalid
DW_INVALID_ARGUMENT - if the calibration routine is not managed by the calibration engine
DW_NOT_SUPPORTED - if calibration routine is not estimating wheel radius
DW_SUCCESS

◆ 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.

Wheel radius can be estimated using multiple data sources. Following variants are currently supported:

Parameters
[out]radiusReturn calibration wheel radius in [m] for a given wheel
[in]wheelWheel to get radius for.
[in]routineSpecifies the handle of the calibration routine to query
[in]engineA pointer to the the calibration engine handle that owns the sensor
Returns
DW_INVALID_ARGUMENT - if given radius is null
DW_INVALID_HANDLE - if any of the provided handles is invalid
DW_NOT_SUPPORTED - if calibration routine is not estimating wheel radius
DW_SUCCESS

◆ dwCalibrationEngine_initialize()

DW_API_PUBLIC dwStatus dwCalibrationEngine_initialize ( dwCalibrationEngineHandle_t engine,
dwRigHandle_t  rig,
dwContextHandle_t  context 
)

Creates and initializes a Calibration Engine.

Parameters
[out]engineA pointer to the calibration handle will be returned here
[in]rigSpecifies the rig module that holds the sensor information
[in]contextSpecifies the handle to the context under which the Calibration Engine module is created
Note
The rig handle must remain valid until the calibration module has been released
Returns
DW_INVALID_ARGUMENT - if pointer to the engine handle is invalid
DW_INVALID_HANDLE - if provided context handle is invalid, i.e., null or of wrong type
DW_SUCCESS

◆ 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.

Parameters
[out]routineA pointer to the new calibration routine handle associated with this engine
[in]sensorIndexThe index of the sensor we are creating a calibration for. This is the same as the sensor index in the rig configuration module
[in]paramsSpecifies the parameters that are used in calibrating the camera
[in]egomotionSpecifies the egomotion module that holds the motion of the vehicle
[in]streamThe CUDA stream to use for all CUDA operations of the calibration routine
[in]engineA pointer to the calibration engine handle that owns the sensor
Runtime calibration dependencies (results will be inaccurate if not respected)
  • any height calibration: absolute scale is inferred from egomotion, which needs to use calibrated odometry properties (e.g., wheel radii via radar self-calibration)
  • side-camera roll calibration: side-camera roll is inferred from egomotion's axis of rotation, which needs to be based on an accurate IMU calibration
Note
The provided egomotion instance should be based on DW_EGOMOTION_IMU_ODOMETRY and the handle must remain valid until the calibration module has been released. Enabling the estimation of egomotion suspension using dwEgomotionSuspensionModel is beneficial for camera calibration accuracy and acceptance rates
Returns
DW_INVALID_ARGUMENT - if the arguments in the parameters are invalid, if the egomotion handle is invalid or if the routine handle is invalid
DW_INVALID_HANDLE - if provided engine handle is invalid, i.e., null or of wrong type
DW_BUFFER_FULL - if the number of sensors need to be calibrated exceeds DW_CALIBRATION_MAXROUTINES value
DW_SUCCESS

◆ 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.

Parameters
[out]routineA pointer to the new calibration routine handle associated with this engine
[in]imuIndexThe index of the sensor we are creating a calibration for. This is the same as the sensor index in the rig module
[in]canIndexIndex of the CAN bus from which speed information will be provided as dwVehicleIOState
[in]paramsSpecifies the parameters that are used to calibrate the IMU
[in]engineA pointer to the calibration engine handle that owns the sensor
Runtime calibration dependencies (results will be inaccurate if not respected)
  • none
Note
The calibration engine must be provided with dwVehicleIOState and dwIMUFrame data using dwCalibrationEngine_addVehicleIOState and dwCalibrationEngine_addIMUFrame, respectively.
Returns
DW_INVALID_ARGUMENT - if the arguments in the parameters are invalid or if the routine handle is invalid
DW_INVALID_HANDLE - if provided engine handle is invalid, i.e., null or of wrong type, or the given indices do point to appropriate entries in the rig file
DW_BUFFER_FULL - if the number of sensors need to be calibrated exceeds the DW_CALIBRATION_MAXROUTINES value
DW_OUT_OF_BOUNDS - if the given indices point outside the rig file
DW_SUCCESS

◆ dwCalibrationEngine_initializeLidar()

DW_API_PUBLIC dwStatus dwCalibrationEngine_initializeLidar ( dwCalibrationRoutineHandle_t routine,
uint32_t  lidarIndex,
uint32_t  canIndex,
const dwLidarProperties lidarProperties,
const dwCalibrationLidarParams params,
cudaStream_t  stream,
dwCalibrationEngineHandle_t  engine 
)

Initializes a lidar calibration routine designated by the sensor provided to the method.

Parameters
[out]routineA pointer to the new calibration routine handle associated with this engine
[in]lidarIndexThe index of the lidar to be calibrated. This is the same as the sensor index in the rig module
[in]canIndexIndex of the CAN bus from which speed information will be provided as dwVehicleIOState
[in]lidarPropertiesA pointer to the sensor properties of the lidar to be calibrated
[in]paramsSpecifies the parameters that are used to in calibrating the lidar
[in]streamThe CUDA stream to use for all CUDA operations of the calibration routine
[in]engineA pointer to the calibration engine handle that owns the sensor
Returns
DW_INVALID_ARGUMENT - if the arguments in the parameters are invalid or if the routine handle is invalid
DW_INVALID_HANDLE - if provided engine handle is invalid,i.e. null or of wrong type
DW_BUFFER_FULL - if the number of sensors need to be calibrated exceeds DW_CALIBRATION_MAXROUTINES value.
DW_SUCCESS

◆ 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.

A radar calibration routine can also estimate odometry properties (speed factor / wheel radii) by matching reported wheel speeds with radar-based speed estimates (enabled in parameters).

Parameters
[out]routineA pointer to the new calibration routine handle associated with this engine
[in]radarIndexThe index of the radar we are creating a calibration for. This is the same as the sensor index in the rig module
[in]canIndexIndex of the CAN bus from which speed information will be provided as dwVehicleIOState
[in]paramsSpecifies the parameters that are used to in calibrating the radar
[in]engineA pointer to the calibration engine handle that owns the sensor
Returns
DW_INVALID_ARGUMENT - if the arguments in the parameters are invalid or if the egomotion handle is invalid
DW_INVALID_HANDLE - if provided engine handle is invalid, i.e., null or of wrong type
DW_BUFFER_FULL - if the number of sensors need to be calibrated exceeds DW_CALIBRATION_MAXSENSORS value
DW_SUCCESS

◆ 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 left camera.

Parameters
[out]routineA pointer to the new calibration routine handle associated with this engine
[in]vehicleSensorIndexThe index of the vehicle sensor. This is the same as the sensor index in the rig configuration module
[in]leftSensorIndexThe index of the left camera sensor. This is the same as the sensor index in the rig configuration module
[in]rightSensorIndexThe index of the right camera sensor. This is the same as the sensor index in the rig configuration module
[in]paramsSpecifies the parameters that are used in calibrating the stereo camera rig
[in]streamThe CUDA stream to use for all CUDA operations of the calibration routine
[in]engineA pointer to the the calibration engine handle that owns the sensor
Runtime calibration dependencies (results will be inaccurate if not respected)
  • none
Returns
DW_INVALID_ARGUMENT - if the arguments in the parameters are invalid
DW_INVALID_HANDLE - if provided engine handle is invalid
DW_BUFFER_FULL - if the number of sensors need to be calibrated exceeds DW_CALIBRATION_MAXROUTINES value
DW_SUCCESS

◆ 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.

Parameters
[out]routineA pointer to the new calibration routine handle associated with this engine.
[in]sensorIndexThe index of the sensor that provides vehicle i/o data. This should be the same as the number in the rig configuration module
[in]paramsSpecifies the parameters that are used to in calibrating the vehicle parameters
[in]egoMotionSpecifies the ego motion module that holds the motion of the vehicle
[in]vehicleA pointer to a vehicle parametere data.
[in]engineA pointer to the calibration engine handle that owns the sensor.
Note
Runtime calibration dependencies (results will be inaccurate if not respected):
  • IMU-based egomotion needs to be based on accurate IMU calibration and odometry properties
Returns
DW_INVALID_ARGUMENT - if the arguments in the parameters are invalid
DW_INVALID_HANDLE - if provided engine handle is invalid
DW_BUFFER_FULL - if the number of sensors need to be calibrated exceeds DW_CALIBRATION_MAXROUTINES value
DW_SUCCESS

◆ dwCalibrationEngine_release()

DW_API_PUBLIC dwStatus dwCalibrationEngine_release ( dwCalibrationEngineHandle_t  engine)

Releases the Calibration Engine module.

This method stops all calibrations that are in process and invalidates all calibration routines associated with the engine.

Note
This method renders the engine handle unusable
Parameters
[in]engineThe calibration engine handle to be released
Returns
DW_INVALID_HANDLE - if provided engine handle is invalid, i.e., null or of wrong type
DW_SUCCESS

◆ dwCalibrationEngine_reset()

DW_API_PUBLIC dwStatus dwCalibrationEngine_reset ( dwCalibrationEngineHandle_t  engine)

Resets the Calibration Engine module.

This method resets all calibrations that are being calculated by the module. The method does not remove all calibration routines associated with the engine, but rather resets each individual one.

Parameters
[in]engineSpecifies the calibration engine handle to reset
Returns
DW_INVALID_HANDLE - if provided engine handle is invalid, i.e., null or of wrong type
DW_SUCCESS
Note
The call is equivalent in calling dwCalibrationEngine_resetCalibration() for all created routines

◆ 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.

Note
Resetting a calibration routine will revert to nominal baseline calibration
Parameters
[in]routineSpecifies the handle of the calibration routine to reset
[in]engineSpecifies the handle to the calibration engine that is managing the calibration
Returns
DW_INVALID_HANDLE - if provided engine handle is invalid, i.e., null or of wrong type or if the calibration routine is not managed by the calibration engine
DW_SUCCESS

◆ dwCalibrationEngine_startCalibration()

DW_API_PUBLIC dwStatus dwCalibrationEngine_startCalibration ( dwCalibrationRoutineHandle_t  routine,
dwCalibrationEngineHandle_t  engine 
)

Starts a calibration routine associated with a calibration engine.

Calibrations should only be started once runtime calibration dependencies are met.

Parameters
[in]routineSpecifies the handle of the calibration routine to start
[in]engineSpecifies the handle of the calibration routine that is managing the calibration
Returns
DW_INVALID_HANDLE - if provided engine handle is invalid, i.e., null or of wrong type or if the calibration routine is not managed by the calibration engine
DW_SUCCESS

◆ dwCalibrationEngine_stopCalibration()

DW_API_PUBLIC dwStatus dwCalibrationEngine_stopCalibration ( dwCalibrationRoutineHandle_t  routine,
dwCalibrationEngineHandle_t  engine 
)

Stops a calibration routine associated with a calibration engine.

Parameters
[in]routineSpecifies the handle of the calibration routine to start
[in]engineSpecifies the handle of the calibration routine that is managing the calibration
Returns
DW_INVALID_HANDLE - if provided engine handle is invalid , i.e., null or of wrong type or if the calibration routine is not managed by the calibration engine
DW_SUCCESS