Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(autoware_traffic_light_classifier): add traffic light classifier schema, README and car and ped launcher #10048

Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ def create_parameter_dict(*args):
plugin="autoware::traffic_light::TrafficLightClassifierNodelet",
name="car_traffic_light_classifier",
namespace="classification",
parameters=[car_traffic_light_classifier_model_param],
parameters=[car_traffic_light_classifier_model_param, {"build_only": False}],
remappings=[
("~/input/image", camera_arguments["input/image"]),
("~/input/rois", camera_arguments["output/rois"]),
Expand All @@ -112,7 +112,7 @@ def create_parameter_dict(*args):
plugin="autoware::traffic_light::TrafficLightClassifierNodelet",
name="pedestrian_traffic_light_classifier",
namespace="classification",
parameters=[pedestrian_traffic_light_classifier_model_param],
parameters=[pedestrian_traffic_light_classifier_model_param, {"build_only": False}],
remappings=[
("~/input/image", camera_arguments["input/image"]),
("~/input/rois", camera_arguments["output/rois"]),
Expand Down Expand Up @@ -179,7 +179,7 @@ def create_parameter_dict(*args):
plugin="autoware::traffic_light::TrafficLightFineDetectorNode",
name="traffic_light_fine_detector",
namespace=f"{namespace}/detection",
parameters=[fine_detector_model_param],
parameters=[fine_detector_model_param, {"build_only": False}],
remappings=[
("~/input/image", camera_arguments["input/image"]),
("~/input/rois", "rough/rois"),
Expand Down Expand Up @@ -227,16 +227,14 @@ def add_launch_arg(name: str, default_value=None, description=None):
# traffic_light_classifier
add_launch_arg(
"car_classifier_param_path",
os.path.join(
classifier_share_dir, "config", "car_traffic_light_classifier_efficientNet.param.yaml"
),
os.path.join(classifier_share_dir, "config", "car_traffic_light_classifier.param.yaml"),
)
add_launch_arg(
"pedestrian_classifier_param_path",
os.path.join(
classifier_share_dir,
"config",
"pedestrian_traffic_light_classifier_efficientNet.param.yaml",
"pedestrian_traffic_light_classifier.param.yaml",
),
)

Expand Down
22 changes: 8 additions & 14 deletions perception/autoware_traffic_light_classifier/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -63,25 +63,19 @@ These colors and shapes are assigned to the message as follows:

### Node Parameters

| Name | Type | Description |
| ----------------------------- | ------ | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| `classifier_type` | int | If the value is `1`, cnn_classifier is used |
| `data_path` | str | Packages data and artifacts directory path |
| `backlight_threshold` | double | If the intensity of light is grater than this threshold, the color and shape of the corresponding ROI will be overwritten with UNKNOWN, and the confidence of the overwritten signal will be set to `0.0`. The value should be set in the range of `[0.0, 1.0]`. If you wouldn't like to use this feature, please set it to `1.0`. |
| `classify_traffic_light_type` | int | If the value is `0`, vehicular signals are classified. If the value is `1`, pedestrian signals are classified. |
#### car_traffic_light_classifier

{{ json_to_markdown("perception/autoware_traffic_light_classifier/schema/car_traffic_light_classifier.schema.json") }}

#### pedestrian_traffic_light_classifier

{{ json_to_markdown("perception/autoware_traffic_light_classifier/schema/pedestrian_traffic_light_classifier.schema.json") }}

### Core Parameters

#### cnn_classifier

| Name | Type | Description |
| ----------------------- | --------------- | ------------------------------------ |
| `classifier_label_path` | str | path to the model file |
| `classifier_model_path` | str | path to the label file |
| `classifier_precision` | str | TensorRT precision, `fp16` or `int8` |
| `classifier_mean` | vector\<double> | 3-channel input image mean |
| `classifier_std` | vector\<double> | 3-channel input image std |
| `apply_softmax` | bool | whether or not apply softmax |
Including [this section](#car_traffic_light_classifier)

#### hsv_classifier

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,5 +7,5 @@
classifier_mean: [123.675, 116.28, 103.53]
classifier_std: [58.395, 57.12, 57.375]
backlight_threshold: 0.85
classifier_type: 1 #classifier_type {hsv_filter: 0, cnn: 1}
classify_traffic_light_type: 0 #classify_traffic_light_type {car: 0, pedestrian:1}
classifier_type: 1
classify_traffic_light_type: 0
Original file line number Diff line number Diff line change
Expand Up @@ -7,5 +7,5 @@
classifier_mean: [123.675, 116.28, 103.53]
classifier_std: [58.395, 57.12, 57.375]
backlight_threshold: 0.85
classifier_type: 1 #classifier_type {hsv_filter: 0, cnn: 1}
classify_traffic_light_type: 1 #classify_traffic_light_type {car: 0, pedestrian:1}
classifier_type: 1
classify_traffic_light_type: 1
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,11 @@
<arg name="input/image" default="~/image_raw"/>
<arg name="input/rois" default="~/rois"/>
<arg name="output/traffic_signals" default="classified/traffic_signals"/>
<arg name="traffic_light_classifier_param_path" default="$(find-pkg-share autoware_traffic_light_classifier)/config/traffic_light_classifier.param.yaml" description="classifier param path"/>
<arg name="data_path" default="$(env HOME)/autoware_data" description="packages data and artifacts directory path"/>
<arg name="traffic_light_classifier_param_path" default="$(find-pkg-share autoware_traffic_light_classifier)/config/car_traffic_light_classifier.param.yaml" description="classifier param path"/>
<arg name="traffic_light_classifier_model_path" default="$(var data_path)/traffic_light_classifier" description="path to car onnx model and label"/>
<arg name="car_traffic_light_classifier_label_name" default="lamp_labels.txt" description="car label name"/>
<arg name="car_traffic_light_classifier_model_name" default="traffic_light_classifier_mobilenetv2_batch_6" description="car onnx model name"/>
<arg name="build_only" default="false" description="exit after trt engine is built"/>

<node pkg="autoware_traffic_light_classifier" exec="traffic_light_classifier_node" name="traffic_light_classifier" output="screen">
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<launch>
<arg name="input/image" default="~/image_raw"/>
<arg name="input/rois" default="~/rois"/>
<arg name="output/traffic_signals" default="classified/traffic_signals"/>
<arg name="data_path" default="$(env HOME)/autoware_data" description="packages data and artifacts directory path"/>
<arg
name="traffic_light_classifier_param_path"
default="$(find-pkg-share autoware_traffic_light_classifier)/config/pedestrian_traffic_light_classifier.param.yaml"
description="classifier param path"
/>
<arg name="traffic_light_classifier_model_path" default="$(var data_path)/traffic_light_classifier" description="path to pedestrian onnx model and label"/>
<arg name="pedestrian_traffic_light_classifier_label_name" default="lamp_labels_ped.txt" description="pedestrian label name"/>
<arg name="pedestrian_traffic_light_classifier_model_name" default="ped_traffic_light_classifier_mobilenetv2_batch_6" description="pedestrian onnx model name"/>
<arg name="build_only" default="false" description="exit after trt engine is built"/>

<node pkg="autoware_traffic_light_classifier" exec="traffic_light_classifier_node" name="traffic_light_classifier" output="screen">
<remap from="~/input/image" to="$(var input/image)"/>
<remap from="~/input/rois" to="$(var input/rois)"/>
<remap from="~/output/traffic_signals" to="$(var output/traffic_signals)"/>
<param from="$(var traffic_light_classifier_param_path)" allow_substs="true"/>
<param name="build_only" value="$(var build_only)"/>
</node>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "autoware_traffic_light_classifier parameter",
"type": "object",
"definitions": {
"car_traffic_light_classifier": {
"type": "object",
"properties": {
"approximate_sync": {
"type": "boolean",
"description": "Enable or disable approximate synchronization.",
"default": false
},
"classifier_label_path": {
"type": "string",
"description": "Path to the label file for the traffic light classifier.",
"default": "$(var traffic_light_classifier_model_path)/$(var car_traffic_light_classifier_label_name)"
},
"classifier_model_path": {
"type": "string",
"description": "Path to the ONNX model file for the traffic light classifier.",
"default": "$(var traffic_light_classifier_model_path)/$(var car_traffic_light_classifier_model_name).onnx"
},
"classifier_precision": {
"type": "string",
"description": "Precision used for traffic light classifier inference. Valid values: [fp32, fp16, int8].",
"default": "fp16"
},
"classifier_mean": {
"type": "array",
"description": "Mean values used for input normalization [R, G, B].",
"items": {
"type": "number"
},
"default": [123.675, 116.28, 103.53]
},
"classifier_std": {
"type": "array",
"description": "Standard deviation values used for input normalization [R, G, B].",
"items": {
"type": "number"
},
"default": [58.395, 57.12, 57.375]
},
"backlight_threshold": {
"type": "number",
"description": "If the intensity get grater than this overwrite with UNKNOWN in corresponding RoI. Note that, if the value is much higher, the node only overwrites in the harsher backlight situations. Therefore, If you wouldn't like to use this feature set this value to `1.0`. The value can be `[0.0, 1.0]`. The confidence of overwritten signal is set to `0.0`.",
"default": 0.85
},
"classifier_type": {
"type": "integer",
"description": "Type of classifier used. {0: hsv_filter, 1: cnn}.",
"default": 1
},
"classify_traffic_light_type": {
"type": "integer",
"description": "Type of traffic light to classify. {0: car, 1: pedestrian}.",
"default": 0
}
},
"required": [
"approximate_sync",
"classifier_label_path",
"classifier_model_path",
"classifier_precision",
"classifier_mean",
"classifier_std",
"backlight_threshold",
"classifier_type",
"classify_traffic_light_type"
],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/car_traffic_light_classifier"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "autoware_traffic_light_classifier parameter",
"type": "object",
"definitions": {
"pedestrian_traffic_light_classifier": {
"type": "object",
"properties": {
"approximate_sync": {
"type": "boolean",
"description": "Enable or disable approximate synchronization.",
"default": false
},
"classifier_label_path": {
"type": "string",
"description": "Path to the label file for the traffic light classifier.",
"default": "$(var traffic_light_classifier_model_path)/$(var pedestrian_traffic_light_classifier_label_name)"
},
"classifier_model_path": {
"type": "string",
"description": "Path to the ONNX model file for the traffic light classifier.",
"default": "$(var traffic_light_classifier_model_path)/$(var pedestrian_traffic_light_classifier_model_name).onnx"
},
"classifier_precision": {
"type": "string",
"description": "Precision used for traffic light classifier inference. Valid values: [fp32, fp16, int8].",
"default": "fp16"
},
"classifier_mean": {
"type": "array",
"description": "Mean values used for input normalization [R, G, B].",
"items": {
"type": "number"
},
"default": [123.675, 116.28, 103.53]
},
"classifier_std": {
"type": "array",
"description": "Standard deviation values used for input normalization [R, G, B].",
"items": {
"type": "number"
},
"default": [58.395, 57.12, 57.375]
},
"backlight_threshold": {
"type": "number",
"description": "If the intensity get grater than this overwrite with UNKNOWN in corresponding RoI. Note that, if the value is much higher, the node only overwrites in the harsher backlight situations. Therefore, If you wouldn't like to use this feature set this value to `1.0`. The value can be `[0.0, 1.0]`. The confidence of overwritten signal is set to `0.0`.",
"default": 0.85
},
"classifier_type": {
"type": "integer",
"description": "Type of classifier used. {0: hsv_filter, 1: cnn}.",
"default": 1
},
"classify_traffic_light_type": {
"type": "integer",
"description": "Type of traffic light to classify. {0: car, 1: pedestrian}.",
"default": 1
}
},
"required": [
"approximate_sync",
"classifier_label_path",
"classifier_model_path",
"classifier_precision",
"classifier_mean",
"classifier_std",
"backlight_threshold",
"classifier_type",
"classify_traffic_light_type"
],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/pedestrian_traffic_light_classifier"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Original file line number Diff line number Diff line change
Expand Up @@ -34,15 +34,13 @@
std::string precision;
std::string label_file_path;
std::string model_file_path;
precision = node_ptr_->declare_parameter("classifier_precision", "fp16");
label_file_path = node_ptr_->declare_parameter("classifier_label_path", "labels.txt");
model_file_path = node_ptr_->declare_parameter("classifier_model_path", "model.onnx");
precision = node_ptr_->declare_parameter<std::string>("classifier_precision");
label_file_path = node_ptr_->declare_parameter<std::string>("classifier_label_path");
model_file_path = node_ptr_->declare_parameter<std::string>("classifier_model_path");

Check warning on line 39 in perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp#L37-L39

Added lines #L37 - L39 were not covered by tests
// ros param does not support loading std::vector<float>
// we have to load std::vector<double> and transfer to std::vector<float>
auto mean_d =
node_ptr->declare_parameter("classifier_mean", std::vector<double>{123.675, 116.28, 103.53});
auto std_d =
node_ptr->declare_parameter("classifier_std", std::vector<double>{58.395, 57.12, 57.375});
auto mean_d = node_ptr->declare_parameter<std::vector<double>>("classifier_mean");
auto std_d = node_ptr->declare_parameter<std::vector<double>>("classifier_std");

Check warning on line 43 in perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp#L42-L43

Added lines #L42 - L43 were not covered by tests
mean_ = std::vector<float>(mean_d.begin(), mean_d.end());
std_ = std::vector<float>(std_d.begin(), std_d.end());
if (mean_.size() != 3 || std_.size() != 3) {
Expand All @@ -55,7 +53,7 @@
classifier_ = std::make_unique<autoware::tensorrt_classifier::TrtClassifier>(
model_file_path, precision, mean_, std_);
batch_size_ = classifier_->getBatchSize();
if (node_ptr_->declare_parameter("build_only", false)) {
if (node_ptr_->declare_parameter<bool>("build_only")) {
RCLCPP_INFO(node_ptr_->get_logger(), "TensorRT engine is built and shutdown node.");
rclcpp::shutdown();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,11 +25,11 @@
TrafficLightClassifierNodelet::TrafficLightClassifierNodelet(const rclcpp::NodeOptions & options)
: Node("traffic_light_classifier_node", options)
{
classify_traffic_light_type_ = this->declare_parameter("classify_traffic_light_type", 0);
classify_traffic_light_type_ = this->declare_parameter<int>("classify_traffic_light_type");

Check warning on line 28 in perception/autoware_traffic_light_classifier/src/traffic_light_classifier_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_traffic_light_classifier/src/traffic_light_classifier_node.cpp#L28

Added line #L28 was not covered by tests

using std::placeholders::_1;
using std::placeholders::_2;
is_approximate_sync_ = this->declare_parameter("approximate_sync", false);
is_approximate_sync_ = this->declare_parameter<bool>("approximate_sync");

Check warning on line 32 in perception/autoware_traffic_light_classifier/src/traffic_light_classifier_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_traffic_light_classifier/src/traffic_light_classifier_node.cpp#L32

Added line #L32 was not covered by tests
backlight_threshold_ = this->declare_parameter<double>("backlight_threshold");

if (is_approximate_sync_) {
Expand All @@ -49,8 +49,7 @@
timer_ = rclcpp::create_timer(
this, get_clock(), 100ms, std::bind(&TrafficLightClassifierNodelet::connectCb, this));

int classifier_type = this->declare_parameter(
"classifier_type", static_cast<int>(TrafficLightClassifierNodelet::ClassifierType::HSVFilter));
int classifier_type = this->declare_parameter<int>("classifier_type");

Check warning on line 52 in perception/autoware_traffic_light_classifier/src/traffic_light_classifier_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_traffic_light_classifier/src/traffic_light_classifier_node.cpp#L52

Added line #L52 was not covered by tests
if (classifier_type == TrafficLightClassifierNodelet::ClassifierType::HSVFilter) {
classifier_ptr_ = std::make_shared<ColorClassifier>(this);
} else if (classifier_type == TrafficLightClassifierNodelet::ClassifierType::CNN) {
Expand Down
Loading