diff --git a/autoware_map_msgs/CMakeLists.txt b/autoware_map_msgs/CMakeLists.txt index 8000c3e..fd6806e 100755 --- a/autoware_map_msgs/CMakeLists.txt +++ b/autoware_map_msgs/CMakeLists.txt @@ -7,8 +7,9 @@ ament_auto_find_build_dependencies() set(msg_files "msg/AreaInfo.msg" "msg/LaneletMapBin.msg" + "msg/PointCloudMapCellWithID.msg" "msg/PointCloudMapCellMetaData.msg" - "msg/PointCloudMapCellWithMetaData.msg" + "msg/PointCloudMapCellMetaDataWithID.msg" "msg/PointCloudMapMetaData.msg" "srv/GetPartialPointCloudMap.srv" "srv/GetDifferentialPointCloudMap.srv" diff --git a/autoware_map_msgs/README.md b/autoware_map_msgs/README.md index 6aa60ef..3e5c623 100644 --- a/autoware_map_msgs/README.md +++ b/autoware_map_msgs/README.md @@ -4,13 +4,13 @@ The message represents an area information. This is intended to be used as a query for partial / differential map loading (see `GetPartialPointCloudMap.srv` and `GetDifferentialPointCloudMap.srv` section). -## PointCloudMapCellMetaData.msg +## PointCloudMapCellWithID.msg -The message contains a pointcloud meta data. These IDs are intended to be used as a query for selected PCD map loading (see `GetSelectedPointCloudMap.srv` section). +The message contains a pointcloud data attached with an ID. -## PointCloudMapCellWithMetaData.msg +## PointCloudMapCellMetaDataWithID.msg -The message contains a pointcloud data attached with a metadata. +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). ## GetPartialPointCloudMap.srv @@ -36,4 +36,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 `PointCloudMapCellMetaData.msg` metadata to retrieve information about IDs. +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. diff --git a/autoware_map_msgs/msg/PointCloudMapCellMetaData.msg b/autoware_map_msgs/msg/PointCloudMapCellMetaData.msg index 51abf61..e3aa55a 100644 --- a/autoware_map_msgs/msg/PointCloudMapCellMetaData.msg +++ b/autoware_map_msgs/msg/PointCloudMapCellMetaData.msg @@ -1,6 +1,5 @@ # Metadata of pointcloud map cell -string cell_id float32 min_x float32 min_y float32 max_x diff --git a/autoware_map_msgs/msg/PointCloudMapCellMetaDataWithID.msg b/autoware_map_msgs/msg/PointCloudMapCellMetaDataWithID.msg new file mode 100644 index 0000000..7a6c0b3 --- /dev/null +++ b/autoware_map_msgs/msg/PointCloudMapCellMetaDataWithID.msg @@ -0,0 +1,4 @@ +# Pointcloud metadata with ID + +string cell_id +PointCloudMapCellMetaData metadata diff --git a/autoware_map_msgs/msg/PointCloudMapCellWithMetaData.msg b/autoware_map_msgs/msg/PointCloudMapCellWithID.msg similarity index 63% rename from autoware_map_msgs/msg/PointCloudMapCellWithMetaData.msg rename to autoware_map_msgs/msg/PointCloudMapCellWithID.msg index d0bb424..0ca496a 100755 --- a/autoware_map_msgs/msg/PointCloudMapCellWithMetaData.msg +++ b/autoware_map_msgs/msg/PointCloudMapCellWithID.msg @@ -1,4 +1,5 @@ -# Pointcloud with metadata +# Pointcloud data with ID +string cell_id sensor_msgs/PointCloud2 pointcloud PointCloudMapCellMetaData metadata diff --git a/autoware_map_msgs/msg/PointCloudMapMetaData.msg b/autoware_map_msgs/msg/PointCloudMapMetaData.msg index f10bbb9..d43e21d 100644 --- a/autoware_map_msgs/msg/PointCloudMapMetaData.msg +++ b/autoware_map_msgs/msg/PointCloudMapMetaData.msg @@ -1,4 +1,4 @@ # Header std_msgs/Header header -PointCloudMapCellMetaData[] metadata_list +PointCloudMapCellMetaDataWithID[] metadata_list diff --git a/autoware_map_msgs/srv/GetDifferentialPointCloudMap.srv b/autoware_map_msgs/srv/GetDifferentialPointCloudMap.srv index e3269a1..b2197a3 100755 --- a/autoware_map_msgs/srv/GetDifferentialPointCloudMap.srv +++ b/autoware_map_msgs/srv/GetDifferentialPointCloudMap.srv @@ -10,7 +10,7 @@ string[] cached_ids std_msgs/Header header # Newly loaded PCD maps with ID -PointCloudMapCellWithMetaData[] new_pointcloud_cells +PointCloudMapCellWithID[] new_pointcloud_with_ids # Map IDs that the client side should remove string[] ids_to_remove diff --git a/autoware_map_msgs/srv/GetPartialPointCloudMap.srv b/autoware_map_msgs/srv/GetPartialPointCloudMap.srv index f66b823..96b76a0 100755 --- a/autoware_map_msgs/srv/GetPartialPointCloudMap.srv +++ b/autoware_map_msgs/srv/GetPartialPointCloudMap.srv @@ -7,4 +7,4 @@ AreaInfo area std_msgs/Header header # Newly loaded PCD maps with ID -PointCloudMapCellWithMetaData[] new_pointcloud_cells +PointCloudMapCellWithID[] new_pointcloud_with_ids diff --git a/autoware_map_msgs/srv/GetSelectedPointCloudMap.srv b/autoware_map_msgs/srv/GetSelectedPointCloudMap.srv index 39d14ba..5b366c3 100644 --- a/autoware_map_msgs/srv/GetSelectedPointCloudMap.srv +++ b/autoware_map_msgs/srv/GetSelectedPointCloudMap.srv @@ -6,4 +6,4 @@ string[] cell_ids std_msgs/Header header # Newly loaded PCD maps with ID -PointCloudMapCellWithMetaData[] new_pointcloud_cells +PointCloudMapCellWithID[] new_pointcloud_with_ids