test_synchronizer.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #include <gtest/gtest.h>
00036 
00037 #include "ros/time.h"
00038 #include <ros/init.h>
00039 #include "message_filters/synchronizer.h"
00040 #include <boost/array.hpp>
00041 
00042 using namespace message_filters;
00043 
00044 struct Header
00045 {
00046   ros::Time stamp;
00047 };
00048 
00049 
00050 struct Msg
00051 {
00052   Header header;
00053   int data;
00054 };
00055 typedef boost::shared_ptr<Msg> MsgPtr;
00056 typedef boost::shared_ptr<Msg const> MsgConstPtr;
00057 
00058 
00059 template<typename M0, typename M1, typename M2 = NullType, typename M3 = NullType, typename M4 = NullType,
00060          typename M5 = NullType, typename M6 = NullType, typename M7 = NullType, typename M8 = NullType>
00061 struct NullPolicy : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
00062 {
00063   typedef Synchronizer<NullPolicy> Sync;
00064   typedef PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8> Super;
00065   typedef typename Super::Messages Messages;
00066   typedef typename Super::Signal Signal;
00067   typedef typename Super::Events Events;
00068   typedef typename Super::RealTypeCount RealTypeCount;
00069 
00070   NullPolicy()
00071   {
00072     for (int i = 0; i < RealTypeCount::value; ++i)
00073     {
00074       added_[i] = 0;
00075     }
00076   }
00077 
00078   void initParent(Sync*)
00079   {
00080   }
00081 
00082   template<int i>
00083   void add(const typename mpl::at_c<Events, i>::type&)
00084   {
00085     ++added_.at(i);
00086   }
00087 
00088   boost::array<int32_t, RealTypeCount::value> added_;
00089 };
00090 typedef NullPolicy<Msg, Msg> Policy2;
00091 typedef NullPolicy<Msg, Msg, Msg> Policy3;
00092 typedef NullPolicy<Msg, Msg, Msg, Msg> Policy4;
00093 typedef NullPolicy<Msg, Msg, Msg, Msg, Msg> Policy5;
00094 typedef NullPolicy<Msg, Msg, Msg, Msg, Msg, Msg> Policy6;
00095 typedef NullPolicy<Msg, Msg, Msg, Msg, Msg, Msg, Msg> Policy7;
00096 typedef NullPolicy<Msg, Msg, Msg, Msg, Msg, Msg, Msg, Msg> Policy8;
00097 typedef NullPolicy<Msg, Msg, Msg, Msg, Msg, Msg, Msg, Msg, Msg> Policy9;
00098 
00099 TEST(Synchronizer, compile2)
00100 {
00101   NullFilter<Msg> f0, f1;
00102   Synchronizer<Policy2> sync(f0, f1);
00103 }
00104 
00105 TEST(Synchronizer, compile3)
00106 {
00107   NullFilter<Msg> f0, f1, f2;
00108   Synchronizer<Policy3> sync(f0, f1, f2);
00109 }
00110 
00111 TEST(Synchronizer, compile4)
00112 {
00113   NullFilter<Msg> f0, f1, f2, f3;
00114   Synchronizer<Policy4> sync(f0, f1, f2, f3);
00115 }
00116 
00117 TEST(Synchronizer, compile5)
00118 {
00119   NullFilter<Msg> f0, f1, f2, f3, f4;
00120   Synchronizer<Policy5> sync(f0, f1, f2, f3, f4);
00121 }
00122 
00123 TEST(Synchronizer, compile6)
00124 {
00125   NullFilter<Msg> f0, f1, f2, f3, f4, f5;
00126   Synchronizer<Policy6> sync(f0, f1, f2, f3, f4, f5);
00127 }
00128 
00129 TEST(Synchronizer, compile7)
00130 {
00131   NullFilter<Msg> f0, f1, f2, f3, f4, f5, f6;
00132   Synchronizer<Policy7> sync(f0, f1, f2, f3, f4, f5, f6);
00133 }
00134 
00135 TEST(Synchronizer, compile8)
00136 {
00137   NullFilter<Msg> f0, f1, f2, f3, f4, f5, f6, f7;
00138   Synchronizer<Policy8> sync(f0, f1, f2, f3, f4, f5, f6, f7);
00139 }
00140 
00141 TEST(Synchronizer, compile9)
00142 {
00143   NullFilter<Msg> f0, f1, f2, f3, f4, f5, f6, f7, f8;
00144   Synchronizer<Policy9> sync(f0, f1, f2, f3, f4, f5, f6, f7, f8);
00145 }
00146 
00147 void function2(const MsgConstPtr&, const MsgConstPtr&) {}
00148 void function3(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
00149 void function4(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
00150 void function5(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
00151 void function6(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
00152 void function7(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
00153 void function8(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
00154 void function9(const MsgConstPtr&, MsgConstPtr, const MsgPtr&, MsgPtr, const Msg&, Msg, const ros::MessageEvent<Msg const>&, const ros::MessageEvent<Msg>&, const MsgConstPtr&) {}
00155 
00156 TEST(Synchronizer, compileFunction2)
00157 {
00158   Synchronizer<Policy2> sync;
00159   sync.registerCallback(function2);
00160 }
00161 
00162 TEST(Synchronizer, compileFunction3)
00163 {
00164   Synchronizer<Policy3> sync;
00165   sync.registerCallback(function3);
00166 }
00167 
00168 TEST(Synchronizer, compileFunction4)
00169 {
00170   Synchronizer<Policy4> sync;
00171   sync.registerCallback(function4);
00172 }
00173 
00174 TEST(Synchronizer, compileFunction5)
00175 {
00176   Synchronizer<Policy5> sync;
00177   sync.registerCallback(function5);
00178 }
00179 
00180 TEST(Synchronizer, compileFunction6)
00181 {
00182   Synchronizer<Policy6> sync;
00183   sync.registerCallback(function6);
00184 }
00185 
00186 TEST(Synchronizer, compileFunction7)
00187 {
00188   Synchronizer<Policy7> sync;
00189   sync.registerCallback(function7);
00190 }
00191 
00192 TEST(Synchronizer, compileFunction8)
00193 {
00194   Synchronizer<Policy8> sync;
00195   sync.registerCallback(function8);
00196 }
00197 
00198 TEST(Synchronizer, compileFunction9)
00199 {
00200   Synchronizer<Policy9> sync;
00201   sync.registerCallback(function9);
00202 }
00203 
00204 struct MethodHelper
00205 {
00206   void method2(const MsgConstPtr&, const MsgConstPtr&) {}
00207   void method3(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
00208   void method4(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
00209   void method5(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
00210   void method6(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
00211   void method7(const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&, const MsgConstPtr&) {}
00212   void method8(const MsgConstPtr&, MsgConstPtr, const MsgPtr&, MsgPtr, const Msg&, Msg, const ros::MessageEvent<Msg const>&, const ros::MessageEvent<Msg>&) {}
00213   // Can only do 8 here because the object instance counts as a parameter and bind only supports 9
00214 };
00215 
00216 TEST(Synchronizer, compileMethod2)
00217 {
00218   MethodHelper h;
00219   Synchronizer<Policy2> sync;
00220   sync.registerCallback(&MethodHelper::method2, &h);
00221 }
00222 
00223 TEST(Synchronizer, compileMethod3)
00224 {
00225   MethodHelper h;
00226   Synchronizer<Policy3> sync;
00227   sync.registerCallback(&MethodHelper::method3, &h);
00228 }
00229 
00230 TEST(Synchronizer, compileMethod4)
00231 {
00232   MethodHelper h;
00233   Synchronizer<Policy4> sync;
00234   sync.registerCallback(&MethodHelper::method4, &h);
00235 }
00236 
00237 TEST(Synchronizer, compileMethod5)
00238 {
00239   MethodHelper h;
00240   Synchronizer<Policy5> sync;
00241   sync.registerCallback(&MethodHelper::method5, &h);
00242 }
00243 
00244 TEST(Synchronizer, compileMethod6)
00245 {
00246   MethodHelper h;
00247   Synchronizer<Policy6> sync;
00248   sync.registerCallback(&MethodHelper::method6, &h);
00249 }
00250 
00251 TEST(Synchronizer, compileMethod7)
00252 {
00253   MethodHelper h;
00254   Synchronizer<Policy7> sync;
00255   sync.registerCallback(&MethodHelper::method7, &h);
00256 }
00257 
00258 TEST(Synchronizer, compileMethod8)
00259 {
00260   MethodHelper h;
00261   Synchronizer<Policy8> sync;
00262   sync.registerCallback(&MethodHelper::method8, &h);
00263 }
00264 
00265 TEST(Synchronizer, add2)
00266 {
00267   Synchronizer<Policy2> sync;
00268   MsgPtr m(boost::make_shared<Msg>());
00269 
00270   ASSERT_EQ(sync.added_[0], 0);
00271   sync.add<0>(m);
00272   ASSERT_EQ(sync.added_[0], 1);
00273   ASSERT_EQ(sync.added_[1], 0);
00274   sync.add<1>(m);
00275   ASSERT_EQ(sync.added_[1], 1);
00276 }
00277 
00278 TEST(Synchronizer, add3)
00279 {
00280   Synchronizer<Policy3> sync;
00281   MsgPtr m(boost::make_shared<Msg>());
00282 
00283   ASSERT_EQ(sync.added_[0], 0);
00284   sync.add<0>(m);
00285   ASSERT_EQ(sync.added_[0], 1);
00286   ASSERT_EQ(sync.added_[1], 0);
00287   sync.add<1>(m);
00288   ASSERT_EQ(sync.added_[1], 1);
00289   ASSERT_EQ(sync.added_[2], 0);
00290   sync.add<2>(m);
00291   ASSERT_EQ(sync.added_[2], 1);
00292 }
00293 
00294 TEST(Synchronizer, add4)
00295 {
00296   Synchronizer<Policy4> sync;
00297   MsgPtr m(boost::make_shared<Msg>());
00298 
00299   ASSERT_EQ(sync.added_[0], 0);
00300   sync.add<0>(m);
00301   ASSERT_EQ(sync.added_[0], 1);
00302   ASSERT_EQ(sync.added_[1], 0);
00303   sync.add<1>(m);
00304   ASSERT_EQ(sync.added_[1], 1);
00305   ASSERT_EQ(sync.added_[2], 0);
00306   sync.add<2>(m);
00307   ASSERT_EQ(sync.added_[2], 1);
00308   ASSERT_EQ(sync.added_[3], 0);
00309   sync.add<3>(m);
00310   ASSERT_EQ(sync.added_[3], 1);
00311 }
00312 
00313 TEST(Synchronizer, add5)
00314 {
00315   Synchronizer<Policy5> sync;
00316   MsgPtr m(boost::make_shared<Msg>());
00317 
00318   ASSERT_EQ(sync.added_[0], 0);
00319   sync.add<0>(m);
00320   ASSERT_EQ(sync.added_[0], 1);
00321   ASSERT_EQ(sync.added_[1], 0);
00322   sync.add<1>(m);
00323   ASSERT_EQ(sync.added_[1], 1);
00324   ASSERT_EQ(sync.added_[2], 0);
00325   sync.add<2>(m);
00326   ASSERT_EQ(sync.added_[2], 1);
00327   ASSERT_EQ(sync.added_[3], 0);
00328   sync.add<3>(m);
00329   ASSERT_EQ(sync.added_[3], 1);
00330   ASSERT_EQ(sync.added_[4], 0);
00331   sync.add<4>(m);
00332   ASSERT_EQ(sync.added_[4], 1);
00333 }
00334 
00335 TEST(Synchronizer, add6)
00336 {
00337   Synchronizer<Policy6> sync;
00338   MsgPtr m(boost::make_shared<Msg>());
00339 
00340   ASSERT_EQ(sync.added_[0], 0);
00341   sync.add<0>(m);
00342   ASSERT_EQ(sync.added_[0], 1);
00343   ASSERT_EQ(sync.added_[1], 0);
00344   sync.add<1>(m);
00345   ASSERT_EQ(sync.added_[1], 1);
00346   ASSERT_EQ(sync.added_[2], 0);
00347   sync.add<2>(m);
00348   ASSERT_EQ(sync.added_[2], 1);
00349   ASSERT_EQ(sync.added_[3], 0);
00350   sync.add<3>(m);
00351   ASSERT_EQ(sync.added_[3], 1);
00352   ASSERT_EQ(sync.added_[4], 0);
00353   sync.add<4>(m);
00354   ASSERT_EQ(sync.added_[4], 1);
00355   ASSERT_EQ(sync.added_[5], 0);
00356   sync.add<5>(m);
00357   ASSERT_EQ(sync.added_[5], 1);
00358 }
00359 
00360 TEST(Synchronizer, add7)
00361 {
00362   Synchronizer<Policy7> sync;
00363   MsgPtr m(boost::make_shared<Msg>());
00364 
00365   ASSERT_EQ(sync.added_[0], 0);
00366   sync.add<0>(m);
00367   ASSERT_EQ(sync.added_[0], 1);
00368   ASSERT_EQ(sync.added_[1], 0);
00369   sync.add<1>(m);
00370   ASSERT_EQ(sync.added_[1], 1);
00371   ASSERT_EQ(sync.added_[2], 0);
00372   sync.add<2>(m);
00373   ASSERT_EQ(sync.added_[2], 1);
00374   ASSERT_EQ(sync.added_[3], 0);
00375   sync.add<3>(m);
00376   ASSERT_EQ(sync.added_[3], 1);
00377   ASSERT_EQ(sync.added_[4], 0);
00378   sync.add<4>(m);
00379   ASSERT_EQ(sync.added_[4], 1);
00380   ASSERT_EQ(sync.added_[5], 0);
00381   sync.add<5>(m);
00382   ASSERT_EQ(sync.added_[5], 1);
00383   ASSERT_EQ(sync.added_[6], 0);
00384   sync.add<6>(m);
00385   ASSERT_EQ(sync.added_[6], 1);
00386 }
00387 
00388 TEST(Synchronizer, add8)
00389 {
00390   Synchronizer<Policy8> sync;
00391   MsgPtr m(boost::make_shared<Msg>());
00392 
00393   ASSERT_EQ(sync.added_[0], 0);
00394   sync.add<0>(m);
00395   ASSERT_EQ(sync.added_[0], 1);
00396   ASSERT_EQ(sync.added_[1], 0);
00397   sync.add<1>(m);
00398   ASSERT_EQ(sync.added_[1], 1);
00399   ASSERT_EQ(sync.added_[2], 0);
00400   sync.add<2>(m);
00401   ASSERT_EQ(sync.added_[2], 1);
00402   ASSERT_EQ(sync.added_[3], 0);
00403   sync.add<3>(m);
00404   ASSERT_EQ(sync.added_[3], 1);
00405   ASSERT_EQ(sync.added_[4], 0);
00406   sync.add<4>(m);
00407   ASSERT_EQ(sync.added_[4], 1);
00408   ASSERT_EQ(sync.added_[5], 0);
00409   sync.add<5>(m);
00410   ASSERT_EQ(sync.added_[5], 1);
00411   ASSERT_EQ(sync.added_[6], 0);
00412   sync.add<6>(m);
00413   ASSERT_EQ(sync.added_[6], 1);
00414   ASSERT_EQ(sync.added_[7], 0);
00415   sync.add<7>(m);
00416   ASSERT_EQ(sync.added_[7], 1);
00417 }
00418 
00419 TEST(Synchronizer, add9)
00420 {
00421   Synchronizer<Policy9> sync;
00422   MsgPtr m(boost::make_shared<Msg>());
00423 
00424   ASSERT_EQ(sync.added_[0], 0);
00425   sync.add<0>(m);
00426   ASSERT_EQ(sync.added_[0], 1);
00427   ASSERT_EQ(sync.added_[1], 0);
00428   sync.add<1>(m);
00429   ASSERT_EQ(sync.added_[1], 1);
00430   ASSERT_EQ(sync.added_[2], 0);
00431   sync.add<2>(m);
00432   ASSERT_EQ(sync.added_[2], 1);
00433   ASSERT_EQ(sync.added_[3], 0);
00434   sync.add<3>(m);
00435   ASSERT_EQ(sync.added_[3], 1);
00436   ASSERT_EQ(sync.added_[4], 0);
00437   sync.add<4>(m);
00438   ASSERT_EQ(sync.added_[4], 1);
00439   ASSERT_EQ(sync.added_[5], 0);
00440   sync.add<5>(m);
00441   ASSERT_EQ(sync.added_[5], 1);
00442   ASSERT_EQ(sync.added_[6], 0);
00443   sync.add<6>(m);
00444   ASSERT_EQ(sync.added_[6], 1);
00445   ASSERT_EQ(sync.added_[7], 0);
00446   sync.add<7>(m);
00447   ASSERT_EQ(sync.added_[7], 1);
00448   ASSERT_EQ(sync.added_[8], 0);
00449   sync.add<8>(m);
00450   ASSERT_EQ(sync.added_[8], 1);
00451 }
00452 
00453 int main(int argc, char **argv){
00454   testing::InitGoogleTest(&argc, argv);
00455   ros::init(argc, argv, "blah");
00456 
00457   ros::Time::init();
00458   ros::Time::setNow(ros::Time());
00459 
00460   return RUN_ALL_TESTS();
00461 }
00462 
00463 


message_filters
Author(s): Josh Faust, Vijay Pradeep
autogenerated on Tue Mar 7 2017 03:45:14