2 #include <gtest/gtest.h>
5 #include "geometry_msgs/PoseStamped.h"
6 #include "nav_msgs/Odometry.h"
8 #include "sensor_msgs/PointCloud2.h"
9 #include "sensor_msgs/TimeReference.h"
10 #include "tf2_msgs/TFMessage.h"
18 #include "outsight_alb_driver/AugmentedCloud.h"
19 #include "outsight_alb_driver/TrackedObjects.h"
50 std::string filename(
"");
54 private_node.
param<std::string>(key, filename,
"");
57 file = fopen(filename.c_str(),
"r");
80 template <
typename ROSMessageType>
84 topic, 1000, &AlbPublisherTest::onMessageReceived<ROSMessageType>,
this);
88 template <
typename ROSMessageType>
98 Tlv::tlv_s *read_tlv =
nullptr;
102 albPublisher.
publish(read_tlv);
146 EXPECT_EQ(alb_subscriber.getNumPublishers(), 1);
148 readAndPublish(alb_publisher);
164 EXPECT_EQ(alb_subscriber.getNumPublishers(), 1);
166 readAndPublish(alb_publisher);
182 EXPECT_EQ(alb_subscriber.getNumPublishers(), 1);
184 readAndPublish(alb_publisher);
200 EXPECT_EQ(alb_subscriber.getNumPublishers(), 1);
202 readAndPublish(alb_publisher);
218 EXPECT_EQ(alb_subscriber.getNumPublishers(), 1);
220 readAndPublish(alb_publisher);
236 EXPECT_EQ(alb_subscriber.getNumPublishers(), 1);
238 readAndPublish(alb_publisher);
254 EXPECT_EQ(alb_subscriber.getNumPublishers(), 1);
256 readAndPublish(alb_publisher);
270 subscribeTo<tf2_msgs::TFMessage>(
"tf");
274 readAndPublish(alb_publisher);
278 int main(
int argc,
char **argv)
280 testing::InitGoogleTest(&argc, argv);
281 ros::init(argc, argv,
"outsight_publishers_test");
282 return RUN_ALL_TESTS();