![]() |
DriveWorks SDK Reference| 0.6.67 Release |
Defines rig configurations of the car.
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... | |
Modules | |
Rig Configuration | |
Defines vehicle rig configuration. | |
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... | |
struct dwFThetaCameraConfig |
Data Fields | ||
---|---|---|
float32_t | backwardsPoly[DW_FTHETA_POLY_LENGTH] | Pixel2ray backward projection polynomial coefficients. |
uint32_t | height | Width of the image (in pixels) |
float32_t | u0 | U 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) |
struct dwOCamCameraConfig |
Data Fields | ||
---|---|---|
float32_t | c | Affine matrix coefficient C. |
float32_t | d | Affine matrix coefficient D. |
float32_t | e | Affine matrix coefficient E. |
uint32_t | height | Width of the image (in pixels) |
float32_t | poly[DW_OCAM_POLY_LENGTH] | Pixel2ray polynomial coefficients. |
float32_t | u0 | U 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) |
struct dwPinholeCameraConfig |
Data Fields | ||
---|---|---|
float32_t | distortion[DW_PINHOLE_DISTORTION_LENGTH] |
Distortion polynomial coefficients [k_1, k_2, k_3]. x' = x * (1 + k_1 * r^2 + k_2 * r^4 + k_3 * r^6) y' = y * (1 + k_1 * r^2 + k_2 * r^4 + k_3 * r^6) |
float32_t | focalX | Focal length in the X axis. |
float32_t | focalY | Focal length in the Y axis. |
uint32_t | height | Width of the image (in pixels) |
float32_t | u0 | U 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) |
struct dwVehicle |
Data Fields | ||
---|---|---|
float32_t | axlebaseFront |
Width of the front axle. [meters] |
float32_t | axlebaseRear |
Width of the rear axle. [meters] |
float32_t | bumperFront |
Distance axle to front bumper. [meters] |
float32_t | bumperRear |
Distance axle to rear bumper. [meters] |
float32_t | centerOfMassToRearAxle |
Distance between vehicle's CoM (center-of-mass) and center of the rear axle. [meters] |
float32_t | frontCorneringStiffness |
front wheel cornering stiffness. |
float32_t | height |
Height of the vehicle. [meters]> |
float32_t | inertia |
vehicle inertia w.r.t its CoM (center-of-mass). [kg/m^2] |
float32_t | length |
Height of the vehicle. [meters] |
float32_t | mass |
vehicle mass [kg]. |
float32_t | rearCorneringStiffness |
rear wheel cornering stiffness. |
float32_t | steeringCoefficient |
Steering coefficient for trivial linear mapping between steering wheel and steering angle, i.e. |
float32_t | wheelbase |
Distance between the centers of the front and rear wheels. [meters] |
float32_t | wheelDiameter |
Diameter of the wheels. [meters] |
float32_t | width |
Width of the vehicle. [meters] |
float32_t | widthWithMirrors |
Width of the vehicle including side mirrors. [meters] |
#define DW_FTHETA_POLY_LENGTH 5 |
Definition at line 177 of file RigConfiguration.h.
#define DW_OCAM_POLY_LENGTH 5 |
Definition at line 146 of file RigConfiguration.h.
#define DW_PINHOLE_DISTORTION_LENGTH 3 |
Definition at line 115 of file RigConfiguration.h.
typedef struct dwRigConfigurationObject const* dwConstRigConfigurationHandle_t |
Definition at line 101 of file RigConfiguration.h.
typedef struct dwRigConfigurationObject* dwRigConfigurationHandle_t |
Handle representing the Sensor Abstraction Layer interface.
Definition at line 100 of file RigConfiguration.h.
enum dwCameraModel |
Specifies the supported optical camera models.
The models define the mapping between optical rays and pixel coordinates, e.g., the intrinsic parameters of the camera.
Enumerator | |
---|---|
DW_CAMERA_MODEL_OCAM | |
DW_CAMERA_MODEL_PINHOLE | |
DW_CAMERA_MODEL_FTHETA |
Definition at line 109 of file RigConfiguration.h.
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.
[out] | sensorID | The Specifies the index of the matching sensor. Undefined if the function fails. |
[in] | sensorName | The name to search for. If the character '*' is found, only the characters before are compared for a match. |
[in] | obj | Specifies the rig configuration module handle. |
DW_API_PUBLIC dwStatus dwRigConfiguration_getCameraModel | ( | dwCameraModel * | cameraModel, |
uint32_t | sensorID, | ||
dwConstRigConfigurationHandle_t | obj | ||
) |
Gets the model type of the camera intrinsics.
The supported models are OCam and Pinhole.
[out] | cameraModel | A pointer to the model type for the camera intrinsics. |
[in] | sensorID | Specifies the index of the queried sensor. |
[in] | obj | Specifies the rig configuration module handle. |
DW_API_PUBLIC dwStatus dwRigConfiguration_getFThetaCameraConfig | ( | dwFThetaCameraConfig * | config, |
uint32_t | sensorID, | ||
dwConstRigConfigurationHandle_t | obj | ||
) |
Gets the parameters of the FTheta camera model.
[out] | config | A pointer to the configuration of the camera intrinsics. |
[in] | sensorID | Specifies the index of the queried sensor. |
[in] | obj | Specifies the rig configuration module handle. |
DW_API_PUBLIC dwStatus dwRigConfiguration_getOCamCameraConfig | ( | dwOCamCameraConfig * | config, |
uint32_t | sensorID, | ||
dwConstRigConfigurationHandle_t | obj | ||
) |
Gets the parameters of the OCam camera model.
[out] | config | A pointer to the configuration of the camera intrinsics. |
[in] | sensorID | Specifies the index of the queried sensor. |
[in] | obj | Specifies the rig configuration module handle. |
DW_API_PUBLIC dwStatus dwRigConfiguration_getPinholeCameraConfig | ( | dwPinholeCameraConfig * | config, |
uint32_t | sensorID, | ||
dwConstRigConfigurationHandle_t | obj | ||
) |
Gets the parameters of the pinhole camera model.
[out] | config | A pointer to the configuration of the camera intrinsics. |
[in] | sensorID | Specifies the index of the queried sensor. |
[in] | obj | Specifies the rig configuration module handle. |
DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorCount | ( | uint32_t * | sensorCount, |
dwConstRigConfigurationHandle_t | obj | ||
) |
Gets the number of available sensors.
[out] | sensorCount | A pointer to the number of sensors in the rig configuration. |
[in] | obj | Specifies the Rig Configuration module handle. |
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.
For example, "Front Camera".
[out] | sensorName | A pointer to the pointer of the given name of the sensor. The pointer is valid until module reset or release is called. |
[in] | sensorID | Specifies the index of the queried sensor. |
[in] | obj | Specifies the rig configuration module handle. |
DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorParameter | ( | const char ** | sensorParameter, |
uint32_t | sensorID, | ||
dwConstRigConfigurationHandle_t | obj | ||
) |
Gets the parameter string for a sensor.
This string can be used in sensor creation.
[out] | sensorParameter | A pointer to the pointer to the parameters of the sensor, for example camera driver and csi port. The returned pointer is valid until module reset or release is called. |
[in] | sensorID | Specifies the index of the queried sensor. |
[in] | obj | Specifies the Rig Configuration module handle. |
DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorProtocol | ( | const char ** | sensorProtocol, |
uint32_t | sensorID, | ||
dwConstRigConfigurationHandle_t | obj | ||
) |
Gets the protocol string of a sensor.
This string can be used in sensor creation or to identify the type of a sensor.
[out] | sensorProtocol | A pointer to the pointer to the protocol of the sensor, for example, camera.gmsl. The returned pointer is valid until module reset or release is called. |
[in] | sensorID | Specifies the index of the queried sensor. |
[in] | obj | Specifies the Rig Configuration module handle. |
DW_API_PUBLIC dwStatus dwRigConfiguration_getSensorToRigTransformation | ( | dwTransformation * | transformation, |
uint32_t | sensorID, | ||
dwConstRigConfigurationHandle_t | obj | ||
) |
Gets the sensor to rig transformation for a sensor.
This transformation relates the sensor and the rig coordinate system to each other. For example, the origin in sensor coordinate system is the position of the sensor in rig coordinates.
[out] | transformation | A pointer to the transformation from sensor to rig coordinate system. |
[in] | sensorID | Specifies the index of the queried sensor. |
[in] | obj | Specifies the rig configuration module handle. |
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.
[out] | sensorType | A pointer to return the type of sensor |
[in] | sensorID | Specifies the index of the queried sensor. |
[in] | obj | Specifies the rig configuration module handle. |
DW_API_PUBLIC dwStatus dwRigConfiguration_getVehicle | ( | const dwVehicle ** | vehicle, |
dwConstRigConfigurationHandle_t | obj | ||
) |
Gets the properties of the vehicle.
[out] | vehicle | A pointer to the struct holding vehicle properties. The returned pointer is valid until module reset or release is called. |
[in] | obj | Specifies the Rig Configuration module handle. |
DW_API_PUBLIC dwStatus dwRigConfiguration_initializeFromFile | ( | dwRigConfigurationHandle_t * | obj, |
dwContextHandle_t | ctx, | ||
const char * | configurationFile | ||
) |
Initializes the Rig Configuration module.
[out] | obj | A pointer to the Rig Configuration handle for the created module. |
[in] | ctx | Specifies the handler to the context under which the Rigconfiguration module is created. |
[in] | configurationFile | A pointer to the XML file that contains the rig configuration. Typically produced by the DriveWorks calibration tool. |
DW_API_PUBLIC dwStatus dwRigConfiguration_release | ( | dwRigConfigurationHandle_t * | obj | ) |
Releases the Rig Configuration module.
[in] | obj | A pointer to the Rig Configuration module handle. |
DW_API_PUBLIC dwStatus dwRigConfiguration_reset | ( | dwRigConfigurationHandle_t | obj | ) |
Resets the Rig Configuration module.
[in] | obj | Specifies the Rig Configuration module handle. |
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.
The output file contains the full state of the rig-configuration and can again be loaded with dwRigConfiguration_initializeFromFile().
The serialization format is selected based on the file name extension; currently supported extensions are json
.
[in] | configurationFile | The name of the file to serialize to. It's extension is used to select the serialization format. This method will overwrite the file if it exists. |
[in] | obj | Specifies the rig configuration module handle. |
DW_API_PUBLIC dwStatus dwRigConfiguration_setSensorToRigTransformation | ( | dwTransformation const * | transformation, |
uint32_t | sensorID, | ||
dwRigConfigurationHandle_t | obj | ||
) |
Sets the sensor to rig transformation for a sensor.
[in] | transformation | A pointer to the transformation from sensor to rig coordinate system. |
[in] | sensorID | Specifies the index of the updates sensor. |
[in] | obj | Specifies the rig configuration module handle. |