Skip to content

Commit

Permalink
cv_bridge test: remove boost
Browse files Browse the repository at this point in the history
  • Loading branch information
zhouchengming committed Dec 25, 2019
1 parent 845f9af commit 3c31a30
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 5 deletions.
1 change: 0 additions & 1 deletion cv_bridge/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
16 changes: 12 additions & 4 deletions cv_bridge/test/test_endian.cpp
Original file line number Diff line number Diff line change
@@ -1,12 +1,20 @@
#include <boost/endian/conversion.hpp>
#include <cv_bridge/cv_bridge.h>
#include <gtest/gtest.h>
#include <memory>

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;
Expand All @@ -18,7 +26,7 @@ TEST(CvBridgeTest, endianness)
int32_t * data = reinterpret_cast<int32_t *>(&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<int32_t>(1));
*data = native_to_big(static_cast<int32_t>(2));
Expand Down

0 comments on commit 3c31a30

Please sign in to comment.