test_endian.cpp
Go to the documentation of this file.
00001 #include "boost/endian/conversion.hpp"
00002 #include <boost/make_shared.hpp>
00003 #include <cv_bridge/cv_bridge.h>
00004 #include <gtest/gtest.h>
00005 
00006 TEST(CvBridgeTest, endianness)
00007 {
00008   using namespace boost::endian;
00009 
00010   // Create an image of the type opposite to the platform
00011   sensor_msgs::Image msg;
00012   msg.height = 1;
00013   msg.width = 1;
00014   msg.encoding = "32SC2";
00015   msg.step = 8;
00016 
00017   msg.data.resize(msg.step);
00018   int32_t* data = reinterpret_cast<int32_t*>(&msg.data[0]);
00019 
00020   // Write 1 and 2 in order, but with an endianness opposite to the platform
00021   if (order::native == order::little)
00022   {
00023     msg.is_bigendian = true;
00024     *(data++) = native_to_big(static_cast<int32_t>(1));
00025     *data = native_to_big(static_cast<int32_t>(2));
00026   } else {
00027     msg.is_bigendian = false;
00028     *(data++) = native_to_little(static_cast<int32_t>(1));
00029     *data = native_to_little(static_cast<int32_t>(2));
00030   }
00031 
00032   // Make sure the values are still the same
00033   cv_bridge::CvImageConstPtr img = cv_bridge::toCvShare(boost::make_shared<sensor_msgs::Image>(msg));
00034   EXPECT_EQ(img->image.at<cv::Vec2i>(0, 0)[0], 1);
00035   EXPECT_EQ(img->image.at<cv::Vec2i>(0, 0)[1], 2);
00036   // Make sure we cannot share data
00037   EXPECT_NE(img->image.data, &msg.data[0]);
00038 }


cv_bridge
Author(s): Patrick Mihelich, James Bowman
autogenerated on Thu Jun 6 2019 21:23:27