test_synchronizer.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #include <gtest/gtest.h>
36 
37 #include "ros/time.h"
38 #include <ros/init.h>
40 #include <boost/array.hpp>
41 
42 using namespace message_filters;
43 
44 struct Header
45 {
46  ros::Time stamp;
47 };
48 
49 
50 struct Msg
51 {
52  Header header;
53  int data;
54 };
57 
58 
59 template<typename M0, typename M1, typename M2 = NullType, typename M3 = NullType, typename M4 = NullType,
60  typename M5 = NullType, typename M6 = NullType, typename M7 = NullType, typename M8 = NullType>
61 struct NullPolicy : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
62 {
65  typedef typename Super::Messages Messages;
66  typedef typename Super::Signal Signal;
67  typedef typename Super::Events Events;
69 
71  {
72  for (int i = 0; i < RealTypeCount::value; ++i)
73  {
74  added_[i] = 0;
75  }
76  }
77 
79  {
80  }
81 
82  template<int i>
83  void add(const typename mpl::at_c<Events, i>::type&)
84  {
85  ++added_.at(i);
86  }
87 
88  boost::array<int32_t, RealTypeCount::value> added_;
89 };
98 
99 TEST(Synchronizer, compile2)
100 {
101  NullFilter<Msg> f0, f1;
102  Synchronizer<Policy2> sync(f0, f1);
103 }
104 
105 TEST(Synchronizer, compile3)
106 {
107  NullFilter<Msg> f0, f1, f2;
108  Synchronizer<Policy3> sync(f0, f1, f2);
109 }
110 
111 TEST(Synchronizer, compile4)
112 {
113  NullFilter<Msg> f0, f1, f2, f3;
114  Synchronizer<Policy4> sync(f0, f1, f2, f3);
115 }
116 
117 TEST(Synchronizer, compile5)
118 {
119  NullFilter<Msg> f0, f1, f2, f3, f4;
120  Synchronizer<Policy5> sync(f0, f1, f2, f3, f4);
121 }
122 
123 TEST(Synchronizer, compile6)
124 {
125  NullFilter<Msg> f0, f1, f2, f3, f4, f5;
126  Synchronizer<Policy6> sync(f0, f1, f2, f3, f4, f5);
127 }
128 
129 TEST(Synchronizer, compile7)
130 {
131  NullFilter<Msg> f0, f1, f2, f3, f4, f5, f6;
132  Synchronizer<Policy7> sync(f0, f1, f2, f3, f4, f5, f6);
133 }
134 
135 TEST(Synchronizer, compile8)
136 {
137  NullFilter<Msg> f0, f1, f2, f3, f4, f5, f6, f7;
138  Synchronizer<Policy8> sync(f0, f1, f2, f3, f4, f5, f6, f7);
139 }
140 
141 TEST(Synchronizer, compile9)
142 {
143  NullFilter<Msg> f0, f1, f2, f3, f4, f5, f6, f7, f8;
144  Synchronizer<Policy9> sync(f0, f1, f2, f3, f4, f5, f6, f7, f8);
145 }
146 
147 void function2(const MsgConstPtr&, const MsgConstPtr&) {}
148 void function3(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
149 void function4(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
150 void function5(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
151 void function6(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
152 void function7(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
153 void function8(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
155 
156 TEST(Synchronizer, compileFunction2)
157 {
160 }
161 
162 TEST(Synchronizer, compileFunction3)
163 {
166 }
167 
168 TEST(Synchronizer, compileFunction4)
169 {
172 }
173 
174 TEST(Synchronizer, compileFunction5)
175 {
178 }
179 
180 TEST(Synchronizer, compileFunction6)
181 {
184 }
185 
186 TEST(Synchronizer, compileFunction7)
187 {
190 }
191 
192 TEST(Synchronizer, compileFunction8)
193 {
196 }
197 
198 TEST(Synchronizer, compileFunction9)
199 {
202 }
203 
205 {
206  void method2(const MsgConstPtr&, const MsgConstPtr&) {}
207  void method3(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
208  void method4(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
209  void method5(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
210  void method6(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
211  void method7(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
213  // Can only do 8 here because the object instance counts as a parameter and bind only supports 9
214 };
215 
216 TEST(Synchronizer, compileMethod2)
217 {
218  MethodHelper h;
221 }
222 
223 TEST(Synchronizer, compileMethod3)
224 {
225  MethodHelper h;
228 }
229 
230 TEST(Synchronizer, compileMethod4)
231 {
232  MethodHelper h;
235 }
236 
237 TEST(Synchronizer, compileMethod5)
238 {
239  MethodHelper h;
242 }
243 
244 TEST(Synchronizer, compileMethod6)
245 {
246  MethodHelper h;
249 }
250 
251 TEST(Synchronizer, compileMethod7)
252 {
253  MethodHelper h;
256 }
257 
258 TEST(Synchronizer, compileMethod8)
259 {
260  MethodHelper h;
263 }
264 
266 {
268  MsgPtr m(boost::make_shared<Msg>());
269 
270  ASSERT_EQ(sync.added_[0], 0);
271  sync.add<0>(m);
272  ASSERT_EQ(sync.added_[0], 1);
273  ASSERT_EQ(sync.added_[1], 0);
274  sync.add<1>(m);
275  ASSERT_EQ(sync.added_[1], 1);
276 }
277 
279 {
281  MsgPtr m(boost::make_shared<Msg>());
282 
283  ASSERT_EQ(sync.added_[0], 0);
284  sync.add<0>(m);
285  ASSERT_EQ(sync.added_[0], 1);
286  ASSERT_EQ(sync.added_[1], 0);
287  sync.add<1>(m);
288  ASSERT_EQ(sync.added_[1], 1);
289  ASSERT_EQ(sync.added_[2], 0);
290  sync.add<2>(m);
291  ASSERT_EQ(sync.added_[2], 1);
292 }
293 
295 {
297  MsgPtr m(boost::make_shared<Msg>());
298 
299  ASSERT_EQ(sync.added_[0], 0);
300  sync.add<0>(m);
301  ASSERT_EQ(sync.added_[0], 1);
302  ASSERT_EQ(sync.added_[1], 0);
303  sync.add<1>(m);
304  ASSERT_EQ(sync.added_[1], 1);
305  ASSERT_EQ(sync.added_[2], 0);
306  sync.add<2>(m);
307  ASSERT_EQ(sync.added_[2], 1);
308  ASSERT_EQ(sync.added_[3], 0);
309  sync.add<3>(m);
310  ASSERT_EQ(sync.added_[3], 1);
311 }
312 
314 {
316  MsgPtr m(boost::make_shared<Msg>());
317 
318  ASSERT_EQ(sync.added_[0], 0);
319  sync.add<0>(m);
320  ASSERT_EQ(sync.added_[0], 1);
321  ASSERT_EQ(sync.added_[1], 0);
322  sync.add<1>(m);
323  ASSERT_EQ(sync.added_[1], 1);
324  ASSERT_EQ(sync.added_[2], 0);
325  sync.add<2>(m);
326  ASSERT_EQ(sync.added_[2], 1);
327  ASSERT_EQ(sync.added_[3], 0);
328  sync.add<3>(m);
329  ASSERT_EQ(sync.added_[3], 1);
330  ASSERT_EQ(sync.added_[4], 0);
331  sync.add<4>(m);
332  ASSERT_EQ(sync.added_[4], 1);
333 }
334 
336 {
338  MsgPtr m(boost::make_shared<Msg>());
339 
340  ASSERT_EQ(sync.added_[0], 0);
341  sync.add<0>(m);
342  ASSERT_EQ(sync.added_[0], 1);
343  ASSERT_EQ(sync.added_[1], 0);
344  sync.add<1>(m);
345  ASSERT_EQ(sync.added_[1], 1);
346  ASSERT_EQ(sync.added_[2], 0);
347  sync.add<2>(m);
348  ASSERT_EQ(sync.added_[2], 1);
349  ASSERT_EQ(sync.added_[3], 0);
350  sync.add<3>(m);
351  ASSERT_EQ(sync.added_[3], 1);
352  ASSERT_EQ(sync.added_[4], 0);
353  sync.add<4>(m);
354  ASSERT_EQ(sync.added_[4], 1);
355  ASSERT_EQ(sync.added_[5], 0);
356  sync.add<5>(m);
357  ASSERT_EQ(sync.added_[5], 1);
358 }
359 
361 {
363  MsgPtr m(boost::make_shared<Msg>());
364 
365  ASSERT_EQ(sync.added_[0], 0);
366  sync.add<0>(m);
367  ASSERT_EQ(sync.added_[0], 1);
368  ASSERT_EQ(sync.added_[1], 0);
369  sync.add<1>(m);
370  ASSERT_EQ(sync.added_[1], 1);
371  ASSERT_EQ(sync.added_[2], 0);
372  sync.add<2>(m);
373  ASSERT_EQ(sync.added_[2], 1);
374  ASSERT_EQ(sync.added_[3], 0);
375  sync.add<3>(m);
376  ASSERT_EQ(sync.added_[3], 1);
377  ASSERT_EQ(sync.added_[4], 0);
378  sync.add<4>(m);
379  ASSERT_EQ(sync.added_[4], 1);
380  ASSERT_EQ(sync.added_[5], 0);
381  sync.add<5>(m);
382  ASSERT_EQ(sync.added_[5], 1);
383  ASSERT_EQ(sync.added_[6], 0);
384  sync.add<6>(m);
385  ASSERT_EQ(sync.added_[6], 1);
386 }
387 
389 {
391  MsgPtr m(boost::make_shared<Msg>());
392 
393  ASSERT_EQ(sync.added_[0], 0);
394  sync.add<0>(m);
395  ASSERT_EQ(sync.added_[0], 1);
396  ASSERT_EQ(sync.added_[1], 0);
397  sync.add<1>(m);
398  ASSERT_EQ(sync.added_[1], 1);
399  ASSERT_EQ(sync.added_[2], 0);
400  sync.add<2>(m);
401  ASSERT_EQ(sync.added_[2], 1);
402  ASSERT_EQ(sync.added_[3], 0);
403  sync.add<3>(m);
404  ASSERT_EQ(sync.added_[3], 1);
405  ASSERT_EQ(sync.added_[4], 0);
406  sync.add<4>(m);
407  ASSERT_EQ(sync.added_[4], 1);
408  ASSERT_EQ(sync.added_[5], 0);
409  sync.add<5>(m);
410  ASSERT_EQ(sync.added_[5], 1);
411  ASSERT_EQ(sync.added_[6], 0);
412  sync.add<6>(m);
413  ASSERT_EQ(sync.added_[6], 1);
414  ASSERT_EQ(sync.added_[7], 0);
415  sync.add<7>(m);
416  ASSERT_EQ(sync.added_[7], 1);
417 }
418 
420 {
422  MsgPtr m(boost::make_shared<Msg>());
423 
424  ASSERT_EQ(sync.added_[0], 0);
425  sync.add<0>(m);
426  ASSERT_EQ(sync.added_[0], 1);
427  ASSERT_EQ(sync.added_[1], 0);
428  sync.add<1>(m);
429  ASSERT_EQ(sync.added_[1], 1);
430  ASSERT_EQ(sync.added_[2], 0);
431  sync.add<2>(m);
432  ASSERT_EQ(sync.added_[2], 1);
433  ASSERT_EQ(sync.added_[3], 0);
434  sync.add<3>(m);
435  ASSERT_EQ(sync.added_[3], 1);
436  ASSERT_EQ(sync.added_[4], 0);
437  sync.add<4>(m);
438  ASSERT_EQ(sync.added_[4], 1);
439  ASSERT_EQ(sync.added_[5], 0);
440  sync.add<5>(m);
441  ASSERT_EQ(sync.added_[5], 1);
442  ASSERT_EQ(sync.added_[6], 0);
443  sync.add<6>(m);
444  ASSERT_EQ(sync.added_[6], 1);
445  ASSERT_EQ(sync.added_[7], 0);
446  sync.add<7>(m);
447  ASSERT_EQ(sync.added_[7], 1);
448  ASSERT_EQ(sync.added_[8], 0);
449  sync.add<8>(m);
450  ASSERT_EQ(sync.added_[8], 1);
451 }
452 
453 int main(int argc, char **argv){
454  testing::InitGoogleTest(&argc, argv);
455  ros::init(argc, argv, "blah");
456 
457  ros::Time::init();
459 
460  return RUN_ALL_TESTS();
461 }
462 
463 
NullPolicy::Events
Super::Events Events
Definition: test_synchronizer.cpp:67
MethodHelper::method2
void method2(const MsgConstPtr &, const MsgConstPtr &)
Definition: test_synchronizer.cpp:206
function7
void function7(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
Definition: test_synchronizer.cpp:152
Msg
Definition: msg_cache_unittest.cpp:50
message_filters::NullFilter
Definition: null_types.h:86
function4
void function4(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
Definition: test_synchronizer.cpp:149
Header
Definition: msg_cache_unittest.cpp:44
message_filters::Synchronizer
Definition: synchronizer.h:100
boost::shared_ptr< Msg >
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
synchronizer.h
MsgPtr
boost::shared_ptr< Msg > MsgPtr
Definition: test_synchronizer.cpp:55
Policy4
NullPolicy< Msg, Msg, Msg, Msg > Policy4
Definition: test_synchronizer.cpp:92
MsgConstPtr
boost::shared_ptr< Msg const > MsgConstPtr
Definition: test_synchronizer.cpp:56
time.h
main
int main(int argc, char **argv)
Definition: test_synchronizer.cpp:453
function2
void function2(const MsgConstPtr &, const MsgConstPtr &)
Definition: test_synchronizer.cpp:147
NullPolicy
Definition: test_synchronizer.cpp:61
message_filters::PolicyBase
Definition: synchronizer.h:404
Policy5
NullPolicy< Msg, Msg, Msg, Msg, Msg > Policy5
Definition: test_synchronizer.cpp:93
init.h
ros::Time::setNow
static void setNow(const Time &new_now)
MethodHelper::method3
void method3(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
Definition: test_synchronizer.cpp:207
message_filters::PolicyBase::RealTypeCount
mpl::fold< Messages, mpl::int_< 0 >, mpl::if_< mpl::not_< boost::is_same< mpl::_2, NullType > >, mpl::next< mpl::_1 >, mpl::_1 > >::type RealTypeCount
Definition: synchronizer.h:411
Policy8
NullPolicy< Msg, Msg, Msg, Msg, Msg, Msg, Msg, Msg > Policy8
Definition: test_synchronizer.cpp:96
message_filters::PolicyBase::Events
mpl::vector< ros::MessageEvent< M0 const >, ros::MessageEvent< M1 const >, ros::MessageEvent< M2 const >, ros::MessageEvent< M3 const >, ros::MessageEvent< M4 const >, ros::MessageEvent< M5 const >, ros::MessageEvent< M6 const >, ros::MessageEvent< M7 const >, ros::MessageEvent< M8 const > > Events
Definition: synchronizer.h:410
function5
void function5(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
Definition: test_synchronizer.cpp:150
MethodHelper::method6
void method6(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
Definition: test_synchronizer.cpp:210
MethodHelper::method8
void method8(const MsgConstPtr &, MsgConstPtr, const MsgPtr &, MsgPtr, const Msg &, Msg, const ros::MessageEvent< Msg const > &, const ros::MessageEvent< Msg > &)
Definition: test_synchronizer.cpp:212
message_filters::Synchronizer::registerCallback
Connection registerCallback(C &callback)
Definition: synchronizer.h:366
TEST
TEST(Synchronizer, compile2)
Definition: test_synchronizer.cpp:99
MethodHelper::method5
void method5(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
Definition: test_synchronizer.cpp:209
NullPolicy::NullPolicy
NullPolicy()
Definition: test_synchronizer.cpp:70
message_filters::NullType
Definition: null_types.h:80
NullPolicy::add
void add(const typename mpl::at_c< Events, i >::type &)
Definition: test_synchronizer.cpp:83
NullPolicy::added_
boost::array< int32_t, RealTypeCount::value > added_
Definition: test_synchronizer.cpp:88
MethodHelper::method7
void method7(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
Definition: test_synchronizer.cpp:211
message_filters::Signal9
Definition: signal9.h:176
Policy9
NullPolicy< Msg, Msg, Msg, Msg, Msg, Msg, Msg, Msg, Msg > Policy9
Definition: test_synchronizer.cpp:97
Policy6
NullPolicy< Msg, Msg, Msg, Msg, Msg, Msg > Policy6
Definition: test_synchronizer.cpp:94
function6
void function6(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
Definition: test_synchronizer.cpp:151
function9
void function9(const MsgConstPtr &, MsgConstPtr, const MsgPtr &, MsgPtr, const Msg &, Msg, const ros::MessageEvent< Msg const > &, const ros::MessageEvent< Msg > &, const MsgConstPtr &)
Definition: test_synchronizer.cpp:154
function3
void function3(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
Definition: test_synchronizer.cpp:148
NullPolicy::RealTypeCount
Super::RealTypeCount RealTypeCount
Definition: test_synchronizer.cpp:68
Policy2
NullPolicy< Msg, Msg > Policy2
Definition: test_synchronizer.cpp:90
Policy7
NullPolicy< Msg, Msg, Msg, Msg, Msg, Msg, Msg > Policy7
Definition: test_synchronizer.cpp:95
NullPolicy::Messages
Super::Messages Messages
Definition: test_synchronizer.cpp:65
NullPolicy::Signal
Super::Signal Signal
Definition: test_synchronizer.cpp:66
ros::Time::init
static void init()
MethodHelper
Definition: test_synchronizer.cpp:204
ros::Time
message_filters::PolicyBase::Messages
mpl::vector< M0, M1, M2, M3, M4, M5, M6, M7, M8 > Messages
Definition: synchronizer.h:406
NullPolicy::initParent
void initParent(Sync *)
Definition: test_synchronizer.cpp:78
Policy3
NullPolicy< Msg, Msg, Msg > Policy3
Definition: test_synchronizer.cpp:91
NullPolicy::Sync
Synchronizer< NullPolicy > Sync
Definition: test_synchronizer.cpp:63
message_filters::Synchronizer::add
void add(const boost::shared_ptr< typename mpl::at_c< Messages, i >::type const > &msg)
Definition: synchronizer.h:404
message_filters
Definition: cache.h:47
NullPolicy::Super
PolicyBase< M0, M1, M2, M3, M4, M5, M6, M7, M8 > Super
Definition: test_synchronizer.cpp:64
header
const std::string header
function8
void function8(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
Definition: test_synchronizer.cpp:153
MethodHelper::method4
void method4(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
Definition: test_synchronizer.cpp:208
ros::MessageEvent


message_filters
Author(s): Josh Faust, Vijay Pradeep, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:01:54