DriveWorks SDK Reference

| 0.6.67 Release

RigConfiguration.h File Reference

Detailed Description

NVIDIA DriveWorks API: Rig Configuration

Description: This file defines vehicle rig configuration methods.

Definition in file RigConfiguration.h.

Go to the source code of this file.

Data Structures

struct  dwFThetaCameraConfig
 Configuration parameters for a calibrated FTheta camera. More...
 
struct  dwOCamCameraConfig
 Configuration parameters for a calibrated OCam sphere camera. More...
 
struct  dwPinholeCameraConfig
 Configuration parameters for a calibrated pinhole camera. More...
 
struct  dwVehicle
 Properties of the vehicle. More...
 

Macros

#define DW_FTHETA_POLY_LENGTH   5
 
#define DW_OCAM_POLY_LENGTH   5
 
#define DW_PINHOLE_DISTORTION_LENGTH   3
 

Typedefs

typedef struct dwRigConfigurationObject const * dwConstRigConfigurationHandle_t
 
typedef struct dwRigConfigurationObject * dwRigConfigurationHandle_t
 Handle representing the Sensor Abstraction Layer interface. More...
 

Enumerations

enum  dwCameraModel {
  DW_CAMERA_MODEL_OCAM = 0,
  DW_CAMERA_MODEL_PINHOLE = 1,
  DW_CAMERA_MODEL_FTHETA = 2
}
 Specifies the supported optical camera models. More...
 

Functions

DW_API_PUBLIC dwStatus dwRigConfiguration_findSensorByName (uint32_t *sensorID, const char *sensorName, dwConstRigConfigurationHandle_t obj)
 Finds a sensor with the given name and returns the index. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_getCameraModel (dwCameraModel *cameraModel, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
 Gets the model type of the camera intrinsics. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_getFThetaCameraConfig (dwFThetaCameraConfig *config, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
 Gets the parameters of the FTheta camera model. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_getOCamCameraConfig (dwOCamCameraConfig *config, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
 Gets the parameters of the OCam camera model. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_getPinholeCameraConfig (dwPinholeCameraConfig *config, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
 Gets the parameters of the pinhole camera model. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorCount (uint32_t *sensorCount, dwConstRigConfigurationHandle_t obj)
 Gets the number of available sensors. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorName (const char **sensorName, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
 Gets the name of a sensor as given in the configuration. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorParameter (const char **sensorParameter, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
 Gets the parameter string for a sensor. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorProtocol (const char **sensorProtocol, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
 Gets the protocol string of a sensor. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorToRigTransformation (dwTransformation *transformation, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
 Gets the sensor to rig transformation for a sensor. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorType (dwSensorType *sensorType, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
 Returns the type of sensor based upon the sensorID sent into the method. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_getVehicle (const dwVehicle **vehicle, dwConstRigConfigurationHandle_t obj)
 Gets the properties of the vehicle. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_initializeFromFile (dwRigConfigurationHandle_t *obj, dwContextHandle_t ctx, const char *configurationFile)
 Initializes the Rig Configuration module. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_release (dwRigConfigurationHandle_t *obj)
 Releases the Rig Configuration module. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_reset (dwRigConfigurationHandle_t obj)
 Resets the Rig Configuration module. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_serializeToFile (const char *configurationFile, dwConstRigConfigurationHandle_t obj)
 This method serializes the rig-configuration object to a human-readable rig-configuration file. More...
 
DW_API_PUBLIC dwStatus dwRigConfiguration_setSensorToRigTransformation (dwTransformation const *transformation, uint32_t sensorID, dwRigConfigurationHandle_t obj)
 Sets the sensor to rig transformation for a sensor. More...