From 61fc0c0040b8e3787b4e8e1ab90cd3a0478ea5eb Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Wed, 24 Jul 2024 18:03:22 +0900 Subject: [PATCH] refactor(autoware_map_msgs): modify pcd metadata msg Signed-off-by: Ryohsuke Mitsudome --- autoware_map_msgs/CMakeLists.txt | 3 +-- autoware_map_msgs/README.md | 10 +++++----- autoware_map_msgs/msg/PointCloudMapCellMetaData.msg | 1 + .../msg/PointCloudMapCellMetaDataWithID.msg | 4 ---- ...ellWithID.msg => PointCloudMapCellWithMetaData.msg} | 3 +-- autoware_map_msgs/msg/PointCloudMapMetaData.msg | 2 +- autoware_map_msgs/srv/GetDifferentialPointCloudMap.srv | 2 +- autoware_map_msgs/srv/GetPartialPointCloudMap.srv | 2 +- autoware_map_msgs/srv/GetSelectedPointCloudMap.srv | 2 +- 9 files changed, 12 insertions(+), 17 deletions(-) delete mode 100644 autoware_map_msgs/msg/PointCloudMapCellMetaDataWithID.msg rename autoware_map_msgs/msg/{PointCloudMapCellWithID.msg => PointCloudMapCellWithMetaData.msg} (63%) diff --git a/autoware_map_msgs/CMakeLists.txt b/autoware_map_msgs/CMakeLists.txt index fd6806e..8000c3e 100755 --- a/autoware_map_msgs/CMakeLists.txt +++ b/autoware_map_msgs/CMakeLists.txt @@ -7,9 +7,8 @@ ament_auto_find_build_dependencies() set(msg_files "msg/AreaInfo.msg" "msg/LaneletMapBin.msg" - "msg/PointCloudMapCellWithID.msg" "msg/PointCloudMapCellMetaData.msg" - "msg/PointCloudMapCellMetaDataWithID.msg" + "msg/PointCloudMapCellWithMetaData.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 3e5c623..6aa60ef 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). -## PointCloudMapCellWithID.msg +## PointCloudMapCellMetaData.msg -The message contains a pointcloud data attached with an ID. +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). -## PointCloudMapCellMetaDataWithID.msg +## PointCloudMapCellWithMetaData.msg -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). +The message contains a pointcloud data attached with a metadata. ## 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 `PointCloudMapCellMetaDataWithID.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 `PointCloudMapCellMetaData.msg` metadata to retrieve information about IDs. diff --git a/autoware_map_msgs/msg/PointCloudMapCellMetaData.msg b/autoware_map_msgs/msg/PointCloudMapCellMetaData.msg index e3aa55a..51abf61 100644 --- a/autoware_map_msgs/msg/PointCloudMapCellMetaData.msg +++ b/autoware_map_msgs/msg/PointCloudMapCellMetaData.msg @@ -1,5 +1,6 @@ # 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 deleted file mode 100644 index 7a6c0b3..0000000 --- a/autoware_map_msgs/msg/PointCloudMapCellMetaDataWithID.msg +++ /dev/null @@ -1,4 +0,0 @@ -# Pointcloud metadata with ID - -string cell_id -PointCloudMapCellMetaData metadata diff --git a/autoware_map_msgs/msg/PointCloudMapCellWithID.msg b/autoware_map_msgs/msg/PointCloudMapCellWithMetaData.msg similarity index 63% rename from autoware_map_msgs/msg/PointCloudMapCellWithID.msg rename to autoware_map_msgs/msg/PointCloudMapCellWithMetaData.msg index 0ca496a..d0bb424 100755 --- a/autoware_map_msgs/msg/PointCloudMapCellWithID.msg +++ b/autoware_map_msgs/msg/PointCloudMapCellWithMetaData.msg @@ -1,5 +1,4 @@ -# Pointcloud data with ID +# Pointcloud with metadata -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 d43e21d..f10bbb9 100644 --- a/autoware_map_msgs/msg/PointCloudMapMetaData.msg +++ b/autoware_map_msgs/msg/PointCloudMapMetaData.msg @@ -1,4 +1,4 @@ # Header std_msgs/Header header -PointCloudMapCellMetaDataWithID[] metadata_list +PointCloudMapCellMetaData[] metadata_list diff --git a/autoware_map_msgs/srv/GetDifferentialPointCloudMap.srv b/autoware_map_msgs/srv/GetDifferentialPointCloudMap.srv index b2197a3..e3269a1 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 -PointCloudMapCellWithID[] new_pointcloud_with_ids +PointCloudMapCellWithMetaData[] new_pointcloud_cells # 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 96b76a0..f66b823 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 -PointCloudMapCellWithID[] new_pointcloud_with_ids +PointCloudMapCellWithMetaData[] new_pointcloud_cells diff --git a/autoware_map_msgs/srv/GetSelectedPointCloudMap.srv b/autoware_map_msgs/srv/GetSelectedPointCloudMap.srv index 5b366c3..39d14ba 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 -PointCloudMapCellWithID[] new_pointcloud_with_ids +PointCloudMapCellWithMetaData[] new_pointcloud_cells