alb_publisher_test.cpp
Go to the documentation of this file.
1 // GTest headers
2 #include <gtest/gtest.h>
3 
4 // ROS headers
5 #include "geometry_msgs/PoseStamped.h"
6 #include "nav_msgs/Odometry.h"
7 #include "ros/ros.h"
8 #include "sensor_msgs/PointCloud2.h"
9 #include "sensor_msgs/TimeReference.h"
10 #include "tf2_msgs/TFMessage.h"
11 
12 // Osef headers
13 #include "tlvParser.h"
14 
15 // Local headers
16 #include "alb_common.h"
17 #include "alb_publisher.h"
18 #include "outsight_alb_driver/AugmentedCloud.h"
19 #include "outsight_alb_driver/TrackedObjects.h"
20 
21 // Constant definition of test data.
22 constexpr const char *k_alb_tracking_file = "tracking_test_file";
23 constexpr const char *k_alb_slam_file = "slam_test_file";
24 
25 constexpr const size_t k_tracking_messages = 60;
26 constexpr const size_t k_slam_messages = 54;
27 
29 class AlbPublisherTest : public ::testing::Test {
30  protected:
31  void SetUp() override
32  {
33  }
34 
35  void TearDown() override
36  {
37  // Delete all test parameters.
39 
40  // Free memory.
41  if (file) {
42  fclose(file);
43  }
44  delete (buffer);
45  }
46 
48  void openFile(const std::string &key)
49  {
50  std::string filename("");
51  ros::NodeHandle private_node("~");
52 
53  if (private_node.hasParam(key)) {
54  private_node.param<std::string>(key, filename, "");
55  }
56 
57  file = fopen(filename.c_str(), "r");
58  }
59 
61  void setTestParam(const std::string &key, bool value)
62  {
63  ros::NodeHandle private_node("~");
64  private_node.setParam(key, value);
65 
66  custom_parameters.push_back(key);
67  }
68 
71  {
72  ros::NodeHandle private_node("~");
73 
74  for (auto key : custom_parameters) {
75  private_node.deleteParam(key);
76  }
77  }
78 
80  template <typename ROSMessageType>
81  void subscribeTo(const std::string &topic)
82  {
83  alb_subscriber = node.subscribe<ROSMessageType>(
84  topic, 1000, &AlbPublisherTest::onMessageReceived<ROSMessageType>, this);
85  }
86 
88  template <typename ROSMessageType>
89  void onMessageReceived(const typename ROSMessageType::ConstPtr &msg)
90  {
92  }
93 
95  void readAndPublish(AlbPublisher &albPublisher)
96  {
97  // Read and publish TLV data.
98  Tlv::tlv_s *read_tlv = nullptr;
99  ros::Rate loop_rate(100);
100 
101  while (read_tlv = Tlv::readFromFile(file, buffer, buffer_size)) {
102  albPublisher.publish(read_tlv);
103  ros::spinOnce();
104  loop_rate.sleep();
105  }
106  }
107 
108  protected:
109  FILE *file = nullptr;
110  uint8_t *buffer = nullptr;
111  size_t buffer_size = 0;
112  size_t received_messages = 0;
113 
114  std::vector<std::string> custom_parameters;
115 
118 };
119 
121 TEST_F(AlbPublisherTest, openTrackingFile)
122 {
123  openFile(k_alb_tracking_file);
124  ASSERT_FALSE(!file);
125 }
126 
128 TEST_F(AlbPublisherTest, openSlamFile)
129 {
130  openFile(k_alb_slam_file);
131  ASSERT_FALSE(!file);
132 }
133 
135 TEST_F(AlbPublisherTest, publishPointCloud)
136 {
137  // Open slam file.
138  openFile(k_alb_slam_file);
139  ASSERT_FALSE(!file);
140 
141  // Set parameter to publish PointCloud message.
142  setTestParam(ALBCommon::k_alb_point_cloud_config, true);
143  subscribeTo<sensor_msgs::PointCloud2>(ALBCommon::k_alb_point_cloud);
144 
145  AlbPublisher alb_publisher(node);
146  EXPECT_EQ(alb_subscriber.getNumPublishers(), 1);
147 
148  readAndPublish(alb_publisher);
149  EXPECT_EQ(received_messages, k_slam_messages);
150 }
151 
154 {
155  // Open tracking file.
156  openFile(k_alb_slam_file);
157  ASSERT_FALSE(!file);
158 
159  // Set parameter to publish Pose message.
160  setTestParam(ALBCommon::k_alb_pose_config, true);
161  subscribeTo<geometry_msgs::PoseStamped>(ALBCommon::k_alb_pose);
162 
163  AlbPublisher alb_publisher(node);
164  EXPECT_EQ(alb_subscriber.getNumPublishers(), 1);
165 
166  readAndPublish(alb_publisher);
167  EXPECT_EQ(received_messages, k_slam_messages);
168 }
169 
171 TEST_F(AlbPublisherTest, publishTimeReference)
172 {
173  // Open tracking file.
174  openFile(k_alb_tracking_file);
175  ASSERT_FALSE(!file);
176 
177  // Set parameter to publish TimeReference message.
178  setTestParam(ALBCommon::k_alb_time_ref_config, true);
179  subscribeTo<sensor_msgs::TimeReference>(ALBCommon::k_alb_time_ref);
180 
181  AlbPublisher alb_publisher(node);
182  EXPECT_EQ(alb_subscriber.getNumPublishers(), 1);
183 
184  readAndPublish(alb_publisher);
185  EXPECT_EQ(received_messages, k_tracking_messages);
186 }
187 
189 TEST_F(AlbPublisherTest, publishTrackedObjects)
190 {
191  // Open tracking file.
192  openFile(k_alb_tracking_file);
193  ASSERT_FALSE(!file);
194 
195  // Set parameter to publish TrackedObjects message.
196  setTestParam(ALBCommon::k_alb_objects_config, true);
197  subscribeTo<outsight_alb_driver::TrackedObjects>(ALBCommon::k_alb_objects);
198 
199  AlbPublisher alb_publisher(node);
200  EXPECT_EQ(alb_subscriber.getNumPublishers(), 1);
201 
202  readAndPublish(alb_publisher);
203  EXPECT_EQ(received_messages, k_tracking_messages);
204 }
205 
207 TEST_F(AlbPublisherTest, publishEgomotion)
208 {
209  // Open tracking file.
210  openFile(k_alb_tracking_file);
211  ASSERT_FALSE(!file);
212 
213  // Set parameter to publish Egomotion message.
214  setTestParam(ALBCommon::k_alb_egomotion_config, true);
215  subscribeTo<geometry_msgs::PoseStamped>(ALBCommon::k_alb_egomotion);
216 
217  AlbPublisher alb_publisher(node);
218  EXPECT_EQ(alb_subscriber.getNumPublishers(), 1);
219 
220  readAndPublish(alb_publisher);
221  EXPECT_EQ(received_messages, k_tracking_messages);
222 }
223 
225 TEST_F(AlbPublisherTest, publishOdometry)
226 {
227  // Open tracking file.
228  openFile(k_alb_tracking_file);
229  ASSERT_FALSE(!file);
230 
231  // Set parameter to publish Odometry message.
232  setTestParam(ALBCommon::k_alb_odometry_config, true);
233  subscribeTo<nav_msgs::Odometry>(ALBCommon::k_alb_odometry);
234 
235  AlbPublisher alb_publisher(node);
236  EXPECT_EQ(alb_subscriber.getNumPublishers(), 1);
237 
238  readAndPublish(alb_publisher);
239  EXPECT_EQ(received_messages, k_tracking_messages);
240 }
241 
243 TEST_F(AlbPublisherTest, publishAugmentedCloud)
244 {
245  // Open slam file.
246  openFile(k_alb_slam_file);
247  ASSERT_FALSE(!file);
248 
249  // Set parameter to publish PointCloud message.
250  setTestParam(ALBCommon::k_alb_augmented_cloud_config, true);
251  subscribeTo<outsight_alb_driver::AugmentedCloud>(ALBCommon::k_alb_augmented_cloud);
252 
253  AlbPublisher alb_publisher(node);
254  EXPECT_EQ(alb_subscriber.getNumPublishers(), 1);
255 
256  readAndPublish(alb_publisher);
257  EXPECT_EQ(received_messages, k_slam_messages);
258 }
259 
261 TEST_F(AlbPublisherTest, broadcastAlbTransform)
262 {
263  // Open slam file.
264  openFile(k_alb_slam_file);
265  ASSERT_FALSE(!file);
266 
267  // Set parameter to publish Alb fixed frame to sensor frame tf.
268  setTestParam(ALBCommon::k_alb_broadcast_tf_config, true);
269  setTestParam(ALBCommon::k_alb_odometry_config, true);
270  subscribeTo<tf2_msgs::TFMessage>("tf");
271 
272  AlbPublisher alb_publisher(node);
273 
274  readAndPublish(alb_publisher);
275  EXPECT_EQ(received_messages, k_slam_messages);
276 }
277 
278 int main(int argc, char **argv)
279 {
280  testing::InitGoogleTest(&argc, argv);
281  ros::init(argc, argv, "outsight_publishers_test");
282  return RUN_ALL_TESTS();
283 }
AlbPublisherTest::node
ros::NodeHandle node
Definition: alb_publisher_test.cpp:116
AlbPublisher::publish
void publish(const Tlv::tlv_s *frame)
Publish messages from the ALB frame.
Definition: alb_publisher.cpp:163
ALBCommon::k_alb_point_cloud_config
constexpr const char * k_alb_point_cloud_config
Definition: alb_common.h:28
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
Tlv::readFromFile
tlv_s * readFromFile(FILE *in_fd, uint8_t *&out_buffer, size_t &out_buffer_sz)
Definition: tlvParser.cpp:27
k_alb_tracking_file
constexpr const char * k_alb_tracking_file
Definition: alb_publisher_test.cpp:22
AlbPublisherTest::setTestParam
void setTestParam(const std::string &key, bool value)
Set test parameter to execute test(s).
Definition: alb_publisher_test.cpp:61
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ALBCommon::k_alb_augmented_cloud_config
constexpr const char * k_alb_augmented_cloud_config
Definition: alb_common.h:35
ros.h
k_tracking_messages
constexpr const size_t k_tracking_messages
Definition: alb_publisher_test.cpp:25
ALBCommon::k_alb_odometry_config
constexpr const char * k_alb_odometry_config
Definition: alb_common.h:34
alb_publisher.h
ALBCommon::k_alb_objects
constexpr const char * k_alb_objects
Definition: alb_common.h:11
AlbPublisherTest::openFile
void openFile(const std::string &key)
Open testing file.
Definition: alb_publisher_test.cpp:48
ros::spinOnce
ROSCPP_DECL void spinOnce()
ALBCommon::k_alb_objects_config
constexpr const char * k_alb_objects_config
Definition: alb_common.h:32
ros::NodeHandle::deleteParam
bool deleteParam(const std::string &key) const
ALBCommon::k_alb_egomotion
constexpr const char * k_alb_egomotion
Definition: alb_common.h:12
main
int main(int argc, char **argv)
Definition: alb_publisher_test.cpp:278
tlvParser.h
TEST_F
TEST_F(AlbPublisherTest, openTrackingFile)
Test to check opening the tracking testing file.
Definition: alb_publisher_test.cpp:121
AlbPublisherTest::subscribeTo
void subscribeTo(const std::string &topic)
Subscribe to the given topic with the template ROS message.
Definition: alb_publisher_test.cpp:81
AlbPublisherTest::alb_subscriber
ros::Subscriber alb_subscriber
Definition: alb_publisher_test.cpp:117
ALBCommon::k_alb_time_ref_config
constexpr const char * k_alb_time_ref_config
Definition: alb_common.h:30
AlbPublisherTest::removeParameters
void removeParameters()
Remove all the test parameters.
Definition: alb_publisher_test.cpp:70
AlbPublisherTest::buffer
uint8_t * buffer
Definition: alb_publisher_test.cpp:110
AlbPublisherTest::SetUp
void SetUp() override
Definition: alb_publisher_test.cpp:31
ALBCommon::k_alb_augmented_cloud
constexpr const char * k_alb_augmented_cloud
Definition: alb_common.h:14
k_slam_messages
constexpr const size_t k_slam_messages
Definition: alb_publisher_test.cpp:26
AlbPublisherTest::file
FILE * file
Definition: alb_publisher_test.cpp:109
alb_common.h
k_alb_slam_file
constexpr const char * k_alb_slam_file
Definition: alb_publisher_test.cpp:23
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
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())
ALBCommon::k_alb_broadcast_tf_config
constexpr const char * k_alb_broadcast_tf_config
Definition: alb_common.h:37
ros::Rate::sleep
bool sleep()
ALBCommon::k_alb_egomotion_config
constexpr const char * k_alb_egomotion_config
Definition: alb_common.h:33
AlbPublisherTest
Class to test the AlbPublisher topics.
Definition: alb_publisher_test.cpp:29
AlbPublisher
Class to publish ROS messages from the ALB.
Definition: alb_publisher.h:19
AlbPublisherTest::onMessageReceived
void onMessageReceived(const typename ROSMessageType::ConstPtr &msg)
Callback function on the subscriber.
Definition: alb_publisher_test.cpp:89
AlbPublisherTest::TearDown
void TearDown() override
Definition: alb_publisher_test.cpp:35
AlbPublisherTest::buffer_size
size_t buffer_size
Definition: alb_publisher_test.cpp:111
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
AlbPublisherTest::received_messages
size_t received_messages
Definition: alb_publisher_test.cpp:112
ALBCommon::k_alb_odometry
constexpr const char * k_alb_odometry
Definition: alb_common.h:13
ros::Rate
ALBCommon::k_alb_time_ref
constexpr const char * k_alb_time_ref
Definition: alb_common.h:10
ALBCommon::k_alb_pose_config
constexpr const char * k_alb_pose_config
Definition: alb_common.h:29
AlbPublisherTest::custom_parameters
std::vector< std::string > custom_parameters
Definition: alb_publisher_test.cpp:114
AlbPublisherTest::readAndPublish
void readAndPublish(AlbPublisher &albPublisher)
Function to read all data and publish them.
Definition: alb_publisher_test.cpp:95
ALBCommon::k_alb_pose
constexpr const char * k_alb_pose
Definition: alb_common.h:9
ros::NodeHandle
ros::Subscriber
ALBCommon::k_alb_point_cloud
constexpr const char * k_alb_point_cloud
Definition: alb_common.h:8


outsight_alb_driver
Author(s): Outsight
autogenerated on Thu Oct 13 2022 02:21:45