From 75e63132ee1f1f1303ba2abd735f5415f75d1cc5 Mon Sep 17 00:00:00 2001 From: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> Date: Wed, 12 Apr 2023 00:45:33 +0900 Subject: [PATCH] feat(autoware_map_msgs): add selected map loading (#57) * feat(map_loader): add support for sequential_map_loading Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * feat(autoware_map_msgs): add PointCloudMetaData.msg Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * docs(autoware_map_msgs): add description of selected_map_loading Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * docs(autoware_map_msgs): remove gif for selected_map_loading Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * docs(autoware_map_msgs): fix typo Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * feat(autoware_map_msgs): make member of msg plural Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * docs(autoware_map_msgs): clarify the client needs to receive msg beforehand Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * docs(autoware_map_msgs): clarify IDs included in msgs are used as query for service Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> --------- Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> --- autoware_map_msgs/CMakeLists.txt | 6 +++++- autoware_map_msgs/README.md | 8 ++++++++ autoware_map_msgs/msg/PointCloudMapCellMetaData.msg | 6 ++++++ .../msg/PointCloudMapCellMetaDataWithID.msg | 4 ++++ autoware_map_msgs/msg/PointCloudMapCellWithID.msg | 6 ++---- autoware_map_msgs/msg/PointCloudMapMetaData.msg | 4 ++++ autoware_map_msgs/srv/GetSelectedPointCloudMap.srv | 9 +++++++++ 7 files changed, 38 insertions(+), 5 deletions(-) create mode 100644 autoware_map_msgs/msg/PointCloudMapCellMetaData.msg create mode 100644 autoware_map_msgs/msg/PointCloudMapCellMetaDataWithID.msg create mode 100644 autoware_map_msgs/msg/PointCloudMapMetaData.msg create mode 100644 autoware_map_msgs/srv/GetSelectedPointCloudMap.srv diff --git a/autoware_map_msgs/CMakeLists.txt b/autoware_map_msgs/CMakeLists.txt index de62c22..fd6806e 100755 --- a/autoware_map_msgs/CMakeLists.txt +++ b/autoware_map_msgs/CMakeLists.txt @@ -8,8 +8,12 @@ set(msg_files "msg/AreaInfo.msg" "msg/LaneletMapBin.msg" "msg/PointCloudMapCellWithID.msg" + "msg/PointCloudMapCellMetaData.msg" + "msg/PointCloudMapCellMetaDataWithID.msg" + "msg/PointCloudMapMetaData.msg" "srv/GetPartialPointCloudMap.srv" - "srv/GetDifferentialPointCloudMap.srv") + "srv/GetDifferentialPointCloudMap.srv" + "srv/GetSelectedPointCloudMap.srv") set(msg_dependencies std_msgs diff --git a/autoware_map_msgs/README.md b/autoware_map_msgs/README.md index 37aba39..3e5c623 100644 --- a/autoware_map_msgs/README.md +++ b/autoware_map_msgs/README.md @@ -8,6 +8,10 @@ The message represents an area information. This is intended to be used as a que The message contains a pointcloud data attached with an ID. +## PointCloudMapCellMetaDataWithID.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). + ## 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. @@ -29,3 +33,7 @@ Let $X_0$ be a set of PCD map ID that the client node has, $X_1$ be a set of PCD ( $x \in A\backslash B \iff x \in A \wedge x \notin B$ ) drawing + +## 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. diff --git a/autoware_map_msgs/msg/PointCloudMapCellMetaData.msg b/autoware_map_msgs/msg/PointCloudMapCellMetaData.msg new file mode 100644 index 0000000..e3aa55a --- /dev/null +++ b/autoware_map_msgs/msg/PointCloudMapCellMetaData.msg @@ -0,0 +1,6 @@ +# Metadata of pointcloud map cell + +float32 min_x +float32 min_y +float32 max_x +float32 max_y 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/PointCloudMapCellWithID.msg b/autoware_map_msgs/msg/PointCloudMapCellWithID.msg index 3228f86..0ca496a 100755 --- a/autoware_map_msgs/msg/PointCloudMapCellWithID.msg +++ b/autoware_map_msgs/msg/PointCloudMapCellWithID.msg @@ -1,7 +1,5 @@ # Pointcloud data with ID + string cell_id sensor_msgs/PointCloud2 pointcloud -float32 min_x -float32 min_y -float32 max_x -float32 max_y +PointCloudMapCellMetaData metadata diff --git a/autoware_map_msgs/msg/PointCloudMapMetaData.msg b/autoware_map_msgs/msg/PointCloudMapMetaData.msg new file mode 100644 index 0000000..d43e21d --- /dev/null +++ b/autoware_map_msgs/msg/PointCloudMapMetaData.msg @@ -0,0 +1,4 @@ +# Header +std_msgs/Header header + +PointCloudMapCellMetaDataWithID[] metadata_list diff --git a/autoware_map_msgs/srv/GetSelectedPointCloudMap.srv b/autoware_map_msgs/srv/GetSelectedPointCloudMap.srv new file mode 100644 index 0000000..5b366c3 --- /dev/null +++ b/autoware_map_msgs/srv/GetSelectedPointCloudMap.srv @@ -0,0 +1,9 @@ +# ID query for map loading +string[] cell_ids + +--- +# Header +std_msgs/Header header + +# Newly loaded PCD maps with ID +PointCloudMapCellWithID[] new_pointcloud_with_ids