Defines rig configurations for the vehicle.
Defines vehicle parameters.
Data Structures | |
struct | dwGenericVehicle |
Vehicle description. More... | |
struct | dwVehicle |
DEPRECATED: Properties of a passenger car vehicle. More... | |
struct | dwVehicleActuationProperties |
Vehicle actuation properties. More... | |
struct | dwVehicleArticulationProperties |
Properties of an articulation linking two vehicle units. More... | |
struct | dwVehicleAxleProperties |
Properties of an axle and its wheels. More... | |
struct | dwVehicleBodyProperties |
Physical properties of a vehicle body. More... | |
struct | dwVehicleCabin |
Vehicle cabin description. More... | |
struct | dwVehicleDynamicsProperties |
Dynamics properties. More... | |
struct | dwVehicleSuspensionProperties |
Suspension properties. More... | |
struct | dwVehicleTorqueLUT |
Throttle and brake state (input) to longitudinal force (output) lookup tables. More... | |
struct | dwVehicleTrailer |
Vehicle trailer description. More... | |
struct | dwVehicleWheelEncoderProperties |
Wheel encoder parameters. More... | |
Modules | |
Rig Configuration | |
Defines vehicle rig configuration. | |
Macros | |
#define | DW_VEHICLE_MAX_NUM_TRAILERS 1U |
#define | DW_VEHICLE_STEER_MAP_POLY_DEGREE 5U |
#define | DW_VEHICLE_STEER_MAP_POLY_DEGREE_PLUS_ONE (DW_VEHICLE_STEER_MAP_POLY_DEGREE + 1U) |
#define | DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE 15U |
Typedefs | |
typedef struct dwRigObject const * | dwConstRigHandle_t |
typedef struct dwRigObject * | dwRigHandle_t |
Handle representing the Rig interface. More... | |
Enumerations | |
enum | dwVehicleTrailerType { DW_VEHICLE_TRAILER_TYPE_FULL = 0 , DW_VEHICLE_TRAILER_TYPE_SEMI = 1 } |
Supported trailer types. More... | |
enum | dwVehicleWheels { DW_VEHICLE_WHEEL_FRONT_LEFT = 0 , DW_VEHICLE_WHEEL_FRONT_RIGHT = 1 , DW_VEHICLE_WHEEL_REAR_LEFT = 2 , DW_VEHICLE_WHEEL_REAR_RIGHT = 3 , DW_VEHICLE_NUM_WHEELS = 4 } |
Define index for each of the wheels on a 4 wheeled vehicle. More... | |
Functions | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
DW_API_PUBLIC dwStatus | dwRig_getFThetaCameraConfigNew (dwFThetaCameraConfig *const config, uint32_t const sensorId, dwConstRigHandle_t const obj) |
Gets the parameters of the FTheta camera model. More... | |
DW_API_PUBLIC dwStatus | dwRig_getGenericVehicle (dwGenericVehicle *const vehicle, dwConstRigHandle_t const obj) |
Gets the properties of a generic vehicle (car or truck). More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
DW_API_PUBLIC dwStatus | dwRig_getSensorCount (uint32_t *const sensorCount, dwConstRigHandle_t const obj) |
Gets the number of all available sensors. More... | |
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. More... | |
DW_API_PUBLIC dwStatus | dwRig_getSensorDataPath (char8_t const **const dataPath, uint32_t const sensorId, dwConstRigHandle_t const obj) |
Gets path to sensor recording. More... | |
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. More... | |
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. More... | |
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. More... | |
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 modified to be in respect to the current rig file's directory (if initializing a rig from file), or in respect to the relativeBasePath (when initializing a rig from string). More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
DW_API_PUBLIC dwStatus | dwRig_getVehicle (dwVehicle const **const vehicle, dwConstRigHandle_t const obj) |
DEPRECATED: Gets the properties of a passenger car vehicle. More... | |
DW_API_PUBLIC dwStatus | dwRig_getVehicleIOConfigCount (uint32_t *const vioConfigCount, dwConstRigHandle_t const obj) |
Gets the number of vehicle IO sensors. More... | |
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. More... | |
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. More... | |
DW_API_PUBLIC dwStatus | dwRig_release (dwRigHandle_t const obj) |
Releases the Rig Configuration module. More... | |
DW_API_PUBLIC dwStatus | dwRig_reset (dwRigHandle_t const obj) |
Resets the Rig Configuration module. More... | |
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. More... | |
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. More... | |
DW_API_PUBLIC dwStatus | dwRig_setGenericVehicle (dwGenericVehicle const *const vehicle, dwRigHandle_t const obj) |
Sets the properties of a generic vehicle (car or truck). More... | |
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. More... | |
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. More... | |
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. More... | |
DW_API_PUBLIC dwStatus | dwRig_setVehicle (dwVehicle const *const vehicle, dwRigHandle_t const obj) |
DEPRECATED: Sets the properties of a passenger car vehicle. More... | |
struct dwGenericVehicle |
Data Fields | ||
---|---|---|
dwVehicleActuationProperties | actuation | Vehicle actuation properties. |
dwVehicleAxleProperties | axleFront | Properties of the front (steering) axle [m]. |
dwVehicleAxleProperties | axleRear |
Properties of the rear axle group [m]. Multiple rear axles are lumped together in an equivalent virtual rear axle, in which case its properties shall be consistent with corresponding vehicle data such as wheel speed. |
dwVehicleBodyProperties | body | Properties of the base body (passenger car body, truck tractor chassis) |
dwVehicleCabin | cabin |
Properties of an optional floating cabin attached to the base body. Applies only to vehicles with a suspended cabin (e.g. trucks). |
dwVehicleDynamicsProperties | dynamics | Vehicle dynamics properties. |
bool | hasCabin | Indicates presence of a cabin. |
uint32_t | numTrailers | Stores the occupied/valid length of trailers. |
dwVehicleSuspensionProperties | suspension | Vehicle suspension properties. |
dwVehicleTrailer | trailers[DW_VEHICLE_MAX_NUM_TRAILERS] |
Properties of trailer units. Applicable only to vehicles with trailer units (e.g. trucks). |
dwVehicleWheelEncoderProperties | wheelEncoder | Wheel encoder properties. |
struct dwVehicle |
Data Fields | ||
---|---|---|
float32_t | aerodynamicDragCoeff |
Aerodynamic drag coefficient.
|
float32_t | aeroHeight |
Equivalent height of aerodynamic force applied (m).
|
float32_t | axlebaseFront | Width of the front axle. [meters]. |
float32_t | axlebaseRear | Width of the rear axle. [meters]. |
float32_t | brakeActuatorTimeConstant | Time constant for first order lp brake system. |
float32_t | bumperFront | Distance front axle to front bumper. [meters]. |
float32_t | bumperRear | Distance rear axle to rear bumper. [meters]. |
float32_t | centerOfMassHeight | Height of the CoM (m). |
float32_t | centerOfMassToFrontAxle | Distance from CoM to the front axle (m). |
float32_t | centerOfMassToRearAxle | Distance between vehicle's CoM (center-of-mass) and center of the rear axle. [meters]. |
float32_t | driveByWireTimeConstant | Drive-by-wire (steer-by-wire) time constant. [s]. |
float32_t | driveByWireTimeDelay | Drive-by-wire (steer-by-wire) time delay. [s]. |
float32_t | effectiveMass | effective mass due to vehicle rotational inertia (wheel rotation, engine, and other parts of the CVT drive-train). [kg] |
float32_t | frontalArea |
Vehicle Frontal area (m^2).
|
float32_t | frontCorneringStiffness | front wheel cornering stiffness. |
float32_t | frontSteeringOffset |
front wheel steering offset [radians]. It is combined with the polynomial function P(steeringWheelAngle) give by steeringWheelToSteeringMap to determine the conversion from steering wheel angle to steering angle as steeringAngle = P(steeringWheelAngle) + frontSteeringOffset and its reverse. |
float32_t | height | Height of the vehicle. [meters]. |
dwVector3f | inertia3D | vehicle inertia around each axis, w.r.t. its center of mass. [kg m^2] |
float32_t | length | Length of the vehicle. [meters]. |
float32_t | mass | vehicle mass [kg]. |
float32_t | maxEnginePower |
Maximum engine power in Watts.
|
float32_t | maxSteeringWheelAngle | maximum steering wheel [radians] |
float32_t | rearCorneringStiffness | rear wheel cornering stiffness. |
float32_t | rollingResistanceCoeff |
Rolling resistance coefficient.
|
float32_t | steeringCoefficient | Steering coefficient for trivial linear mapping between steering wheel and steering angle, i.e. steeringAngle = steeringWheelAngle / steeringCoefficient. |
float32_t | steeringWheelToSteeringMap[DW_VEHICLE_STEER_MAP_POLY_DEGREE_PLUS_ONE] |
polynomial coefficents of steering wheel angle to steering angle as given in c0 + c1*x + c2*x^2 + ... + cn*x^n. If not 0, then these have precedence over steeringCoefficient |
float32_t | throttleActuatorTimeConstant | Time constant for first order lp throttle system. |
dwVehicleTorqueLUT | torqueLUT | Lookup table mapping throttle and brake pedal position to torque. |
float32_t | wheelbase | Distance between the centers of the front and rear wheels. [meters]. |
float32_t | wheelRadius[DW_VEHICLE_NUM_WHEELS] | Radius of each individual wheel [m]. |
float32_t | width | Width of the vehicle, without side mirrors. [meters]. |
float32_t | widthWithMirrors | Width of the vehicle including side mirrors. [meters]. |
struct dwVehicleActuationProperties |
Data Fields | ||
---|---|---|
float32_t | brakeActuatorTimeConstant | Time constant for first order + time delay brake system [s]. |
float32_t | brakeActuatorTimeDelay | Time delay for first order + time delay brake system [s]. |
float32_t | driveByWireDampingRatio | Damping ratio for second order + time delay drive-by-wire / steer-by-wire [unitless]. |
float32_t | driveByWireNaturalFrequency | Natural frequency for second order + time delay drive-by-wire / steer-by-wire [hz]. |
float32_t | driveByWireTimeConstant | Time constant for first order + time delay drive-by-wire / steer-by-wire [s]. |
float32_t | driveByWireTimeDelay | Time delay for first order + time delay drive-by-wire / steer-by-wire [s]. |
float32_t | effectiveMass | Effective mass due to rotational inertia (wheel, engine, and other parts of the CVT drivetrain) [kg]. |
bool | isDriveByWireSecondOrder | Indicates whether the drive-by-wire / steer-by-wire is second-order or not. |
float32_t | maxSteeringWheelAngle | Maximum steering wheel angle [rad]. |
float32_t | steeringWheelToSteeringMap[DW_VEHICLE_STEER_MAP_POLY_DEGREE_PLUS_ONE] |
Polynomial relating steering wheel angle [rad] to steering angle [rad]. Coefficients ordered in array by increasing power, where first element is constant term (steering offset) |
float32_t | throttleActuatorTimeConstant | Time constant for first order + time delay throttle system [s]. |
float32_t | throttleActuatorTimeDelay | Time delay for first order + time delay throttle system [s]. |
dwVehicleTorqueLUT | torqueLUT | Torque lookup tables. |
struct dwVehicleArticulationProperties |
Data Fields | ||
---|---|---|
dwVector3f | leadingVehicleHingePosition | Position of leading vehicle hinge attach point in leading vehicle coordinate system (DW_COORDINATE_SYSTEM_VEHICLE_BASE or, if multiple trailer units DW_COORDINATE_SYSTEM_VEHICLE_TRAILER) [m]. |
dwVector3f | trailingVehicleHingePosition | Position of trailing vehicle hinge attach point in trailer coordinate system (DW_COORDINATE_SYSTEM_VEHICLE_TRAILER) [m]. |
struct dwVehicleAxleProperties |
Data Fields | ||
---|---|---|
float32_t | corneringStiffness | Cornering stiffness for a single tire [N/rad]. |
float32_t | position | Position of axle midpoint along X-axis in corresponding vehicle coordinate system (DW_COORDINATE_SYSTEM_VEHICLE_BASE or DW_COORDINATE_SYSTEM_VEHICLE_TRAILER) [m]. |
float32_t | track | Width of the axle, measured between center line of wheels [m]. |
float32_t | wheelRadiusLeft | Radius of left wheel, when facing towards the forward direction of the vehicle [m]. |
float32_t | wheelRadiusRight | Radius of right wheel, when facing towards the forward direction of the vehicle [m]. |
struct dwVehicleBodyProperties |
Data Fields | ||
---|---|---|
dwVector3f | boundingBoxPosition |
Position of bounding box origin in body coordinate system [m].
|
dwVector3f | centerOfMass |
Position of center of mass in body coordinate system [m].
|
float32_t | height | Height of the bounding box (vertical dimension, along Z) [m]. |
dwVector3f | inertia |
Principal moments of inertia with respect to center of mass [kg m^2].
|
float32_t | length | Length of the bounding box (longitudinal dimension, along X) [m]. |
float32_t | mass |
Mass [kg].
|
float32_t | rearAxleToAPillar |
Distance from rear axle to A pillar [m].
|
float32_t | rearAxleToBPillar |
Distance from rear axle to B pillar [m].
|
float32_t | rearAxleToCPillar |
Distance from rear axle to C pillar [m].
|
float32_t | width | Width of the bounding box (lateral dimension, along Y) [m]. |
float32_t | widthWithoutMirrors | Width of the body without any side-mirrors, if applicable, otherwise same as width. |
struct dwVehicleCabin |
Data Fields | ||
---|---|---|
dwVehicleBodyProperties | body | Properties of the cabin body. |
struct dwVehicleDynamicsProperties |
Data Fields | ||
---|---|---|
float32_t | sideSlipAngleGradient |
Side slip angle gradient relating lateral acceleration to side slip angle. [rad s^2 / m] A positive side slip angle gradient indicates the vehicle slips to the outside of the curve. |
float32_t | understeerAngleGradient |
Understeer angle gradient relating lateral acceleration to steering angle deviation. [rad s^2 / m] The understeer angle is the difference between the the actual on-road wheel angle and the steering angle of the bicycle model that follows the effective vehicle trajectory. A positive value indicates the vehicle steers to the outside of the curve. |
struct dwVehicleSuspensionProperties |
struct dwVehicleTorqueLUT |
Data Fields | ||
---|---|---|
float32_t | brakePedalInput[DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE] | 1-d array of range of brake pedal values (Brake Look-up Table Input) |
float32_t | brakeTorqueOutput[DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE] | 1-d torque Table, mapping a given brake pedal position to a torque value (Brake Look-up Table Output) |
float32_t | throttlePedalInput[DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE] | 1-d array of range of throttle pedal values (Throttle Look-up Table Input) |
float32_t | throttleSpeedInput[DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE] | 1-d array of range of vehicle linear speed values (Throttle Look-up Table Input) [m/s] |
float32_t | throttleTorqueOutput[DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE][DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE] |
2-d torque table, mapping a given throttle pedal position at a given speed to a torque value (Throttle Look-up Table Output) The 2d table is represented in row-major matrix with speed varying over the columns, and pedal input over rows, i.e.
|
struct dwVehicleTrailer |
Data Fields | ||
---|---|---|
dwVehicleArticulationProperties | articulation | Articulation linking trailer to leading vehicle unit. |
dwVehicleAxleProperties | axleFront | Properties of the front (steering) axle [m]. |
dwVehicleAxleProperties | axleRear |
Properties of the rear axle group [m]. Multiple rear axles are lumped together in an equivalent virtual rear axle, in which case its properties shall be consistent with corresponding vehicle data such as wheel speed. |
dwVehicleBodyProperties | body | Properties of the trailer body. |
dwVehicleTrailerType | type | Trailer type, either full or semi, indicates presence of front axle. |
struct dwVehicleWheelEncoderProperties |
Data Fields | ||
---|---|---|
float32_t | speedQuantization |
Wheel speed quantization. Must be provided if wheel speed signal is quantized with rounding-down operation (floor). [rad/s] |
int32_t | ticksCountInvalid |
Invalid tick count, optional value provided by vehicle in case of error, must be outside of [ticksCountMin, ticksCountMax] range. [-] |
int32_t | ticksCountMax | Number above which counter rolls over. [-]. |
int32_t | ticksCountMin | Number below which counter rolls under. [-]. |
int32_t | ticksPerTurn | Ticks per wheel turn. [-]. |
#define DW_VEHICLE_STEER_MAP_POLY_DEGREE_PLUS_ONE (DW_VEHICLE_STEER_MAP_POLY_DEGREE + 1U) |
typedef struct dwRigObject const* dwConstRigHandle_t |
typedef struct dwRigObject* dwRigHandle_t |
enum dwVehicleTrailerType |
enum dwVehicleWheels |
Define index for each of the wheels on a 4 wheeled vehicle.
These indices are to be used to point into dwVehicleIOState or dwVehicle.
Enumerator | |
---|---|
DW_VEHICLE_WHEEL_FRONT_LEFT | |
DW_VEHICLE_WHEEL_FRONT_RIGHT | |
DW_VEHICLE_WHEEL_REAR_LEFT | |
DW_VEHICLE_WHEEL_REAR_RIGHT | |
DW_VEHICLE_NUM_WHEELS | Number of wheels describing the vehicle. |
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.
If property does not exists, it will be added. Properties are stored as name=value pairs.
[in] | propertyValue | Value of the property to be changed to. Maximal length limited to 256 characters. |
[in] | propertyName | Name of the property to change |
[in] | obj | Specifies the rig configuration module handle. |
DW_INVALID_ARGUMENT | when given pointer is null |
DW_BUFFER_FULL | when there are no more space for new properties, max 32 |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
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.
If property does not exists, it will be added. Properties are stored as name=value pairs.
[in] | propertyValue | Value of the property to be changed to. Maximal length limited to 512 characters. |
[in] | propertyName | Name of the property to change |
[in] | sensorId | Specifies the index of the queried sensor. |
[in] | obj | Specifies the rig configuration module handle. |
DW_INVALID_ARGUMENT | when given pointer is null or sensorId doesn't exist |
DW_BUFFER_FULL | when there are no more space for new properties, max 32 |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
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.
[out] | sensorId | The index of the matching sensor (unchanged if the function fails). |
[in] | sensorName | The sensor 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_INVALID_ARGUMENT | when given pointer is null |
DW_NOT_AVAILABLE | when no sensor matches the name |
DW_INVALID_HANDLE | when the rig configuration module handle is invalid, i.e NULL or wrong type |
DW_SUCCESS | when operation succeeded |
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.
[out] | sensorId | The index of the matching sensor (unchanged if the function fails). |
[in] | sensorType | The type of the sensor to search for. |
[in] | sensorTypeIndex | The idx of the sensor within that type. |
[in] | obj | Specifies the rig configuration module handle. |
DW_INVALID_ARGUMENT | when given pointer is null |
DW_NOT_AVAILABLE | when no sensor matches the type |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
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.
[out] | sensorId | The Specifies the index of the matching sensor. Undefined if the function fails. |
[in] | vehicleIOId | The vehicleIO ID to search for. |
[in] | obj | Specifies the rig configuration module handle. |
DW_INVALID_ARGUMENT | when given pointer is null |
DW_NOT_AVAILABLE | when no sensor matches the vehicle IO ID |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
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.
The supported models are OCam, Pinhole, and FTheta.
[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_INVALID_ARGUMENT | when the pointer to the model type is NULL |
DW_INVALID_HANDLE | when the rig configuration handle is invalid, i.e null or wrong type |
DW_OUT_OF_BOUNDS | when the index of the queried sensor is more than MAX_SENSOR_COUNT |
DW_NOT_AVAILABLE | when the sensor has no camera model |
DW_SUCCESS | when operation succeeded |
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.
The call is only relevant for virtual h264/h265 cameras. Otherwise returned value is always nullptr.
[out] | timestampPath | A pointer to the path containing timestamp data. |
[in] | sensorId | Specifies the index of the queried sensor. |
[in] | obj | Specifies the rig configuration module handle. |
DW_INVALID_ARGUMENT | when given pointer is null |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
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.
[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_INVALID_ARGUMENT | when the config pointer is NULL |
DW_INVALID_HANDLE | when the rig configuration handle is invalid, i.e null or wrong type |
DW_OUT_OF_BOUNDS | when the index of the queried sensor is more than MAX_SENSOR_COUNT |
DW_NOT_AVAILABLE | when the sensor has no camera model |
DW_SUCCESS | when operation succeeded |
DW_API_PUBLIC dwStatus dwRig_getFThetaCameraConfigNew | ( | dwFThetaCameraConfig *const | config, |
uint32_t const | sensorId, | ||
dwConstRigHandle_t const | 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_INVALID_ARGUMENT | when the config pointer is NULL |
DW_INVALID_HANDLE | when the rig configuration handle is invalid, i.e null or wrong type |
DW_OUT_OF_BOUNDS | when the index of the queried sensor is more than MAX_SENSOR_COUNT |
DW_NOT_AVAILABLE | when the sensor has no camera model |
DW_SUCCESS | when operation succeeded |
DW_API_PUBLIC dwStatus dwRig_getGenericVehicle | ( | dwGenericVehicle *const | vehicle, |
dwConstRigHandle_t const | obj | ||
) |
Gets the properties of a generic vehicle (car or truck).
[out] | vehicle | A pointer to the struct to be filled with vehicle properties. |
[in] | obj | Specifies the Rig Configuration module handle. |
DW_INVALID_ARGUMENT | when the rig configuration handle is NULL |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_NOT_AVAILABLE | when no generic vehicle in configuration is available |
DW_SUCCESS | when operation succeeded |
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.
This transform differs from transform T provided by getSensorToRigTransformation() in that it represents a static reference transformation from factory calibration and/or mechanical drawings, whereas T can change over time. Also, if the sensor's type doesn't support extrinsics, the identity transformation will be returned.
[out] | transformation | A pointer to the nominal 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_INVALID_ARGUMENT | when the transformation pointer is NULL |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
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.
This transform differs from transform T provided by getSensorToSensorTransformation() in that it represents a static reference transformation from factory calibration and/or mechanical drawings, whereas T can change over time. Identity transformations are used for sensors that don't support a native extrinsic frame.
[out] | transformation | A pointer to the nominal transformation from sensor to sensor coordinate system. |
[in] | sensorIdFrom | Specifies the index of the source sensor. |
[in] | sensorIdTo | Specifies the index of the destination sensor. |
[in] | obj | Specifies the rig configuration module handle. |
DW_INVALID_ARGUMENT | when the transformation pointer is NULL |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
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.
[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_INVALID_ARGUMENT | when the config pointer is NULL |
DW_INVALID_HANDLE | when the rig configuration handle is invalid, i.e null or wrong type |
DW_OUT_OF_BOUNDS | when the index of the queried sensor is more than MAX_SENSOR_COUNT |
DW_NOT_AVAILABLE | when the sensor has no camera model |
DW_SUCCESS | when operation succeeded |
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.
Properties are stored in name=value pairs and implement properties which are specific for the rig in a generic way. For example a particular sensor layout or configuration
[out] | propertyValue | A pointer to return the value of a certain property |
[in] | propertyName | Name of the property to retrieve value from |
[in] | obj | Specifies the rig configuration module handle. |
DW_INVALID_ARGUMENT | when given pointer is null |
DW_NOT_AVAILABLE | when a certain property is not available in the rig configration |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
DW_API_PUBLIC dwStatus dwRig_getSensorCount | ( | uint32_t *const | sensorCount, |
dwConstRigHandle_t const | obj | ||
) |
Gets the number of all available sensors.
[out] | sensorCount | A pointer to the number of sensors in the rig configuration. |
[in] | obj | Specifies the Rig Configuration module handle. |
DW_INVALID_ARGUMENT | when given pointer is null |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
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.
[out] | sensorCount | Return number of sensors available of the given type |
[in] | sensorType | Type of the sensor to query |
[in] | obj | Specifies the rig configuration module handle. |
DW_INVALID_ARGUMENT | `given pointer is null |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
DW_API_PUBLIC dwStatus dwRig_getSensorDataPath | ( | char8_t const **const | dataPath, |
uint32_t const | sensorId, | ||
dwConstRigHandle_t const | obj | ||
) |
Gets path to sensor recording.
The call is only valid for virtual sensors.
[out] | dataPath | A pointer to the path with sensor data. 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_INVALID_ARGUMENT | when given pointer is null |
DW_NOT_AVAILABLE | when data path for the given sensor is not available |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
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.
This transformation relates the sensor FLU 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_INVALID_ARGUMENT | when the transformation pointer is NULL |
DW_INVALID_HANDLE | when the rig configuration handle is invalid, i.e null or wrong type |
DW_OUT_OF_BOUNDS | when the index of the queried sensor is more than MAX_SENSOR_COUNT |
DW_SUCCESS | when operation succeeded |
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.
For example, "Front Camera".
[out] | sensorName | A pointer to the 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_INVALID_ARGUMENT | when the sensor pointer is NULL |
DW_INVALID_HANDLE | when the rig configuration handle is invalid, i.e null or wrong type |
DW_OUT_OF_BOUNDS | when the index of the queried sensor is more than MAX_SENSOR_COUNT |
DW_SUCCESS | when operation succeeded |
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.
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_INVALID_ARGUMENT | when the pointer to the pointer of sensor parameters is NULL |
DW_INVALID_HANDLE | when the rig configuration handle is invalid, i.e null or wrong type |
DW_OUT_OF_BOUNDS | when the index of the queried sensor is more than MAX_SENSOR_COUNT |
DW_SUCCESS | when operation succeeded |
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 modified to be in respect to the current rig file's directory (if initializing a rig from file), or in respect to the relativeBasePath (when initializing a rig from string).
For example, given a rig.json file stored at this/is/rig.json with a virtual sensor pointing to file=video.lraw, the call to this function will return sensor properties modified as file=this/is/video.lraw.
[out] | sensorParameter | Sensor parameters with modified path inside of file=,video=,timestamp= returned here. |
[in] | sensorId | Specifies the index of the queried sensor. |
[in] | obj | Specifies the Rig Configuration module handle. |
DW_INVALID_ARGUMENT | when the pointer to the pointer of sensor parameters is NULL |
DW_INVALID_HANDLE | when the rig configuration handle is invalid, i.e null or wrong type |
DW_OUT_OF_BOUNDS | when the index of the queried sensor is more than MAX_SENSOR_COUNT |
DW_SUCCESS | when operation succeeded |
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.
Properties are stored in name=value pairs and implement properties which are specific for a certain sensor in a generic way. For example a camera might store calibration data there, an IMU might store bias values there, etc.
[out] | propertyValue | A pointer to return the value of a certain property |
[in] | propertyName | Name of the property to retrieve value from |
[in] | sensorId | Specifies the index of the queried sensor. |
[in] | obj | Specifies the rig configuration module handle. |
DW_INVALID_ARGUMENT | when given pointer is null or sensorId doesn't exist |
DW_NOT_AVAILABLE | when a certain property is not available in the rig configuration |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
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.
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_INVALID_ARGUMENT | when the pointer to the pointer of sensor protocol is NULL |
DW_INVALID_HANDLE | when the rig configuration handle is invalid, i.e null or wrong type |
DW_OUT_OF_BOUNDS | when the index of the queried sensor is more than MAX_SENSOR_COUNT |
DW_SUCCESS | when operation succeeded |
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.
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. Also, if the sensor's type doesn't support extrinsics, the identity transformation will be returned.
[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_INVALID_ARGUMENT | when the transformation pointer is NULL |
DW_INVALID_HANDLE | when the rig configuration handle is invalid, i.e null or wrong type |
DW_OUT_OF_BOUNDS | when the index of the queried sensor is more than MAX_SENSOR_COUNT |
DW_SUCCESS | when operation succeeded |
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.
This transformation relates the first and second sensor coordinate systems to each other. Identity transformations are used for sensors that don't support a native extrinsic frame.
[out] | transformation | A pointer to the transformation from sensor to sensor coordinate system. |
[in] | sensorIdFrom | Specifies the index of the source sensor. |
[in] | sensorIdTo | Specifies the index of the destination sensor. |
[in] | obj | Specifies the rig configuration module handle. |
DW_INVALID_ARGUMENT | when the transformation pointer is NULL |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
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.
[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_INVALID_ARGUMENT | when given pointer is null or sensorId doesn't exist |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
DW_API_PUBLIC dwStatus dwRig_getVehicle | ( | dwVehicle const **const | vehicle, |
dwConstRigHandle_t const | obj | ||
) |
DEPRECATED: Gets the properties of a passenger car 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_INVALID_ARGUMENT | when the rig configuration handle is NULL |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_NOT_AVAILABLE | when no vehicle in configuration is available |
DW_SUCCESS | when operation succeeded |
DW_API_PUBLIC dwStatus dwRig_getVehicleIOConfigCount | ( | uint32_t *const | vioConfigCount, |
dwConstRigHandle_t const | obj | ||
) |
Gets the number of vehicle IO sensors.
[out] | vioConfigCount | A pointer to the number of vehicle IO sensors in the Rig Configuration. |
[in] | obj | Specifies the Rig Configuration module handle. |
DW_INVALID_ARGUMENT | when the rig configuration handle is NULL |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
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.
[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 | The path of a rig file that contains the rig configuration. Typically produced by the DriveWorks calibration tool. |
DW_INVALID_ARGUMENT | when the rig configuration handle is NULL or if the json file has no extension |
DW_INVALID_HANDLE | when the context handle is invalid, i.e null or wrong type |
DW_FILE_INVALID | when the json file is invalid |
DW_FILE_NOT_FOUND | when the json file cannot be found |
DW_INTERNAL_ERROR | when internal error happens |
DW_BUFFER_FULL | when too many extrinsic profiles are available (> 3) |
DW_SUCCESS | when operation succeeded |
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.
[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] | configurationString | A pointer to a JSON string that contains the rig configuration. Typically produced by the DriveWorks calibration tool. |
[in] | relativeBasePath | A base path all relative file references in the rig will be resolved with respect to. If NULL, then the current working directory of the process will be used implicitly. |
DW_INVALID_ARGUMENT | when the rig configuration handle is NULL or if the json file has no extension |
DW_INVALID_HANDLE | when the context handle is invalid, i.e null or wrong type |
DW_INTERNAL_ERROR | when internal error happens |
DW_BUFFER_FULL | when too many extrinsic profiles are available (> 3) |
DW_SUCCESS | when operation succeeded |
DW_API_PUBLIC dwStatus dwRig_release | ( | dwRigHandle_t const | obj | ) |
Releases the Rig Configuration module.
[in] | obj | The Rig Configuration module handle. |
DW_INVALID_HANDLE | when the configuration handle is invalid , i.e NULL or wrong type |
DW_SUCCESS | when operation succeeded |
DW_API_PUBLIC dwStatus dwRig_reset | ( | dwRigHandle_t const | obj | ) |
Resets the Rig Configuration module.
[in] | obj | Specifies the Rig Configuration module handle. |
DW_INVALID_HANDLE | when the rig handle is invalid, i.e null or wrong type |
DW_SUCCESS | when operation succeeded |
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.
The output file contains the full state of the rig-configuration and can again be loaded with dwRig_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_INVALID_ARGUMENT | when the configurationFile pointer is invalid, or if the serialization format is not supported |
DW_INVALID_HANDLE | when provided RigConfigurationHandle handle is invalid. |
DW_FILE_INVALID | in case of error during serialization. |
DW_SUCCESS | when operation succeeded |
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.
[in] | 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_INVALID_ARGUMENT | when the config pointer is NULL |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_CANNOT_CREATE_OBJECT | when the sensor has no camera model |
DW_SUCCESS | when operation succeeded |
DW_API_PUBLIC dwStatus dwRig_setGenericVehicle | ( | dwGenericVehicle const *const | vehicle, |
dwRigHandle_t const | obj | ||
) |
Sets the properties of a generic vehicle (car or truck).
[in] | vehicle | A pointer to the struct holding vehicle properties. |
[in] | obj | Specifies the Rig Configuration module handle. |
DW_INVALID_ARGUMENT | when the rig configuration handle is NULL |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_NOT_AVAILABLE | when no generic vehicle in configuration is available |
DW_SUCCESS | when operation succeeded |
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.
[in] | 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_INVALID_ARGUMENT | when the config pointer is NULL |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_NOT_AVAILABLE | when the sensor has no camera model |
DW_SUCCESS | when operation succeeded |
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.
This string can be used in sensor creation.
[in] | sensorParameter | string representing sensor parameters, for example camera driver and csi port. Maximal length is limited to 512. |
[in] | sensorId | Specifies the index of the sensor of which to set sensor parameter. |
[in] | obj | Specifies the Rig Configuration module handle. |
DW_INVALID_ARGUMENT | when the sensor parameter string is NULL |
DW_INVALID_HANDLE | when the rig configuration handle is invalid, i.e null or wrong type |
DW_OUT_OF_BOUNDS | when the index of the sensor to be updated is more than MAX_SENSOR_COUNT |
DW_SUCCESS | when operation succeeded |
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.
[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. |
DW_INVALID_ARGUMENT | when the transformation pointer is NULL |
DW_INVALID_HANDLE | when the transformation pointer is NULL |
DW_CALL_NOT_ALLOWED | when the sensor's type doesn't support extrinsics |
DW_SUCCESS | when operation succeeded |
DW_API_PUBLIC dwStatus dwRig_setVehicle | ( | dwVehicle const *const | vehicle, |
dwRigHandle_t const | obj | ||
) |
DEPRECATED: Sets the properties of a passenger car vehicle.
[in] | vehicle | A pointer to the struct holding vehicle properties. |
[in] | obj | Specifies the Rig Configuration module handle. |
DW_INVALID_ARGUMENT | when the rig configuration handle is NULL |
DW_INVALID_HANDLE | when at least one of the input handles is invalid, i.e null or wrong type |
DW_NOT_AVAILABLE | when no vehicle in configuration is available |
DW_SUCCESS | when operation succeeded |