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

feat(autoware_ground_segmentation): Created the schema file, updated the readme file and deleted the default parameter in node files #10086

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
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
15 changes: 4 additions & 11 deletions perception/autoware_ground_segmentation/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -31,17 +31,10 @@ Detail description of each ground segmentation algorithm is in the following lin

## Parameters

### Node Parameters

| Name | Type | Default Value | Description |
| -------------------- | ------ | ------------- | ------------------------------------- |
| `input_frame` | string | " " | input frame id |
| `output_frame` | string | " " | output frame id |
| `has_static_tf_only` | bool | false | flag to listen TF only once |
| `max_queue_size` | int | 5 | max queue size of input/output topics |
| `use_indices` | bool | false | flag to use pointcloud indices |
| `latched_indices` | bool | false | flag to latch pointcloud indices |
| `approximate_sync` | bool | false | flag to use approximate sync option |
{{ json_to_markdown("perception/autoware_ground_segmentation/schema/ground_segmentation.schema.json") }}
{{ json_to_markdown("perception/autoware_ground_segmentation/schema/ransac_ground_filter.schema.json") }}
{{ json_to_markdown("perception/autoware_ground_segmentation/schema/ray_ground_filter.schema.json") }}
{{ json_to_markdown("perception/autoware_ground_segmentation/schema/scan_ground_filter.schema.json") }}

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,150 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "autoware_ground_segmentation",
"type": "object",
"definitions": {
"ground_segmentation": {
"type": "object",
"properties": {
"plugin": {
"type": "string",
"description": "The plugin name used for ground segmentation.",
"default": "autoware::ground_segmentation::ScanGroundFilterComponent"
},
"parameters": {
"type": "object",
"properties": {
"global_slope_max_angle_deg": {
"type": "number",
"description": "Maximum allowable global slope angle in degrees.",
"default": 10.0
},
"local_slope_max_angle_deg": {
"type": "number",
"description": "Maximum allowable local slope angle in degrees. Recommended 30.0 for non-elevation grid mode.",
"default": 13.0
},
"split_points_distance_tolerance": {
"type": "number",
"description": "Distance tolerance for split points.",
"default": 0.2
},
"use_virtual_ground_point": {
"type": "boolean",
"description": "Enable the use of virtual ground points.",
"default": true
},
"split_height_distance": {
"type": "number",
"description": "Height distance threshold for splitting.",
"default": 0.2
},
"non_ground_height_threshold": {
"type": "number",
"description": "Height threshold for non-ground points.",
"default": 0.2
},
"grid_size_m": {
"type": "number",
"description": "Size of the grid in meters.",
"default": 0.1
},
"grid_mode_switch_radius": {
"type": "number",
"description": "Radius for switching grid mode.",
"default": 20.0
},
"gnd_grid_buffer_size": {
"type": "integer",
"description": "Buffer size for ground grid processing.",
"default": 4
},
"detection_range_z_max": {
"type": "number",
"description": "Maximum detection range in the Z direction.",
"default": 2.5
},
"elevation_grid_mode": {
"type": "boolean",
"description": "Enable elevation grid mode for ground filtering.",
"default": true
},
"low_priority_region_x": {
"type": "number",
"description": "X-coordinate defining the low-priority region.",
"default": -20.0
},
"center_pcl_shift": {
"type": "number",
"description": "Shift applied to the center of the point cloud.",
"default": 0.0
},
"radial_divider_angle_deg": {
"type": "number",
"description": "Angle step for radial segmentation in degrees.",
"default": 1.0
},
"use_recheck_ground_cluster": {
"type": "boolean",
"description": "Enable rechecking of ground clusters for refinement.",
"default": true
},
"use_lowest_point": {
"type": "boolean",
"description": "Use the lowest point for ground estimation.",
"default": true
},
"publish_processing_time_detail": {
"type": "boolean",
"description": "Enable publishing of detailed processing time for debugging.",
"default": false
}
},
"required": [
"global_slope_max_angle_deg",
"local_slope_max_angle_deg",
"split_points_distance_tolerance",
"use_virtual_ground_point",
"split_height_distance",
"non_ground_height_threshold",
"grid_size_m",
"grid_mode_switch_radius",
"gnd_grid_buffer_size",
"detection_range_z_max",
"elevation_grid_mode",
"low_priority_region_x",
"center_pcl_shift",
"radial_divider_angle_deg",
"use_recheck_ground_cluster",
"use_lowest_point",
"publish_processing_time_detail"
],
"additionalProperties": false
}
},
"required": ["plugin", "parameters"],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"type": "object",
"properties": {
"common_ground_filter": {
"$ref": "#/definitions/ground_segmentation"
}
},
"required": ["common_ground_filter"],
"additionalProperties": false
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,114 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "autoware_ground_segmentation parameters",
"type": "object",
"definitions": {
"ransac_ground_filter": {
"type": "object",
"properties": {
"base_frame": {
"type": "string",
"description": "The reference coordinate frame for the base.",
"default": "base_link"
},
"unit_axis": {
"type": "string",
"description": "The primary axis used for unit vector computations.",
"default": "z"
},
"max_iterations": {
"type": "integer",
"description": "The maximum number of iterations for the segmentation algorithm.",
"default": 1000
},
"min_trial": {
"type": "integer",
"description": "The minimum number of trials required for segmentation.",
"default": 5000
},
"min_points": {
"type": "integer",
"description": "The minimum number of points required to fit a plane.",
"default": 1000
},
"outlier_threshold": {
"type": "number",
"description": "Threshold for detecting outliers in the plane segmentation process.",
"default": 0.01
},
"plane_slope_threshold": {
"type": "number",
"description": "Maximum allowable slope angle for detected planes (in degrees).",
"default": 10.0
},
"voxel_size_x": {
"type": "number",
"description": "Voxel grid size in the X direction.",
"default": 0.04
},
"voxel_size_y": {
"type": "number",
"description": "Voxel grid size in the Y direction.",
"default": 0.04
},
"voxel_size_z": {
"type": "number",
"description": "Voxel grid size in the Z direction.",
"default": 0.04
},
"height_threshold": {
"type": "number",
"description": "Height difference threshold for plane segmentation.",
"default": 0.01
},
"debug": {
"type": "boolean",
"description": "Enable debug mode for additional logging and output.",
"default": false
},
"publish_processing_time_detail": {
"type": "boolean",
"description": "Enable publishing of detailed processing time for debugging.",
"default": false
}
},
"required": [
"base_frame",
"unit_axis",
"max_iterations",
"min_trial",
"min_points",
"outlier_threshold",
"plane_slope_threshold",
"voxel_size_x",
"voxel_size_y",
"voxel_size_z",
"height_threshold",
"debug",
"publish_processing_time_detail"
],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"type": "object",
"properties": {
"plane_segmentation": {
"$ref": "#/definitions/ransac_ground_filter"
}
},
"required": ["plane_segmentation"],
"additionalProperties": false
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Loading
Loading