diff --git a/cv_bridge/include/cv_bridge/cv_mat_sensor_msgs_image_type_adapter.hpp b/cv_bridge/include/cv_bridge/cv_mat_sensor_msgs_image_type_adapter.hpp index 7902304c1..38bc63c39 100644 --- a/cv_bridge/include/cv_bridge/cv_mat_sensor_msgs_image_type_adapter.hpp +++ b/cv_bridge/include/cv_bridge/cv_mat_sensor_msgs_image_type_adapter.hpp @@ -22,6 +22,7 @@ #include "opencv2/core/mat.hpp" #include "rclcpp/type_adapter.hpp" +#include "rcpputils/endian.hpp" #include "sensor_msgs/msg/image.hpp" #include "cv_bridge/visibility_control.h" @@ -30,24 +31,6 @@ namespace cv_bridge { -namespace detail -{ -// TODO(audrow): Replace with std::endian when C++ 20 is available -// https://en.cppreference.com/w/cpp/types/endian -enum class endian -{ -#ifdef _WIN32 - little = 0, - big = 1, - native = little -#else - little = __ORDER_LITTLE_ENDIAN__, - big = __ORDER_BIG_ENDIAN__, - native = __BYTE_ORDER__ -#endif -}; - -} // namespace detail /// A potentially owning, potentially non-owning, container of a cv::Mat and ROS header. @@ -85,7 +68,7 @@ enum class endian */ class ROSCvMatContainer { - static constexpr bool is_bigendian_system = detail::endian::native == detail::endian::big; + static constexpr bool is_bigendian_system = rcpputils::endian::native == rcpputils::endian::big; public: using SensorMsgsImageStorageType = std::variant< diff --git a/cv_bridge/package.xml b/cv_bridge/package.xml index fe34f46d8..9c6c3e193 100644 --- a/cv_bridge/package.xml +++ b/cv_bridge/package.xml @@ -19,7 +19,6 @@ ament_cmake_ros python_cmake_module - libboost-dev libboost-python-dev libopencv-dev diff --git a/cv_bridge/src/cv_bridge.cpp b/cv_bridge/src/cv_bridge.cpp index e763e5da7..1ccd337c0 100644 --- a/cv_bridge/src/cv_bridge.cpp +++ b/cv_bridge/src/cv_bridge.cpp @@ -36,7 +36,6 @@ #include #include -#include #include #include #include diff --git a/cv_bridge/test/test_endian.cpp b/cv_bridge/test/test_endian.cpp index 088091822..92d151aec 100644 --- a/cv_bridge/test/test_endian.cpp +++ b/cv_bridge/test/test_endian.cpp @@ -1,12 +1,10 @@ -#include #include #include #include +#include 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; @@ -15,17 +13,31 @@ TEST(CvBridgeTest, endianness) msg.step = 8; msg.data.resize(msg.step); - int32_t * data = reinterpret_cast(&msg.data[0]); + uint8_t * raw = msg.data.data(); // Write 1 and 2 in order, but with an endianness opposite to the platform - if (order::native == order::little) { + if (rcpputils::endian::native == rcpputils::endian::little) { msg.is_bigendian = true; - *(data++) = native_to_big(static_cast(1)); - *data = native_to_big(static_cast(2)); + raw[0] = 0x00; + raw[1] = 0x00; + raw[2] = 0x00; + raw[3] = 0x01; + + raw[4] = 0x00; + raw[5] = 0x00; + raw[6] = 0x00; + raw[7] = 0x02; } else { msg.is_bigendian = false; - *(data++) = native_to_little(static_cast(1)); - *data = native_to_little(static_cast(2)); + raw[0] = 0x01; + raw[1] = 0x00; + raw[2] = 0x00; + raw[3] = 0x00; + + raw[4] = 0x02; + raw[5] = 0x00; + raw[6] = 0x00; + raw[7] = 0x00; } // Make sure the values are still the same