DriveWorks SDK Reference
5.10.90 Release
For Test and Development only

Rig.h
Go to the documentation of this file.
1
2//
3// Notice
4// ALL NVIDIA DESIGN SPECIFICATIONS AND CODE ("MATERIALS") ARE PROVIDED "AS IS" NVIDIA MAKES
5// NO REPRESENTATIONS, WARRANTIES, EXPRESSED, IMPLIED, STATUTORY, OR OTHERWISE WITH RESPECT TO
6// THE MATERIALS, AND EXPRESSLY DISCLAIMS ANY IMPLIED WARRANTIES OF NONINFRINGEMENT,
7// MERCHANTABILITY, OR FITNESS FOR A PARTICULAR PURPOSE.
8//
9// NVIDIA CORPORATION & AFFILIATES assumes no responsibility for the consequences of use of such
10// information or for any infringement of patents or other rights of third parties that may
11// result from its use. No license is granted by implication or otherwise under any patent
12// or patent rights of NVIDIA CORPORATION & AFFILIATES. No third party distribution is allowed unless
13// expressly authorized by NVIDIA. Details are subject to change without notice.
14// This code supersedes and replaces all information previously supplied.
15// NVIDIA CORPORATION & AFFILIATES products are not authorized for use as critical
16// components in life support devices or systems without express written approval of
17// NVIDIA CORPORATION & AFFILIATES.
18//
19// SPDX-FileCopyrightText: Copyright (c) 2015-2022 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
20// SPDX-License-Identifier: LicenseRef-NvidiaProprietary
21//
22// NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
23// property and proprietary rights in and to this material, related
24// documentation and any modifications thereto. Any use, reproduction,
25// disclosure or distribution of this material and related documentation
26// without an express license agreement from NVIDIA CORPORATION or
27// its affiliates is strictly prohibited.
28//
30
46#ifndef DW_RIG_RIG_H_
47#define DW_RIG_RIG_H_
48
49#include <dw/core/base/Config.h>
52#include <dw/core/base/Types.h>
53#include <dw/sensors/Sensors.h>
54#include <dw/rig/Vehicle.h>
55#include <stdint.h>
56
57#ifdef __cplusplus
58extern "C" {
59#endif
60
70typedef struct dwRigObject* dwRigHandle_t;
71typedef struct dwRigObject const* dwConstRigHandle_t;
72
74// Calibrated cameras
75
77#define DW_MAX_RIG_SENSOR_COUNT 128U
78
80#define DW_MAX_RIG_CAMERA_COUNT DW_MAX_RIG_SENSOR_COUNT
81
83#define DW_MAX_RIG_SENSOR_NAME_SIZE 64U
84
86#define DW_MAX_EXTRINSIC_PROFILE_NAME_SIZE 64U
87
89#define MAX_EXTRINSIC_PROFILE_COUNT 3U
90
95typedef enum dwCameraModel {
96
100
104#define DW_PINHOLE_DISTORTION_LENGTH 3U
105
106/*
107 * Configuration parameters for a calibrated pinhole camera.
108 *
109 * The (forward) projection of a three-dimensional ray to a two-dimensional pixel coordinate
110 * is performed in three steps:
111 *
112 * **Step 1**: Projection of a ray `(x, y, z)` to normalized image coordinates, i.e.,
113 *
114 * (xn, yn) = (x/z, y/z) .
115 *
116 * **Step 2**: Distortion of the normalized image coordinates by a polynomial with coefficients
117 * `[k_1, k_2, k_3]` given in dwPinholeCameraConfig::distortion, i.e.,
118 *
119 * xd = xn * (1 + k_1 * r^2 + k_2 * r^4 + k_3 * r^6),
120 * yd = yn * (1 + k_1 * r^2 + k_2 * r^4 + k_3 * r^6),
121 *
122 * whereas
123 * r^2 = (xn^2 + yn^2) .
124 *
125 * **Step 3**: Mapping of distorted normalized image coordinates `(xd, yd)` to
126 * pixel coordinates `(u, v)`, i.e.,
127 *
128 * [u] = [focalX 0] * [xd] + [u0]
129 * [v] [0 focalY] [yd] [v0] .
130 */
132{
134 uint32_t width;
135
137 uint32_t height;
138
141
144
147
150
157
161#define DW_FTHETA_POLY_LENGTH 6U
162
169{
171 uint32_t width;
172
174 uint32_t height;
175
178
181
185
203
211
221/*
222 * The camera model is defined by three major components
223 *
224 * - the polynomial `polynomial`
225 * - the principal point `(u0, v0)`, and
226 * - the transformation matrix `A`
227 *
228 *
229 * A = [ c d ]
230 * [ e 1 ] .
231 *
232 * The bottom right element of `A` is implicitly set to 1. This is general enough
233 * for relevant linear transformations because any matrix can be brought into this form
234 * by incorporating an absolute scale into the polynomial.
235 *
236 *
237 * The forward projection of a three-dimensional ray to a two-dimensional pixel coordinates
238 * by means of the FTheta camera model can be described in four steps:
239 *
240 * **Step 1**: Projection of a ray `(x, y, z)` to spherical coordinates `(direction, theta)`:
241 *
242 * direction = (x, y) / norm((x, y))
243 * theta = atan2(norm((x, y)), z)
244 *
245 * **Step 2**: Mapping of the angle `theta` to pixel distances according to the polynomial
246 * coefficients `polynomial` and polynomial type `type` :
247 *
248 * distance = map_angle_to_pixeldistance( polynomial, type, theta )
249 *
250 * **Step 3**: Mapping of `distance` and the two-dimensional `direction` to a pixel offset:
251 *
252 * offset = distance * direction
253 *
254 * **Step 4**: Linear transformation of the two-dimensional pixel offset to pixel coordinate `(u, v)`:
255 *
256 * [u] = [c d] * offset^T + [u0]
257 * [v] [e 1] [v0]
258 *
259 *
260 * Conversely, the backward projection of a two-dimensional pixel coordinate to
261 * a three-dimensional ray is performed in four steps reversely to the forward projection:
262 *
263 * **Step 1**: Linear transformation of pixel coordinates `(u, v)` to pixel offset:
264 *
265 * offset = inverse(A) * [u - u0]
266 * [v - v0]
267 *
268 * **Step 2**: Mapping of the two-dimensional pixel offset to polar coordinates `(direction, distance)`:
269 *
270 * direction = offset / norm(offset)
271 * distance = norm(offset)
272 *
273 * **Step 3**: Mapping of the pixel distance to the sight ray angle `theta` according to the polynomial
274 * coefficients `polynomial` and the polynomial type `type` :
275 *
276 * theta = map_pixel_distance_to_angle( polynomial, type, distance )
277 *
278 * **Step 4**: Computation of the sight ray `(x, y, z)` based on polar coordinates `(direction, angle)`:
279 *
280 * (x, y) = sin(theta) * direction
281 * z = cos(theta)
282 *
283 *
284 * The functions `map_angle_to_pixel_distance(.)` and `map_pixel_distance_to_angle(.)` depend on the
285 * polynomial coefficients `polynomial` and the type of the polynomial, i.e.,
286 *
287 * - whenever the type of polynomial corresponds to the requested direction,
288 * the function corresponds to a simple evaluation of the polynomial:
289 *
290 * map_a_to_b( polynomial, a_to_b, x ) = polynomial[0] + polynomial[1] * x + ... + polynomial[DW_FTHETA_POLY_LENGTH - 1] * x^(DW_FTHETA_POLY_LENGTH - 1)
291 *
292 * - whenever the type of polynomial is the inverse to the requested direction,
293 * the function is equivalent to the inverse of the polynomial:
294 *
295 * map_a_to_b( polynomial, b_to_a, x ) = y
296 *
297 * with `map_b_to_a( polynomial, b_to_a, y ) == x`.
298 * The solution is computed via iterative local inversion. The valid ranges are defined by the
299 * camera's resolution and field of view.
300 *
301 *
302 * In literature, the closest description is found in [Courbon et al, 2007], TABLE II:
303 *
304 * [Courbon et al, 2007]: Courbon, J., Mezouar, Y., Eckt, L., and Martinet, P. (2007, October).
305 * A generic fisheye camera model for robotic applications. In Intelligent Robots and Systems, 2007.
306 * IROS 2007, pp. 1683–1688.
307 */
309{
311 uint32_t width;
312
314 uint32_t height;
315
327
330
338
341
344
353
361
369/*
370 * The model is described by three major components:
371 *
372 * - the image size `(width, height)`,
373 * - the principal point `(u0, v0)`, and
374 * - the horizontal field of view `hFOV`.
375 *
376 *
377 * The horizontal field of view determines the radius `r` of the sphere
378 * used in the projection:
379 *
380 * r = 0.5 / tan(hFOV/4)
381 *
382 * The radius determines
383 *
384 * - the distance of the image plane to the origin of the camera coordinate system and
385 * - the distance of the pole of the projection to the origin of the camera coordinate system.
386 *
387 *
388 * The forward projection of a three-dimensional ray to a two-dimensional pixel coordinate
389 * by means of the stereographic camera model can be described in two steps:
390 *
391 * **Step 1**: Projection of a ray `(x, y, z)` of length 1 onto a normalized coordinate `(xn, yn)`
392 * on the image plane at distance r, i.e.,
393 *
394 * (xn, yn) = 2 * r * (x, y) / (1 + z)
395 *
396 * **Step 2**: Scaling and shift to pixel coordinate `(u, v)`, i.e.,
397 *
398 * u = xn * width / 2 + u0
399 * v = yn * height / 2 + v0
400 *
401 *
402 * Conversely, the backward projection of a two-dimensional pixel coordinate to
403 * a three-dimensional ray is performed in two steps reversely to the forward projection:
404 *
405 * **Step 1**: Scaling and shift of pixel coordinate `(u, v)` to normalized image coordinate `(xn, yn)`, i.e.,
406 *
407 * xn = (u - u0) / (width / 2)
408 * yn = (v - v0) / (height / 2)
409 *
410 * **Step 2**: Projection of normalized image coordinates to three-dimensional unit ray `(x, y, z)`, i.e.,
411 *
412 * (x, y, z) = (4 * r * xn, 4 * r * yn, - xn^2 - yn^2 + 4 * r^2)) / (xn^2 + yn^2 + 4 * r^2)
413 */
415{
417 uint32_t width;
418
420 uint32_t height;
421
424
427
431
453 dwContextHandle_t const ctx,
454 char8_t const* const configurationFile);
455
475 dwContextHandle_t const ctx,
476 char8_t const* const configurationString,
477 char8_t const* const relativeBasePath);
478
490
502
518dwStatus dwRig_getVehicle(dwVehicle const** const vehicle, dwConstRigHandle_t const obj);
519
534
549dwStatus dwRig_setVehicle(dwVehicle const* const vehicle, dwRigHandle_t const obj);
550
565
578dwStatus dwRig_getVehicleIOConfigCount(uint32_t* const vioConfigCount,
579 dwConstRigHandle_t const obj);
580
592dwStatus dwRig_getSensorCount(uint32_t* const sensorCount,
593 dwConstRigHandle_t const obj);
594
607dwStatus dwRig_getSensorCountOfType(uint32_t* const sensorCount,
608 dwSensorType const sensorType,
609 dwConstRigHandle_t const obj);
610
626dwStatus dwRig_getSensorProtocol(char8_t const** const sensorProtocol,
627 uint32_t const sensorId,
628 dwConstRigHandle_t const obj);
629
643DW_API_PUBLIC dwStatus dwRig_getSensorParameter(char8_t const** const sensorParameter,
644 uint32_t const sensorId,
645 dwConstRigHandle_t const obj);
646
660DW_API_PUBLIC dwStatus dwRig_setSensorParameter(char8_t const* const sensorParameter,
661 uint32_t const sensorId,
662 dwRigHandle_t const obj);
663
681DW_API_PUBLIC dwStatus dwRig_getSensorParameterUpdatedPath(char8_t const** const sensorParameter,
682 uint32_t const sensorId,
683 dwConstRigHandle_t const obj);
684
702 uint32_t const sensorId,
703 dwConstRigHandle_t const obj);
704
721 uint32_t const sensorId,
722 dwConstRigHandle_t const obj);
723
741 uint32_t const sensorId,
742 dwConstRigHandle_t const obj);
743
761 uint32_t const sensorIdFrom,
762 uint32_t const sensorIdTo,
763 dwConstRigHandle_t const obj);
764
783 uint32_t const sensorIdFrom,
784 uint32_t const sensorIdTo,
785 dwConstRigHandle_t const obj);
786
803 uint32_t const sensorId,
804 dwRigHandle_t const obj);
805
820dwStatus dwRig_getSensorName(char8_t const** const sensorName,
821 uint32_t const sensorId,
822 dwConstRigHandle_t const obj);
823
839dwStatus dwRig_getSensorDataPath(char8_t const** const dataPath,
840 uint32_t const sensorId,
841 dwConstRigHandle_t const obj);
842
857dwStatus dwRig_getCameraTimestampPath(char8_t const** const timestampPath,
858 uint32_t const sensorId,
859 dwConstRigHandle_t const obj);
860
878dwStatus dwRig_getSensorPropertyByName(char8_t const** const propertyValue,
879 char8_t const* const propertyName,
880 uint32_t const sensorId,
881 dwConstRigHandle_t const obj);
882
898dwStatus dwRig_addOrSetSensorPropertyByName(char8_t const* const propertyValue,
899 char8_t const* const propertyName,
900 uint32_t const sensorId,
901 dwRigHandle_t const obj);
918dwStatus dwRig_getPropertyByName(char8_t const** const propertyValue,
919 char8_t const* const propertyName,
920 dwConstRigHandle_t const obj);
921
936dwStatus dwRig_addOrSetPropertyByName(char8_t const* const propertyValue,
937 char8_t const* const propertyName,
938 dwRigHandle_t const obj);
939
954dwStatus dwRig_findSensorByName(uint32_t* const sensorId,
955 char8_t const* const sensorName,
956 dwConstRigHandle_t const obj);
972 uint32_t const vehicleIOId,
973 dwConstRigHandle_t const obj);
974
990dwStatus dwRig_findSensorByTypeIndex(uint32_t* const sensorId,
991 dwSensorType const sensorType,
992 uint32_t const sensorTypeIndex,
993 dwConstRigHandle_t const obj);
994
1009 uint32_t const sensorId,
1010 dwConstRigHandle_t const obj);
1011
1028 uint32_t const sensorId,
1029 dwConstRigHandle_t const obj);
1030
1046 uint32_t const sensorId,
1047 dwConstRigHandle_t const obj);
1048
1066DW_DEPRECATED("dwRig_getFThetaCameraConfig is replaced by dwRig_getFThetaCameraConfigNew.")
1068 uint32_t const sensorId,
1069 dwConstRigHandle_t const obj);
1070
1089 uint32_t const sensorId,
1090 dwConstRigHandle_t const obj);
1091
1107 uint32_t const sensorId,
1108 dwRigHandle_t const obj);
1109
1126 uint32_t const sensorId,
1127 dwRigHandle_t const obj);
1128
1144 uint32_t const sensorId,
1145 dwRigHandle_t const obj);
1146
1166dwStatus dwRig_serializeToFile(char8_t const* const configurationFile,
1167 dwConstRigHandle_t const obj);
1168
1169#ifdef __cplusplus
1170}
1171#endif
1172
1174#endif // DW_RIG_RIG_H_
NVIDIA DriveWorks API: Core Methods
Specifies a 3D rigid transformation.
Definition: MatrixTypes.h:186
NVIDIA DriveWorks API: Sensors
NVIDIA DriveWorks API: Core Types
NVIDIA DriveWorks API: Vehicle Parameters
NVIDIA DriveWorks API: Core Exports
float float32_t
Specifies POD types.
Definition: BasicTypes.h:57
struct dwContextObject * dwContextHandle_t
Context handle.
Definition: Context.h:83
#define DW_DEPRECATED(msg)
Definition: Exports.h:66
#define DW_API_PUBLIC
Definition: Exports.h:54
dwStatus
Status definition.
Definition: Status.h:173
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:171
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:140
float32_t focalY
Focal length in the Y axis (in pixels)
Definition: Rig.h:149
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:143
float32_t backwardsPoly[DW_FTHETA_POLY_LENGTH]
Pixel2ray backward projection polynomial coefficients.
Definition: Rig.h:183
dwFThetaCameraPolynomialType polynomialType
Defines whether the polynomial parameter either map angles to pixel-distances (called forward directi...
Definition: Rig.h:359
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:134
float32_t distortion[DW_PINHOLE_DISTORTION_LENGTH]
Polynomial coefficients [k_1, k_2, k_3] that allow to map undistored, normalized image coordinates (x...
Definition: Rig.h:155
float32_t focalX
Focal length in the X axis (in pixels)
Definition: Rig.h:146
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:423
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:180
float32_t c
Linear pixel transformation matrix coefficient c (top left element) If all c, d, and e are set to 0....
Definition: Rig.h:337
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:177
uint32_t height
Height of the image (in pixels)
Definition: Rig.h:314
float32_t d
Linear pixel transformation coefficient d (top right element).
Definition: Rig.h:340
float32_t u0
Principal point coordinates: indicating the horizontal / vertical image coordinates of the principal ...
Definition: Rig.h:326
uint32_t height
Height of the image (in pixels)
Definition: Rig.h:137
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:417
uint32_t height
Height of the image (in pixels)
Definition: Rig.h:174
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:426
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:311
float32_t e
Linear pixel transformation coefficient e (bottom left element).
Definition: Rig.h:343
float32_t polynomial[DW_FTHETA_POLY_LENGTH]
Polynomial describing either the mapping of angles to pixel-distances or the mapping of pixel-distanc...
Definition: Rig.h:352
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:329
float32_t hFOV
Horizontal FOV (in radians)
Definition: Rig.h:429
uint32_t height
Height of the image (in pixels)
Definition: Rig.h:420
DW_API_PUBLIC dwStatus dwRig_getSensorName(char8_t const **const sensorName, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the name of a sensor as given in the configuration.
DW_API_PUBLIC dwStatus dwRig_getSensorDataPath(char8_t const **const dataPath, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets path to sensor recording.
DW_API_PUBLIC dwStatus dwRig_setVehicle(dwVehicle const *const vehicle, dwRigHandle_t const obj)
DEPRECATED: Sets the properties of a passenger car vehicle.
DW_API_PUBLIC dwStatus dwRig_setFThetaCameraConfig(dwFThetaCameraConfig const *const config, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the parameters of the FTheta camera model.
DW_API_PUBLIC dwStatus dwRig_getSensorProtocol(char8_t const **const sensorProtocol, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the protocol string of a sensor.
DW_API_PUBLIC dwStatus dwRig_getSensorType(dwSensorType *const sensorType, uint32_t const sensorId, dwConstRigHandle_t const obj)
Returns the type of sensor based upon the sensorID sent into the method.
DW_API_PUBLIC dwStatus dwRig_getNominalSensorToSensorTransformation(dwTransformation3f *const transformation, uint32_t const sensorIdFrom, uint32_t const sensorIdTo, dwConstRigHandle_t const obj)
Gets the nominal sensor to sensor transformation for a pair of sensors.
DW_API_PUBLIC dwStatus dwRig_setPinholeCameraConfig(dwPinholeCameraConfig const *const config, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the parameters of the pinhole camera model.
DW_API_PUBLIC dwStatus dwRig_release(dwRigHandle_t const obj)
Releases the Rig Configuration module.
DW_API_PUBLIC dwStatus dwRig_getPinholeCameraConfig(dwPinholeCameraConfig *const config, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the parameters of the Pinhole camera model.
DW_API_PUBLIC dwStatus dwRig_initializeFromString(dwRigHandle_t *const obj, dwContextHandle_t const ctx, char8_t const *const configurationString, char8_t const *const relativeBasePath)
Initializes the Rig Configuration module from a string.
DW_API_PUBLIC dwStatus dwRig_getSensorPropertyByName(char8_t const **const propertyValue, char8_t const *const propertyName, uint32_t const sensorId, dwConstRigHandle_t const obj)
Returns property stored inside of a sensor.
DW_API_PUBLIC dwStatus dwRig_getPropertyByName(char8_t const **const propertyValue, char8_t const *const propertyName, dwConstRigHandle_t const obj)
Returns property stored inside of rig.
DW_API_PUBLIC dwStatus dwRig_getSensorToSensorTransformation(dwTransformation3f *const transformation, uint32_t const sensorIdFrom, uint32_t const sensorIdTo, dwConstRigHandle_t const obj)
Gets the sensor to sensor transformation for a pair of sensors.
DW_API_PUBLIC dwStatus dwRig_findSensorIdFromVehicleIOId(uint32_t *const sensorId, uint32_t const vehicleIOId, dwConstRigHandle_t const obj)
Finds a sensor with the given vehicleIO ID and returns the index.
dwCameraModel
Specifies the supported optical camera models.
Definition: Rig.h:95
DW_API_PUBLIC dwStatus dwRig_reset(dwRigHandle_t const obj)
Resets the Rig Configuration module.
DW_API_PUBLIC dwStatus dwRig_findSensorByTypeIndex(uint32_t *const sensorId, dwSensorType const sensorType, uint32_t const sensorTypeIndex, dwConstRigHandle_t const obj)
Finds the absolute sensor index of the Nth sensor of a given type.
DW_API_PUBLIC dwStatus dwRig_getGenericVehicle(dwGenericVehicle *const vehicle, dwConstRigHandle_t const obj)
Gets the properties of a generic vehicle (car or truck).
DW_API_PUBLIC dwStatus dwRig_setFThetaCameraConfigNew(dwFThetaCameraConfigNew const *const config, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the parameters of the FTheta camera model.
struct dwRigObject * dwRigHandle_t
Handle representing the Rig interface.
Definition: Rig.h:70
#define DW_FTHETA_POLY_LENGTH
Defines the number of distortion coefficients for the ftheta camera model.
Definition: Rig.h:161
DW_API_PUBLIC dwStatus dwRig_getNominalSensorToRigTransformation(dwTransformation3f *const transformation, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the nominal sensor to rig transformation for a sensor.
DW_API_PUBLIC dwStatus dwRig_serializeToFile(char8_t const *const configurationFile, dwConstRigHandle_t const obj)
This method serializes the rig-configuration object to a human-readable rig-configuration file.
DW_API_PUBLIC dwStatus dwRig_getSensorToRigTransformation(dwTransformation3f *const transformation, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the sensor to rig transformation for a sensor.
DW_API_PUBLIC dwStatus dwRig_findSensorByName(uint32_t *const sensorId, char8_t const *const sensorName, dwConstRigHandle_t const obj)
Finds the sensor with the given name and returns its index.
DW_API_PUBLIC dwStatus dwRig_getSensorCountOfType(uint32_t *const sensorCount, dwSensorType const sensorType, dwConstRigHandle_t const obj)
Find number of sensors of a given type.
DW_API_PUBLIC dwStatus dwRig_setSensorParameter(char8_t const *const sensorParameter, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the parameter string for a sensor.
DW_API_PUBLIC dwStatus dwRig_getFThetaCameraConfigNew(dwFThetaCameraConfigNew *const config, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the parameters of the FTheta camera model.
DW_API_PUBLIC dwStatus dwRig_getVehicle(dwVehicle const **const vehicle, dwConstRigHandle_t const obj)
DEPRECATED: Gets the properties of a passenger car vehicle.
DW_API_PUBLIC dwStatus dwRig_getSensorFLUToRigTransformation(dwTransformation3f *const transformation, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the sensor FLU to rig transformation for a sensor.
DW_API_PUBLIC dwStatus dwRig_addOrSetPropertyByName(char8_t const *const propertyValue, char8_t const *const propertyName, dwRigHandle_t const obj)
Overwrite content of an existing rig property.
DW_API_PUBLIC dwStatus dwRig_getSensorCount(uint32_t *const sensorCount, dwConstRigHandle_t const obj)
Gets the number of all available sensors.
DW_API_PUBLIC dwStatus dwRig_initializeFromFile(dwRigHandle_t *const obj, dwContextHandle_t const ctx, char8_t const *const configurationFile)
Initializes the Rig Configuration module from a file.
#define DW_PINHOLE_DISTORTION_LENGTH
Defines the number of distortion coefficients for the pinhole camera model.
Definition: Rig.h:104
DW_API_PUBLIC dwStatus dwRig_getSensorParameterUpdatedPath(char8_t const **const sensorParameter, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the parameter string for a sensor with any path described by file=,video=,timestamp= property mo...
struct dwRigObject const * dwConstRigHandle_t
Definition: Rig.h:71
dwFThetaCameraPolynomialType
Type of polynomial stored in FTheta.
Definition: Rig.h:196
DW_API_PUBLIC dwStatus dwRig_getCameraTimestampPath(char8_t const **const timestampPath, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets path to camera timestamp file.
DW_API_PUBLIC dwStatus dwRig_setSensorToRigTransformation(dwTransformation3f const *const transformation, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the sensor to rig transformation for a sensor.
DW_API_PUBLIC dwStatus dwRig_getFThetaCameraConfig(dwFThetaCameraConfig *const config, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the parameters of the FTheta camera model.
DW_API_PUBLIC dwStatus dwRig_addOrSetSensorPropertyByName(char8_t const *const propertyValue, char8_t const *const propertyName, uint32_t const sensorId, dwRigHandle_t const obj)
Overwrite content of an existing sensor property.
DW_API_PUBLIC dwStatus dwRig_getCameraModel(dwCameraModel *const cameraModel, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the model type of the camera intrinsics.
DW_API_PUBLIC dwStatus dwRig_getSensorParameter(char8_t const **const sensorParameter, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the parameter string for a sensor.
DW_API_PUBLIC dwStatus dwRig_getVehicleIOConfigCount(uint32_t *const vioConfigCount, dwConstRigHandle_t const obj)
Gets the number of vehicle IO sensors.
DW_API_PUBLIC dwStatus dwRig_setGenericVehicle(dwGenericVehicle const *const vehicle, dwRigHandle_t const obj)
Sets the properties of a generic vehicle (car or truck).
@ DW_CAMERA_MODEL_FTHETA
Definition: Rig.h:98
@ DW_CAMERA_MODEL_PINHOLE
Definition: Rig.h:97
@ DW_FTHETA_CAMERA_POLYNOMIAL_TYPE_PIXELDISTANCE_TO_ANGLE
Backward polynomial type, mapping pixel distances (offset from principal point) to angles (angle betw...
Definition: Rig.h:202
@ DW_FTHETA_CAMERA_POLYNOMIAL_TYPE_ANGLE_TO_PIXELDISTANCE
Forward polynomial type, mapping angles (angle between ray and forward direction) to pixel distances ...
Definition: Rig.h:209
DEPRECATED: Configuration parameters for a calibrated FTheta camera.
Definition: Rig.h:169
Configuration parameters for a calibrated FTheta camera.
Definition: Rig.h:309
Vehicle description.
Definition: Vehicle.h:263
Configuration parameters for a calibrated stereographic camera.
Definition: Rig.h:415
DEPRECATED: Properties of a passenger car vehicle.
Definition: Vehicle.h:316
dwSensorType
Defines the type of sensors that are available in DriveWorks.
Definition: Sensors.h:189