DriveWorks SDK Reference
3.0.4260 Release
For Test and Development only

Maps
Note
SW Release Applicability: This module is available in NVIDIA DRIVE Software releases.

About This Module

The maps module provides an API to access NVIDIA® DriveWorks HD maps data.

DriveWorks currently provides a conversion tool of HERE HD maps format into a DriveWorks map cache file (XML). For more details about the tool, please refer to HERE Maps to DriveWorks Maps Converter Tool.

Map Content Scope

In DriveWorks the Map represents both geometric landmarks and semantic "payload" information that is used to enable safe operation and planning for an autonomous vehicle (AV).

In-memory representation of a "complete map" of drivable roads is a non-goal of DriveWorks Maps. It is assumed that the Map contains a relevant local scope for the vehicle, representing a fraction of the full world data available from a regional, continental or global scale backend database.

In general, multiple Map requests may be required over the duration of a long-distance drive.

Core Layer Data

The Core Layer of the Map contains the basic data required for camera-only localization and short to medium-range planning. This data is fully loaded in RAM as an object graph covering the full extent of the requested Map.

The basic elements are the Road Segments, all data can be accessed through them. A Road Segment represents a piece of road containing several Lanes, Lane Groups, Lane Dividers, and Features. Every Road Segment has an associated local ENU coordinate system defined by its WGS84 Origin. Element geometries for the Road Segment are polylines of 3D points in local ENU coordinates.

Each Lane Group represents a "bundle" of adjacent Lanes with associated Lane Group Traversability. This bitmask is used by the Lane Planner module to determine connectivity between adjacent lanes. Lane Group Traversability may be determined automatically by Lane Divider Type or directly modified by a server-side manual annotation or editing process.

For Lanes, a local polyline represents the centerline geometry of the Lane. Each Lane has pointers to adjacent Lane Divider Groups, representing physical boundaries both left and right of the Lane. Lane Divider Groups are contained by a parent Road Segment along with all referencing Lanes making the ownership model for a Road Segment fully "self-contained".

Lane Dividers belonging to a Lane Divider Group are modeled by local polylines with an associated Lane Divider Type. Although usually there is often a single Lane Divider at a lane boundary, there are cases where Lanes are separated with multiple Lane Dividers, for example a painted solid line and a physical Jersey barrier.

Features are a generic representation of objects encountered along the road, e.g. traffic signs, traffic lights, etc. Each Feature is described by its type field and local geometry, expressed like other elements in local ENU coordinates of its parent Road Segment.

Connections

Road Segments and Lanes have connections to predecessors and successors along the road, represented by dwMapsRoadSegmentConnection and dwMapsLaneConnection structs. Lane Connections for a Lane may be next or previous. This is a reflection not of driving direction, but geometry ordering.

A connection is represented by the ID of the connected element, and if available, a pointer to it. If the connected element is currently not in memory, the pointer is a NULL. It is possible that connected elements have opposite geometry directions, meaning for a next connection, the end of a polyline connects to the end of the connected polyline (and similarly on the start side for previous connections). The sameDirection boolean flag in the Lane Connection struct indicates the geometry directions of connected Lanes are either matching or opposing each other.

Lane Groups, Lanes, Lane Dividers, Lane Divider Groups, and Features each have pointers to parents:

Intersections

As of this release there is no publicly available encoding for data specific to road junctions in DriveWorks Maps. That is a feature that we are currently developing and plan to expose publicly in a future DriveWorks release.

Attributes

Road Segments, Lanes, Lane Dividers and Features have attributes specifying type and properties.

Main Data Structure Type and Properties
Road Segment Type (bridge, tunnel, etc.)
Lane Type (shoulder, car pool, etc.)
Driving direction, relative to the geometry polyline
Lane Divider Type (dashed, solid, etc.)
Material
Color
Feature Type (traffic sign, traffic light, etc.)

Lane Groups are defined such that Lane attributes are constant over the full length of all Lanes. Wherever Lane or Lane Divider attributes change, that may affect the Lane Group Traversability therefore a new Lane Group is required.

Map Provider

The Map Provider interface defines methods for requesting a Map according to application needs. Map requests are the way clients communicate their needs for Map content to the Map Provider.

Each implementation of Map Provider is specialized to a particular backend Map data source. Initially we provide only a basic implementation of Map Provider assuming content exists in the local filesystem as a cache file (XML) or "map directory" also containing Core and Content Layers.

General Usage

Here is an example of using the Map Provider to request a Map and query the Core Layer content:

// init map provider with XML cache file
// select bounds of interest
dwMapsBounds mapBounds{...};
// request a map with core layer only (no content layers)
// request processing occurs asynchronously on a worker thread
dwMapProvider_requestMapForBounds(&requestToken, &mapBounds, NULL, providerHandle);
// handle to the requested map
dwConstMapHandle mapHandle = DW_NULL_HANDLE;
// poll for request completion
dwStatus requestStatus = DW_NOT_READY;
while (requestStatus != DW_SUCCESS)
{
// application code needs to handle error cases
requestStatus = dwMapProvider_tryGetRequestedMap(&mapHandle, requestToken, providerHandle);
}
// memory for road segment query result
dwMapsRoadSegmentBuffer roadSegments{...};
while (...)
{
// select bounds of interest
dwMapsBounds queryBounds{...};
// query data
roadSegments.size = 0;
dwMaps_getRoadSegments(&roadSegments, &queryBounds, ...);
// access data
for (uint32_t i = 0; i < roadSegments.size; ++i)
{
const dwMapsRoadSegment& roadSegment = roadSegments.buffer[i];
...
}
}
// release map back to map provider
dwMapProvider_releaseMap(mapHandle, providerHandle);
// release map provider

Relevant Tutorials

APIs