DriveWorks SDK Reference

| 0.6.67 Release

RigConfiguration.h
Go to the documentation of this file.
1 // This code contains NVIDIA Confidential Information and is disclosed
3 // under the Mutual Non-Disclosure Agreement.
4 //
5 // Notice
6 // ALL NVIDIA DESIGN SPECIFICATIONS AND CODE ("MATERIALS") ARE PROVIDED "AS IS" NVIDIA MAKES
7 // NO REPRESENTATIONS, WARRANTIES, EXPRESSED, IMPLIED, STATUTORY, OR OTHERWISE WITH RESPECT TO
8 // THE MATERIALS, AND EXPRESSLY DISCLAIMS ANY IMPLIED WARRANTIES OF NONINFRINGEMENT,
9 // MERCHANTABILITY, OR FITNESS FOR A PARTICULAR PURPOSE.
10 //
11 // NVIDIA Corporation assumes no responsibility for the consequences of use of such
12 // information or for any infringement of patents or other rights of third parties that may
13 // result from its use. No license is granted by implication or otherwise under any patent
14 // or patent rights of NVIDIA Corporation. No third party distribution is allowed unless
15 // expressly authorized by NVIDIA. Details are subject to change without notice.
16 // This code supersedes and replaces all information previously supplied.
17 // NVIDIA Corporation products are not authorized for use as critical
18 // components in life support devices or systems without express written approval of
19 // NVIDIA Corporation.
20 //
21 // Copyright (c) 2015-2016 NVIDIA Corporation. All rights reserved.
22 //
23 // NVIDIA Corporation and its licensors retain all intellectual property and proprietary
24 // rights in and to this software and related documentation and any modifications thereto.
25 // Any use, reproduction, disclosure or distribution of this software and related
26 // documentation without an express license agreement from NVIDIA Corporation is
27 // strictly prohibited.
28 //
30 
45 #ifndef DW_RIGCONFIGURATION_RIGCONFIGURATION_H__
46 #define DW_RIGCONFIGURATION_RIGCONFIGURATION_H__
47 
48 #include <dw/core/Config.h>
49 #include <dw/core/Exports.h>
50 #include <dw/core/Context.h>
51 #include <dw/core/Types.h>
52 #include <dw/sensors/Sensors.h>
53 #include <stdint.h>
54 
55 #ifdef __cplusplus
56 extern "C" {
57 #endif
58 
99 typedef struct dwRigConfigurationObject *dwRigConfigurationHandle_t;
101 typedef struct dwRigConfigurationObject const *dwConstRigConfigurationHandle_t;
102 
104 // Calibrated cameras
109 typedef enum dwCameraModel {
113 } dwCameraModel;
114 
115 #define DW_PINHOLE_DISTORTION_LENGTH 3
116 
120 typedef struct dwPinholeCameraConfig {
122  uint32_t width;
123 
125  uint32_t height;
126 
129 
132 
135 
138 
145 
146 #define DW_OCAM_POLY_LENGTH 5
147 
151 typedef struct dwOCamCameraConfig {
153  uint32_t width;
154 
156  uint32_t height;
157 
160 
163 
166 
169 
172 
176 
177 #define DW_FTHETA_POLY_LENGTH 5
178 
182 typedef struct dwFThetaCameraConfig {
184  uint32_t width;
185 
187  uint32_t height;
188 
191 
194 
198 
200 typedef struct dwVehicle {
218 } dwVehicle ;
219 
230 DW_API_PUBLIC dwStatus dwRigConfiguration_initializeFromFile(dwRigConfigurationHandle_t *obj,
231  dwContextHandle_t ctx,
232  const char *configurationFile);
233 
242 DW_API_PUBLIC dwStatus dwRigConfiguration_reset(dwRigConfigurationHandle_t obj);
243 
252 DW_API_PUBLIC dwStatus dwRigConfiguration_release(dwRigConfigurationHandle_t *obj);
253 
265  dwConstRigConfigurationHandle_t obj);
266 
277  dwConstRigConfigurationHandle_t obj);
278 
291 DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorProtocol(const char **sensorProtocol, uint32_t sensorID,
292  dwConstRigConfigurationHandle_t obj);
293 
305 DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorParameter(const char **sensorParameter, uint32_t sensorID,
306  dwConstRigConfigurationHandle_t obj);
307 
321  uint32_t sensorID,
322  dwConstRigConfigurationHandle_t obj);
323 
335 DW_API_PUBLIC dwStatus dwRigConfiguration_setSensorToRigTransformation(dwTransformation const *transformation,
336  uint32_t sensorID,
337  dwRigConfigurationHandle_t obj);
338 
350 DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorName(const char **sensorName, uint32_t sensorID,
351  dwConstRigConfigurationHandle_t obj);
352 
366 DW_API_PUBLIC dwStatus dwRigConfiguration_findSensorByName(uint32_t *sensorID, const char *sensorName,
367  dwConstRigConfigurationHandle_t obj);
368 
382  dwConstRigConfigurationHandle_t obj);
383 
395  uint32_t sensorID,
396  dwConstRigConfigurationHandle_t obj);
397 
409  uint32_t sensorID,
410  dwConstRigConfigurationHandle_t obj);
411 
425  uint32_t sensorID,
426  dwConstRigConfigurationHandle_t obj);
427 
441  uint32_t sensorID,
442  dwConstRigConfigurationHandle_t obj);
443 
463 dwStatus dwRigConfiguration_serializeToFile(const char *configurationFile, dwConstRigConfigurationHandle_t obj);
464 
465 #ifdef __cplusplus
466 }
467 #endif
468 
469 #endif // DW_RIGCONFIGURATION_RIGCONFIGURATION_H__
float32_t wheelDiameter
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.
Definition: Types.h:77
float32_t d
Affine matrix coefficient D.
dwSensorType
Defines the type of sensors that are available in DriveWorks.
Definition: Sensors.h:120
uint32_t height
Width of the image (in pixels)
float32_t c
Affine matrix coefficient C.
Configuration parameters for a calibrated FTheta camera.
float32_t wheelbase
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 bumperRear
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.
Definition: Status.h:167
NVIDIA DriveWorks API: Sensors
float32_t length
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.
float32_t axlebaseFront
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
float32_t bumperFront
float32_t inertia
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.
Definition: Context.h:78
float32_t steeringCoefficient
float32_t widthWithMirrors
float32_t mass
float32_t u0
U coordinate for the principal point (in pixels)
float32_t height
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)
float32_t axlebaseRear
float32_t width
#define DW_API_PUBLIC
Definition: Exports.h:76
uint32_t width
Width of the image (in pixels)
Properties of the vehicle.