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
Expand Up @@ -221,22 +221,22 @@ class Filter : public rclcpp::Node
* ~indices topics must be synchronised in time, either exact or within a
* specified jitter. See also @ref latched_indices_ and approximate_sync.
**/
bool use_indices_ = false;
bool use_indices_;
/** \brief Set to true if the indices topic is latched.
*
* If use_indices_ is true, the ~input and ~indices topics generally must
* be synchronised in time. By setting this flag to true, the most recent
* value from ~indices can be used instead of requiring a synchronised
* message.
**/
bool latched_indices_ = false;
bool latched_indices_;

/** \brief The maximum queue size (default: 3). */
size_t max_queue_size_ = 3;
size_t max_queue_size_;

/** \brief True if we use an approximate time synchronizer
* versus an exact one (false by default). */
bool approximate_sync_ = false;
bool approximate_sync_;

std::unique_ptr<autoware::universe_utils::ManagedTransformBuffer> managed_tf_buffer_{nullptr};

Expand Down
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,15 +70,15 @@ 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", ""));
tf_input_frame_ = declare_parameter<std::string>("input_frame");
tf_output_frame_ = declare_parameter<std::string>("output_frame");
max_queue_size_ = static_cast<size_t>(declare_parameter<int64_t>("max_queue_size"));
has_static_tf_only_ = static_cast<bool>(declare_parameter("has_static_tf_only", false));
vividf marked this conversation as resolved.
Show resolved Hide resolved
max_queue_size_ = static_cast<std::size_t>(declare_parameter("max_queue_size", 5));

// ---[ 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