test_endian.cpp
Go to the documentation of this file.
1 #include "boost/endian/conversion.hpp"
2 #include <boost/make_shared.hpp>
3 #include <cv_bridge/cv_bridge.h>
4 #include <gtest/gtest.h>
5 
6 TEST(CvBridgeTest, endianness)
7 {
8  using namespace boost::endian;
9 
10  // Create an image of the type opposite to the platform
11  sensor_msgs::Image msg;
12  msg.height = 1;
13  msg.width = 1;
14  msg.encoding = "32SC2";
15  msg.step = 8;
16 
17  msg.data.resize(msg.step);
18  int32_t* data = reinterpret_cast<int32_t*>(&msg.data[0]);
19 
20  // Write 1 and 2 in order, but with an endianness opposite to the platform
21  if (order::native == order::little)
22  {
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));
26  } else {
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));
30  }
31 
32  // Make sure the values are still the same
33  cv_bridge::CvImageConstPtr img = cv_bridge::toCvShare(boost::make_shared<sensor_msgs::Image>(msg));
34  EXPECT_EQ(img->image.at<cv::Vec2i>(0, 0)[0], 1);
35  EXPECT_EQ(img->image.at<cv::Vec2i>(0, 0)[1], 2);
36  // Make sure we cannot share data
37  EXPECT_NE(img->image.data, &msg.data[0]);
38 }
cv_bridge.h
TEST
TEST(CvBridgeTest, endianness)
Definition: test_endian.cpp:6
boost::shared_ptr
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Convert an immutable sensor_msgs::Image message to an OpenCV-compatible CvImage, sharing the image da...
Definition: cv_bridge.cpp:439


cv_bridge
Author(s): Patrick Mihelich, James Bowman
autogenerated on Mon Oct 3 2022 02:45:56