From 6c5d6d6ba8d9672354f6d2bda4250ed1744c290e Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Thu, 9 Nov 2023 15:20:55 +0900 Subject: [PATCH 1/2] docs(sensing): update lidar data field requirement (#478) * modify point field description Signed-off-by: Kento Yabuuchi * default T's name is `time_stamp` but not `time` Signed-off-by: Kento Yabuuchi --------- Signed-off-by: Kento Yabuuchi --- .../sensing/data-types/point-cloud.md | 35 ++++++++----------- 1 file changed, 15 insertions(+), 20 deletions(-) diff --git a/docs/design/autoware-architecture/sensing/data-types/point-cloud.md b/docs/design/autoware-architecture/sensing/data-types/point-cloud.md index 7c44603b7de..2a5ff323f05 100644 --- a/docs/design/autoware-architecture/sensing/data-types/point-cloud.md +++ b/docs/design/autoware-architecture/sensing/data-types/point-cloud.md @@ -37,17 +37,17 @@ It is recommended that these modules are used in a single container as component In the ideal case, the driver is expected to output a point cloud with the `PointXYZIRCADT` point type. -| name | datatype | derived | description | -| ----------------- | --------- | ------- | ---------------------------------------------------------------------------- | -| `X` | `FLOAT32` | `false` | X position | -| `Y` | `FLOAT32` | `false` | Y position | -| `Z` | `FLOAT32` | `false` | Z position | -| `I` (intensity) | `UINT8` | `false` | Measured reflectivity, intensity of the point | -| `R` (return type) | `UINT8` | `false` | Laser return type for dual return lidars | -| `C` (channel) | `UINT16` | `false` | Vertical channel id of the laser that measured the point | -| `A` (azimuth) | `FLOAT32` | `true` | `atan2(Y, X)`, Horizontal angle from the front of the lidar to the point | -| `D` (distance) | `FLOAT32` | `true` | `hypot(X, Y, Z)`, Euclidean distance of the point to lidar | -| `T` (time) | `UINT32` | `false` | Nanoseconds passed since the time of the header when this point was measured | +| name | datatype | derived | description | +| ----------------- | --------- | ------- | ------------------------------------------------------------------------ | +| `X` | `FLOAT32` | `false` | X position | +| `Y` | `FLOAT32` | `false` | Y position | +| `Z` | `FLOAT32` | `false` | Z position | +| `I` (intensity) | `FLOAT32` | `false` | Measured reflectivity, intensity of the point | +| `R` (return type) | `UINT8` | `false` | Laser return type for dual return lidars | +| `C` (channel) | `UINT16` | `false` | Vertical channel id of the laser that measured the point | +| `A` (azimuth) | `FLOAT32` | `true` | `atan2(Y, X)`, Horizontal angle from the front of the lidar to the point | +| `D` (distance) | `FLOAT32` | `true` | `hypot(X, Y, Z)`, Euclidean distance of the point to lidar | +| `T` (time stamp) | `FLOAT64` | `false` | Seconds passed since the time of the header when this point was measured | !!! note @@ -180,7 +180,7 @@ For solid state lidars that have lines, assign row number as the channel id. For petal pattern lidars, you can keep channel 0. -### Time +### Time stamp In lidar point clouds, each point measurement can have its individual time stamp. This information can be used to eliminate the motion blur that is caused by the movement of the lidar during the scan. @@ -204,13 +204,8 @@ The header of the point cloud message is expected to have the time of the earlie **More info at:** https://github.com/ros2/rcl_interfaces/issues/85 -#### Individual point time +#### Individual point time stamp -Each `PointXYZIRCT` point type has the `T` field for representing the nanoseconds passed since the first-shot point of the point cloud. +Each `PointXYZIRCT` point type has the `T` field for representing the seconds passed since the first-shot point of the point cloud. -To calculate exact time each point was shot, the `T` nanoseconds are added to the header time. - -!!! note - - The `T` field is `uint32` type. The largest value it can represent is 2^32 nanoseconds, which equates to roughly - 4.29 seconds. Usual point clouds don't last more than 100ms for full cycle. So this field should be enough. +To calculate exact time each point was shot, the `T` seconds are added to the header time. From b360af40e1590d6caee936a160963ab198f7cea7 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 10 Nov 2023 10:34:34 +0900 Subject: [PATCH 2/2] feat: add split map tutorial (#477) * docs: add using-divided-map tutorial Signed-off-by: kminoda * update google drive link Signed-off-by: kminoda * add related links Signed-off-by: kminoda * style(pre-commit): autofix * add instruction for playing rosbag Signed-off-by: kminoda --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../how-to-guides/others/using-divided-map.md | 30 +++++++++++++++++++ 1 file changed, 30 insertions(+) create mode 100644 docs/how-to-guides/others/using-divided-map.md diff --git a/docs/how-to-guides/others/using-divided-map.md b/docs/how-to-guides/others/using-divided-map.md new file mode 100644 index 00000000000..82e81cb9b8c --- /dev/null +++ b/docs/how-to-guides/others/using-divided-map.md @@ -0,0 +1,30 @@ +# Using divided pointcloud map + +Divided pointcloud map is necessary when handling large pointcloud map, in which case Autoware may not be capable of sending the whole map via ROS 2 topic or loading the whole map into memory. By using the pre-divided map, Autoware will dynamically load the pointcloud map according to the vehicle's position. + +## Tutorial + +Download the [sample-map-rosbag_split](TODO) and locate the map under `$HOME/autoware_map/`. + +```bash +gdown -O ~/autoware_map/ 'https://docs.google.com/uc?export=download&id=11tLC9T4MS8fnZ9Wo0D8-Ext7hEDl2YJ4' +unzip -d ~/autoware_map/ ~/autoware_map/sample-rosbag_split.zip +``` + +Then, you may launch logging_simulator with the following command to load the divided map. +Note that you need to specify the `map_path` and `pointcloud_map_file` arguments. + +```bash +source ~/autoware/install/setup.bash +ros2 launch autoware_launch logging_simulator.launch.xml \ + map_path:=$HOME/autoware_map/sample-map-rosbag pointcloud_map_file:=pointcloud_map \ + vehicle_model:=sample_vehicle_split sensor_model:=sample_sensor_kit +``` + +For playing rosbag to simulate Autoware, please refer to the instruction in [the tutorial for rosbag replay simulation](https://autowarefoundation.github.io/autoware-documentation/main/tutorials/ad-hoc-simulation/rosbag-replay-simulation/). + +## Related links + +- For specific format definition of the divided map, please refer to [Map component design page](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/) +- [The Readme of map_loader](https://github.com/autowarefoundation/autoware.universe/tree/main/map/map_loader) may be useful specific instructions for dividing maps +- When dividing your own pointcloud map, you may use [pointcloud_divider](https://github.com/MapIV/pointcloud_divider), which can divide the map as well as generating the compatible metadata