From 4d8d61af3116839cf5aa0bdfb0f44a924f7f1ebe Mon Sep 17 00:00:00 2001 From: vish0012 Date: Thu, 6 Feb 2025 07:27:14 +0900 Subject: [PATCH 1/2] feat(autoware_bytetrack): Created Schema file and updated ReadME file for parameters setting Signed-off-by: vish0012 --- perception/autoware_bytetrack/README.md | 15 +-- .../schema/bytetrack.schema.json | 34 +++++++ .../schema/bytetrack_visualizer.schema.json | 34 +++++++ .../schema/kalman_filter.schema.json | 99 +++++++++++++++++++ .../autoware_bytetrack/src/bytetrack_node.cpp | 2 +- 5 files changed, 171 insertions(+), 13 deletions(-) create mode 100644 perception/autoware_bytetrack/schema/bytetrack.schema.json create mode 100644 perception/autoware_bytetrack/schema/bytetrack_visualizer.schema.json create mode 100644 perception/autoware_bytetrack/schema/kalman_filter.schema.json diff --git a/perception/autoware_bytetrack/README.md b/perception/autoware_bytetrack/README.md index 90116c4dae7e5..800e4a16a0a9a 100644 --- a/perception/autoware_bytetrack/README.md +++ b/perception/autoware_bytetrack/README.md @@ -64,18 +64,9 @@ Kalman filter settings can be controlled by the parameters in `config/bytetrack_ | `out/image` | `sensor_msgs/Image` | The image that detection bounding boxes and their UUIDs are drawn | ## Parameters - -### bytetrack_node - -| Name | Type | Default Value | Description | -| --------------------- | ---- | ------------- | -------------------------------------------------------- | -| `track_buffer_length` | int | 30 | The frame count that a tracklet is considered to be lost | - -### bytetrack_visualizer - -| Name | Type | Default Value | Description | -| --------- | ---- | ------------- | --------------------------------------------------------------------------------------------- | -| `use_raw` | bool | false | The flag for the node to switch `sensor_msgs/Image` or `sensor_msgs/CompressedImage` as input | +{{ json_to_markdown("perception/autoware_bytetrack/schema/bytetrack_visualizer.schema.json") }} +{{ json_to_markdown("perception/autoware_bytetrack/schema/bytetrack.schema.json") }} +{{ json_to_markdown("perception/autoware_bytetrack/schema/kalman_filter.schema.json") }} ## Assumptions/Known limits diff --git a/perception/autoware_bytetrack/schema/bytetrack.schema.json b/perception/autoware_bytetrack/schema/bytetrack.schema.json new file mode 100644 index 0000000000000..3dbe6e9900c3f --- /dev/null +++ b/perception/autoware_bytetrack/schema/bytetrack.schema.json @@ -0,0 +1,34 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "autoware_bytetrack parameter", + "type": "object", + "definitions": { + "bytetrack": { + "type": "object", + "properties": { + "track_buffer_length": { + "type": "integer", + "description": "The frame count that a tracklet is considered to be lost.", + "default": 30 + } + }, + "required": ["track_buffer_length"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/bytetrack" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false + } + \ No newline at end of file diff --git a/perception/autoware_bytetrack/schema/bytetrack_visualizer.schema.json b/perception/autoware_bytetrack/schema/bytetrack_visualizer.schema.json new file mode 100644 index 0000000000000..7feb160bac195 --- /dev/null +++ b/perception/autoware_bytetrack/schema/bytetrack_visualizer.schema.json @@ -0,0 +1,34 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "autoware_bytetrack parameter", + "type": "object", + "definitions": { + "bytetrack_visualizer": { + "type": "object", + "properties": { + "use_raw": { + "type": "boolean", + "description": "The flag for the node to switch between `sensor_msgs/Image` or `sensor_msgs/CompressedImage` as input.", + "default": false + } + }, + "required": ["use_raw"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/bytetrack_visualizer" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false + } + \ No newline at end of file diff --git a/perception/autoware_bytetrack/schema/kalman_filter.schema.json b/perception/autoware_bytetrack/schema/kalman_filter.schema.json new file mode 100644 index 0000000000000..031f82bcb7c39 --- /dev/null +++ b/perception/autoware_bytetrack/schema/kalman_filter.schema.json @@ -0,0 +1,99 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "autoware_bytetrack parameter", + "type": "object", + "definitions": { + "kalman_filter": { + "type": "object", + "properties": { + "dt": { + "type": "number", + "description": "Time step [s].", + "default": 0.1 + }, + "dim_x": { + "type": "integer", + "description": "State dimension (tlbr + velocity).", + "default": 8 + }, + "dim_z": { + "type": "integer", + "description": "Measurement dimension (tlbr).", + "default": 4 + }, + "q_cov_x": { + "type": "number", + "description": "Process noise covariance for x.", + "default": 0.1 + }, + "q_cov_y": { + "type": "number", + "description": "Process noise covariance for y.", + "default": 0.1 + }, + "q_cov_vx": { + "type": "number", + "description": "Process noise covariance for velocity x.", + "default": 0.1 + }, + "q_cov_vy": { + "type": "number", + "description": "Process noise covariance for velocity y.", + "default": 0.1 + }, + "r_cov_x": { + "type": "number", + "description": "Measurement noise covariance for x.", + "default": 0.1 + }, + "r_cov_y": { + "type": "number", + "description": "Measurement noise covariance for y.", + "default": 0.1 + }, + "p0_cov_x": { + "type": "number", + "description": "Initial covariance for x.", + "default": 100.0 + }, + "p0_cov_y": { + "type": "number", + "description": "Initial covariance for y.", + "default": 100.0 + }, + "p0_cov_vx": { + "type": "number", + "description": "Initial covariance for velocity x.", + "default": 100.0 + }, + "p0_cov_vy": { + "type": "number", + "description": "Initial covariance for velocity y.", + "default": 100.0 + } + }, + "required": [ + "dt", "dim_x", "dim_z", + "q_cov_x", "q_cov_y", "q_cov_vx", "q_cov_vy", + "r_cov_x", "r_cov_y", + "p0_cov_x", "p0_cov_y", "p0_cov_vx", "p0_cov_vy" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/kalman_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false + } + \ No newline at end of file diff --git a/perception/autoware_bytetrack/src/bytetrack_node.cpp b/perception/autoware_bytetrack/src/bytetrack_node.cpp index bee93b623ae06..2201f297764e9 100644 --- a/perception/autoware_bytetrack/src/bytetrack_node.cpp +++ b/perception/autoware_bytetrack/src/bytetrack_node.cpp @@ -33,7 +33,7 @@ ByteTrackNode::ByteTrackNode(const rclcpp::NodeOptions & node_options) using std::placeholders::_1; using std::chrono_literals::operator""ms; - int track_buffer_length = declare_parameter("track_buffer_length", 30); + int track_buffer_length = declare_parameter("track_buffer_length"); this->bytetrack_ = std::make_unique(track_buffer_length); From b3389998361702fa54a9258a043925af535882cf Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 5 Feb 2025 22:38:24 +0000 Subject: [PATCH 2/2] style(pre-commit): autofix --- perception/autoware_bytetrack/README.md | 1 + .../schema/bytetrack.schema.json | 65 +++--- .../schema/bytetrack_visualizer.schema.json | 65 +++--- .../schema/kalman_filter.schema.json | 200 +++++++++--------- 4 files changed, 169 insertions(+), 162 deletions(-) diff --git a/perception/autoware_bytetrack/README.md b/perception/autoware_bytetrack/README.md index 800e4a16a0a9a..67c0cba6e1511 100644 --- a/perception/autoware_bytetrack/README.md +++ b/perception/autoware_bytetrack/README.md @@ -64,6 +64,7 @@ Kalman filter settings can be controlled by the parameters in `config/bytetrack_ | `out/image` | `sensor_msgs/Image` | The image that detection bounding boxes and their UUIDs are drawn | ## Parameters + {{ json_to_markdown("perception/autoware_bytetrack/schema/bytetrack_visualizer.schema.json") }} {{ json_to_markdown("perception/autoware_bytetrack/schema/bytetrack.schema.json") }} {{ json_to_markdown("perception/autoware_bytetrack/schema/kalman_filter.schema.json") }} diff --git a/perception/autoware_bytetrack/schema/bytetrack.schema.json b/perception/autoware_bytetrack/schema/bytetrack.schema.json index 3dbe6e9900c3f..e544418139ea7 100644 --- a/perception/autoware_bytetrack/schema/bytetrack.schema.json +++ b/perception/autoware_bytetrack/schema/bytetrack.schema.json @@ -1,34 +1,33 @@ { - "$schema": "http://json-schema.org/draft-07/schema#", - "title": "autoware_bytetrack parameter", - "type": "object", - "definitions": { - "bytetrack": { - "type": "object", - "properties": { - "track_buffer_length": { - "type": "integer", - "description": "The frame count that a tracklet is considered to be lost.", - "default": 30 - } - }, - "required": ["track_buffer_length"], - "additionalProperties": false - } - }, - "properties": { - "/**": { - "type": "object", - "properties": { - "ros__parameters": { - "$ref": "#/definitions/bytetrack" - } - }, - "required": ["ros__parameters"], - "additionalProperties": false - } - }, - "required": ["/**"], - "additionalProperties": false - } - \ No newline at end of file + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "autoware_bytetrack parameter", + "type": "object", + "definitions": { + "bytetrack": { + "type": "object", + "properties": { + "track_buffer_length": { + "type": "integer", + "description": "The frame count that a tracklet is considered to be lost.", + "default": 30 + } + }, + "required": ["track_buffer_length"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/bytetrack" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/autoware_bytetrack/schema/bytetrack_visualizer.schema.json b/perception/autoware_bytetrack/schema/bytetrack_visualizer.schema.json index 7feb160bac195..38820de5dc698 100644 --- a/perception/autoware_bytetrack/schema/bytetrack_visualizer.schema.json +++ b/perception/autoware_bytetrack/schema/bytetrack_visualizer.schema.json @@ -1,34 +1,33 @@ { - "$schema": "http://json-schema.org/draft-07/schema#", - "title": "autoware_bytetrack parameter", - "type": "object", - "definitions": { - "bytetrack_visualizer": { - "type": "object", - "properties": { - "use_raw": { - "type": "boolean", - "description": "The flag for the node to switch between `sensor_msgs/Image` or `sensor_msgs/CompressedImage` as input.", - "default": false - } - }, - "required": ["use_raw"], - "additionalProperties": false - } - }, - "properties": { - "/**": { - "type": "object", - "properties": { - "ros__parameters": { - "$ref": "#/definitions/bytetrack_visualizer" - } - }, - "required": ["ros__parameters"], - "additionalProperties": false - } - }, - "required": ["/**"], - "additionalProperties": false - } - \ No newline at end of file + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "autoware_bytetrack parameter", + "type": "object", + "definitions": { + "bytetrack_visualizer": { + "type": "object", + "properties": { + "use_raw": { + "type": "boolean", + "description": "The flag for the node to switch between `sensor_msgs/Image` or `sensor_msgs/CompressedImage` as input.", + "default": false + } + }, + "required": ["use_raw"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/bytetrack_visualizer" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/autoware_bytetrack/schema/kalman_filter.schema.json b/perception/autoware_bytetrack/schema/kalman_filter.schema.json index 031f82bcb7c39..4faefff497d4e 100644 --- a/perception/autoware_bytetrack/schema/kalman_filter.schema.json +++ b/perception/autoware_bytetrack/schema/kalman_filter.schema.json @@ -1,99 +1,107 @@ { - "$schema": "http://json-schema.org/draft-07/schema#", - "title": "autoware_bytetrack parameter", - "type": "object", - "definitions": { - "kalman_filter": { - "type": "object", - "properties": { - "dt": { - "type": "number", - "description": "Time step [s].", - "default": 0.1 - }, - "dim_x": { - "type": "integer", - "description": "State dimension (tlbr + velocity).", - "default": 8 - }, - "dim_z": { - "type": "integer", - "description": "Measurement dimension (tlbr).", - "default": 4 - }, - "q_cov_x": { - "type": "number", - "description": "Process noise covariance for x.", - "default": 0.1 - }, - "q_cov_y": { - "type": "number", - "description": "Process noise covariance for y.", - "default": 0.1 - }, - "q_cov_vx": { - "type": "number", - "description": "Process noise covariance for velocity x.", - "default": 0.1 - }, - "q_cov_vy": { - "type": "number", - "description": "Process noise covariance for velocity y.", - "default": 0.1 - }, - "r_cov_x": { - "type": "number", - "description": "Measurement noise covariance for x.", - "default": 0.1 - }, - "r_cov_y": { - "type": "number", - "description": "Measurement noise covariance for y.", - "default": 0.1 - }, - "p0_cov_x": { - "type": "number", - "description": "Initial covariance for x.", - "default": 100.0 - }, - "p0_cov_y": { - "type": "number", - "description": "Initial covariance for y.", - "default": 100.0 - }, - "p0_cov_vx": { - "type": "number", - "description": "Initial covariance for velocity x.", - "default": 100.0 - }, - "p0_cov_vy": { - "type": "number", - "description": "Initial covariance for velocity y.", - "default": 100.0 - } + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "autoware_bytetrack parameter", + "type": "object", + "definitions": { + "kalman_filter": { + "type": "object", + "properties": { + "dt": { + "type": "number", + "description": "Time step [s].", + "default": 0.1 }, - "required": [ - "dt", "dim_x", "dim_z", - "q_cov_x", "q_cov_y", "q_cov_vx", "q_cov_vy", - "r_cov_x", "r_cov_y", - "p0_cov_x", "p0_cov_y", "p0_cov_vx", "p0_cov_vy" - ], - "additionalProperties": false - } - }, - "properties": { - "/**": { - "type": "object", - "properties": { - "ros__parameters": { - "$ref": "#/definitions/kalman_filter" - } + "dim_x": { + "type": "integer", + "description": "State dimension (tlbr + velocity).", + "default": 8 }, - "required": ["ros__parameters"], - "additionalProperties": false - } - }, - "required": ["/**"], - "additionalProperties": false - } - \ No newline at end of file + "dim_z": { + "type": "integer", + "description": "Measurement dimension (tlbr).", + "default": 4 + }, + "q_cov_x": { + "type": "number", + "description": "Process noise covariance for x.", + "default": 0.1 + }, + "q_cov_y": { + "type": "number", + "description": "Process noise covariance for y.", + "default": 0.1 + }, + "q_cov_vx": { + "type": "number", + "description": "Process noise covariance for velocity x.", + "default": 0.1 + }, + "q_cov_vy": { + "type": "number", + "description": "Process noise covariance for velocity y.", + "default": 0.1 + }, + "r_cov_x": { + "type": "number", + "description": "Measurement noise covariance for x.", + "default": 0.1 + }, + "r_cov_y": { + "type": "number", + "description": "Measurement noise covariance for y.", + "default": 0.1 + }, + "p0_cov_x": { + "type": "number", + "description": "Initial covariance for x.", + "default": 100.0 + }, + "p0_cov_y": { + "type": "number", + "description": "Initial covariance for y.", + "default": 100.0 + }, + "p0_cov_vx": { + "type": "number", + "description": "Initial covariance for velocity x.", + "default": 100.0 + }, + "p0_cov_vy": { + "type": "number", + "description": "Initial covariance for velocity y.", + "default": 100.0 + } + }, + "required": [ + "dt", + "dim_x", + "dim_z", + "q_cov_x", + "q_cov_y", + "q_cov_vx", + "q_cov_vy", + "r_cov_x", + "r_cov_y", + "p0_cov_x", + "p0_cov_y", + "p0_cov_vx", + "p0_cov_vy" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/kalman_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +}