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

refactor(autoware_pointcloud_preprocessor): rework filter parameters #8469

Closed
Closed
9 changes: 1 addition & 8 deletions sensing/autoware_pointcloud_preprocessor/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -45,14 +45,7 @@ Detail description of each filter's algorithm is in the following links.

### Node Parameters

| Name | Type | Default Value | Description |
| ------------------ | ------ | ------------- | ------------------------------------- |
| `input_frame` | string | " " | input frame id |
| `output_frame` | string | " " | output frame id |
| `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("schema/filter.schema.json") }}

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
/**:
ros__parameters:
input_frame: ""
output_frame: ""
max_queue_size: 5
use_indices: false
latched_indices: false
approximate_sync: false
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Filter Class",
"type": "object",
"definitions": {
"filter": {
"type": "object",
"properties": {
"input_frame": {
"type": "string",
"description": "input frame id",
knzo25 marked this conversation as resolved.
Show resolved Hide resolved
"default": ""
},
"output_frame": {
"type": "string",
"description": "output frame id",
"default": ""
},
"max_queue_size": {
"type": "integer",
"minimum": 0,
"description": "max queue size of input/output topics",
"default": 5
},
"use_indices": {
"type": "boolean",
"description": "flag to use pointcloud indices",
"default": false
},
"latched_indices": {
"type": "boolean",
"description": "flag to latch pointcloud indices",
"default": false
},
"approximate_sync": {
"type": "boolean",
"description": "flag to use approximate sync option",
"default": false
}
},
"required": [
"input_frame",
"output_frame",
"max_queue_size",
"use_indices",
"latched_indices",
"approximate_sync"
],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/filter"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
12 changes: 6 additions & 6 deletions sensing/autoware_pointcloud_preprocessor/src/filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,14 +70,14 @@ autoware::pointcloud_preprocessor::Filter::Filter(
{
// Set parameters (moved from NodeletLazy onInit)
{
tf_input_frame_ = static_cast<std::string>(declare_parameter("input_frame", ""));
tf_output_frame_ = static_cast<std::string>(declare_parameter("output_frame", ""));
max_queue_size_ = static_cast<std::size_t>(declare_parameter("max_queue_size", 5));
tf_input_frame_ = declare_parameter<std::string>("input_frame");
tf_output_frame_ = declare_parameter<std::string>("output_frame");
max_queue_size_ = declare_parameter<int64_t>("max_queue_size");
knzo25 marked this conversation as resolved.
Show resolved Hide resolved

// ---[ Optional parameters
use_indices_ = static_cast<bool>(declare_parameter("use_indices", false));
latched_indices_ = static_cast<bool>(declare_parameter("latched_indices", false));
approximate_sync_ = static_cast<bool>(declare_parameter("approximate_sync", false));
use_indices_ = declare_parameter<bool>("use_indices");
latched_indices_ = declare_parameter<bool>("latched_indices");
approximate_sync_ = declare_parameter<bool>("approximate_sync");

RCLCPP_DEBUG_STREAM(
this->get_logger(),
Expand Down
Loading