@@ -97,9 +97,11 @@ const char BAYER_GRBG16[] = "bayer_grbg16";
9797// https://www.kernel.org/doc/html/latest/userspace-api/media/v4l/pixfmt-packed-yuv.html#id1
9898// fourcc: UYVY
9999const char UYVY[] = " uyvy" ;
100+ [[deprecated(" use sensor_msgs::image_encodings::UYVY" )]]
100101const char YUV422[] = " yuv422" ; // deprecated
101102// fourcc: YUYV
102103const char YUYV[] = " yuyv" ;
104+ [[deprecated(" use sensor_msgs::image_encodings::YUYV" )]]
103105const char YUV422_YUY2[] = " yuv422_yuy2" ; // deprecated
104106
105107// YUV 4:2:0 encodings with an 8-bit depth
@@ -120,13 +122,16 @@ const std::regex cv_type_regex("(8|16|32|64)(U|S|F)C([0-9]*)");
120122// Utility functions for inspecting an encoding string
121123static inline bool isColor (const std::string & encoding)
122124{
125+ #pragma GCC diagnostic push
126+ #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
123127 return encoding == RGB8 || encoding == BGR8 ||
124128 encoding == RGBA8 || encoding == BGRA8 ||
125129 encoding == RGB16 || encoding == BGR16 ||
126130 encoding == RGBA16 || encoding == BGRA16 ||
127131 encoding == YUV422 || encoding == YUV422_YUY2 ||
128132 encoding == UYVY || encoding == YUYV ||
129133 encoding == NV21 || encoding == NV24;
134+ #pragma GCC diagnostic pop
130135}
131136
132137static inline bool isMono (const std::string & encoding)
@@ -189,6 +194,8 @@ static inline int numChannels(const std::string & encoding)
189194 return (m[3 ] == " " ) ? 1 : std::atoi (m[3 ].str ().c_str ());
190195 }
191196
197+ #pragma GCC diagnostic push
198+ #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
192199 if (encoding == YUV422 ||
193200 encoding == YUV422_YUY2 ||
194201 encoding == UYVY ||
@@ -198,6 +205,7 @@ static inline int numChannels(const std::string & encoding)
198205 {
199206 return 2 ;
200207 }
208+ #pragma GCC diagnostic pop
201209
202210 throw std::runtime_error (" Unknown encoding " + encoding);
203211 return -1 ;
@@ -241,6 +249,8 @@ static inline int bitDepth(const std::string & encoding)
241249 return std::atoi (m[0 ].str ().c_str ());
242250 }
243251
252+ #pragma GCC diagnostic push
253+ #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
244254 if (encoding == YUV422 ||
245255 encoding == YUV422_YUY2 ||
246256 encoding == UYVY ||
@@ -250,6 +260,7 @@ static inline int bitDepth(const std::string & encoding)
250260 {
251261 return 8 ;
252262 }
263+ #pragma GCC diagnostic pop
253264
254265 throw std::runtime_error (" Unknown encoding " + encoding);
255266 return -1 ;
0 commit comments