Skip to content

Commit

Permalink
perception-traffic-light-classifier
Browse files Browse the repository at this point in the history
  • Loading branch information
karishma1911 committed Dec 6, 2023
1 parent 60b4030 commit 4d8fd78
Show file tree
Hide file tree
Showing 3 changed files with 175 additions and 21 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,154 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for traffic_light_classifier",
"type": "object",
"definitions": {
"traffic_light_classifier": {
"type": "object",
"properties": {
"classifier_label_path": {
"type": "string",
"default": "labels.txt",
"description": "path to the model file."
},
"classifier_model_path": {
"type": "string",
"default": "model.onnx",
"description": "path to the label file."
},
"classifier_precision": {
"type": "string",
"default": "fp16",
"description": "TensorRT precision, `fp16` or `int8."
},
"classifier_mean": {
"type": "number",
"default": 123.675,
"description": "3-channel input image mean."
},
"classifier_std": {
"type": "number",
"default": 58.395,
"description": "3-channel input image std."
},
"apply_softmax": {
"type": "boolean",
"description": "whether or not apply softmax."
},
"green_min_h": {
"type": "number",
"default": 10,
"description": "the minimum hue of green color."
},
"green_min_s": {
"type": "number",
"default": 100,
"description": "the minimum saturation of green color."
},
"green_min_v": {
"type": "number",
"default": 150,
"description": "the minimum value (brightness) of green color."
},
"green_max_h": {
"type": "number",
"default": 120,
"description": "the maximum hue of green color."
},
"green_max_s": {
"type": "number",
"default": 200,
"description": "the maximum saturation of green color."
},
"green_max_v": {
"type": "number",
"default": 255,
"description": "the maximum value (brightness) of green color."
},
"yellow_min_h": {
"type": "number",
"default": 0,
"description": "the minimum hue of yellow color."
},
"yellow_min_s": {
"type": "number",
"default": 80,
"description": "the minimum saturation of yellow color."
},
"yellow_min_v": {
"type": "number",
"default": 150,
"description": "the minimum value (brightness) of yellow color."
},
"yellow_max_h": {
"type": "number",
"default": 50,
"description": "the maximum hue of yellow color."
},
"yellow_max_s": {
"type": "number",
"default": 200,
"description": "the maximum saturation of yellow color."
},
"yellow_max_v": {
"type": "number",
"default": 255,
"description": "the maximum value (brightness) of yellow color."
},
"red_min_h": {
"type": "number",
"default": 160,
"description": "the minimum hue of red color."
},
"red_min_s": {
"type": "number",
"default": 100,
"description": "the minimum saturation of red color."
},
"red_min_v": {
"type": "number",
"default": 150,
"description": "the minimum value (brightness) of red color."
},
"red_max_h": {
"type": "number",
"default": 180,
"description": "the maximum hue of red color."
},
"red_max_s": {
"type": "number",
"default": 255,
"description": "the maximum saturation of red color."
},
"red_max_v": {
"type": "number",
"default": 255,
"description": "the maximum value (brightness) of red color."
}
},
"required": [
"warn_rate",
"window_size",
"timeout",
"error_rate",
"update_rate",
"topic",
"transient_local",
"best_effort",
"diag_name"
]
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/traffic_light_classifier"
}
},
"required": ["ros__parameters"]
}
},
"required": ["/**"]
}
6 changes: 3 additions & 3 deletions perception/traffic_light_classifier/src/cnn_classifier.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,9 @@ CNNClassifier::CNNClassifier(rclcpp::Node * node_ptr) : node_ptr_(node_ptr)
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");
// 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 =
Expand Down
36 changes: 18 additions & 18 deletions perception/traffic_light_classifier/src/color_classifier.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,24 +27,24 @@ ColorClassifier::ColorClassifier(rclcpp::Node * node_ptr) : node_ptr_(node_ptr)
image_pub_ = image_transport::create_publisher(
node_ptr_, "~/debug/image", rclcpp::QoS{1}.get_rmw_qos_profile());

hsv_config_.green_min_h = node_ptr_->declare_parameter("green_min_h", 50);
hsv_config_.green_min_s = node_ptr_->declare_parameter("green_min_s", 100);
hsv_config_.green_min_v = node_ptr_->declare_parameter("green_min_v", 150);
hsv_config_.green_max_h = node_ptr_->declare_parameter("green_max_h", 120);
hsv_config_.green_max_s = node_ptr_->declare_parameter("green_max_s", 200);
hsv_config_.green_max_v = node_ptr_->declare_parameter("green_max_v", 255);
hsv_config_.yellow_min_h = node_ptr_->declare_parameter("yellow_min_h", 0);
hsv_config_.yellow_min_s = node_ptr_->declare_parameter("yellow_min_s", 80);
hsv_config_.yellow_min_v = node_ptr_->declare_parameter("yellow_min_v", 150);
hsv_config_.yellow_max_h = node_ptr_->declare_parameter("yellow_max_h", 50);
hsv_config_.yellow_max_s = node_ptr_->declare_parameter("yellow_max_s", 200);
hsv_config_.yellow_max_v = node_ptr_->declare_parameter("yellow_max_v", 255);
hsv_config_.red_min_h = node_ptr_->declare_parameter("red_min_h", 160);
hsv_config_.red_min_s = node_ptr_->declare_parameter("red_min_s", 100);
hsv_config_.red_min_v = node_ptr_->declare_parameter("red_min_v", 150);
hsv_config_.red_max_h = node_ptr_->declare_parameter("red_max_h", 180);
hsv_config_.red_max_s = node_ptr_->declare_parameter("red_max_s", 255);
hsv_config_.red_max_v = node_ptr_->declare_parameter("red_max_v", 255);
hsv_config_.green_min_h = node_ptr_->declare_parameter<int>("green_min_h");
hsv_config_.green_min_s = node_ptr_->declare_parameter<int>("green_min_s");
hsv_config_.green_min_v = node_ptr_->declare_parameter<int>("green_min_v");
hsv_config_.green_max_h = node_ptr_->declare_parameter<int>("green_max_h");
hsv_config_.green_max_s = node_ptr_->declare_parameter<int>("green_max_s");
hsv_config_.green_max_v = node_ptr_->declare_parameter<int>("green_max_v");
hsv_config_.yellow_min_h = node_ptr_->declare_parameter<int>("yellow_min_h");
hsv_config_.yellow_min_s = node_ptr_->declare_parameter<int>("yellow_min_s");
hsv_config_.yellow_min_v = node_ptr_->declare_parameter<int>("yellow_min_v");
hsv_config_.yellow_max_h = node_ptr_->declare_parameter<int>("yellow_max_h");
hsv_config_.yellow_max_s = node_ptr_->declare_parameter<int>("yellow_max_s");
hsv_config_.yellow_max_v = node_ptr_->declare_parameter<int>("yellow_max_v");
hsv_config_.red_min_h = node_ptr_->declare_parameter<int>("red_min_h");
hsv_config_.red_min_s = node_ptr_->declare_parameter<int>("red_min_s");
hsv_config_.red_min_v = node_ptr_->declare_parameter<int>("red_min_v");
hsv_config_.red_max_h = node_ptr_->declare_parameter<int>("red_max_h");
hsv_config_.red_max_s = node_ptr_->declare_parameter<int>("red_max_s");
hsv_config_.red_max_v = node_ptr_->declare_parameter<int>("red_max_v");

// set parameter callback
set_param_res_ = node_ptr_->add_on_set_parameters_callback(
Expand Down

0 comments on commit 4d8fd78

Please sign in to comment.