diff --git a/cv_bridge/test/CMakeLists.txt b/cv_bridge/test/CMakeLists.txt index cbc03e98d..367ae8685 100644 --- a/cv_bridge/test/CMakeLists.txt +++ b/cv_bridge/test/CMakeLists.txt @@ -14,7 +14,6 @@ endif() # enable cv_bridge C++ tests find_package(ament_cmake_gtest REQUIRED) ament_add_gtest(${PROJECT_NAME}-utest - test_endian.cpp test_compression.cpp utest.cpp utest2.cpp test_rgb_colors.cpp diff --git a/cv_bridge/test/test_endian.cpp b/cv_bridge/test/test_endian.cpp index 270105413..a276c52a3 100644 --- a/cv_bridge/test/test_endian.cpp +++ b/cv_bridge/test/test_endian.cpp @@ -1,12 +1,20 @@ -#include #include #include #include +typedef union uEndianTest { + struct { + bool flittle_endian; + bool fill[3]; + }; + long value; +} EndianTest; + +static const EndianTest __Endian_Test__ = { .value=1 }; +const bool platform_big_endian = !__Endian_Test__.flittle_endian; + TEST(CvBridgeTest, endianness) { - using namespace boost::endian; - // Create an image of the type opposite to the platform sensor_msgs::msg::Image msg; msg.height = 1; @@ -18,7 +26,7 @@ TEST(CvBridgeTest, endianness) int32_t * data = reinterpret_cast(&msg.data[0]); // Write 1 and 2 in order, but with an endianness opposite to the platform - if (order::native == order::little) { + if (!platform_big_endian) { msg.is_bigendian = true; *(data++) = native_to_big(static_cast(1)); *data = native_to_big(static_cast(2));