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(front_vehicle_velocity_estimator): rework parameters #5241

1 change: 1 addition & 0 deletions perception/front_vehicle_velocity_estimator/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,4 +27,5 @@ endif()
ament_auto_package(
INSTALL_TO_SHARE
launch
config
)
16 changes: 2 additions & 14 deletions perception/front_vehicle_velocity_estimator/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -28,18 +28,6 @@ This package can:
| `~/output/objects` | autoware_auto_perception_msgs/msg/DetectedObjects.msg | 3D detected object with twist. |
| `~/debug/nearest_neighbor_pointcloud` | sensor_msgs/msg/PointCloud2.msg | The pointcloud msg of nearest neighbor point. |

## Node parameter
## Parameter

| Name | Type | Description | Default value |
| :--------------- | :----- | :-------------------- | :------------ |
| `update_rate_hz` | double | The update rate [hz]. | 10.0 |

## Core parameter

| Name | Type | Description | Default value |
| :---------------------------- | :----- | :-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ |
| `moving_average_num` | int | The moving average number for velocity estimation. | 1 |
| `threshold_pointcloud_z_high` | float | The threshold for z position value of point when choosing nearest neighbor point within front vehicle [m]. If z > `threshold_pointcloud_z_high`, the point is considered to noise. | 1.0f |
| `threshold_pointcloud_z_low` | float | The threshold for z position value of point when choosing nearest neighbor point within front vehicle [m]. If z < `threshold_pointcloud_z_low`, the point is considered to noise like ground. | 0.6f |
| `threshold_relative_velocity` | double | The threshold for min and max of estimated relative velocity ($v_{re}$) [m/s]. If $v_{re}$ < - `threshold_relative_velocity` , then $v_{re}$ = - `threshold_relative_velocity`. If $v_{re}$ > `threshold_relative_velocity`, then $v_{re}$ = `threshold_relative_velocity`. | 10.0 |
| `threshold_absolute_velocity` | double | The threshold for max of estimated absolute velocity ($v_{ae}$) [m/s]. If $v_{ae}$ > `threshold_absolute_velocity`, then $v_{ae}$ = `threshold_absolute_velocity`. | 20.0 |
{{ json_to_markdown("perception/front_vehicle_velocity_estimator/schema/front_vehicle_velocity_estimator.schema.json") }}
scepter914 marked this conversation as resolved.
Show resolved Hide resolved
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
/**:
ros__parameters:
node_params:
update_rate_hz: 10.0
core_params:
moving_average_num: 1
threshold_pointcloud_z_high: 1.0
threshold_pointcloud_z_low: 0.6
threshold_relative_velocity: 10.0
threshold_absolute_velocity: 20.0
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
<arg name="debug/nearest_neighbor_pointcloud" default="~/debug/nearest_neighbor_pointcloud"/>

<!-- Parameter -->
<arg name="core_params.moving_average_num" default="1"/>
<arg name="front_vehicle_velocity_estimator_param_file" default="$(find-pkg-share front_vehicle_velocity_estimator)/config/front_vehicle_velocity_estimator.param.yaml"/>

<!-- Node -->
<node pkg="front_vehicle_velocity_estimator" exec="front_vehicle_velocity_estimator_node" name="front_vehicle_velocity_estimator" output="screen">
Expand All @@ -23,6 +23,6 @@
<remap from="~/debug/nearest_neighbor_pointcloud" to="$(var debug/nearest_neighbor_pointcloud)"/>

<!-- Parameter -->
<param name="core_params.moving_average_num" value="$(var core_params.moving_average_num)"/>
<param from="$(var front_vehicle_velocity_estimator_param_file)"/>
</node>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for front vehicle velocity estinator node",
"type": "object",
"definitions": {
"front_vehicle_velocity_estimator": {
"type": "object",
"properties": {
"node_params": {
"type": "object",
"properties": {
"update_rate_hz": {
"type": "number",
"description": "Update rate of the node in Hz",
"default": 10.0
}
},
"required": ["update_rate_hz"]
},
"core_params": {
"type": "object",
"properties": {
"moving_average_num": {
"type": "integer",
"description": "The moving average number for velocity estimation.",
"default": 1
},
"threshold_pointcloud_z_high": {
"type": "number",
"description": "The threshold for z position value of point when choosing nearest neighbor point within front vehicle [m]. If z > `threshold_pointcloud_z_high`, the point is considered to noise.",
"default": 1.0
},
"threshold_pointcloud_z_low": {
"type": "number",
"description": "The threshold for z position value of point when choosing nearest neighbor point within front vehicle [m]. If z < `threshold_pointcloud_z_low`, the point is considered to noise like ground.",
"default": 0.6
},
"threshold_relative_velocity": {
"type": "number",
"description": "The threshold for min and max of estimated relative velocity ($v_{re}$) [m/s]. If $v_{re}$ < - `threshold_relative_velocity` , then $v_{re}$ = - `threshold_relative_velocity`. If $v_{re}$ > `threshold_relative_velocity`, then $v_{re}$ = `threshold_relative_velocity`.",
"default": 10.0
},
"threshold_absolute_velocity": {
"type": "number",
"description": "The threshold for max of estimated absolute velocity ($v_{ae}$) [m/s]. If $v_{ae}$ > `threshold_absolute_velocity`, then $v_{ae}$ = `threshold_absolute_velocity`.",
"default": 20.0
}
}
}
},
"required": ["node_params", "core_params"],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/front_vehicle_velocity_estimator"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Original file line number Diff line number Diff line change
Expand Up @@ -57,18 +57,18 @@
std::bind(&FrontVehicleVelocityEstimatorNode::onSetParam, this, std::placeholders::_1));

// Node Parameter
node_param_.update_rate_hz = declare_parameter<double>("node_params.update_rate_hz", 10.0);
node_param_.update_rate_hz = declare_parameter<double>("node_params.update_rate_hz");

Check warning on line 60 in perception/front_vehicle_velocity_estimator/src/front_vehicle_velocity_estimator_node/front_vehicle_velocity_estimator_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/front_vehicle_velocity_estimator/src/front_vehicle_velocity_estimator_node/front_vehicle_velocity_estimator_node.cpp#L60

Added line #L60 was not covered by tests

// Core Parameter
core_param_.moving_average_num = declare_parameter<int>("core_params.moving_average_num", 1);
core_param_.moving_average_num = declare_parameter<int>("core_params.moving_average_num");

Check warning on line 63 in perception/front_vehicle_velocity_estimator/src/front_vehicle_velocity_estimator_node/front_vehicle_velocity_estimator_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/front_vehicle_velocity_estimator/src/front_vehicle_velocity_estimator_node/front_vehicle_velocity_estimator_node.cpp#L63

Added line #L63 was not covered by tests
core_param_.threshold_pointcloud_z_high =
declare_parameter<float>("core_params.threshold_pointcloud_z_high", 1.0f);
declare_parameter<float>("core_params.threshold_pointcloud_z_high");

Check warning on line 65 in perception/front_vehicle_velocity_estimator/src/front_vehicle_velocity_estimator_node/front_vehicle_velocity_estimator_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/front_vehicle_velocity_estimator/src/front_vehicle_velocity_estimator_node/front_vehicle_velocity_estimator_node.cpp#L65

Added line #L65 was not covered by tests
core_param_.threshold_pointcloud_z_low =
declare_parameter<float>("core_params.threshold_pointcloud_z_low", 0.6f);
declare_parameter<float>("core_params.threshold_pointcloud_z_low");

Check warning on line 67 in perception/front_vehicle_velocity_estimator/src/front_vehicle_velocity_estimator_node/front_vehicle_velocity_estimator_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/front_vehicle_velocity_estimator/src/front_vehicle_velocity_estimator_node/front_vehicle_velocity_estimator_node.cpp#L67

Added line #L67 was not covered by tests
core_param_.threshold_relative_velocity =
declare_parameter<double>("core_params.threshold_relative_velocity", 10.0);
declare_parameter<double>("core_params.threshold_relative_velocity");

Check warning on line 69 in perception/front_vehicle_velocity_estimator/src/front_vehicle_velocity_estimator_node/front_vehicle_velocity_estimator_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/front_vehicle_velocity_estimator/src/front_vehicle_velocity_estimator_node/front_vehicle_velocity_estimator_node.cpp#L69

Added line #L69 was not covered by tests
core_param_.threshold_absolute_velocity =
declare_parameter<double>("core_params.threshold_absolute_velocity", 20.0);
declare_parameter<double>("core_params.threshold_absolute_velocity");

Check warning on line 71 in perception/front_vehicle_velocity_estimator/src/front_vehicle_velocity_estimator_node/front_vehicle_velocity_estimator_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/front_vehicle_velocity_estimator/src/front_vehicle_velocity_estimator_node/front_vehicle_velocity_estimator_node.cpp#L71

Added line #L71 was not covered by tests

// Core
front_vehicle_velocity_estimator_ = std::make_unique<FrontVehicleVelocityEstimator>(get_logger());
Expand Down
Loading