Skip to content

Commit f1a33ee

Browse files
tby-udelchtseng
authored and
chtseng
committed
refactor(tensorrt_yolox): rework parameters (autowarefoundation#7338)
Signed-off-by: chtseng <chtseng@itri.org.tw>
1 parent 8bf6936 commit f1a33ee

File tree

4 files changed

+27
-100
lines changed

4 files changed

+27
-100
lines changed

perception/tensorrt_yolox/README.md

+2-38
Original file line numberDiff line numberDiff line change
@@ -31,44 +31,8 @@ Zheng Ge, Songtao Liu, Feng Wang, Zeming Li, Jian Sun, "YOLOX: Exceeding YOLO Se
3131

3232
## Parameters
3333

34-
### Core Parameters
35-
36-
| Name | Type | Default Value | Description |
37-
| ----------------- | ----- | ------------- | -------------------------------------------------------------------------------------- |
38-
| `score_threshold` | float | 0.3 | If the objectness score is less than this value, the object is ignored in yolox layer. |
39-
| `nms_threshold` | float | 0.7 | The IoU threshold for NMS method |
40-
41-
**NOTE:** These two parameters are only valid for "plain" model (described later).
42-
43-
### Node Parameters
44-
45-
| Name | Type | Default Value | Description |
46-
| -------------------------------------- | ------ | ------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
47-
| `model_path` | string | "" | The onnx file name for yolox model |
48-
| `model_name` | string | "" | The yolox model name: <br /> "yolox-sPlus-T4-960x960-pseudo-finetune" for detection only, could reduce resource and processing_time <br /> "yolox-sPlus-opt-pseudoV2-T4-960x960-T4-seg16cls" for multi-task including semantic segmentation |
49-
| `label_path` | string | "" | The label file with label names for detected objects written on it |
50-
| `precision` | string | "fp16" | The inference mode: "fp32", "fp16", "int8" |
51-
| `build_only` | bool | false | shutdown node after TensorRT engine file is built |
52-
| `calibration_algorithm` | string | "MinMax" | Calibration algorithm to be used for quantization when precision==int8. Valid value is one of: Entropy",("Legacy" \| "Percentile"), "MinMax"] |
53-
| `dla_core_id` | int | -1 | If positive ID value is specified, the node assign inference task to the DLA core |
54-
| `quantize_first_layer` | bool | false | If true, set the operating precision for the first (input) layer to be fp16. This option is valid only when precision==int8 |
55-
| `quantize_last_layer` | bool | false | If true, set the operating precision for the last (output) layer to be fp16. This option is valid only when precision==int8 |
56-
| `profile_per_layer` | bool | false | If true, profiler function will be enabled. Since the profile function may affect execution speed, it is recommended to set this flag true only for development purpose. |
57-
| `clip_value` | double | 0.0 | If positive value is specified, the value of each layer output will be clipped between [0.0, clip_value]. This option is valid only when precision==int8 and used to manually specify the dynamic range instead of using any calibration |
58-
| `preprocess_on_gpu` | bool | true | If true, pre-processing is performed on GPU |
59-
| `calibration_image_list_path` | string | "" | Path to a file which contains path to images. Those images will be used for int8 quantization. |
60-
| `yolox_s_plus_opt_param_path` | string | "" | Path to parameter file |
61-
| `is_publish_color_mask` | bool | false | If true, publish color mask for result visualization |
62-
| `is_roi_overlap_segment` | bool | true | If true, overlay detected object roi onto semantic segmentation to avoid over-filtering pointcloud especially small size objects |
63-
| `overlap_roi_score_threshold` | float | 0.3 | minimum existence_probability of detected roi considered to replace segmentation |
64-
| `roi_overlay_segment_label.UNKNOWN` | bool | true | If true, unknown objects roi will be overlaid onto sematic segmentation mask. |
65-
| `roi_overlay_segment_label.CAR` | bool | false | If true, car objects roi will be overlaid onto sematic segmentation mask. |
66-
| `roi_overlay_segment_label.TRUCK` | bool | false | If true, truck objects roi will be overlaid onto sematic segmentation mask. |
67-
| `roi_overlay_segment_label.BUS` | bool | false | If true, bus objects roi will be overlaid onto sematic segmentation mask. |
68-
| `roi_overlay_segment_label.MOTORCYCLE` | bool | true | If true, motorcycle objects roi will be overlaid onto sematic segmentation mask. |
69-
| `roi_overlay_segment_label.BICYCLE` | bool | true | If true, bicycle objects roi will be overlaid onto sematic segmentation mask. |
70-
| `roi_overlay_segment_label.PEDESTRIAN` | bool | true | If true, pedestrian objects roi will be overlaid onto sematic segmentation mask. |
71-
| `roi_overlay_segment_label.ANIMAL` | bool | true | If true, animal objects roi will be overlaid onto sematic segmentation mask. |
34+
{{ json_to_markdown("perception/tensorrt_yolox/schema/yolox_s_plus_opt.schema.json") }}
35+
{{ json_to_markdown("perception/tensorrt_yolox/schema/yolox_tiny.schema.json") }}
7236

7337
## Assumptions / Known limits
7438

perception/tensorrt_yolox/config/yolox_s_plus_opt.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
# cspell: ignore semseg
22
/**:
33
ros__parameters:
4+
45
# refine segmentation mask by overlay roi class
56
# disable when sematic segmentation accuracy is good enough
67
is_roi_overlap_segment: true
@@ -26,6 +27,7 @@
2627
color_map_path: "$(var data_path)/tensorrt_yolox/semseg_color_map.csv"
2728
score_threshold: 0.35
2829
nms_threshold: 0.7
30+
2931
precision: "int8" # Operation precision to be used on inference. Valid value is one of: [fp32, fp16, int8].
3032
calibration_algorithm: "Entropy" # Calibration algorithm to be used for quantization when precision==int8. Valid value is one of: [Entropy, (Legacy | Percentile), MinMax].
3133
dla_core_id: -1 # If positive ID value is specified, the node assign inference task to the DLA core.

perception/tensorrt_yolox/config/yolox_tiny.param.yaml

+4-4
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,9 @@
11
/**:
22
ros__parameters:
3-
model_path: "$(var data_path)/tensorrt_yolox/$(var model_name).onnx"
4-
label_path: "$(var data_path)/tensorrt_yolox/label.txt"
5-
score_threshold: 0.35
6-
nms_threshold: 0.7
3+
model_path: "$(var data_path)/tensorrt_yolox/$(var model_name).onnx" # The onnx file name for YOLOX model.
4+
label_path: "$(var data_path)/tensorrt_yolox/label.txt" # The label file path for YOLOX model.
5+
score_threshold: 0.35 # 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.
6+
nms_threshold: 0.7 # Detection results will be ignored if IoU over this value. This threshold will be ignored if specified model contains EfficientNMS_TRT module in it.
77
precision: "fp16" # Operation precision to be used on inference. Valid value is one of: [fp32, fp16, int8].
88
calibration_algorithm: "MinMax" # Calibration algorithm to be used for quantization when precision==int8. Valid value is one of: [Entropy, (Legacy | Percentile), MinMax].
99
dla_core_id: -1 # If positive ID value is specified, the node assign inference task to the DLA core.

perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp

+19-58
Original file line numberDiff line numberDiff line change
@@ -40,64 +40,25 @@ TrtYoloXNode::TrtYoloXNode(const rclcpp::NodeOptions & node_options)
4040
using std::placeholders::_1;
4141
using std::chrono_literals::operator""ms;
4242

43-
auto declare_parameter_with_description =
44-
[this](std::string name, auto default_val, std::string description = "") {
45-
auto param_desc = rcl_interfaces::msg::ParameterDescriptor{};
46-
param_desc.description = description;
47-
return this->declare_parameter(name, default_val, param_desc);
48-
};
49-
50-
std::string model_path =
51-
declare_parameter_with_description("model_path", "", "The onnx file name for YOLOX model");
52-
std::string label_path = declare_parameter_with_description(
53-
"label_path", "",
54-
"The label file that consists of label name texts for detected object categories");
55-
std::string precision = declare_parameter_with_description(
56-
"precision", "fp32",
57-
"operation precision to be used on inference. Valid value is one of: [fp32, fp16, int8]");
58-
float score_threshold = declare_parameter_with_description(
59-
"score_threshold", 0.3,
60-
("Objects with a score lower than this value will be ignored. "
61-
"This threshold will be ignored if specified model contains EfficientNMS_TRT module in it"));
62-
float nms_threshold = declare_parameter_with_description(
63-
"nms_threshold", 0.7,
64-
("Detection results will be ignored if IoU over this value. "
65-
"This threshold will be ignored if specified model contains EfficientNMS_TRT module in it"));
66-
std::string calibration_algorithm = declare_parameter_with_description(
67-
"calibration_algorithm", "MinMax",
68-
("Calibration algorithm to be used for quantization when precision==int8. "
69-
"Valid value is one of: [Entropy, (Legacy | Percentile), MinMax]"));
70-
int dla_core_id = declare_parameter_with_description(
71-
"dla_core_id", -1,
72-
"If positive ID value is specified, the node assign inference task to the DLA core");
73-
bool quantize_first_layer = declare_parameter_with_description(
74-
"quantize_first_layer", false,
75-
("If true, set the operating precision for the first (input) layer to be fp16. "
76-
"This option is valid only when precision==int8"));
77-
bool quantize_last_layer = declare_parameter_with_description(
78-
"quantize_last_layer", false,
79-
("If true, set the operating precision for the last (output) layer to be fp16. "
80-
"This option is valid only when precision==int8"));
81-
bool profile_per_layer = declare_parameter_with_description(
82-
"profile_per_layer", false,
83-
("If true, profiler function will be enabled. "
84-
"Since the profile function may affect execution speed, it is recommended "
85-
"to set this flag true only for development purpose."));
86-
double clip_value = declare_parameter_with_description(
87-
"clip_value", 0.0,
88-
("If positive value is specified, "
89-
"the value of each layer output will be clipped between [0.0, clip_value]. "
90-
"This option is valid only when precision==int8 and used to manually specify "
91-
"the dynamic range instead of using any calibration"));
92-
bool preprocess_on_gpu = declare_parameter_with_description(
93-
"preprocess_on_gpu", true, "If true, pre-processing is performed on GPU");
94-
std::string calibration_image_list_path = declare_parameter_with_description(
95-
"calibration_image_list_path", "",
96-
("Path to a file which contains path to images."
97-
"Those images will be used for int8 quantization."));
98-
99-
std::string color_map_path = declare_parameter_with_description(
100-
"color_map_path", "", ("Path to a file which contains path to color map."));
43+
const std::string model_path = this->declare_parameter<std::string>("model_path");
44+
const std::string label_path = this->declare_parameter<std::string>("label_path");
45+
const std::string precision = this->declare_parameter<std::string>("precision");
46+
const float score_threshold =
47+
static_cast<float>(this->declare_parameter<double>("score_threshold"));
48+
const float nms_threshold = static_cast<float>(this->declare_parameter<double>("nms_threshold"));
49+
const std::string calibration_algorithm =
50+
this->declare_parameter<std::string>("calibration_algorithm");
51+
const int dla_core_id = this->declare_parameter<int>("dla_core_id");
52+
const bool quantize_first_layer = this->declare_parameter<bool>("quantize_first_layer");
53+
const bool quantize_last_layer = this->declare_parameter<bool>("quantize_last_layer");
54+
const bool profile_per_layer = this->declare_parameter<bool>("profile_per_layer");
55+
const double clip_value = this->declare_parameter<double>("clip_value");
56+
const bool preprocess_on_gpu = this->declare_parameter<bool>("preprocess_on_gpu");
57+
const std::string calibration_image_list_path =
58+
this->declare_parameter<std::string>("calibration_image_list_path");
59+
60+
std::string color_map_path = this->declare_parameter<std::string>("color_map_path");
61+
10162
if (!readLabelFile(label_path)) {
10263
RCLCPP_ERROR(this->get_logger(), "Could not find label file");
10364
rclcpp::shutdown();

0 commit comments

Comments
 (0)