From 2cd5ec755d3bccdcc175cb4d2cd36b67c0ab3d8a Mon Sep 17 00:00:00 2001 From: Christian Rauch Date: Sat, 11 May 2024 17:12:38 +0200 Subject: [PATCH 1/4] mark encodings YUV422 and YUV422_YUY2 as deprecated Signed-off-by: Christian Rauch --- sensor_msgs/include/sensor_msgs/image_encodings.hpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/sensor_msgs/include/sensor_msgs/image_encodings.hpp b/sensor_msgs/include/sensor_msgs/image_encodings.hpp index c3274700..eac5a144 100644 --- a/sensor_msgs/include/sensor_msgs/image_encodings.hpp +++ b/sensor_msgs/include/sensor_msgs/image_encodings.hpp @@ -97,9 +97,11 @@ const char BAYER_GRBG16[] = "bayer_grbg16"; // https://www.kernel.org/doc/html/latest/userspace-api/media/v4l/pixfmt-packed-yuv.html#id1 // fourcc: UYVY const char UYVY[] = "uyvy"; +[[deprecated("use sensor_msgs::image_encodings::UYVY")]] const char YUV422[] = "yuv422"; // deprecated // fourcc: YUYV const char YUYV[] = "yuyv"; +[[deprecated("use sensor_msgs::image_encodings::YUYV")]] const char YUV422_YUY2[] = "yuv422_yuy2"; // deprecated // YUV 4:2:0 encodings with an 8-bit depth From 23e84d3c6cb98fb637b4c603be8e378e53fbfa93 Mon Sep 17 00:00:00 2001 From: Christian Rauch Date: Sat, 11 May 2024 18:57:38 +0200 Subject: [PATCH 2/4] replace deprecated encodings in encoding test Signed-off-by: Christian Rauch --- sensor_msgs/test/test_image_encodings.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/sensor_msgs/test/test_image_encodings.cpp b/sensor_msgs/test/test_image_encodings.cpp index 9cfef93e..c2aefd5f 100644 --- a/sensor_msgs/test/test_image_encodings.cpp +++ b/sensor_msgs/test/test_image_encodings.cpp @@ -48,8 +48,8 @@ TEST(sensor_msgs, NumChannels) ASSERT_EQ(sensor_msgs::image_encodings::numChannels("64FC"), 1); ASSERT_EQ(sensor_msgs::image_encodings::numChannels("64FC3"), 3); ASSERT_EQ(sensor_msgs::image_encodings::numChannels("64FC10"), 10); - ASSERT_EQ(sensor_msgs::image_encodings::numChannels("yuv422"), 2); - ASSERT_EQ(sensor_msgs::image_encodings::numChannels("yuv422_yuy2"), 2); + ASSERT_EQ(sensor_msgs::image_encodings::numChannels("uyvy"), 2); + ASSERT_EQ(sensor_msgs::image_encodings::numChannels("yuyv"), 2); } TEST(sensor_msgs, bitDepth) @@ -68,6 +68,6 @@ TEST(sensor_msgs, bitDepth) ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("64FC"), 64); ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("64FC3"), 64); ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("64FC10"), 64); - ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("yuv422"), 8); - ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("yuv422_yuy2"), 8); + ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("uyvy"), 8); + ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("yuyv"), 8); } From e387982e53251499cffb658b4004722cf8f4b297 Mon Sep 17 00:00:00 2001 From: Christian Rauch Date: Sat, 25 May 2024 12:10:37 +0200 Subject: [PATCH 3/4] ignore deprecation warning inside the encoding header Signed-off-by: Christian Rauch --- sensor_msgs/include/sensor_msgs/image_encodings.hpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/sensor_msgs/include/sensor_msgs/image_encodings.hpp b/sensor_msgs/include/sensor_msgs/image_encodings.hpp index eac5a144..63ff15d5 100644 --- a/sensor_msgs/include/sensor_msgs/image_encodings.hpp +++ b/sensor_msgs/include/sensor_msgs/image_encodings.hpp @@ -122,6 +122,8 @@ const std::regex cv_type_regex("(8|16|32|64)(U|S|F)C([0-9]*)"); // Utility functions for inspecting an encoding string static inline bool isColor(const std::string & encoding) { +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" return encoding == RGB8 || encoding == BGR8 || encoding == RGBA8 || encoding == BGRA8 || encoding == RGB16 || encoding == BGR16 || @@ -129,6 +131,7 @@ static inline bool isColor(const std::string & encoding) encoding == YUV422 || encoding == YUV422_YUY2 || encoding == UYVY || encoding == YUYV || encoding == NV21 || encoding == NV24; +#pragma GCC diagnostic pop } static inline bool isMono(const std::string & encoding) @@ -191,6 +194,8 @@ static inline int numChannels(const std::string & encoding) return (m[3] == "") ? 1 : std::atoi(m[3].str().c_str()); } +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" if (encoding == YUV422 || encoding == YUV422_YUY2 || encoding == UYVY || @@ -200,6 +205,7 @@ static inline int numChannels(const std::string & encoding) { return 2; } +#pragma GCC diagnostic pop throw std::runtime_error("Unknown encoding " + encoding); return -1; @@ -243,6 +249,8 @@ static inline int bitDepth(const std::string & encoding) return std::atoi(m[0].str().c_str()); } +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" if (encoding == YUV422 || encoding == YUV422_YUY2 || encoding == UYVY || @@ -252,6 +260,7 @@ static inline int bitDepth(const std::string & encoding) { return 8; } +#pragma GCC diagnostic pop throw std::runtime_error("Unknown encoding " + encoding); return -1; From ae55818fb0e58e7c7ccfcb55a2a69f8004b6c176 Mon Sep 17 00:00:00 2001 From: Christian Rauch Date: Thu, 5 Sep 2024 23:08:26 +0200 Subject: [PATCH 4/4] ignore deprecation warning inside the encoding header on Windows Signed-off-by: Christian Rauch --- .../include/sensor_msgs/image_encodings.hpp | 27 +++++++++++++++++++ 1 file changed, 27 insertions(+) diff --git a/sensor_msgs/include/sensor_msgs/image_encodings.hpp b/sensor_msgs/include/sensor_msgs/image_encodings.hpp index 63ff15d5..1cabbbf2 100644 --- a/sensor_msgs/include/sensor_msgs/image_encodings.hpp +++ b/sensor_msgs/include/sensor_msgs/image_encodings.hpp @@ -122,8 +122,13 @@ const std::regex cv_type_regex("(8|16|32|64)(U|S|F)C([0-9]*)"); // Utility functions for inspecting an encoding string static inline bool isColor(const std::string & encoding) { +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable : 4996) +#else #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif return encoding == RGB8 || encoding == BGR8 || encoding == RGBA8 || encoding == BGRA8 || encoding == RGB16 || encoding == BGR16 || @@ -131,7 +136,11 @@ static inline bool isColor(const std::string & encoding) encoding == YUV422 || encoding == YUV422_YUY2 || encoding == UYVY || encoding == YUYV || encoding == NV21 || encoding == NV24; +#ifdef _MSC_VER +#pragma warning(pop) +#else #pragma GCC diagnostic pop +#endif } static inline bool isMono(const std::string & encoding) @@ -194,8 +203,13 @@ static inline int numChannels(const std::string & encoding) return (m[3] == "") ? 1 : std::atoi(m[3].str().c_str()); } +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable : 4996) +#else #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif if (encoding == YUV422 || encoding == YUV422_YUY2 || encoding == UYVY || @@ -205,7 +219,11 @@ static inline int numChannels(const std::string & encoding) { return 2; } +#ifdef _MSC_VER +#pragma warning(pop) +#else #pragma GCC diagnostic pop +#endif throw std::runtime_error("Unknown encoding " + encoding); return -1; @@ -249,8 +267,13 @@ static inline int bitDepth(const std::string & encoding) return std::atoi(m[0].str().c_str()); } +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable : 4996) +#else #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif if (encoding == YUV422 || encoding == YUV422_YUY2 || encoding == UYVY || @@ -260,7 +283,11 @@ static inline int bitDepth(const std::string & encoding) { return 8; } +#ifdef _MSC_VER +#pragma warning(pop) +#else #pragma GCC diagnostic pop +#endif throw std::runtime_error("Unknown encoding " + encoding); return -1;