Skip to content

Commit 446e749

Browse files
ZeysthingzZeynep Akbalıkpre-commit-ci[bot]
authored
feat(traffic_light_classifier): add parameters to launch file for using different tensorrt models (autowarefoundation#2794)
* feat(traffic_light_classifier): add params to launch file Signed-off-by: Zeynep Akbalık <zeynep@leodrive.ai> --------- Signed-off-by: Zeynep Akbalık <zeynep@leodrive.ai> Co-authored-by: Zeynep Akbalık <zeynep@leodrive.ai> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 4267add commit 446e749

File tree

4 files changed

+24
-13
lines changed

4 files changed

+24
-13
lines changed

perception/traffic_light_classifier/README.md

+13-9
Original file line numberDiff line numberDiff line change
@@ -54,15 +54,19 @@ These colors and shapes are assigned to the message as follows:
5454

5555
#### cnn_classifier
5656

57-
| Name | Type | Description |
58-
| ----------------- | ---- | ------------------------------------------------- |
59-
| `model_file_path` | str | path to the model file |
60-
| `label_file_path` | str | path to the label file |
61-
| `precision` | str | TensorRT precision, `fp16` or `int8` |
62-
| `input_c` | str | the channel size of an input image |
63-
| `input_h` | str | the height of an input image |
64-
| `input_w` | str | the width of an input image |
65-
| `build_only` | bool | shutdown node after TensorRT engine file is built |
57+
| Name | Type | Description |
58+
| ----------------- | ------ | ------------------------------------------------- |
59+
| `model_file_path` | str | path to the model file |
60+
| `label_file_path` | str | path to the label file |
61+
| `precision` | str | TensorRT precision, `fp16` or `int8` |
62+
| `input_c` | str | the channel size of an input image |
63+
| `input_h` | str | the height of an input image |
64+
| `input_w` | str | the width of an input image |
65+
| `input_name` | str | the name of neural network's input layer |
66+
| `output_name` | str | the name of neural network's output name |
67+
| `mean` | double | mean values for image normalization |
68+
| `std` | double | std values for image normalization |
69+
| `build_only` | bool | shutdown node after TensorRT engine file is built |
6670

6771
#### hsv_classifier
6872

perception/traffic_light_classifier/include/traffic_light_classifier/cnn_classifier.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -101,8 +101,8 @@ class CNNClassifier : public ClassifierInterface
101101
std::shared_ptr<Tn::TrtCommon> trt_;
102102
image_transport::Publisher image_pub_;
103103
std::vector<std::string> labels_;
104-
std::vector<float> mean_{0.242, 0.193, 0.201};
105-
std::vector<float> std_{1.0, 1.0, 1.0};
104+
std::vector<double> mean_;
105+
std::vector<double> std_;
106106
int input_c_;
107107
int input_h_;
108108
int input_w_;

perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml

+5
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,12 @@
1919
<param name="classifier_type" value="$(var classifier_type)"/>
2020
<param name="model_file_path" value="$(find-pkg-share traffic_light_classifier)/data/traffic_light_classifier_mobilenetv2.onnx"/>
2121
<param name="label_file_path" value="$(find-pkg-share traffic_light_classifier)/data/lamp_labels.txt"/>
22+
<param name="mean" value="[0.242, 0.193, 0.201]"/>
23+
<param name="std" value="[1.0, 1.0, 1.0]"/>
2224
<param name="precision" value="fp16"/>
25+
<param name="input_name" value="input_0"/>
26+
<param name="output_name" value="output_0"/>
27+
<param name="apply_softmax" value="true"/>
2328
<param name="input_c" value="3"/>
2429
<param name="input_h" value="224"/>
2530
<param name="input_w" value="224"/>

perception/traffic_light_classifier/src/cnn_classifier.cpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -39,8 +39,10 @@ CNNClassifier::CNNClassifier(rclcpp::Node * node_ptr) : node_ptr_(node_ptr)
3939
input_c_ = node_ptr_->declare_parameter("input_c", 3);
4040
input_h_ = node_ptr_->declare_parameter("input_h", 224);
4141
input_w_ = node_ptr_->declare_parameter("input_w", 224);
42-
auto input_name = node_ptr_->declare_parameter("input_name", "input_0");
43-
auto output_name = node_ptr_->declare_parameter("output_name", "output_0");
42+
mean_ = node_ptr_->declare_parameter("mean", std::vector<double>({0.242, 0.193, 0.201}));
43+
std_ = node_ptr_->declare_parameter("std", std::vector<double>({1.0, 1.0, 1.0}));
44+
std::string input_name = node_ptr_->declare_parameter("input_name", std::string("input_0"));
45+
std::string output_name = node_ptr_->declare_parameter("output_name", std::string("output_0"));
4446
apply_softmax_ = node_ptr_->declare_parameter("apply_softmax", true);
4547

4648
readLabelfile(label_file_path, labels_);

0 commit comments

Comments
 (0)