Skip to content

Commit 6efa91b

Browse files
authored
refactor(perception-tensortt-yolo): rework parameters (#5918)
perception-tensortt-yolo Signed-off-by: karishma <karishma@interpl.ai>
1 parent 51a8af8 commit 6efa91b

File tree

2 files changed

+116
-8
lines changed

2 files changed

+116
-8
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,108 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Parameters for tensorrt_yolo",
4+
"type": "object",
5+
"definitions": {
6+
"tensorrt_yolo": {
7+
"type": "object",
8+
"properties": {
9+
"num_anchors": {
10+
"type": "number",
11+
"default": [
12+
10.0, 13.0, 16.0, 30.0, 33.0, 23.0, 30.0, 61.0, 62.0, 45.0, 59.0, 119.0, 116.0, 90.0,
13+
156.0, 198.0, 373.0, 326.0
14+
],
15+
"description": "The anchors to create bounding box candidates."
16+
},
17+
"scale_x_y": {
18+
"type": "number",
19+
"default": [1.0, 1.0, 1.0],
20+
"description": "scale parameter to eliminate grid sensitivity."
21+
},
22+
"score_thresh": {
23+
"type": "number",
24+
"default": 0.1,
25+
"description": "If the objectness score is less than this value, the object is ignored in yolo layer."
26+
},
27+
"iou_thresh": {
28+
"type": "number",
29+
"default": 0.45,
30+
"description": "The iou threshold for NMS method."
31+
},
32+
"detections_per_im": {
33+
"type": "number",
34+
"default": 100,
35+
"description": " The maximum detection number for one frame."
36+
},
37+
"use_darknet_layer": {
38+
"type": "boolean",
39+
"default": true,
40+
"description": "The flag to use yolo layer in darknet."
41+
},
42+
"ignore_thresh": {
43+
"type": "number",
44+
"default": 0.5,
45+
"description": "If the output score is less than this value, this object is ignored."
46+
},
47+
"onnx_file": {
48+
"type": "string",
49+
"description": "The onnx file name for yolo model."
50+
},
51+
"engine_file": {
52+
"type": "string",
53+
"description": "The tensorrt engine file name for yolo model."
54+
},
55+
"label_file": {
56+
"type": "string",
57+
"description": "The label file with label names for detected objects written on it."
58+
},
59+
"calib_image_directory": {
60+
"type": "string",
61+
"description": "The directory name including calibration images for int8 inference."
62+
},
63+
"calib_cache_file": {
64+
"type": "string",
65+
"description": "The calibration cache file for int8 inference."
66+
},
67+
"mode": {
68+
"type": "string",
69+
"default": "FP32",
70+
"description": "The inference mode: FP32, FP16, INT8."
71+
},
72+
"gpu_id": {
73+
"type": "number",
74+
"default": 0,
75+
"description": "GPU device ID that runs the model."
76+
}
77+
},
78+
"required": [
79+
"num_anchors",
80+
"scale_x_y",
81+
"score_thresh",
82+
"iou_thresh",
83+
"detections_per_im",
84+
"use_darknet_layer",
85+
"ignore_thresh",
86+
"onnx_file",
87+
"engine_file",
88+
"label_file",
89+
"calib_image_directory",
90+
"calib_cache_file",
91+
"mode",
92+
"gpu_id"
93+
]
94+
}
95+
},
96+
"properties": {
97+
"/**": {
98+
"type": "object",
99+
"properties": {
100+
"ros__parameters": {
101+
"$ref": "#/definitions/tensorrt_yolo"
102+
}
103+
},
104+
"required": ["ros__parameters"]
105+
}
106+
},
107+
"required": ["/**"]
108+
}

perception/tensorrt_yolo/src/nodelet.cpp

+8-8
Original file line numberDiff line numberDiff line change
@@ -50,9 +50,9 @@ TensorrtYoloNodelet::TensorrtYoloNodelet(const rclcpp::NodeOptions & options)
5050
std::string label_file = declare_parameter("label_file", "");
5151
std::string calib_image_directory = declare_parameter("calib_image_directory", "");
5252
std::string calib_cache_file = declare_parameter("calib_cache_file", "");
53-
std::string mode = declare_parameter("mode", "FP32");
54-
gpu_device_id_ = declare_parameter("gpu_id", 0);
55-
yolo_config_.num_anchors = declare_parameter("num_anchors", 3);
53+
std::string mode = declare_parameter<std::string>("mode");
54+
gpu_device_id_ = declare_parameter<int>("gpu_id");
55+
yolo_config_.num_anchors = declare_parameter<int>("num_anchors");
5656
auto anchors = declare_parameter(
5757
"anchors", std::vector<double>{
5858
10, 13, 16, 30, 33, 23, 30, 61, 62, 45, 59, 119, 116, 90, 156, 198, 373, 326});
@@ -61,11 +61,11 @@ TensorrtYoloNodelet::TensorrtYoloNodelet(const rclcpp::NodeOptions & options)
6161
auto scale_x_y = declare_parameter("scale_x_y", std::vector<double>{1.0, 1.0, 1.0});
6262
std::vector<float> scale_x_y_float(scale_x_y.begin(), scale_x_y.end());
6363
yolo_config_.scale_x_y = scale_x_y_float;
64-
yolo_config_.score_thresh = declare_parameter("score_thresh", 0.1);
65-
yolo_config_.iou_thresh = declare_parameter("iou_thresh", 0.45);
66-
yolo_config_.detections_per_im = declare_parameter("detections_per_im", 100);
67-
yolo_config_.use_darknet_layer = declare_parameter("use_darknet_layer", true);
68-
yolo_config_.ignore_thresh = declare_parameter("ignore_thresh", 0.5);
64+
yolo_config_.score_thresh = declare_parameter<double>("score_thresh");
65+
yolo_config_.iou_thresh = declare_parameter<double>("iou_thresh");
66+
yolo_config_.detections_per_im = declare_parameter<int>("detections_per_im");
67+
yolo_config_.use_darknet_layer = declare_parameter<bool>("use_darknet_layer");
68+
yolo_config_.ignore_thresh = declare_parameter<double>("ignore_thresh");
6969

7070
if (!yolo::set_cuda_device(gpu_device_id_)) {
7171
RCLCPP_ERROR(this->get_logger(), "Given GPU not exist or suitable");

0 commit comments

Comments
 (0)