DriveWorks SDK Reference
3.5.78 Release
For Test and Development only

SensorManager.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) 2017-2020 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 
48 #ifndef DW_SENSORS_SENSORMANAGER_H_
49 #define DW_SENSORS_SENSORMANAGER_H_
50 
51 #include <dw/rig/Rig.h>
52 #include <dw/sensors/Sensors.h>
54 #include <dw/sensors/imu/IMU.h>
55 #include <dw/sensors/lidar/Lidar.h>
56 #include <dw/sensors/gps/GPS.h>
57 #include <dw/sensors/canbus/CAN.h>
58 #include <dw/sensors/radar/Radar.h>
59 #include <dw/sensors/lidar/Lidar.h>
60 #include <dw/sensors/data/Data.h>
61 
62 #ifdef __cplusplus
63 extern "C" {
64 #endif
65 
66 #define DW_SENSORMANGER_MAX_CAMERAS 16U
67 #define DW_SENSORMANGER_MAX_NUM_SENSORS 64U
68 
69 typedef struct dwSensorManagerObject* dwSensorManagerHandle_t;
70 
72 typedef struct
73 {
76 
80  uint32_t sensorTypeIndex;
81 
84 
88  uint32_t sensorIndex;
89 
91  uint32_t sensorIndices[DW_SENSORMANGER_MAX_CAMERAS];
92 
94  uint32_t numCamFrames;
96 
104  const uint8_t* rawData;
105  size_t rawDataSize;
106 } dwSensorEvent;
107 
109 {
112 };
113 
114 typedef struct
115 {
123 
124 typedef struct
125 {
128 
130  uint32_t enableSensors[DW_SENSORMANGER_MAX_NUM_SENSORS];
131 
136 
137 typedef void (*dwSensorManagerDispatcher_t)(const dwSensorEvent*, void*, dwStatus);
138 
151 dwStatus dwSensorManager_initialize(dwSensorManagerHandle_t* sm,
152  size_t poolSize, dwSALHandle_t sal);
153 
174 dwStatus dwSensorManager_initializeFromRig(dwSensorManagerHandle_t* sm,
175  dwRigHandle_t rc,
176  size_t poolSize, dwSALHandle_t sal);
177 
200 dwStatus dwSensorManager_initializeFromRigWithParams(dwSensorManagerHandle_t* sm,
201  dwRigHandle_t rc,
202  const dwSensorManagerParams* params,
203  size_t poolSize, dwSALHandle_t sal);
204 
214 dwStatus dwSensorManager_release(dwSensorManagerHandle_t sm);
215 
234 dwStatus dwSensorManager_addSensor(dwSensorParams params, uint64_t clientData,
235  dwSensorManagerHandle_t sm);
236 
259 dwStatus dwSensorManager_addCameraSensor(const char8_t* groupName, uint32_t siblingIndex,
260  dwSensorParams params, uint64_t clientData,
261  dwSensorManagerHandle_t sm);
262 
273 dwStatus dwSensorManager_start(dwSensorManagerHandle_t sm);
274 
285 dwStatus dwSensorManager_stop(dwSensorManagerHandle_t sm);
286 
297 dwStatus dwSensorManager_reset(dwSensorManagerHandle_t sm);
298 
316 dwStatus dwSensorManager_acquireNextEvent(const dwSensorEvent** ev, dwTime_t timeoutMicroSeconds,
317  dwSensorManagerHandle_t sm);
318 
332 dwStatus dwSensorManager_releaseAcquiredEvent(const dwSensorEvent* ev,
333  dwSensorManagerHandle_t sm);
334 
347 dwStatus dwSensorManager_getNumSensors(uint32_t* count, dwSensorType type, dwSensorManagerHandle_t sm);
348 
361 dwStatus dwSensorManager_getSensorHandle(dwSensorHandle_t* handle, uint32_t sensorIndex, dwSensorManagerHandle_t sm);
362 
375 dwStatus dwSensorManager_getSensorClientData(uint64_t* cd, uint32_t sensorIndex, dwSensorManagerHandle_t sm);
376 
390 dwStatus dwSensorManager_getSensorIndex(uint32_t* sensorIndex, dwSensorType type,
391  uint32_t sensorTypeIndex, dwSensorManagerHandle_t sm);
392 
407 dwStatus dwSensorManager_getSensorTypeIndex(uint32_t* sensorTypeIndex, dwSensorType* type,
408  uint32_t sensorIndex, dwSensorManagerHandle_t sm);
409 
422 dwStatus dwSensorManager_setDispatcher(dwSensorManagerDispatcher_t dispatchPtr, void* cookie, dwSensorManagerHandle_t sm);
423 
424 #ifdef __cplusplus
425 }
426 #endif
427 
429 
430 #endif // DW_SENSORS_SENSORMANAGER_H_
dwDispatcherParams dispatcherParams
Parameters to configure dispatcher mode.
Holds sets of parameters for sensor creation.
Definition: Sensors.h:96
Defines the structure for a complete radar scan.
Definition: Radar.h:231
NVIDIA DriveWorks API: Rig Configuration
NVIDIA DriveWorks API: Radar
DW_API_PUBLIC dwStatus dwSensorManager_reset(dwSensorManagerHandle_t sm)
Resets all sensors.
uint32_t sensorIndex
The index of the sensor as defined by the order in which it was created.
Definition: SensorManager.h:88
NVIDIA DriveWorks API: Lidar
const dwRadarScan * radFrame
NVIDIA DriveWorks API: Cameras
dwSensorType
Defines the type of sensors that are available in DriveWorks.
Definition: Sensors.h:152
#define DW_SENSORMANGER_MAX_NUM_SENSORS
Definition: SensorManager.h:67
DW_API_PUBLIC dwStatus dwSensorManager_acquireNextEvent(const dwSensorEvent **ev, dwTime_t timeoutMicroSeconds, dwSensorManagerHandle_t sm)
Called by the application to consume the next available sensor event ready for consumption.
DW_API_PUBLIC dwStatus dwSensorManager_start(dwSensorManagerHandle_t sm)
Starts all sensors.
DW_API_PUBLIC dwStatus dwSensorManager_getSensorHandle(dwSensorHandle_t *handle, uint32_t sensorIndex, dwSensorManagerHandle_t sm)
Gets the sensor handle to the specified sensor.
void(* dwSensorManagerDispatcher_t)(const dwSensorEvent *, void *, dwStatus)
uint32_t numEnableSensors
Number of entries in the &#39;enableSensors&#39; list.
Structure for returning data upon any sensor event.
Definition: SensorManager.h:72
DW_API_PUBLIC dwStatus dwSensorManager_addSensor(dwSensorParams params, uint64_t clientData, dwSensorManagerHandle_t sm)
Adds a sensor to the SAL instance.
uint32_t numCamFrames
Data accessor for camera.
Definition: SensorManager.h:94
DW_API_PUBLIC dwStatus dwSensorManager_setDispatcher(dwSensorManagerDispatcher_t dispatchPtr, void *cookie, dwSensorManagerHandle_t sm)
Sets sensor&#39;s dispatcher function when the feature is turned on.
struct dwSensorManagerObject * dwSensorManagerHandle_t
Definition: SensorManager.h:69
NVIDIA DriveWorks API: Data
DW_API_PUBLIC dwStatus dwSensorManager_getNumSensors(uint32_t *count, dwSensorType type, dwSensorManagerHandle_t sm)
Gets the number of sensors instantiated for a given sensor type.
DW_API_PUBLIC dwStatus dwSensorManager_getSensorClientData(uint64_t *cd, uint32_t sensorIndex, dwSensorManagerHandle_t sm)
Gets sensor&#39;s clientData.
dwTime_t timestamp_us
Timestamp (us)
Definition: SensorManager.h:83
dwTime_t camFramesTimeDiffLimit
Up to how much can timstamps of camera frames accumulated in a single event differ.
DW_API_PUBLIC dwStatus dwSensorManager_stop(dwSensorManagerHandle_t sm)
Stops all sensors.
size_t rawDataSize
struct dwSensorObject * dwSensorHandle_t
Handle representing a sensor.
Definition: Sensors.h:88
dwStatus
Status definition.
Definition: Status.h:178
NVIDIA DriveWorks API: Sensors
const dwLidarDecodedPacket * lidFrame
const dwDataPacket * dataFrame
uint32_t sensorTypeIndex
Index of the given sensor as defined by the order in which it was created and the type of sensor it i...
Definition: SensorManager.h:80
DW_API_PUBLIC dwStatus dwSensorManager_releaseAcquiredEvent(const dwSensorEvent *ev, dwSensorManagerHandle_t sm)
Releases a previously acquired event back to the pool.
int64_t dwTime_t
Specifies a timestamp unit, in microseconds.
Definition: Types.h:82
DW_API_PUBLIC dwStatus dwSensorManager_initializeFromRigWithParams(dwSensorManagerHandle_t *sm, dwRigHandle_t rc, const dwSensorManagerParams *params, size_t poolSize, dwSALHandle_t sal)
Creates and initializes a SensorManager module, adding enabled sensors in the provided Rig Configurat...
Holds a data packet.
Definition: Data.h:60
An IMU frame containing sensor readings from the IMU sensor.
Definition: IMU.h:104
dwSensorManagerDataMode
bool accumCamFrames
Whether Dispatcher shall accumulated frames from all cameras into a single event. ...
struct dwSALObject * dwSALHandle_t
Handle representing the Sensor Abstraction Layer interface.
Definition: Sensors.h:85
DW_API_PUBLIC dwStatus dwSensorManager_getSensorTypeIndex(uint32_t *sensorTypeIndex, dwSensorType *type, uint32_t sensorIndex, dwSensorManagerHandle_t sm)
Gets sensor&#39;s relative index and type based upon its sensor index.
const uint8_t * rawData
DW_API_PUBLIC dwStatus dwSensorManager_initializeFromRig(dwSensorManagerHandle_t *sm, dwRigHandle_t rc, size_t poolSize, dwSALHandle_t sal)
Creates and initializes a SensorManager module, adding all sensors in the provided Rig Configuration...
NVIDIA DriveWorks API: GPS
NVIDIA DriveWorks API: CAN
DW_API_PUBLIC dwStatus dwSensorManager_getSensorIndex(uint32_t *sensorIndex, dwSensorType type, uint32_t sensorTypeIndex, dwSensorManagerHandle_t sm)
Gets sensor&#39;s index.
dwIMUFrame imuFrame
Definition: SensorManager.h:99
#define DW_SENSORMANGER_MAX_CAMERAS
Definition: SensorManager.h:66
dwGPSFrame gpsFrame
Data accessor for all other sensors.
Definition: SensorManager.h:98
DW_API_PUBLIC dwStatus dwSensorManager_addCameraSensor(const char8_t *groupName, uint32_t siblingIndex, dwSensorParams params, uint64_t clientData, dwSensorManagerHandle_t sm)
Adds a camera sensor to the SAL instance.
struct dwCameraFrame * dwCameraFrameHandle_t
Handle to captured frame.
Definition: Camera.h:75
char char8_t
Definition: Types.h:72
dwTime_t timeout
Timeout value to be used in dispatcher mode for virtual files.
DW_API_PUBLIC dwStatus dwSensorManager_initialize(dwSensorManagerHandle_t *sm, size_t poolSize, dwSALHandle_t sal)
Creates and initializes a SensorManager module.
DW_API_PUBLIC dwStatus dwSensorManager_release(dwSensorManagerHandle_t sm)
Releases the SensorManager module.
dwCANMessage canFrame
#define DW_API_PUBLIC
Definition: Exports.h:56
NVIDIA DriveWorks API: IMU
dwSensorType type
Type of sensor providing data for this event.
Definition: SensorManager.h:75
Holds a CAN package.
Definition: CAN.h:114
A GPS packet containing localization information.
Definition: GPS.h:80
struct dwRigObject * dwRigHandle_t
Handle representing the Sensor Abstraction Layer interface.
Definition: Rig.h:72