35 #include <gtest/gtest.h> 40 #include <boost/array.hpp> 72 for (
int i = 0; i < RealTypeCount::value; ++i)
83 void add(
const typename mpl::at_c<Events, i>::type&)
88 boost::array<int32_t, RealTypeCount::value>
added_;
268 MsgPtr m(boost::make_shared<Msg>());
270 ASSERT_EQ(sync.added_[0], 0);
272 ASSERT_EQ(sync.added_[0], 1);
273 ASSERT_EQ(sync.added_[1], 0);
275 ASSERT_EQ(sync.added_[1], 1);
281 MsgPtr m(boost::make_shared<Msg>());
283 ASSERT_EQ(sync.added_[0], 0);
285 ASSERT_EQ(sync.added_[0], 1);
286 ASSERT_EQ(sync.added_[1], 0);
288 ASSERT_EQ(sync.added_[1], 1);
289 ASSERT_EQ(sync.added_[2], 0);
291 ASSERT_EQ(sync.added_[2], 1);
297 MsgPtr m(boost::make_shared<Msg>());
299 ASSERT_EQ(sync.added_[0], 0);
301 ASSERT_EQ(sync.added_[0], 1);
302 ASSERT_EQ(sync.added_[1], 0);
304 ASSERT_EQ(sync.added_[1], 1);
305 ASSERT_EQ(sync.added_[2], 0);
307 ASSERT_EQ(sync.added_[2], 1);
308 ASSERT_EQ(sync.added_[3], 0);
310 ASSERT_EQ(sync.added_[3], 1);
316 MsgPtr m(boost::make_shared<Msg>());
318 ASSERT_EQ(sync.added_[0], 0);
320 ASSERT_EQ(sync.added_[0], 1);
321 ASSERT_EQ(sync.added_[1], 0);
323 ASSERT_EQ(sync.added_[1], 1);
324 ASSERT_EQ(sync.added_[2], 0);
326 ASSERT_EQ(sync.added_[2], 1);
327 ASSERT_EQ(sync.added_[3], 0);
329 ASSERT_EQ(sync.added_[3], 1);
330 ASSERT_EQ(sync.added_[4], 0);
332 ASSERT_EQ(sync.added_[4], 1);
338 MsgPtr m(boost::make_shared<Msg>());
340 ASSERT_EQ(sync.added_[0], 0);
342 ASSERT_EQ(sync.added_[0], 1);
343 ASSERT_EQ(sync.added_[1], 0);
345 ASSERT_EQ(sync.added_[1], 1);
346 ASSERT_EQ(sync.added_[2], 0);
348 ASSERT_EQ(sync.added_[2], 1);
349 ASSERT_EQ(sync.added_[3], 0);
351 ASSERT_EQ(sync.added_[3], 1);
352 ASSERT_EQ(sync.added_[4], 0);
354 ASSERT_EQ(sync.added_[4], 1);
355 ASSERT_EQ(sync.added_[5], 0);
357 ASSERT_EQ(sync.added_[5], 1);
363 MsgPtr m(boost::make_shared<Msg>());
365 ASSERT_EQ(sync.added_[0], 0);
367 ASSERT_EQ(sync.added_[0], 1);
368 ASSERT_EQ(sync.added_[1], 0);
370 ASSERT_EQ(sync.added_[1], 1);
371 ASSERT_EQ(sync.added_[2], 0);
373 ASSERT_EQ(sync.added_[2], 1);
374 ASSERT_EQ(sync.added_[3], 0);
376 ASSERT_EQ(sync.added_[3], 1);
377 ASSERT_EQ(sync.added_[4], 0);
379 ASSERT_EQ(sync.added_[4], 1);
380 ASSERT_EQ(sync.added_[5], 0);
382 ASSERT_EQ(sync.added_[5], 1);
383 ASSERT_EQ(sync.added_[6], 0);
385 ASSERT_EQ(sync.added_[6], 1);
391 MsgPtr m(boost::make_shared<Msg>());
393 ASSERT_EQ(sync.added_[0], 0);
395 ASSERT_EQ(sync.added_[0], 1);
396 ASSERT_EQ(sync.added_[1], 0);
398 ASSERT_EQ(sync.added_[1], 1);
399 ASSERT_EQ(sync.added_[2], 0);
401 ASSERT_EQ(sync.added_[2], 1);
402 ASSERT_EQ(sync.added_[3], 0);
404 ASSERT_EQ(sync.added_[3], 1);
405 ASSERT_EQ(sync.added_[4], 0);
407 ASSERT_EQ(sync.added_[4], 1);
408 ASSERT_EQ(sync.added_[5], 0);
410 ASSERT_EQ(sync.added_[5], 1);
411 ASSERT_EQ(sync.added_[6], 0);
413 ASSERT_EQ(sync.added_[6], 1);
414 ASSERT_EQ(sync.added_[7], 0);
416 ASSERT_EQ(sync.added_[7], 1);
422 MsgPtr m(boost::make_shared<Msg>());
424 ASSERT_EQ(sync.added_[0], 0);
426 ASSERT_EQ(sync.added_[0], 1);
427 ASSERT_EQ(sync.added_[1], 0);
429 ASSERT_EQ(sync.added_[1], 1);
430 ASSERT_EQ(sync.added_[2], 0);
432 ASSERT_EQ(sync.added_[2], 1);
433 ASSERT_EQ(sync.added_[3], 0);
435 ASSERT_EQ(sync.added_[3], 1);
436 ASSERT_EQ(sync.added_[4], 0);
438 ASSERT_EQ(sync.added_[4], 1);
439 ASSERT_EQ(sync.added_[5], 0);
441 ASSERT_EQ(sync.added_[5], 1);
442 ASSERT_EQ(sync.added_[6], 0);
444 ASSERT_EQ(sync.added_[6], 1);
445 ASSERT_EQ(sync.added_[7], 0);
447 ASSERT_EQ(sync.added_[7], 1);
448 ASSERT_EQ(sync.added_[8], 0);
450 ASSERT_EQ(sync.added_[8], 1);
453 int main(
int argc,
char **argv){
454 testing::InitGoogleTest(&argc, argv);
460 return RUN_ALL_TESTS();
void function7(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
int main(int argc, char **argv)
NullPolicy< Msg, Msg, Msg, Msg > Policy4
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
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
NullPolicy< Msg, Msg, Msg, Msg, Msg, Msg, Msg > Policy7
void function6(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
void function5(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
void method7(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
void add(const typename mpl::at_c< Events, i >::type &)
boost::array< int32_t, RealTypeCount::value > added_
mpl::fold< Messages, mpl::int_< 0 >, mpl::if_< mpl::not_< boost::is_same< mpl::_2, NullType > >, mpl::next< mpl::_1 >, mpl::_1 > >::type RealTypeCount
static void setNow(const Time &new_now)
void function2(const MsgConstPtr &, const MsgConstPtr &)
boost::shared_ptr< Msg const > MsgConstPtr
void method6(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
Super::RealTypeCount RealTypeCount
Connection registerCallback(C &callback)
NullPolicy< Msg, Msg, Msg, Msg, Msg, Msg, Msg, Msg > Policy8
NullPolicy< Msg, Msg, Msg, Msg, Msg, Msg, Msg, Msg, Msg > Policy9
mpl::vector< M0, M1, M2, M3, M4, M5, M6, M7, M8 > Messages
NullPolicy< Msg, Msg, Msg, Msg, Msg, Msg > Policy6
NullPolicy< Msg, Msg, Msg, Msg, Msg > Policy5
void method2(const MsgConstPtr &, const MsgConstPtr &)
PolicyBase< M0, M1, M2, M3, M4, M5, M6, M7, M8 > Super
NullPolicy< Msg, Msg, Msg > Policy3
Synchronizer< NullPolicy > Sync
TEST(Synchronizer, compile2)
void method8(const MsgConstPtr &, MsgConstPtr, const MsgPtr &, MsgPtr, const Msg &, Msg, const ros::MessageEvent< Msg const > &, const ros::MessageEvent< Msg > &)
void method4(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
void function8(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
void method3(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
boost::shared_ptr< Msg > MsgPtr
void function9(const MsgConstPtr &, MsgConstPtr, const MsgPtr &, MsgPtr, const Msg &, Msg, const ros::MessageEvent< Msg const > &, const ros::MessageEvent< Msg > &, const MsgConstPtr &)
void add(const boost::shared_ptr< typename mpl::at_c< Messages, i >::type const > &msg)
NullPolicy< Msg, Msg > Policy2
void function4(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
void function3(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)
void method5(const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &, const MsgConstPtr &)