18 #ifndef ROS_IGN_IMAGE__TEST_UTILS_H_
19 #define ROS_IGN_IMAGE__TEST_UTILS_H_
21 #include <gtest/gtest.h>
23 #include <std_msgs/Header.h>
24 #include <sensor_msgs/Image.h>
28 #include <ignition/msgs.hh>
43 template <
class Rep,
class Period>
46 const std::chrono::duration<Rep, Period> &_sleepEach,
50 while (!_boolVar && i < _retries)
53 std::this_thread::sleep_for(_sleepEach);
66 template <
class Rep,
class Period>
69 const std::chrono::duration<Rep, Period> &_sleepEach,
73 while (!_boolVar && i < _retries)
76 std::this_thread::sleep_for(_sleepEach);
92 _msg.frame_id =
"frame_id_value";
99 std_msgs::Header expected_msg;
102 EXPECT_GE(expected_msg.seq, 0u);
103 EXPECT_EQ(expected_msg.stamp.sec, _msg.stamp.sec);
104 EXPECT_EQ(expected_msg.stamp.nsec, _msg.stamp.nsec);
105 EXPECT_EQ(expected_msg.frame_id, _msg.frame_id);
112 std_msgs::Header header_msg;
115 _msg.header = header_msg;
118 _msg.encoding =
"rgb8";
119 _msg.is_bigendian =
false;
120 _msg.step = _msg.width * 3;
121 _msg.data.resize(_msg.height * _msg.step,
'1');
128 sensor_msgs::Image expected_msg;
132 EXPECT_EQ(expected_msg.width, _msg.width);
133 EXPECT_EQ(expected_msg.height, _msg.height);
134 EXPECT_EQ(expected_msg.encoding, _msg.encoding);
135 EXPECT_EQ(expected_msg.is_bigendian, _msg.is_bigendian);
136 EXPECT_EQ(expected_msg.step, _msg.step);
147 auto seq_entry = _msg.add_data();
148 seq_entry->set_key(
"seq");
149 seq_entry->add_value(
"1");
150 _msg.mutable_stamp()->set_sec(2);
151 _msg.mutable_stamp()->set_nsec(3);
152 auto frame_id_entry = _msg.add_data();
153 frame_id_entry->set_key(
"frame_id");
154 frame_id_entry->add_value(
"frame_id_value");
161 ignition::msgs::Header expected_msg;
164 EXPECT_EQ(expected_msg.stamp().sec(), _msg.stamp().sec());
165 EXPECT_EQ(expected_msg.stamp().nsec(), _msg.stamp().nsec());
166 EXPECT_GE(_msg.data_size(), 2);
167 EXPECT_EQ(expected_msg.data(0).key(), _msg.data(0).key());
168 EXPECT_EQ(1, _msg.data(0).value_size());
169 std::string value = _msg.data(0).value(0);
172 uint32_t ul = std::stoul(value,
nullptr);
175 catch (std::exception & e)
179 EXPECT_EQ(expected_msg.data(1).key(), _msg.data(1).key());
180 EXPECT_EQ(1, _msg.data(1).value_size());
181 EXPECT_EQ(expected_msg.data(1).value(0), _msg.data(1).value(0));
188 ignition::msgs::Header header_msg;
191 _msg.mutable_header()->CopyFrom(header_msg);
193 _msg.set_height(240);
194 _msg.set_pixel_format_type(ignition::msgs::PixelFormatType::RGB_INT8);
195 _msg.set_step(_msg.width() * 3);
196 _msg.set_data(std::string(_msg.height() * _msg.step(),
'1'));
203 ignition::msgs::Image expected_msg;
207 EXPECT_EQ(expected_msg.width(), _msg.width());
208 EXPECT_EQ(expected_msg.height(), _msg.height());
209 EXPECT_EQ(expected_msg.pixel_format_type(), _msg.pixel_format_type());
210 EXPECT_EQ(expected_msg.step(), _msg.step());
211 EXPECT_EQ(expected_msg.data(), _msg.data());
216 #endif // ROS_IGN_BRIDGE__TEST_UTILS_H_