Skip to content

Commit

Permalink
refactor(perception-tensortt-yolo): rework parameters (#5918)
Browse files Browse the repository at this point in the history
perception-tensortt-yolo

Signed-off-by: karishma <karishma@interpl.ai>
  • Loading branch information
karishma1911 authored Dec 28, 2023
1 parent 51a8af8 commit 6efa91b
Show file tree
Hide file tree
Showing 2 changed files with 116 additions and 8 deletions.
108 changes: 108 additions & 0 deletions perception/tensorrt_yolo/schema/tensortt_yolo.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,108 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for tensorrt_yolo",
"type": "object",
"definitions": {
"tensorrt_yolo": {
"type": "object",
"properties": {
"num_anchors": {
"type": "number",
"default": [
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,
156.0, 198.0, 373.0, 326.0
],
"description": "The anchors to create bounding box candidates."
},
"scale_x_y": {
"type": "number",
"default": [1.0, 1.0, 1.0],
"description": "scale parameter to eliminate grid sensitivity."
},
"score_thresh": {
"type": "number",
"default": 0.1,
"description": "If the objectness score is less than this value, the object is ignored in yolo layer."
},
"iou_thresh": {
"type": "number",
"default": 0.45,
"description": "The iou threshold for NMS method."
},
"detections_per_im": {
"type": "number",
"default": 100,
"description": " The maximum detection number for one frame."
},
"use_darknet_layer": {
"type": "boolean",
"default": true,
"description": "The flag to use yolo layer in darknet."
},
"ignore_thresh": {
"type": "number",
"default": 0.5,
"description": "If the output score is less than this value, this object is ignored."
},
"onnx_file": {
"type": "string",
"description": "The onnx file name for yolo model."
},
"engine_file": {
"type": "string",
"description": "The tensorrt engine file name for yolo model."
},
"label_file": {
"type": "string",
"description": "The label file with label names for detected objects written on it."
},
"calib_image_directory": {
"type": "string",
"description": "The directory name including calibration images for int8 inference."
},
"calib_cache_file": {
"type": "string",
"description": "The calibration cache file for int8 inference."
},
"mode": {
"type": "string",
"default": "FP32",
"description": "The inference mode: FP32, FP16, INT8."
},
"gpu_id": {
"type": "number",
"default": 0,
"description": "GPU device ID that runs the model."
}
},
"required": [
"num_anchors",
"scale_x_y",
"score_thresh",
"iou_thresh",
"detections_per_im",
"use_darknet_layer",
"ignore_thresh",
"onnx_file",
"engine_file",
"label_file",
"calib_image_directory",
"calib_cache_file",
"mode",
"gpu_id"
]
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/tensorrt_yolo"
}
},
"required": ["ros__parameters"]
}
},
"required": ["/**"]
}
16 changes: 8 additions & 8 deletions perception/tensorrt_yolo/src/nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,9 +50,9 @@ TensorrtYoloNodelet::TensorrtYoloNodelet(const rclcpp::NodeOptions & options)
std::string label_file = declare_parameter("label_file", "");
std::string calib_image_directory = declare_parameter("calib_image_directory", "");
std::string calib_cache_file = declare_parameter("calib_cache_file", "");
std::string mode = declare_parameter("mode", "FP32");
gpu_device_id_ = declare_parameter("gpu_id", 0);
yolo_config_.num_anchors = declare_parameter("num_anchors", 3);
std::string mode = declare_parameter<std::string>("mode");
gpu_device_id_ = declare_parameter<int>("gpu_id");
yolo_config_.num_anchors = declare_parameter<int>("num_anchors");
auto anchors = declare_parameter(
"anchors", std::vector<double>{
10, 13, 16, 30, 33, 23, 30, 61, 62, 45, 59, 119, 116, 90, 156, 198, 373, 326});
Expand All @@ -61,11 +61,11 @@ TensorrtYoloNodelet::TensorrtYoloNodelet(const rclcpp::NodeOptions & options)
auto scale_x_y = declare_parameter("scale_x_y", std::vector<double>{1.0, 1.0, 1.0});
std::vector<float> scale_x_y_float(scale_x_y.begin(), scale_x_y.end());
yolo_config_.scale_x_y = scale_x_y_float;
yolo_config_.score_thresh = declare_parameter("score_thresh", 0.1);
yolo_config_.iou_thresh = declare_parameter("iou_thresh", 0.45);
yolo_config_.detections_per_im = declare_parameter("detections_per_im", 100);
yolo_config_.use_darknet_layer = declare_parameter("use_darknet_layer", true);
yolo_config_.ignore_thresh = declare_parameter("ignore_thresh", 0.5);
yolo_config_.score_thresh = declare_parameter<double>("score_thresh");
yolo_config_.iou_thresh = declare_parameter<double>("iou_thresh");
yolo_config_.detections_per_im = declare_parameter<int>("detections_per_im");
yolo_config_.use_darknet_layer = declare_parameter<bool>("use_darknet_layer");
yolo_config_.ignore_thresh = declare_parameter<double>("ignore_thresh");

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

0 comments on commit 6efa91b

Please sign in to comment.