45 #ifndef DW_RIGCONFIGURATION_RIGCONFIGURATION_H__ 46 #define DW_RIGCONFIGURATION_RIGCONFIGURATION_H__ 48 #include <dw/core/Config.h> 115 #define DW_PINHOLE_DISTORTION_LENGTH 3 146 #define DW_OCAM_POLY_LENGTH 5 177 #define DW_FTHETA_POLY_LENGTH 5 232 const char *configurationFile);
265 dwConstRigConfigurationHandle_t obj);
277 dwConstRigConfigurationHandle_t obj);
292 dwConstRigConfigurationHandle_t obj);
306 dwConstRigConfigurationHandle_t obj);
322 dwConstRigConfigurationHandle_t obj);
337 dwRigConfigurationHandle_t obj);
351 dwConstRigConfigurationHandle_t obj);
367 dwConstRigConfigurationHandle_t obj);
382 dwConstRigConfigurationHandle_t obj);
396 dwConstRigConfigurationHandle_t obj);
410 dwConstRigConfigurationHandle_t obj);
426 dwConstRigConfigurationHandle_t obj);
442 dwConstRigConfigurationHandle_t obj);
469 #endif // DW_RIGCONFIGURATION_RIGCONFIGURATION_H__
DW_API_PUBLIC dwStatus dwRigConfiguration_getFThetaCameraConfig(dwFThetaCameraConfig *config, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
Gets the parameters of the FTheta camera model.
DW_API_PUBLIC dwStatus dwRigConfiguration_reset(dwRigConfigurationHandle_t obj)
Resets the Rig Configuration module.
NVIDIA DriveWorks API: Core Types
uint32_t width
Width of the image (in pixels)
float float32_t
Specifies POD types.
float32_t d
Affine matrix coefficient D.
dwSensorType
Defines the type of sensors that are available in DriveWorks.
uint32_t height
Width of the image (in pixels)
float32_t c
Affine matrix coefficient C.
Configuration parameters for a calibrated FTheta camera.
DW_API_PUBLIC dwStatus dwRigConfiguration_release(dwRigConfigurationHandle_t *obj)
Releases the Rig Configuration module.
DW_API_PUBLIC dwStatus dwRigConfiguration_getPinholeCameraConfig(dwPinholeCameraConfig *config, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
Gets the parameters of the pinhole camera model.
DW_API_PUBLIC dwStatus dwRigConfiguration_initializeFromFile(dwRigConfigurationHandle_t *obj, dwContextHandle_t ctx, const char *configurationFile)
Initializes the Rig Configuration module.
DW_API_PUBLIC dwStatus dwRigConfiguration_getOCamCameraConfig(dwOCamCameraConfig *config, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
Gets the parameters of the OCam camera model.
float32_t focalY
Focal length in the Y axis.
struct dwRigConfigurationObject const * dwConstRigConfigurationHandle_t
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...
uint32_t height
Width of the image (in pixels)
struct dwRigConfigurationObject * dwRigConfigurationHandle_t
Handle representing the Sensor Abstraction Layer interface.
float32_t e
Affine matrix coefficient E.
float32_t u0
U coordinate for the principal point (in pixels)
NVIDIA DriveWorks API: Core Methods
float32_t frontCorneringStiffness
float32_t distortion[DW_PINHOLE_DISTORTION_LENGTH]
Distortion polynomial coefficients [k_1, k_2, k_3].
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.
float32_t centerOfMassToRearAxle
NVIDIA DriveWorks API: Core Exports
DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorParameter(const char **sensorParameter, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
Gets the parameter string for a sensor.
uint32_t height
Width of the image (in pixels)
DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorCount(uint32_t *sensorCount, dwConstRigConfigurationHandle_t obj)
Gets the number of available sensors.
DW_API_PUBLIC dwStatus dwRigConfiguration_setSensorToRigTransformation(dwTransformation const *transformation, uint32_t sensorID, dwRigConfigurationHandle_t obj)
Sets the sensor to rig transformation for a sensor.
dwStatus
Status definition.
NVIDIA DriveWorks API: Sensors
uint32_t width
Width of the image (in pixels)
float32_t u0
U coordinate for the principal point (in pixels)
Configuration parameters for a calibrated OCam sphere camera.
DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorToRigTransformation(dwTransformation *transformation, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
Gets the sensor to rig transformation for a sensor.
DW_API_PUBLIC dwStatus dwRigConfiguration_getCameraModel(dwCameraModel *cameraModel, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
Gets the model type of the camera intrinsics.
dwCameraModel
Specifies the supported optical camera models.
DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorProtocol(const char **sensorProtocol, uint32_t sensorID, dwConstRigConfigurationHandle_t obj)
Gets the protocol string of a sensor.
float32_t v0
V coordinate for the principal point (in pixels)
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.
#define DW_FTHETA_POLY_LENGTH
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.
float32_t rearCorneringStiffness
struct dwContextObject * dwContextHandle_t
Context handle.
float32_t steeringCoefficient
float32_t widthWithMirrors
float32_t u0
U coordinate for the principal point (in pixels)
float32_t focalX
Focal length in the X axis.
Configuration parameters for a calibrated pinhole camera.
#define DW_OCAM_POLY_LENGTH
#define DW_PINHOLE_DISTORTION_LENGTH
DW_API_PUBLIC dwStatus dwRigConfiguration_getVehicle(const dwVehicle **vehicle, dwConstRigConfigurationHandle_t obj)
Gets the properties of the vehicle.
float32_t v0
V coordinate for the principal point (in pixels)
float32_t v0
V coordinate for the principal point (in pixels)
uint32_t width
Width of the image (in pixels)
Properties of the vehicle.