diff --git a/perception/autoware_bytetrack/README.md b/perception/autoware_bytetrack/README.md index 90116c4dae7e5..67c0cba6e1511 100644 --- a/perception/autoware_bytetrack/README.md +++ b/perception/autoware_bytetrack/README.md @@ -65,17 +65,9 @@ Kalman filter settings can be controlled by the parameters in `config/bytetrack_ ## 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..e544418139ea7 --- /dev/null +++ b/perception/autoware_bytetrack/schema/bytetrack.schema.json @@ -0,0 +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 +} 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..38820de5dc698 --- /dev/null +++ b/perception/autoware_bytetrack/schema/bytetrack_visualizer.schema.json @@ -0,0 +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 +} 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..4faefff497d4e --- /dev/null +++ b/perception/autoware_bytetrack/schema/kalman_filter.schema.json @@ -0,0 +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 + } + }, + "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 +} 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);