33 #include <sensor_msgs/PointCloud2.h>
37 #include <gtest/gtest.h>
43 const sensor_msgs::PointCloud2::Ptr
msg(
new sensor_msgs::PointCloud2);
45 const auto process = [&seq]()
49 const auto accumulateOK = [&seq,
msg](
const sensor_msgs::PointCloud2::ConstPtr& msg2) ->
bool
55 const auto accumulateNG = [&seq,
msg](
const sensor_msgs::PointCloud2::ConstPtr& msg2) ->
bool
61 const auto clear = [&seq]()
65 accum.
push(
"1",
msg, process, accumulateOK, clear);
66 ASSERT_EQ(std::string(
"cap"), seq);
68 accum.
push(
"2",
msg, process, accumulateNG, clear);
69 ASSERT_EQ(std::string(
"capca'"), seq);
72 TEST(CloudAccumulationLogic, Accumulate)
76 const sensor_msgs::PointCloud2::Ptr
msg(
new sensor_msgs::PointCloud2);
78 const auto process = [&seq]()
82 const auto accumulateOK = [&seq,
msg](
const sensor_msgs::PointCloud2::ConstPtr& msg2) ->
bool
88 const auto accumulateNG = [&seq,
msg](
const sensor_msgs::PointCloud2::ConstPtr& msg2) ->
bool
94 const auto clear = [&seq]()
99 accum.
push(
"1",
msg, process, accumulateOK, clear);
100 ASSERT_EQ(std::string(
"a"), seq);
102 accum.
push(
"2",
msg, process, accumulateOK, clear);
103 ASSERT_EQ(std::string(
"aa"), seq);
105 accum.
push(
"1",
msg, process, accumulateOK, clear);
106 ASSERT_EQ(std::string(
"aaa"), seq);
108 accum.
push(
"2",
msg, process, accumulateOK, clear);
109 ASSERT_EQ(std::string(
"aaaa"), seq);
113 accum.
push(
"1",
msg, process, accumulateOK, clear);
114 ASSERT_EQ(std::string(
"aaaapca"), seq);
116 accum.
push(
"2",
msg, process, accumulateOK, clear);
117 ASSERT_EQ(std::string(
"aaaapcaa"), seq);
120 accum.
push(
"2",
msg, process, accumulateOK, clear);
121 ASSERT_EQ(std::string(
"aaaapcaaa"), seq);
123 accum.
push(
"1",
msg, process, accumulateOK, clear);
124 ASSERT_EQ(std::string(
"aaaapcaaaa"), seq);
126 accum.
push(
"2",
msg, process, accumulateOK, clear);
127 ASSERT_EQ(std::string(
"aaaapcaaaaa"), seq);
130 accum.
push(
"1",
msg, process, accumulateOK, clear);
131 ASSERT_EQ(std::string(
"aaaapcaaaaapca"), seq);
134 accum.
push(
"2",
msg, process, accumulateNG, clear);
135 ASSERT_EQ(std::string(
"aaaapcaaaaapcaa'c"), seq);
137 accum.
push(
"2",
msg, process, accumulateOK, clear);
138 ASSERT_EQ(std::string(
"aaaapcaaaaapcaa'ca"), seq);
140 accum.
push(
"1",
msg, process, accumulateOK, clear);
141 ASSERT_EQ(std::string(
"aaaapcaaaaapcaa'caa"), seq);
144 accum.
push(
"1",
msg, process, accumulateOK, clear);
145 ASSERT_EQ(std::string(
"aaaapcaaaaapcaa'caaa"), seq);
147 accum.
push(
"1",
msg, process, accumulateOK, clear);
148 ASSERT_EQ(std::string(
"aaaapcaaaaapcaa'caaaa"), seq);
150 accum.
push(
"1",
msg, process, accumulateOK, clear);
151 ASSERT_EQ(std::string(
"aaaapcaaaaapcaa'caaaaa"), seq);
153 accum.
push(
"1",
msg, process, accumulateOK, clear);
154 ASSERT_EQ(std::string(
"aaaapcaaaaapcaa'caaaaaa"), seq);
157 accum.
push(
"1",
msg, process, accumulateOK, clear);
158 ASSERT_EQ(std::string(
"aaaapcaaaaapcaa'caaaaaapca"), seq);
160 accum.
push(
"1",
msg, process, accumulateNG, clear);
161 ASSERT_EQ(std::string(
"aaaapcaaaaapcaa'caaaaaapcaa'c"), seq);
164 int main(
int argc,
char** argv)
166 testing::InitGoogleTest(&argc, argv);
168 return RUN_ALL_TESTS();