ign_subscriber.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #include <gtest/gtest.h>
19 #include <chrono>
20 #include <string>
21 #include <ignition/transport.hh>
22 #include "../test_utils.h"
23 
26 template <typename IGN_T>
28 {
31  public: MyTestClass(const std::string &_topic)
32  {
33  EXPECT_TRUE(this->node.Subscribe(_topic, &MyTestClass::Cb, this));
34  }
35 
37  public: void Cb(const IGN_T &_msg)
38  {
40  this->callbackExecuted = true;
41  };
42 
44  public: bool callbackExecuted = false;
45 
47  private: ignition::transport::Node node;
48 };
49 
51 TEST(IgnSubscriberTest, Boolean)
52 {
54 
55  using namespace std::chrono_literals;
57  client.callbackExecuted, 10ms, 200);
58 
59  EXPECT_TRUE(client.callbackExecuted);
60 }
61 
63 TEST(IgnSubscriberTest, Color)
64 {
65  MyTestClass<ignition::msgs::Color> client("color");
66 
67  using namespace std::chrono_literals;
69  client.callbackExecuted, 10ms, 200);
70 
71  EXPECT_TRUE(client.callbackExecuted);
72 }
73 
75 TEST(IgnSubscriberTest, Empty)
76 {
77  MyTestClass<ignition::msgs::Empty> client("empty");
78 
79  using namespace std::chrono_literals;
81  client.callbackExecuted, 10ms, 200);
82 
83  EXPECT_TRUE(client.callbackExecuted);
84 }
85 
87 TEST(IgnSubscriberTest, Int32)
88 {
89  MyTestClass<ignition::msgs::Int32> client("int32");
90 
91  using namespace std::chrono_literals;
93  client.callbackExecuted, 10ms, 200);
94 
95  EXPECT_TRUE(client.callbackExecuted);
96 }
97 
99 TEST(IgnSubscriberTest, Float)
100 {
101  MyTestClass<ignition::msgs::Float> client("float");
102 
103  using namespace std::chrono_literals;
105  client.callbackExecuted, 10ms, 200);
106 
107  EXPECT_TRUE(client.callbackExecuted);
108 }
109 
111 TEST(IgnSubscriberTest, Header)
112 {
113  MyTestClass<ignition::msgs::Header> client("header");
114 
115  using namespace std::chrono_literals;
117  client.callbackExecuted, 10ms, 200);
118 
119  EXPECT_TRUE(client.callbackExecuted);
120 }
121 
123 TEST(IgnSubscriberTest, String)
124 {
126 
127  using namespace std::chrono_literals;
129  client.callbackExecuted, 10ms, 200);
130 
131  EXPECT_TRUE(client.callbackExecuted);
132 }
133 
135 TEST(IgnSubscriberTest, Quaternion)
136 {
137  MyTestClass<ignition::msgs::Quaternion> client("quaternion");
138 
139  using namespace std::chrono_literals;
141  client.callbackExecuted, 10ms, 200);
142 
143  EXPECT_TRUE(client.callbackExecuted);
144 }
145 
147 TEST(IgnSubscriberTest, Vector3)
148 {
149  MyTestClass<ignition::msgs::Vector3d> client("vector3");
150 
151  using namespace std::chrono_literals;
153  client.callbackExecuted, 10ms, 200);
154 
155  EXPECT_TRUE(client.callbackExecuted);
156 }
157 
159 TEST(IgnSubscriberTest, Clock)
160 {
161  MyTestClass<ignition::msgs::Clock> client("clock");
162 
163  using namespace std::chrono_literals;
165  client.callbackExecuted, 10ms, 200);
166 
167  EXPECT_TRUE(client.callbackExecuted);
168 }
169 
171 TEST(IgnSubscriberTest, Point)
172 {
174 
175  using namespace std::chrono_literals;
177  client.callbackExecuted, 10ms, 200);
178 
179  EXPECT_TRUE(client.callbackExecuted);
180 }
181 
183 TEST(IgnSubscriberTest, Pose)
184 {
185  MyTestClass<ignition::msgs::Pose> client("pose");
186 
187  using namespace std::chrono_literals;
189  client.callbackExecuted, 10ms, 200);
190 
191  EXPECT_TRUE(client.callbackExecuted);
192 }
193 
195 TEST(IgnSubscriberTest, Pose_V)
196 {
197  MyTestClass<ignition::msgs::Pose_V> client("pose_array");
198 
199  using namespace std::chrono_literals;
201  client.callbackExecuted, 10ms, 200);
202 
203  EXPECT_TRUE(client.callbackExecuted);
204 }
205 
207 TEST(IgnSubscriberTest, PoseStamped)
208 {
209  MyTestClass<ignition::msgs::Pose> client("pose_stamped");
210 
211  using namespace std::chrono_literals;
213  client.callbackExecuted, 10ms, 200);
214 
215  EXPECT_TRUE(client.callbackExecuted);
216 }
217 
219 TEST(IgnSubscriberTest, Transform)
220 {
221  MyTestClass<ignition::msgs::Pose> client("transform");
222 
223  using namespace std::chrono_literals;
225  client.callbackExecuted, 10ms, 200);
226 
227  EXPECT_TRUE(client.callbackExecuted);
228 }
229 
231 TEST(IgnSubscriberTest, TransformStamped)
232 {
233  MyTestClass<ignition::msgs::Pose> client("transform_stamped");
234 
235  using namespace std::chrono_literals;
237  client.callbackExecuted, 10ms, 200);
238 
239  EXPECT_TRUE(client.callbackExecuted);
240 }
241 
243 TEST(IgnSubscriberTest, TF2Message)
244 {
245  MyTestClass<ignition::msgs::Pose_V> client("tf2_message");
246 
247  using namespace std::chrono_literals;
249  client.callbackExecuted, 10ms, 200);
250 
251  EXPECT_TRUE(client.callbackExecuted);
252 }
253 
255 TEST(IgnSubscriberTest, Twist)
256 {
257  MyTestClass<ignition::msgs::Twist> client("twist");
258 
259  using namespace std::chrono_literals;
261  client.callbackExecuted, 10ms, 200);
262 
263  EXPECT_TRUE(client.callbackExecuted);
264 }
265 
267 TEST(IgnSubscriberTest, Image)
268 {
269  MyTestClass<ignition::msgs::Image> client("image");
270 
271  using namespace std::chrono_literals;
273  client.callbackExecuted, 10ms, 200);
274 
275  EXPECT_TRUE(client.callbackExecuted);
276 }
277 
279 TEST(IgnSubscriberTest, CameraInfo)
280 {
281  MyTestClass<ignition::msgs::CameraInfo> client("camera_info");
282 
283  using namespace std::chrono_literals;
285  client.callbackExecuted, 10ms, 200);
286 
287  EXPECT_TRUE(client.callbackExecuted);
288 }
289 
291 TEST(IgnSubscriberTest, FluidPressure)
292 {
293  MyTestClass<ignition::msgs::FluidPressure> client("fluid_pressure");
294 
295  using namespace std::chrono_literals;
297  client.callbackExecuted, 10ms, 200);
298 
299  EXPECT_TRUE(client.callbackExecuted);
300 }
301 
303 TEST(IgnSubscriberTest, Imu)
304 {
305  MyTestClass<ignition::msgs::IMU> client("imu");
306 
307  using namespace std::chrono_literals;
309  client.callbackExecuted, 10ms, 200);
310 
311  EXPECT_TRUE(client.callbackExecuted);
312 }
313 
315 TEST(IgnSubscriberTest, LaserScan)
316 {
317  MyTestClass<ignition::msgs::LaserScan> client("laserscan");
318 
319  using namespace std::chrono_literals;
321  client.callbackExecuted, 10ms, 200);
322 
323  EXPECT_TRUE(client.callbackExecuted);
324 }
325 
327 TEST(IgnSubscriberTest, Magnetometer)
328 {
330 
331  using namespace std::chrono_literals;
333  client.callbackExecuted, 10ms, 200);
334 
335  EXPECT_TRUE(client.callbackExecuted);
336 }
337 
339 TEST(IgnSubscriberTest, NavSat)
340 {
341  MyTestClass<ignition::msgs::NavSat> client("navsat");
342 
343  using namespace std::chrono_literals;
345  client.callbackExecuted, 10ms, 200);
346 
347  EXPECT_TRUE(client.callbackExecuted);
348 }
349 
351 //TEST(IgnSubscriberTest, Actuators)
352 //{
353 // MyTestClass<ignition::msgs::Actuators> client("actuators");
354 //
355 // using namespace std::chrono_literals;
356 // ros_ign_bridge::testing::waitUntilBoolVar(
357 // client.callbackExecuted, 10ms, 200);
358 //
359 // EXPECT_TRUE(client.callbackExecuted);
360 //}
361 
363 TEST(IgnSubscriberTest, OccupancyGrid)
364 {
366 
367  using namespace std::chrono_literals;
369  client.callbackExecuted, 10ms, 200);
370 
371  EXPECT_TRUE(client.callbackExecuted);
372 }
373 
375 TEST(IgnSubscriberTest, Odometry)
376 {
377  MyTestClass<ignition::msgs::Odometry> client("odometry");
378 
379  using namespace std::chrono_literals;
381  client.callbackExecuted, 10ms, 200);
382 
383  EXPECT_TRUE(client.callbackExecuted);
384 }
385 
387 TEST(IgnSubscriberTest, JointStates)
388 {
389  MyTestClass<ignition::msgs::Model> client("joint_states");
390 
391  using namespace std::chrono_literals;
393  client.callbackExecuted, 10ms, 200);
394 
395  EXPECT_TRUE(client.callbackExecuted);
396 }
397 
399 TEST(IgnSubscriberTest, PointCloudPacked)
400 {
401  MyTestClass<ignition::msgs::PointCloudPacked> client("pointcloud2");
402 
403  using namespace std::chrono_literals;
405  client.callbackExecuted, 10ms, 200);
406 
407  EXPECT_TRUE(client.callbackExecuted);
408 }
409 
411 TEST(IgnSubscriberTest, BatteryState)
412 {
413  MyTestClass<ignition::msgs::BatteryState> client("battery_state");
414 
415  using namespace std::chrono_literals;
417  client.callbackExecuted, 10ms, 200);
418 
419  EXPECT_TRUE(client.callbackExecuted);
420 }
421 
423 TEST(IgnSubscriberTest, Marker)
424 {
425  MyTestClass<ignition::msgs::Marker> client("marker");
426 
427  using namespace std::chrono_literals;
429  client.callbackExecuted, 10ms, 200);
430 
431  EXPECT_TRUE(client.callbackExecuted);
432 }
433 
435 TEST(IgnSubscriberTest, MarkerArray)
436 {
437  MyTestClass<ignition::msgs::Marker_V> client("marker_array");
438 
439  using namespace std::chrono_literals;
441  client.callbackExecuted, 10ms, 200);
442 
443  EXPECT_TRUE(client.callbackExecuted);
444 }
445 
447 int main(int argc, char **argv)
448 {
449  ::testing::InitGoogleTest(&argc, argv);
450  ros::init(argc, argv, "ign_string_subscriber");
451 
452  return RUN_ALL_TESTS();
453 }
MyTestClass::MyTestClass
MyTestClass(const std::string &_topic)
Class constructor.
Definition: ign_subscriber.cpp:31
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros_ign_bridge::testing::compareTestMsg
void compareTestMsg(const std_msgs::Bool &_msg)
Compare a message with the populated for testing.
Definition: test_utils.h:127
MyTestClass::node
ignition::transport::Node node
Transport node;.
Definition: ign_subscriber.cpp:47
MyTestClass::callbackExecuted
bool callbackExecuted
Member variables that flag when the actions are executed.
Definition: ign_subscriber.cpp:44
roslib::Header_< std::allocator< void > >
ros_ign_bridge::testing::waitUntilBoolVar
void waitUntilBoolVar(bool &_boolVar, const std::chrono::duration< Rep, Period > &_sleepEach, const int _retries)
Wait until a boolean variable is set to true for a given number of times.
Definition: test_utils.h:77
main
int main(int argc, char **argv)
Definition: ign_subscriber.cpp:447
MyTestClass::Cb
void Cb(const IGN_T &_msg)
Member function called each time a topic update is received.
Definition: ign_subscriber.cpp:37
TEST
TEST(IgnSubscriberTest, Boolean)
Definition: ign_subscriber.cpp:51
MyTestClass
A class for testing Ignition Transport topic subscription.
Definition: ign_subscriber.cpp:27


ros_ign_bridge
Author(s):
autogenerated on Sat Mar 11 2023 04:02:16