Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <gtest/gtest.h>
00036
00037 #include "ros/time.h"
00038 #include <ros/init.h>
00039 #include "message_filters/simple_filter.h"
00040
00041 using namespace message_filters;
00042
00043 struct Msg
00044 {
00045 };
00046 typedef boost::shared_ptr<Msg> MsgPtr;
00047 typedef boost::shared_ptr<Msg const> MsgConstPtr;
00048
00049 struct Filter : public SimpleFilter<Msg>
00050 {
00051 typedef ros::MessageEvent<Msg const> EventType;
00052
00053 void add(const EventType& evt)
00054 {
00055 signalMessage(evt);
00056 }
00057 };
00058
00059 class Helper
00060 {
00061 public:
00062 Helper()
00063 {
00064 counts_.assign(0);
00065 }
00066
00067 void cb0(const MsgConstPtr&)
00068 {
00069 ++counts_[0];
00070 }
00071
00072 void cb1(const Msg&)
00073 {
00074 ++counts_[1];
00075 }
00076
00077 void cb2(MsgConstPtr)
00078 {
00079 ++counts_[2];
00080 }
00081
00082 void cb3(const ros::MessageEvent<Msg const>&)
00083 {
00084 ++counts_[3];
00085 }
00086
00087 void cb4(Msg)
00088 {
00089 ++counts_[4];
00090 }
00091
00092 void cb5(const MsgPtr&)
00093 {
00094 ++counts_[5];
00095 }
00096
00097 void cb6(MsgPtr)
00098 {
00099 ++counts_[6];
00100 }
00101
00102 void cb7(const ros::MessageEvent<Msg>&)
00103 {
00104 ++counts_[7];
00105 }
00106
00107 boost::array<int32_t, 30> counts_;
00108 };
00109
00110 TEST(SimpleFilter, callbackTypes)
00111 {
00112 Helper h;
00113 Filter f;
00114 f.registerCallback(boost::bind(&Helper::cb0, &h, _1));
00115 f.registerCallback<const Msg&>(boost::bind(&Helper::cb1, &h, _1));
00116 f.registerCallback<MsgConstPtr>(boost::bind(&Helper::cb2, &h, _1));
00117 f.registerCallback<const ros::MessageEvent<Msg const>&>(boost::bind(&Helper::cb3, &h, _1));
00118 f.registerCallback<Msg>(boost::bind(&Helper::cb4, &h, _1));
00119 f.registerCallback<const MsgPtr&>(boost::bind(&Helper::cb5, &h, _1));
00120 f.registerCallback<MsgPtr>(boost::bind(&Helper::cb6, &h, _1));
00121 f.registerCallback<const ros::MessageEvent<Msg>&>(boost::bind(&Helper::cb7, &h, _1));
00122
00123 f.add(Filter::EventType(boost::make_shared<Msg>()));
00124 EXPECT_EQ(h.counts_[0], 1);
00125 EXPECT_EQ(h.counts_[1], 1);
00126 EXPECT_EQ(h.counts_[2], 1);
00127 EXPECT_EQ(h.counts_[3], 1);
00128 EXPECT_EQ(h.counts_[4], 1);
00129 EXPECT_EQ(h.counts_[5], 1);
00130 EXPECT_EQ(h.counts_[6], 1);
00131 EXPECT_EQ(h.counts_[7], 1);
00132 }
00133
00134 struct OldFilter
00135 {
00136 Connection registerCallback(const boost::function<void(const MsgConstPtr&)>&)
00137 {
00138 return Connection();
00139 }
00140 };
00141
00142 TEST(SimpleFilter, oldRegisterWithNewFilter)
00143 {
00144 OldFilter f;
00145 Helper h;
00146 f.registerCallback(boost::bind(&Helper::cb3, &h, _1));
00147 }
00148
00149 int main(int argc, char **argv){
00150 testing::InitGoogleTest(&argc, argv);
00151 ros::init(argc, argv, "blah");
00152 ros::Time::init();
00153
00154 return RUN_ALL_TESTS();
00155 }
00156
00157
00158