@@ -27,24 +27,24 @@ ColorClassifier::ColorClassifier(rclcpp::Node * node_ptr) : node_ptr_(node_ptr)
27
27
image_pub_ = image_transport::create_publisher (
28
28
node_ptr_, " ~/debug/image" , rclcpp::QoS{1 }.get_rmw_qos_profile ());
29
29
30
- hsv_config_.green_min_h = node_ptr_->declare_parameter (" green_min_h" , 50 );
31
- hsv_config_.green_min_s = node_ptr_->declare_parameter (" green_min_s" , 100 );
32
- hsv_config_.green_min_v = node_ptr_->declare_parameter (" green_min_v" , 150 );
33
- hsv_config_.green_max_h = node_ptr_->declare_parameter (" green_max_h" , 120 );
34
- hsv_config_.green_max_s = node_ptr_->declare_parameter (" green_max_s" , 200 );
35
- hsv_config_.green_max_v = node_ptr_->declare_parameter (" green_max_v" , 255 );
36
- hsv_config_.yellow_min_h = node_ptr_->declare_parameter (" yellow_min_h" , 0 );
37
- hsv_config_.yellow_min_s = node_ptr_->declare_parameter (" yellow_min_s" , 80 );
38
- hsv_config_.yellow_min_v = node_ptr_->declare_parameter (" yellow_min_v" , 150 );
39
- hsv_config_.yellow_max_h = node_ptr_->declare_parameter (" yellow_max_h" , 50 );
40
- hsv_config_.yellow_max_s = node_ptr_->declare_parameter (" yellow_max_s" , 200 );
41
- hsv_config_.yellow_max_v = node_ptr_->declare_parameter (" yellow_max_v" , 255 );
42
- hsv_config_.red_min_h = node_ptr_->declare_parameter (" red_min_h" , 160 );
43
- hsv_config_.red_min_s = node_ptr_->declare_parameter (" red_min_s" , 100 );
44
- hsv_config_.red_min_v = node_ptr_->declare_parameter (" red_min_v" , 150 );
45
- hsv_config_.red_max_h = node_ptr_->declare_parameter (" red_max_h" , 180 );
46
- hsv_config_.red_max_s = node_ptr_->declare_parameter (" red_max_s" , 255 );
47
- hsv_config_.red_max_v = node_ptr_->declare_parameter (" red_max_v" , 255 );
30
+ hsv_config_.green_min_h = node_ptr_->declare_parameter < int > (" green_min_h" );
31
+ hsv_config_.green_min_s = node_ptr_->declare_parameter < int > (" green_min_s" );
32
+ hsv_config_.green_min_v = node_ptr_->declare_parameter < int > (" green_min_v" );
33
+ hsv_config_.green_max_h = node_ptr_->declare_parameter < int > (" green_max_h" );
34
+ hsv_config_.green_max_s = node_ptr_->declare_parameter < int > (" green_max_s" );
35
+ hsv_config_.green_max_v = node_ptr_->declare_parameter < int > (" green_max_v" );
36
+ hsv_config_.yellow_min_h = node_ptr_->declare_parameter < int > (" yellow_min_h" );
37
+ hsv_config_.yellow_min_s = node_ptr_->declare_parameter < int > (" yellow_min_s" );
38
+ hsv_config_.yellow_min_v = node_ptr_->declare_parameter < int > (" yellow_min_v" );
39
+ hsv_config_.yellow_max_h = node_ptr_->declare_parameter < int > (" yellow_max_h" );
40
+ hsv_config_.yellow_max_s = node_ptr_->declare_parameter < int > (" yellow_max_s" );
41
+ hsv_config_.yellow_max_v = node_ptr_->declare_parameter < int > (" yellow_max_v" );
42
+ hsv_config_.red_min_h = node_ptr_->declare_parameter < int > (" red_min_h" );
43
+ hsv_config_.red_min_s = node_ptr_->declare_parameter < int > (" red_min_s" );
44
+ hsv_config_.red_min_v = node_ptr_->declare_parameter < int > (" red_min_v" );
45
+ hsv_config_.red_max_h = node_ptr_->declare_parameter < int > (" red_max_h" );
46
+ hsv_config_.red_max_s = node_ptr_->declare_parameter < int > (" red_max_s" );
47
+ hsv_config_.red_max_v = node_ptr_->declare_parameter < int > (" red_max_v" );
48
48
49
49
// set parameter callback
50
50
set_param_res_ = node_ptr_->add_on_set_parameters_callback (
0 commit comments