Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(autoware_map_msgs): add MapProjectorInfo message #102

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
5 changes: 5 additions & 0 deletions autoware_map_msgs/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,11 @@ 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 coordinates 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 Down
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 @@ -14,6 +14,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>rosidl_default_generators</buildtool_depend>

<depend>geographic_msgs</depend>
<depend>geometry_msgs</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
Expand Down
Loading