Skip to content

Commit

Permalink
feat(autoware_map_msgs): add MapProjectorInfo message
Browse files Browse the repository at this point in the history
Signed-off-by: mitsudome-r <[email protected]>
  • Loading branch information
mitsudome-r committed Oct 31, 2024
1 parent 4f9f1c0 commit cc5fdd1
Show file tree
Hide file tree
Showing 4 changed files with 28 additions and 0 deletions.
2 changes: 2 additions & 0 deletions autoware_map_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ set(msg_files
"msg/LaneletMapBin.msg"
"msg/LaneletMapMetaData.msg"
"msg/LaneletMapCellMetaData.msg"
"msg/MapProjectorInfo.msg"
"msg/PointCloudMapCellWithID.msg"
"msg/PointCloudMapCellMetaData.msg"
"msg/PointCloudMapCellMetaDataWithID.msg"
Expand All @@ -21,6 +22,7 @@ set(msg_files
set(msg_dependencies
std_msgs
geometry_msgs
geographic_msgs
sensor_msgs)

rosidl_generate_interfaces(${PROJECT_NAME}
Expand Down
7 changes: 7 additions & 0 deletions autoware_map_msgs/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,12 @@ The message contains a pointcloud data attached with an ID.

The message contains a pointcloud meta data attached with an ID. These IDs are intended to be used as a query for selected PCD map loading (see `GetSelectedPointCloudMap.srv` section).

## MapProjectorInfo.msg

The message contains the information required to project global coordinates to local coodraintes used by Autoware, which includes the name of the projection method and the parameters for the projection.
For further information, please refer to the readme of [map_projection_loader](https://github.com/autowarefoundation/autoware.universe/blob/main/map/autoware_map_projection_loader/README.md) in Autoware Universe.


## GetPartialPointCloudMap.srv

Given an area query (`AreaInfo`), the response is expected to contain the PCD maps (each of which attached with unique ID) whose area overlaps with the query.
Expand All @@ -37,3 +43,4 @@ Let $X_0$ be a set of PCD map ID that the client node has, $X_1$ be a set of PCD
## GetSelectedPointCloudMap.srv

Given IDs query, the response is expected to contain the PCD maps (each of which attached with unique ID) specified by query. Before using this interface, the client is expected to receive the `PointCloudMapCellMetaDataWithID.msg` metadata to retrieve information about IDs.

18 changes: 18 additions & 0 deletions autoware_map_msgs/msg/MapProjectorInfo.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
# Projector type
string LOCAL = "local"
string LOCAL_CARTESIAN_UTM = "LocalCartesianUTM"
string MGRS = "MGRS"
string TRANSVERSE_MERCATOR = "TransverseMercator"
string projector_type

# Vertical datum
string WGS84 = "WGS84"
string EGM2008 = "EGM2008"
string vertical_datum

# Used for MGRS map
string mgrs_grid

# Used for some map projection types
# altitude may not be in ellipsoid height
geographic_msgs/GeoPoint map_origin
1 change: 1 addition & 0 deletions autoware_map_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<buildtool_depend>rosidl_default_generators</buildtool_depend>

<depend>geometry_msgs</depend>
<depend>geographic_msgs</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>

Expand Down

0 comments on commit cc5fdd1

Please sign in to comment.