@@ -66,6 +66,7 @@ bool ColorDetector::load_configuration(const std::string & path)
6666 try {
6767 utils::Color color (
6868 item.key (),
69+ item.value ().at (" invert_hue" ).get <bool >(),
6970 item.value ().at (" min_hsv" )[0 ],
7071 item.value ().at (" max_hsv" )[0 ],
7172 item.value ().at (" min_hsv" )[1 ],
@@ -96,11 +97,13 @@ bool ColorDetector::save_configuration()
9697 nlohmann::json config = nlohmann::json::array ();
9798
9899 for (auto & item : colors) {
100+ bool invert_hue = item.invert_hue ;
99101 int min_hsv[] = {item.min_hue , item.min_saturation , item.min_value };
100102 int max_hsv[] = {item.max_hue , item.max_saturation , item.max_value };
101103
102104 nlohmann::json color = {
103105 {item.name , {
106+ {" invert_hue" , invert_hue},
104107 {" min_hsv" , min_hsv},
105108 {" max_hsv" , max_hsv}
106109 }}
@@ -129,6 +132,7 @@ void ColorDetector::configure_color_setting(utils::Color color)
129132{
130133 for (auto & item : colors) {
131134 if (item.name == color.name ) {
135+ item.invert_hue = color.invert_hue ;
132136 item.min_hue = color.min_hue ;
133137 item.max_hue = color.max_hue ;
134138 item.min_saturation = color.min_saturation ;
@@ -143,8 +147,8 @@ void ColorDetector::configure_color_setting(utils::Color color)
143147
144148cv::Mat ColorDetector::classify (cv::Mat input)
145149{
146- int h_min = (min_hue * 255 ) / 100 ;
147- int h_max = (max_hue * 255 ) / 100 ;
150+ int h_min = (min_hue * 180 ) / 360 ;
151+ int h_max = (max_hue * 180 ) / 360 ;
148152
149153 int s_min = (min_saturation * 255 ) / 100 ;
150154 int s_max = (max_saturation * 255 ) / 100 ;
@@ -157,7 +161,29 @@ cv::Mat ColorDetector::classify(cv::Mat input)
157161
158162 cv::Mat output = input.clone ();
159163
160- cv::inRange (input, hsv_min, hsv_max, output);
164+ if (invert_hue) {
165+ cv::Mat mask1, mask2;
166+
167+ cv::inRange (input,
168+ cv::Scalar (0 , s_min, v_min),
169+ cv::Scalar (h_min, s_max, v_max),
170+ mask1
171+ );
172+
173+ cv::inRange (input,
174+ cv::Scalar (h_max, s_min, v_min),
175+ cv::Scalar (180 , s_max, v_max),
176+ mask2
177+ );
178+
179+ cv::bitwise_or (mask1, mask2, output);
180+ } else {
181+ cv::inRange (input,
182+ cv::Scalar (h_min, s_min, v_min),
183+ cv::Scalar (h_max, s_max, v_max),
184+ output
185+ );
186+ }
161187
162188 cv::Mat element = cv::getStructuringElement (cv::MORPH_ELLIPSE, cv::Size (3 , 3 ), cv::Point (1 , 1 ));
163189 cv::morphologyEx (output, output, cv::MORPH_CLOSE, element);
@@ -202,6 +228,7 @@ void ColorDetector::detection(const cv::Mat & image)
202228 // iterate every color in colors
203229 for (auto & color : colors) {
204230 color_name = color.name ;
231+ invert_hue = color.invert_hue ;
205232 min_hue = color.min_hue ;
206233 max_hue = color.max_hue ;
207234 min_saturation = color.min_saturation ;
0 commit comments