Skip to content

Commit

Permalink
feat(autoware_bytetrack): Created Schema file and updated ReadME file…
Browse files Browse the repository at this point in the history
… for parameters setting

Signed-off-by: vish0012 <[email protected]>
  • Loading branch information
vish0012 committed Feb 5, 2025
1 parent b107ac7 commit 4d8d61a
Show file tree
Hide file tree
Showing 5 changed files with 171 additions and 13 deletions.
15 changes: 3 additions & 12 deletions perception/autoware_bytetrack/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
34 changes: 34 additions & 0 deletions perception/autoware_bytetrack/schema/bytetrack.schema.json
Original file line number Diff line number Diff line change
@@ -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
}

Original file line number Diff line number Diff line change
@@ -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
}

99 changes: 99 additions & 0 deletions perception/autoware_bytetrack/schema/kalman_filter.schema.json
Original file line number Diff line number Diff line change
@@ -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
}

2 changes: 1 addition & 1 deletion perception/autoware_bytetrack/src/bytetrack_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<autoware::bytetrack::ByteTrack>(track_buffer_length);

Expand Down

0 comments on commit 4d8d61a

Please sign in to comment.