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_euclidean_cluster): Created the schema file, updated the readme file and deleted the default parameter in node files code #10085

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
16 changes: 2 additions & 14 deletions perception/autoware_euclidean_cluster/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -39,23 +39,11 @@ This package has two clustering methods: `euclidean_cluster` and `voxel_grid_bas

#### euclidean_cluster

| Name | Type | Description |
| ------------------ | ----- | -------------------------------------------------------------------------------------------- |
| `use_height` | bool | use point.z for clustering |
| `min_cluster_size` | int | the minimum number of points that a cluster needs to contain in order to be considered valid |
| `max_cluster_size` | int | the maximum number of points that a cluster needs to contain in order to be considered valid |
| `tolerance` | float | the spatial cluster tolerance as a measure in the L2 Euclidean space |
{{ json_to_markdown("perception/autoware_euclidean_cluster/schema/euclidean_cluster.schema.json") }}

#### voxel_grid_based_euclidean_cluster

| Name | Type | Description |
| ----------------------------- | ----- | -------------------------------------------------------------------------------------------- |
| `use_height` | bool | use point.z for clustering |
| `min_cluster_size` | int | the minimum number of points that a cluster needs to contain in order to be considered valid |
| `max_cluster_size` | int | the maximum number of points that a cluster needs to contain in order to be considered valid |
| `tolerance` | float | the spatial cluster tolerance as a measure in the L2 Euclidean space |
| `voxel_leaf_size` | float | the voxel leaf size of x and y |
| `min_points_number_per_voxel` | int | the minimum number of points for a voxel |
{{ json_to_markdown("perception/autoware_euclidean_cluster/schema/voxel_grid_based_euclidean_cluster.schema.json") }}

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "autoware_eucidean Parameters",
"type": "object",
"definitions": {
"euclidean_cluster": {
"type": "object",
"properties": {
"max_cluster_size": {
"type": "integer",
"description": "The maximum number of points that a cluster needs to contain in order to be considered valid.",
"default": 1000
},
"min_cluster_size": {
"type": "integer",
"description": "The minimum number of points that a cluster needs to contain in order to be considered valid.",
"default": 10
},
"tolerance": {
"type": "number",
"description": "The spatial cluster tolerance as a measure in the L2 Euclidean space.",
"default": 0.7
},
"use_height": {
"type": "boolean",
"description": "Whether to use point.z for clustering.",
"default": false
}
},
"required": ["max_cluster_size", "min_cluster_size", "tolerance", "use_height"],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/euclidean_cluster"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,113 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "autoware_euclidean_cluster Parameters",
"type": "object",
"definitions": {
"voxel_grid_based_euclidean_cluster": {
"type": "object",
"properties": {
"tolerance": {
"type": "number",
"description": "The spatial cluster tolerance as a measure in the L2 Euclidean space.",
"default": 0.7
},
"voxel_leaf_size": {
"type": "number",
"description": "The voxel leaf size of x and y.",
"default": 0.3
},
"min_points_number_per_voxel": {
"type": "integer",
"description": "The minimum number of points required per voxel.",
"default": 1
},
"min_cluster_size": {
"type": "integer",
"description": "The minimum number of points that a cluster needs to contain in order to be considered valid.",
"default": 10
},
"max_cluster_size": {
"type": "integer",
"description": "The maximum number of points that a cluster needs to contain in order to be considered valid.",
"default": 3000
},
"use_height": {
"type": "boolean",
"description": "Use point.z for clustering.",
"default": false
},
"input_frame": {
"type": "string",
"description": "The reference frame for input data processing.",
"default": "base_link"
},
"max_x": {
"type": "number",
"description": "Maximum X coordinate for the low height crop box filter.",
"default": 200.0
},
"min_x": {
"type": "number",
"description": "Minimum X coordinate for the low height crop box filter.",
"default": -200.0
},
"max_y": {
"type": "number",
"description": "Maximum Y coordinate for the low height crop box filter.",
"default": 200.0
},
"min_y": {
"type": "number",
"description": "Minimum Y coordinate for the low height crop box filter.",
"default": -200.0
},
"max_z": {
"type": "number",
"description": "Maximum Z coordinate for the low height crop box filter.",
"default": 2.0
},
"min_z": {
"type": "number",
"description": "Minimum Z coordinate for the low height crop box filter.",
"default": -10.0
},
"negative": {
"type": "boolean",
"description": "Whether to invert the crop box filtering effect.",
"default": false
}
},
"required": [
"tolerance",
"voxel_leaf_size",
"min_points_number_per_voxel",
"min_cluster_size",
"max_cluster_size",
"use_height",
"input_frame",
"max_x",
"min_x",
"max_y",
"min_y",
"max_z",
"min_z",
"negative"
],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/voxel_grid_based_euclidean_cluster"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Original file line number Diff line number Diff line change
Expand Up @@ -24,10 +24,10 @@ namespace autoware::euclidean_cluster
EuclideanClusterNode::EuclideanClusterNode(const rclcpp::NodeOptions & options)
: Node("euclidean_cluster_node", options)
{
const bool use_height = this->declare_parameter("use_height", false);
const int min_cluster_size = this->declare_parameter("min_cluster_size", 3);
const int max_cluster_size = this->declare_parameter("max_cluster_size", 200);
const float tolerance = this->declare_parameter("tolerance", 1.0);
const bool use_height = this->declare_parameter("use_height");
const int min_cluster_size = this->declare_parameter("min_cluster_size");
const int max_cluster_size = this->declare_parameter("max_cluster_size");
const float tolerance = this->declare_parameter("tolerance");
cluster_ =
std::make_shared<EuclideanCluster>(use_height, min_cluster_size, max_cluster_size, tolerance);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,12 +25,12 @@ VoxelGridBasedEuclideanClusterNode::VoxelGridBasedEuclideanClusterNode(
const rclcpp::NodeOptions & options)
: Node("voxel_grid_based_euclidean_cluster_node", options)
{
const bool use_height = this->declare_parameter("use_height", false);
const int min_cluster_size = this->declare_parameter("min_cluster_size", 1);
const int max_cluster_size = this->declare_parameter("max_cluster_size", 500);
const float tolerance = this->declare_parameter("tolerance", 1.0);
const float voxel_leaf_size = this->declare_parameter("voxel_leaf_size", 0.5);
const int min_points_number_per_voxel = this->declare_parameter("min_points_number_per_voxel", 3);
const bool use_height = this->declare_parameter("use_height");
const int min_cluster_size = this->declare_parameter("min_cluster_size");
const int max_cluster_size = this->declare_parameter("max_cluster_size");
const float tolerance = this->declare_parameter("tolerance");
const float voxel_leaf_size = this->declare_parameter("voxel_leaf_size");
const int min_points_number_per_voxel = this->declare_parameter("min_points_number_per_voxel");
cluster_ = std::make_shared<VoxelGridBasedEuclideanCluster>(
use_height, min_cluster_size, max_cluster_size, tolerance, voxel_leaf_size,
min_points_number_per_voxel);
Expand Down
Loading