Skip to content

Commit

Permalink
feat(autoware_traffic_light_fine_detector): created the schema file,u…
Browse files Browse the repository at this point in the history
…pdated the readme file and deleted the default parameter in node files code (autowarefoundation#10106)

* feat(autoware_traffic_light_fine_detector): Created the schema file, updated the readme file and deleted the default parameter in node files code

Signed-off-by: vish0012 <vishalchhn42@gmail.com>

* style(pre-commit): autofix

* fix declare_parameter

Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp>

* chore

Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp>

* change launch file

Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp>

* change type

Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp>

* style(pre-commit): autofix

* fix definition name

Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp>

* run build

Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp>

---------

Signed-off-by: vish0012 <vishalchhn42@gmail.com>
Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: MasatoSaeki <masato.saeki@tier4.jp>
  • Loading branch information
3 people authored Feb 13, 2025
1 parent 3274695 commit 5e36840
Show file tree
Hide file tree
Showing 4 changed files with 85 additions and 25 deletions.
18 changes: 1 addition & 17 deletions perception/autoware_traffic_light_fine_detector/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -43,23 +43,7 @@ ROIs detected from YOLOX will be selected by a combination of `expect/rois`. At

## Parameters

### Core Parameters

| Name | Type | Default Value | Description |
| ---------------------------- | ------ | ------------- | ---------------------------------------------------------------------- |
| `fine_detector_score_thresh` | double | 0.3 | If the objectness score is less than this value, the object is ignored |
| `fine_detector_nms_thresh` | double | 0.65 | IoU threshold to perform Non-Maximum Suppression |

### Node Parameters

| Name | Type | Default Value | Description |
| -------------------------- | ------- | --------------------------- | ------------------------------------------------------------------ |
| `data_path` | string | "$(env HOME)/autoware_data" | packages data and artifacts directory path |
| `fine_detector_model_path` | string | "" | The onnx file name for yolo model |
| `fine_detector_label_path` | string | "" | The label file with label names for detected objects written on it |
| `fine_detector_precision` | string | "fp16" | The inference mode: "fp32", "fp16" |
| `approximate_sync` | bool | false | Flag for whether to ues approximate sync policy |
| `gpu_id` | integer | 0 | ID for the selecting CUDA GPU device |
{{ json_to_markdown("perception/autoware_traffic_light_fine_detector/schema/traffic_light_fine_detector.schema.json") }} |

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,15 @@
<arg name="input/rois" default="/traffic_light_map_based_detector/output/rois"/>
<arg name="expect/rois" default="~/expect/rois"/>
<arg name="output/rois" default="~/output/rois"/>
<arg name="data_path" default="$(env HOME)/autoware_data" description="packages data and artifacts directory path"/>
<arg
name="traffic_light_fine_detector_param_path"
default="$(find-pkg-share autoware_traffic_light_fine_detector)/config/traffic_light_fine_detector.param.yaml"
description="fine detector param path"
/>
<arg name="traffic_light_fine_detector_model_path" default="$(var data_path)/traffic_light_fine_detector" description="path to fine detector onnx model and label"/>
<arg name="traffic_light_fine_detector_label_name" default="tlr_labels.txt" description="fine detector label name"/>
<arg name="traffic_light_fine_detector_model_name" default="tlr_car_ped_yolox_s_batch_6" description="fine detector onnx model name"/>
<arg name="build_only" default="false" description="exit after trt engine is built"/>

<node pkg="autoware_traffic_light_fine_detector" exec="traffic_light_fine_detector_node" name="traffic_light_fine_detector" output="screen">
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "autoware_traffic_light_fine_detector parameter",
"type": "object",
"definitions": {
"traffic_light_fine_detector": {
"type": "object",
"properties": {
"fine_detector_label_path": {
"type": "string",
"description": "The label file with label names for detected objects written on it.",
"default": "$(var traffic_light_fine_detector_model_path)/$(var traffic_light_fine_detector_label_name)"
},
"fine_detector_model_path": {
"type": "string",
"description": "The ONNX file name for the YOLO model.",
"default": "$(var traffic_light_fine_detector_model_path)/$(var traffic_light_fine_detector_model_name).onnx"
},
"fine_detector_precision": {
"type": "string",
"description": "Precision used for traffic light fine detector inference. Valid values: [fp32, fp16].",
"default": "fp16"
},
"fine_detector_score_thresh": {
"type": "number",
"description": "If the objectness score is less than this value, the object is ignored.",
"default": 0.3
},
"fine_detector_nms_thresh": {
"type": "number",
"description": "IoU threshold to perform Non-Maximum Suppression (NMS).",
"default": 0.65
},
"approximate_sync": {
"type": "boolean",
"description": "Flag for whether to use approximate sync policy.",
"default": false
},
"gpu_id": {
"type": "integer",
"description": "ID for selecting the CUDA GPU device.",
"default": 0
}
},
"required": [
"fine_detector_label_path",
"fine_detector_model_path",
"fine_detector_precision",
"fine_detector_score_thresh",
"fine_detector_nms_thresh",
"approximate_sync",
"gpu_id"
],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/traffic_light_fine_detector"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Original file line number Diff line number Diff line change
Expand Up @@ -59,17 +59,18 @@ TrafficLightFineDetectorNode::TrafficLightFineDetectorNode(const rclcpp::NodeOpt
using std::placeholders::_2;
using std::placeholders::_3;

std::string model_path = declare_parameter("fine_detector_model_path", "");
std::string label_path = declare_parameter("fine_detector_label_path", "");
std::string precision = declare_parameter("fine_detector_precision", "fp16");
const uint8_t gpu_id = declare_parameter("gpu_id", 0);
std::string model_path = this->declare_parameter<std::string>("fine_detector_model_path");
std::string label_path = this->declare_parameter<std::string>("fine_detector_label_path");
std::string precision = this->declare_parameter<std::string>("fine_detector_precision");
const uint8_t gpu_id = this->declare_parameter<uint8_t>("gpu_id");
// Objects with a score lower than this value will be ignored.
// This threshold will be ignored if specified model contains EfficientNMS_TRT module in it
score_thresh_ = declare_parameter("fine_detector_score_thresh", 0.3);
score_thresh_ = this->declare_parameter<double>("fine_detector_score_thresh");
// Detection results will be ignored if IoU over this value.
// This threshold will be ignored if specified model contains EfficientNMS_TRT module in it
float nms_threshold = declare_parameter("fine_detector_nms_thresh", 0.65);
is_approximate_sync_ = this->declare_parameter<bool>("approximate_sync", false);
float nms_threshold =
static_cast<float>(this->declare_parameter<double>("fine_detector_nms_thresh"));
is_approximate_sync_ = this->declare_parameter<bool>("approximate_sync");

if (!readLabelFile(label_path, tlr_label_id_, num_class)) {
RCLCPP_ERROR(this->get_logger(), "Could not find tlr id");
Expand Down Expand Up @@ -113,7 +114,7 @@ TrafficLightFineDetectorNode::TrafficLightFineDetectorNode(const rclcpp::NodeOpt
sync_->registerCallback(std::bind(&TrafficLightFineDetectorNode::callback, this, _1, _2, _3));
}

if (declare_parameter("build_only", false)) {
if (this->declare_parameter<bool>("build_only")) {
RCLCPP_INFO(get_logger(), "TensorRT engine is built and shutdown node.");
rclcpp::shutdown();
}
Expand Down

0 comments on commit 5e36840

Please sign in to comment.