-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathrt_logger_test.cpp
More file actions
71 lines (60 loc) · 1.86 KB
/
rt_logger_test.cpp
File metadata and controls
71 lines (60 loc) · 1.86 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
#include <gtest/gtest.h>
#include <ros/ros.h>
#include <rt_logger/rt_logger.h>
using namespace rt_logger;
static std::vector<double> std_vector(3);
static double scalar;
static Eigen::VectorXd eigen_vector(10);
static Eigen::MatrixXd eigen_matrix(10,10);
TEST(RtLoggerTest, StdVectorPublisher)
{
EXPECT_NO_THROW(RtLogger::getLogger().addPublisher("/std_vector",std_vector));
}
TEST(RtLoggerTest, ScalarPublisher)
{
EXPECT_NO_THROW(RtLogger::getLogger().addPublisher("/scalar",scalar));
}
TEST(RtLoggerTest, EigenVectorPublisher)
{
EXPECT_NO_THROW(RtLogger::getLogger().addPublisher("/eigen_vector",eigen_vector));
}
TEST(RtLoggerTest, EigenMatrixPublisher)
{
EXPECT_NO_THROW(RtLogger::getLogger().addPublisher("/eigen_matrix",eigen_matrix));
}
TEST(RtLoggerTest, SinglePublisher)
{
EXPECT_NO_THROW(RtLogger::getLogger().addPublisher("/single_publisher",std_vector,"std_vector"));
EXPECT_NO_THROW(RtLogger::getLogger().addPublisher("/single_publisher",scalar,"scalar"));
EXPECT_NO_THROW(RtLogger::getLogger().addPublisher("/single_publisher",eigen_vector,"eigen_vector"));
EXPECT_NO_THROW(RtLogger::getLogger().addPublisher("/single_publisher",eigen_matrix,"eigen_matrix"));
}
TEST(RtLoggerTest, PublishAll)
{
int cnt = 0;
while(ros::ok() && cnt++<50)
{
EXPECT_NO_THROW(RtLogger::getLogger().publish(ros::Time::now()));
ros::Duration(0.1).sleep();
}
}
TEST(RtLoggerTest, Publish)
{
int cnt = 0;
while(ros::ok() && cnt++<50)
{
EXPECT_NO_THROW(RtLogger::getLogger().publish(ros::Time::now(),"/single_publisher"));
ros::Duration(0.1).sleep();
}
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "rt_logger_test");
testing::InitGoogleTest(&argc, argv);
ros::AsyncSpinner spinner(1);
spinner.start();
int ret = RUN_ALL_TESTS();
spinner.stop();
ros::shutdown();
return ret;
}