ros_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 <ros/ros.h>
20 #include <std_msgs/Bool.h>
21 #include <std_msgs/ColorRGBA.h>
22 #include <std_msgs/Float32.h>
23 #include <std_msgs/Float64.h>
24 #include <std_msgs/Header.h>
25 #include <std_msgs/Int32.h>
26 #include <std_msgs/String.h>
27 #include <geometry_msgs/Point.h>
28 #include <geometry_msgs/Pose.h>
29 #include <geometry_msgs/PoseArray.h>
30 #include <geometry_msgs/PoseStamped.h>
31 #include <geometry_msgs/Transform.h>
32 #include <geometry_msgs/TransformStamped.h>
33 #include <geometry_msgs/Twist.h>
34 #include <geometry_msgs/Quaternion.h>
35 #include <geometry_msgs/Vector3.h>
36 // #include <mav_msgs/Actuators.h>
37 #include <nav_msgs/OccupancyGrid.h>
38 #include <nav_msgs/Odometry.h>
39 #include <rosgraph_msgs/Clock.h>
40 #include <sensor_msgs/BatteryState.h>
41 #include <sensor_msgs/CameraInfo.h>
42 #include <sensor_msgs/Image.h>
43 #include <sensor_msgs/Imu.h>
44 #include <sensor_msgs/JointState.h>
45 #include <sensor_msgs/LaserScan.h>
46 #include <sensor_msgs/MagneticField.h>
47 #include <sensor_msgs/NavSatFix.h>
48 #include <sensor_msgs/PointCloud2.h>
49 #include <visualization_msgs/Marker.h>
50 #include <visualization_msgs/MarkerArray.h>
51 #include <tf2_msgs/TFMessage.h>
52 #include <chrono>
53 #include "../test_utils.h"
54 
57 template <typename ROS_T>
58 class MyTestClass
59 {
61  public: MyTestClass(const std::string &_topic)
62  {
63  this->sub = this->n.subscribe(_topic, 1000, &MyTestClass::Cb, this);
64  }
65 
67  public: void Cb(const ROS_T& _msg)
68  {
70  this->callbackExecuted = true;
71  };
72 
74  public: bool callbackExecuted = false;
75 
77  private: ros::NodeHandle n;
78 
80  private: ros::Subscriber sub;
81 };
82 
84 TEST(ROSSubscriberTest, Bool)
85 {
86  MyTestClass<std_msgs::Bool> client("bool");
87 
88  using namespace std::chrono_literals;
90  client.callbackExecuted, 10ms, 200);
91 
92  EXPECT_TRUE(client.callbackExecuted);
93 }
94 
96 TEST(ROSSubscriberTest, ColorRGBA)
97 {
98  MyTestClass<std_msgs::ColorRGBA> client("color");
99 
100  using namespace std::chrono_literals;
102  client.callbackExecuted, 10ms, 200);
103 
104  EXPECT_TRUE(client.callbackExecuted);
105 }
106 
108 TEST(ROSSubscriberTest, Empty)
109 {
110  MyTestClass<std_msgs::Empty> client("empty");
111 
112  using namespace std::chrono_literals;
114  client.callbackExecuted, 10ms, 200);
115 
116  EXPECT_TRUE(client.callbackExecuted);
117 }
118 
120 TEST(ROSSubscriberTest, Int32)
121 {
122  MyTestClass<std_msgs::Int32> client("int32");
123 
124  using namespace std::chrono_literals;
126  client.callbackExecuted, 10ms, 200);
127 
128  EXPECT_TRUE(client.callbackExecuted);
129 }
130 
132 TEST(ROSSubscriberTest, Float)
133 {
134  MyTestClass<std_msgs::Float32> client("float");
135 
136  using namespace std::chrono_literals;
138  client.callbackExecuted, 10ms, 200);
139 
140  EXPECT_TRUE(client.callbackExecuted);
141 }
142 
144 TEST(ROSSubscriberTest, Double)
145 {
146  MyTestClass<std_msgs::Float64> client("double");
147 
148  using namespace std::chrono_literals;
150  client.callbackExecuted, 10ms, 200);
151 
152  EXPECT_TRUE(client.callbackExecuted);
153 }
154 
156 TEST(ROSSubscriberTest, Header)
157 {
158  MyTestClass<std_msgs::Header> client("header");
159 
160  using namespace std::chrono_literals;
162  client.callbackExecuted, 10ms, 200);
163 
164  EXPECT_TRUE(client.callbackExecuted);
165 }
166 
168 TEST(ROSSubscriberTest, String)
169 {
170  MyTestClass<std_msgs::String> client("string");
171 
172  using namespace std::chrono_literals;
174  client.callbackExecuted, 10ms, 200);
175 
176  EXPECT_TRUE(client.callbackExecuted);
177 }
178 
180 TEST(ROSSubscriberTest, Quaternion)
181 {
182  MyTestClass<geometry_msgs::Quaternion> client("quaternion");
183 
184  using namespace std::chrono_literals;
186  client.callbackExecuted, 10ms, 200);
187 
188  EXPECT_TRUE(client.callbackExecuted);
189 }
190 
192 TEST(ROSSubscriberTest, Vector3)
193 {
194  MyTestClass<geometry_msgs::Vector3> client("vector3");
195 
196  using namespace std::chrono_literals;
198  client.callbackExecuted, 10ms, 200);
199 
200  EXPECT_TRUE(client.callbackExecuted);
201 }
202 
204 TEST(ROSSubscriberTest, Clock)
205 {
206  MyTestClass<rosgraph_msgs::Clock> client("clock");
207 
208  using namespace std::chrono_literals;
210  client.callbackExecuted, 10ms, 200);
211 
212  EXPECT_TRUE(client.callbackExecuted);
213 }
214 
216 TEST(ROSSubscriberTest, Point)
217 {
218  MyTestClass<geometry_msgs::Point> client("point");
219 
220  using namespace std::chrono_literals;
222  client.callbackExecuted, 10ms, 200);
223 
224  EXPECT_TRUE(client.callbackExecuted);
225 }
226 
228 TEST(ROSSubscriberTest, Pose)
229 {
230  MyTestClass<geometry_msgs::Pose> client("pose");
231 
232  using namespace std::chrono_literals;
234  client.callbackExecuted, 10ms, 200);
235 
236  EXPECT_TRUE(client.callbackExecuted);
237 }
238 
240 TEST(ROSSubscriberTest, PoseArray)
241 {
242  MyTestClass<geometry_msgs::PoseArray> client("pose_array");
243 
244  using namespace std::chrono_literals;
246  client.callbackExecuted, 10ms, 200);
247 
248  EXPECT_TRUE(client.callbackExecuted);
249 }
250 
252 TEST(ROSSubscriberTest, PoseStamped)
253 {
254  MyTestClass<geometry_msgs::PoseStamped> client("pose_stamped");
255 
256  using namespace std::chrono_literals;
258  client.callbackExecuted, 10ms, 200);
259 
260  EXPECT_TRUE(client.callbackExecuted);
261 }
262 
264 TEST(ROSSubscriberTest, Transform)
265 {
266  MyTestClass<geometry_msgs::Transform> client("transform");
267 
268  using namespace std::chrono_literals;
270  client.callbackExecuted, 10ms, 200);
271 
272  EXPECT_TRUE(client.callbackExecuted);
273 }
274 
276 TEST(ROSSubscriberTest, TransformStamped)
277 {
278  MyTestClass<geometry_msgs::TransformStamped> client("transform_stamped");
279 
280  using namespace std::chrono_literals;
282  client.callbackExecuted, 10ms, 200);
283 
284  EXPECT_TRUE(client.callbackExecuted);
285 }
286 
288 TEST(ROSSubscriberTest, TF2Message)
289 {
290  MyTestClass<tf2_msgs::TFMessage> client("tf2_message");
291 
292  using namespace std::chrono_literals;
294  client.callbackExecuted, 10ms, 200);
295 
296  EXPECT_TRUE(client.callbackExecuted);
297 }
298 
300 TEST(ROSSubscriberTest, Twist)
301 {
302  MyTestClass<geometry_msgs::Twist> client("twist");
303 
304  using namespace std::chrono_literals;
306  client.callbackExecuted, 10ms, 200);
307 
308  EXPECT_TRUE(client.callbackExecuted);
309 }
310 
312 TEST(ROSSubscriberTest, Image)
313 {
314  MyTestClass<sensor_msgs::Image> client("image");
315 
316  using namespace std::chrono_literals;
318  client.callbackExecuted, 10ms, 200);
319 
320  EXPECT_TRUE(client.callbackExecuted);
321 }
322 
324 TEST(ROSSubscriberTest, CameraInfo)
325 {
326  MyTestClass<sensor_msgs::CameraInfo> client("camera_info");
327 
328  using namespace std::chrono_literals;
330  client.callbackExecuted, 10ms, 200);
331 
332  EXPECT_TRUE(client.callbackExecuted);
333 }
334 
336 TEST(ROSSubscriberTest, FluidPressure)
337 {
338  MyTestClass<sensor_msgs::FluidPressure> client("fluid_pressure");
339 
340  using namespace std::chrono_literals;
342  client.callbackExecuted, 10ms, 200);
343 
344  EXPECT_TRUE(client.callbackExecuted);
345 }
346 
348 TEST(ROSSubscriberTest, Imu)
349 {
350  MyTestClass<sensor_msgs::Imu> client("imu");
351 
352  using namespace std::chrono_literals;
354  client.callbackExecuted, 10ms, 200);
355 
356  EXPECT_TRUE(client.callbackExecuted);
357 }
358 
360 TEST(ROSSubscriberTest, JointStates)
361 {
362  MyTestClass<sensor_msgs::JointState> client("joint_states");
363 
364  using namespace std::chrono_literals;
366  client.callbackExecuted, 10ms, 200);
367 
368  EXPECT_TRUE(client.callbackExecuted);
369 }
370 
372 TEST(ROSSubscriberTest, LaserScan)
373 {
374  MyTestClass<sensor_msgs::LaserScan> client("laserscan");
375 
376  using namespace std::chrono_literals;
378  client.callbackExecuted, 10ms, 200);
379 
380  EXPECT_TRUE(client.callbackExecuted);
381 }
382 
384 TEST(ROSSubscriberTest, MagneticField)
385 {
386  MyTestClass<sensor_msgs::MagneticField> client("magnetic");
387 
388  using namespace std::chrono_literals;
390  client.callbackExecuted, 10ms, 200);
391 
392  EXPECT_TRUE(client.callbackExecuted);
393 }
394 
395 TEST(ROSSubscriberTest, NavSatFix)
396 {
397  MyTestClass<sensor_msgs::NavSatFix> client("navsat");
398 
399  using namespace std::chrono_literals;
401  client.callbackExecuted, 10ms, 200);
402 
403  EXPECT_TRUE(client.callbackExecuted);
404 }
405 
407 // TEST(ROSSubscriberTest, Actuators)
408 // {
409 // MyTestClass<mav_msgs::Actuators> client("actuators");
410 //
411 // using namespace std::chrono_literals;
412 // ros_ign_bridge::testing::waitUntilBoolVarAndSpin(
413 // client.callbackExecuted, 10ms, 200);
414 //
415 // EXPECT_TRUE(client.callbackExecuted);
416 // }
417 
419 TEST(ROSSubscriberTest, OccupancyGrid)
420 {
422 
423  using namespace std::chrono_literals;
425  client.callbackExecuted, 10ms, 200);
426 
427  EXPECT_TRUE(client.callbackExecuted);
428 }
429 
431 TEST(ROSSubscriberTest, Odometry)
432 {
433  MyTestClass<nav_msgs::Odometry> client("odometry");
434 
435  using namespace std::chrono_literals;
437  client.callbackExecuted, 10ms, 200);
438 
439  EXPECT_TRUE(client.callbackExecuted);
440 }
441 
443 TEST(ROSSubscriberTest, PointCloud2)
444 {
445  MyTestClass<sensor_msgs::PointCloud2> client("pointcloud2");
446 
447  using namespace std::chrono_literals;
449  client.callbackExecuted, 10ms, 200);
450 
451  EXPECT_TRUE(client.callbackExecuted);
452 }
453 
455 TEST(ROSSubscriberTest, BatteryState)
456 {
457  MyTestClass<sensor_msgs::BatteryState> client("battery_state");
458 
459  using namespace std::chrono_literals;
461  client.callbackExecuted, 10ms, 200);
462 
463  EXPECT_TRUE(client.callbackExecuted);
464 }
465 
467 TEST(ROSSubscriberTest, Marker)
468 {
470 
471  using namespace std::chrono_literals;
473  client.callbackExecuted, 10ms, 200);
474 
475  EXPECT_TRUE(client.callbackExecuted);
476 }
477 
479 TEST(ROSSubscriberTest, MarkerArray)
480 {
481  MyTestClass<visualization_msgs::MarkerArray> client("marker_array");
482 
483  using namespace std::chrono_literals;
485  client.callbackExecuted, 10ms, 200);
486 
487  EXPECT_TRUE(client.callbackExecuted);
488 }
489 
491 int main(int argc, char **argv)
492 {
493  ::testing::InitGoogleTest(&argc, argv);
494  ros::init(argc, argv, "ros_string_subscriber");
495 
496  return RUN_ALL_TESTS();
497 }
MyTestClass::sub
ros::Subscriber sub
ROS subscriber;.
Definition: ros_subscriber.cpp:80
MyTestClass::MyTestClass
MyTestClass(const std::string &_topic)
Class constructor.
Definition: ros_subscriber.cpp:61
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
MyTestClass::Cb
void Cb(const ROS_T &_msg)
Member function called each time a topic update is received.
Definition: ros_subscriber.cpp:67
MyTestClass::n
ros::NodeHandle n
ROS node handle;.
Definition: ros_subscriber.cpp:77
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
main
int main(int argc, char **argv)
Definition: ros_subscriber.cpp:491
TEST
TEST(ROSSubscriberTest, Bool)
Definition: ros_subscriber.cpp:84
MyTestClass::callbackExecuted
bool callbackExecuted
Member variables that flag when the actions are executed.
Definition: ign_subscriber.cpp:44
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
roslib::Header_< std::allocator< void > >
ros_ign_bridge::testing::waitUntilBoolVarAndSpin
void waitUntilBoolVarAndSpin(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. This function calls ros::sp...
Definition: test_utils.h:100
MyTestClass::Cb
void Cb(const IGN_T &_msg)
Member function called each time a topic update is received.
Definition: ign_subscriber.cpp:37
MyTestClass
A class for testing Ignition Transport topic subscription.
Definition: ign_subscriber.cpp:27
ros::NodeHandle
ros::Subscriber


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