Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand All @@ -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.
Expand Down Expand Up @@ -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<
Expand Down
1 change: 0 additions & 1 deletion cv_bridge/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
<buildtool_depend>ament_cmake_ros</buildtool_depend>
<buildtool_depend>python_cmake_module</buildtool_depend>

<build_depend>libboost-dev</build_depend>
<build_depend>libboost-python-dev</build_depend>

<depend>libopencv-dev</depend>
Expand Down
1 change: 0 additions & 1 deletion cv_bridge/src/cv_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,6 @@

#include <cv_bridge/cv_bridge.hpp>
#include <cv_bridge/rgb_colors.hpp>
#include <boost/endian/conversion.hpp>
#include <opencv2/imgcodecs.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <sensor_msgs/image_encodings.hpp>
Expand Down
30 changes: 21 additions & 9 deletions cv_bridge/test/test_endian.cpp
Original file line number Diff line number Diff line change
@@ -1,12 +1,10 @@
#include <boost/endian/conversion.hpp>
#include <cv_bridge/cv_bridge.hpp>
#include <gtest/gtest.h>
#include <memory>
#include <rcpputils/endian.hpp>

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;
Expand All @@ -15,17 +13,31 @@ TEST(CvBridgeTest, endianness)
msg.step = 8;

msg.data.resize(msg.step);
int32_t * data = reinterpret_cast<int32_t *>(&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<int32_t>(1));
*data = native_to_big(static_cast<int32_t>(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<int32_t>(1));
*data = native_to_little(static_cast<int32_t>(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
Expand Down