Skip to content

Commit

Permalink
feat(autoware_map_msgs): add selected map loading (#57)
Browse files Browse the repository at this point in the history
* 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>
  • Loading branch information
Shin-kyoto authored Apr 11, 2023
1 parent 8667820 commit 75e6313
Show file tree
Hide file tree
Showing 7 changed files with 38 additions and 5 deletions.
6 changes: 5 additions & 1 deletion autoware_map_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
8 changes: 8 additions & 0 deletions autoware_map_msgs/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand All @@ -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$ )

<img src="./media/differential_area_loading.gif" alt="drawing" width="400"/>

## 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.
6 changes: 6 additions & 0 deletions autoware_map_msgs/msg/PointCloudMapCellMetaData.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# Metadata of pointcloud map cell

float32 min_x
float32 min_y
float32 max_x
float32 max_y
4 changes: 4 additions & 0 deletions autoware_map_msgs/msg/PointCloudMapCellMetaDataWithID.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Pointcloud metadata with ID

string cell_id
PointCloudMapCellMetaData metadata
6 changes: 2 additions & 4 deletions autoware_map_msgs/msg/PointCloudMapCellWithID.msg
Original file line number Diff line number Diff line change
@@ -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
4 changes: 4 additions & 0 deletions autoware_map_msgs/msg/PointCloudMapMetaData.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Header
std_msgs/Header header

PointCloudMapCellMetaDataWithID[] metadata_list
9 changes: 9 additions & 0 deletions autoware_map_msgs/srv/GetSelectedPointCloudMap.srv
Original file line number Diff line number Diff line change
@@ -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

0 comments on commit 75e6313

Please sign in to comment.