Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(lidar): change point cloud format from PointXYZIRCEADT to PointXYZIRCAEDT #357

Merged
merged 1 commit into from
Sep 11, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions Assets/AWSIM/Scripts/Sensors/LiDAR/PointCloudFormatLibrary.cs
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ public enum PointCloudFormat : UInt32
{
Pcl24,
Pcl48,
PointXYZIRCEADT,
PointXYZIRCAEDT,
MLInstanceSegmentation,
RadarSmartMicro,
Custom,
Expand Down Expand Up @@ -61,15 +61,15 @@ public static class PointCloudFormatLibrary
RGLField.PADDING_32,
RGLField.TIME_STAMP_F64
}},
// PointXYZIRCEADT format used by Autoware
{PointCloudFormat.PointXYZIRCEADT, new[]
// PointXYZIRCAEDT format used by Autoware
{PointCloudFormat.PointXYZIRCAEDT, new[]
{
RGLField.XYZ_VEC3_F32,
RGLField.INTENSITY_U8,
RGLField.RETURN_TYPE_U8,
RGLField.RING_ID_U16,
RGLField.ELEVATION_F32,
RGLField.AZIMUTH_F32,
RGLField.ELEVATION_F32,
RGLField.DISTANCE_F32,
RGLField.TIME_STAMP_U32
}},
Expand Down
2 changes: 1 addition & 1 deletion Assets/AWSIM/Scripts/Sensors/LiDAR/RglLidarPublisher.cs
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ public class RglLidarPublisher : MonoBehaviour
{
topic = "lidar/pointcloud_ex",
publish = true,
fieldsPreset = PointCloudFormat.PointXYZIRCEADT,
fieldsPreset = PointCloudFormat.PointXYZIRCAEDT,
},
};

Expand Down
8 changes: 4 additions & 4 deletions docs/Components/Sensors/LiDARSensor/LiDARSensor/index.md
Original file line number Diff line number Diff line change
Expand Up @@ -165,14 +165,14 @@ Currently, `RglLidarPublisher` implements ROS2 publishers for two message types:
| Preset | Description | Fields |
| :--------: | :--------------------- | :---------------------------------- |
| Pcl 24 | 24-byte point cloud format used by *Autoware* | XYZ_VEC3_F32, PADDING_32, INTENSITY_F32, RING_ID_U16, PADDING_16 |
| PointXYZIRCEADT | PointXYZIRCEADT format used by *Autoware* | XYZ_VEC3_F32, INTENSITY_U8, RETURN_TYPE_U8, RING_ID_U16, ELEVATION_F32, AZIMUTH_F32, DISTANCE_F32, TIME_STAMP_U32 |
| PointXYZIRCAEDT | PointXYZIRCAEDT format used by *Autoware* | XYZ_VEC3_F32, INTENSITY_U8, RETURN_TYPE_U8, RING_ID_U16, AZIMUTH_F32, ELEVATION_F32, DISTANCE_F32, TIME_STAMP_U32 |
| Pcl 48 | 48-byte extended version point cloud format used by *Autoware* (legacy) | XYZ_VEC3_F32, PADDING_32, INTENSITY_F32, RING_ID_U16, PADDING_16, AZIMUTH_F32, DISTANCE_F32, RETURN_TYPE_U8, PADDING_8, PADDING_16, PADDING_32, TIME_STAMP_F64 |
| ML Instance Segmentation | Machine learning format for instance/semantic segmentation tasks | XYZ_VEC3_F32, ENTITY_ID_I32, INTENSITY_F32 |
| Radar Smart Micro | Format used in Radar Smart Micro | XYZ_VEC3_F32, RADIAL_SPEED_F32, POWER_F32, RCS_F32, NOISE_F32, SNR_F32 |
| Custom | Empty format that allows the user to define its fieldsets | |

!!! note "*PointXYZIRCEADT* format"
For a better understanding of the *PointXYZIRCEADT* format, we encourage you to familiarize yourself with the point cloud pre-processing process in *Autoware*, which is described [here](https://autowarefoundation.github.io/autoware-documentation/latest/design/autoware-architecture/sensing/data-types/point-cloud/#point-cloud-fields).
!!! note "*PointXYZIRCAEDT* format"
For a better understanding of the *PointXYZIRCAEDT* format, we encourage you to familiarize yourself with the point cloud pre-processing process in *Autoware*, which is described [here](https://autowarefoundation.github.io/autoware-documentation/latest/design/autoware-architecture/sensing/data-types/point-cloud/#point-cloud-fields).

#### Elements configurable from the editor level
- `Frame ID` - frame in which data are published, used in [`Header`](https://docs.ros2.org/latest/api/std_msgs/msg/Header.html) (default: `"world"`)
Expand Down Expand Up @@ -200,7 +200,7 @@ Currently, `RglLidarPublisher` implements ROS2 publishers for two message types:
| Category | Topic | Message type | `frame_id` |
| :-----------------------: | :--------------------- | :--------------------------------------- | :--------: |
| PointCloud 24-byte format | `/lidar/pointcloud` | [`sensor_msgs/PointCloud2`][pointcloud2] | `world` |
| PointXYZIRCEADT format | `/lidar/pointcloud_ex` | [`sensor_msgs/PointCloud2`][pointcloud2] | `world` |
| PointXYZIRCAEDT format | `/lidar/pointcloud_ex` | [`sensor_msgs/PointCloud2`][pointcloud2] | `world` |

## Point Cloud Visualization (script)
![script_visualization](script_visualization.png)
Expand Down
Loading