1 #include "boost/endian/conversion.hpp"
2 #include <boost/make_shared.hpp>
4 #include <gtest/gtest.h>
6 TEST(CvBridgeTest, endianness)
8 using namespace boost::endian;
11 sensor_msgs::Image msg;
14 msg.encoding =
"32SC2";
17 msg.data.resize(msg.step);
18 int32_t* data =
reinterpret_cast<int32_t*
>(&msg.data[0]);
21 if (order::native == order::little)
23 msg.is_bigendian =
true;
24 *(data++) = native_to_big(
static_cast<int32_t
>(1));
25 *data = native_to_big(
static_cast<int32_t
>(2));
27 msg.is_bigendian =
false;
28 *(data++) = native_to_little(
static_cast<int32_t
>(1));
29 *data = native_to_little(
static_cast<int32_t
>(2));
34 EXPECT_EQ(img->image.at<cv::Vec2i>(0, 0)[0], 1);
35 EXPECT_EQ(img->image.at<cv::Vec2i>(0, 0)[1], 2);
37 EXPECT_NE(img->image.data, &msg.data[0]);