synchronizer.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2009, 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 #ifndef MESSAGE_FILTERS_SYNCHRONIZER_H
36 #define MESSAGE_FILTERS_SYNCHRONIZER_H
37 
38 #include <boost/tuple/tuple.hpp>
39 #include <boost/shared_ptr.hpp>
40 #include <boost/function.hpp>
41 #include <boost/thread/mutex.hpp>
42 
43 #include <boost/bind.hpp>
44 #include <boost/type_traits/is_same.hpp>
45 #include <boost/noncopyable.hpp>
46 #include <boost/mpl/or.hpp>
47 #include <boost/mpl/at.hpp>
48 #include <boost/mpl/vector.hpp>
49 #include <boost/function_types/function_arity.hpp>
50 #include <boost/function_types/is_nonmember_callable_builtin.hpp>
51 
52 #include "connection.h"
53 #include "null_types.h"
54 #include "signal9.h"
55 #include <ros/message_traits.h>
56 #include <ros/message_event.h>
57 
58 #include <deque>
59 #include <vector>
60 #include <string>
61 
62 namespace message_filters
63 {
64 
65 namespace mpl = boost::mpl;
66 
67 template<class Policy>
68 class Synchronizer : public boost::noncopyable, public Policy
69 {
70 public:
71  typedef typename Policy::Messages Messages;
72  typedef typename Policy::Events Events;
73  typedef typename Policy::Signal Signal;
74  typedef typename mpl::at_c<Messages, 0>::type M0;
75  typedef typename mpl::at_c<Messages, 1>::type M1;
76  typedef typename mpl::at_c<Messages, 2>::type M2;
77  typedef typename mpl::at_c<Messages, 3>::type M3;
78  typedef typename mpl::at_c<Messages, 4>::type M4;
79  typedef typename mpl::at_c<Messages, 5>::type M5;
80  typedef typename mpl::at_c<Messages, 6>::type M6;
81  typedef typename mpl::at_c<Messages, 7>::type M7;
82  typedef typename mpl::at_c<Messages, 8>::type M8;
83  typedef typename mpl::at_c<Events, 0>::type M0Event;
84  typedef typename mpl::at_c<Events, 1>::type M1Event;
85  typedef typename mpl::at_c<Events, 2>::type M2Event;
86  typedef typename mpl::at_c<Events, 3>::type M3Event;
87  typedef typename mpl::at_c<Events, 4>::type M4Event;
88  typedef typename mpl::at_c<Events, 5>::type M5Event;
89  typedef typename mpl::at_c<Events, 6>::type M6Event;
90  typedef typename mpl::at_c<Events, 7>::type M7Event;
91  typedef typename mpl::at_c<Events, 8>::type M8Event;
92 
93  static const uint8_t MAX_MESSAGES = 9;
94 
95  template<class F0, class F1>
96  Synchronizer(F0& f0, F1& f1)
97  {
98  connectInput(f0, f1);
99  init();
100  }
101 
102  template<class F0, class F1, class F2>
103  Synchronizer(F0& f0, F1& f1, F2& f2)
104  {
105  connectInput(f0, f1, f2);
106  init();
107  }
108 
109  template<class F0, class F1, class F2, class F3>
110  Synchronizer(F0& f0, F1& f1, F2& f2, F3& f3)
111  {
112  connectInput(f0, f1, f2, f3);
113  init();
114  }
115 
116  template<class F0, class F1, class F2, class F3, class F4>
117  Synchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4)
118  {
119  connectInput(f0, f1, f2, f3, f4);
120  init();
121  }
122 
123  template<class F0, class F1, class F2, class F3, class F4, class F5>
124  Synchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5)
125  {
126  connectInput(f0, f1, f2, f3, f4, f5);
127  init();
128  }
129 
130  template<class F0, class F1, class F2, class F3, class F4, class F5, class F6>
131  Synchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6)
132  {
133  connectInput(f0, f1, f2, f3, f4, f5, f6);
134  init();
135  }
136 
137  template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7>
138  Synchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, F7& f7)
139  {
140  connectInput(f0, f1, f2, f3, f4, f5, f6, f7);
141  init();
142  }
143 
144  template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7, class F8>
145  Synchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, F7& f7, F8& f8)
146  {
147  connectInput(f0, f1, f2, f3, f4, f5, f6, f7, f8);
148  init();
149  }
150 
152  {
153  init();
154  }
155 
156  template<class F0, class F1>
157  Synchronizer(const Policy& policy, F0& f0, F1& f1)
158  : Policy(policy)
159  {
160  connectInput(f0, f1);
161  init();
162  }
163 
164  template<class F0, class F1, class F2>
165  Synchronizer(const Policy& policy, F0& f0, F1& f1, F2& f2)
166  : Policy(policy)
167  {
168  connectInput(f0, f1, f2);
169  init();
170  }
171 
172  template<class F0, class F1, class F2, class F3>
173  Synchronizer(const Policy& policy, F0& f0, F1& f1, F2& f2, F3& f3)
174  : Policy(policy)
175  {
176  connectInput(f0, f1, f2, f3);
177  init();
178  }
179 
180  template<class F0, class F1, class F2, class F3, class F4>
181  Synchronizer(const Policy& policy, F0& f0, F1& f1, F2& f2, F3& f3, F4& f4)
182  : Policy(policy)
183  {
184  connectInput(f0, f1, f2, f3, f4);
185  init();
186  }
187 
188  template<class F0, class F1, class F2, class F3, class F4, class F5>
189  Synchronizer(const Policy& policy, F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5)
190  : Policy(policy)
191  {
192  connectInput(f0, f1, f2, f3, f4, f5);
193  init();
194  }
195 
196  template<class F0, class F1, class F2, class F3, class F4, class F5, class F6>
197  Synchronizer(const Policy& policy, F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6)
198  : Policy(policy)
199  {
200  connectInput(f0, f1, f2, f3, f4, f5, f6);
201  init();
202  }
203 
204  template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7>
205  Synchronizer(const Policy& policy, F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, F7& f7)
206  : Policy(policy)
207  {
208  connectInput(f0, f1, f2, f3, f4, f5, f6, f7);
209  init();
210  }
211 
212  template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7, class F8>
213  Synchronizer(const Policy& policy, F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, F7& f7, F8& f8)
214  : Policy(policy)
215  {
216  connectInput(f0, f1, f2, f3, f4, f5, f6, f7, f8);
217  init();
218  }
219 
220  Synchronizer(const Policy& policy)
221  : Policy(policy)
222  {
223  init();
224  }
225 
226  ~Synchronizer()
227  {
228  disconnectAll();
229  }
230 
231  void init()
232  {
233  Policy::initParent(this);
234  }
235 
236  template<class F0, class F1>
237  void connectInput(F0& f0, F1& f1)
238  {
239  NullFilter<M2> f2;
240  connectInput(f0, f1, f2);
241  }
242 
243  template<class F0, class F1, class F2>
244  void connectInput(F0& f0, F1& f1, F2& f2)
245  {
246  NullFilter<M3> f3;
247  connectInput(f0, f1, f2, f3);
248  }
249 
250  template<class F0, class F1, class F2, class F3>
251  void connectInput(F0& f0, F1& f1, F2& f2, F3& f3)
252  {
254  connectInput(f0, f1, f2, f3, f4);
255  }
256 
257  template<class F0, class F1, class F2, class F3, class F4>
258  void connectInput(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4)
259  {
260  NullFilter<M5> f5;
261  connectInput(f0, f1, f2, f3, f4, f5);
262  }
263 
264  template<class F0, class F1, class F2, class F3, class F4, class F5>
265  void connectInput(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5)
266  {
267  NullFilter<M6> f6;
268  connectInput(f0, f1, f2, f3, f4, f5, f6);
269  }
270 
271  template<class F0, class F1, class F2, class F3, class F4, class F5, class F6>
272  void connectInput(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6)
273  {
274  NullFilter<M7> f7;
275  connectInput(f0, f1, f2, f3, f4, f5, f6, f7);
276  }
277 
278  template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7>
279  void connectInput(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, F7& f7)
280  {
281  NullFilter<M8> f8;
282  connectInput(f0, f1, f2, f3, f4, f5, f6, f7, f8);
283  }
284 
285  template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7, class F8>
286  void connectInput(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, F7& f7, F8& f8)
287  {
288  disconnectAll();
289 
290  input_connections_[0] = f0.registerCallback(boost::function<void(const M0Event&)>(boost::bind(&Synchronizer::template cb<0>, this, boost::placeholders::_1)));
291  input_connections_[1] = f1.registerCallback(boost::function<void(const M1Event&)>(boost::bind(&Synchronizer::template cb<1>, this, boost::placeholders::_1)));
292  input_connections_[2] = f2.registerCallback(boost::function<void(const M2Event&)>(boost::bind(&Synchronizer::template cb<2>, this, boost::placeholders::_1)));
293  input_connections_[3] = f3.registerCallback(boost::function<void(const M3Event&)>(boost::bind(&Synchronizer::template cb<3>, this, boost::placeholders::_1)));
294  input_connections_[4] = f4.registerCallback(boost::function<void(const M4Event&)>(boost::bind(&Synchronizer::template cb<4>, this, boost::placeholders::_1)));
295  input_connections_[5] = f5.registerCallback(boost::function<void(const M5Event&)>(boost::bind(&Synchronizer::template cb<5>, this, boost::placeholders::_1)));
296  input_connections_[6] = f6.registerCallback(boost::function<void(const M6Event&)>(boost::bind(&Synchronizer::template cb<6>, this, boost::placeholders::_1)));
297  input_connections_[7] = f7.registerCallback(boost::function<void(const M7Event&)>(boost::bind(&Synchronizer::template cb<7>, this, boost::placeholders::_1)));
298  input_connections_[8] = f8.registerCallback(boost::function<void(const M8Event&)>(boost::bind(&Synchronizer::template cb<8>, this, boost::placeholders::_1)));
299  }
300 
301  template<class C>
302  Connection registerCallback(C& callback)
303  {
304  return signal_.addCallback(callback);
305  }
306 
307  template<class C>
308  Connection registerCallback(const C& callback)
309  {
310  return signal_.addCallback(callback);
311  }
312 
313  template<class C, typename T>
314  Connection registerCallback(const C& callback, T* t)
315  {
316  return signal_.addCallback(callback, t);
317  }
318 
319  template<class C, typename T>
320  Connection registerCallback(C& callback, T* t)
321  {
322  return signal_.addCallback(callback, t);
323  }
324 
325  void setName(const std::string& name) { name_ = name; }
326  const std::string& getName() { return name_; }
327 
328 
329  void signal(const M0Event& e0, const M1Event& e1, const M2Event& e2, const M3Event& e3, const M4Event& e4,
330  const M5Event& e5, const M6Event& e6, const M7Event& e7, const M8Event& e8)
331  {
332  signal_.call(e0, e1, e2, e3, e4, e5, e6, e7, e8);
333  }
334 
335  Policy* getPolicy() { return static_cast<Policy*>(this); }
336 
337  using Policy::add;
338 
339  template<int i>
340  void add(const boost::shared_ptr<typename mpl::at_c<Messages, i>::type const>& msg)
341  {
342  this->template add<i>(typename mpl::at_c<Events, i>::type(msg));
343  }
344 
345 private:
346 
347  void disconnectAll()
348  {
349  for (int i = 0; i < MAX_MESSAGES; ++i)
350  {
352  }
353  }
354 
355  template<int i>
356  void cb(const typename mpl::at_c<Events, i>::type& evt)
357  {
358  this->template add<i>(evt);
359  }
360 
361  uint32_t queue_size_;
362 
363  Signal signal_;
364 
365  Connection input_connections_[MAX_MESSAGES];
366 
367  std::string name_;
368 };
369 
370 template<typename M0, typename M1, typename M2, typename M3, typename M4,
371  typename M5, typename M6, typename M7, typename M8>
373 {
374  typedef mpl::vector<M0, M1, M2, M3, M4, M5, M6, M7, M8> Messages;
376  typedef mpl::vector<ros::MessageEvent<M0 const>, ros::MessageEvent<M1 const>, ros::MessageEvent<M2 const>, ros::MessageEvent<M3 const>,
379  typedef typename mpl::fold<Messages, mpl::int_<0>, mpl::if_<mpl::not_<boost::is_same<mpl::_2, NullType> >, mpl::next<mpl::_1>, mpl::_1> >::type RealTypeCount;
380  typedef typename mpl::at_c<Events, 0>::type M0Event;
381  typedef typename mpl::at_c<Events, 1>::type M1Event;
382  typedef typename mpl::at_c<Events, 2>::type M2Event;
383  typedef typename mpl::at_c<Events, 3>::type M3Event;
384  typedef typename mpl::at_c<Events, 4>::type M4Event;
385  typedef typename mpl::at_c<Events, 5>::type M5Event;
386  typedef typename mpl::at_c<Events, 6>::type M6Event;
387  typedef typename mpl::at_c<Events, 7>::type M7Event;
388  typedef typename mpl::at_c<Events, 8>::type M8Event;
389 };
390 
391 } // namespace message_filters
392 
393 #endif // MESSAGE_FILTERS_SYNCHRONIZER_H
message_filters::Synchronizer::Signal
Policy::Signal Signal
Definition: synchronizer.h:137
message_filters::NullFilter
Definition: null_types.h:86
message_filters::Synchronizer::M4
mpl::at_c< Messages, 4 >::type M4
Definition: synchronizer.h:142
message_filters::Connection
Encapsulates a connection from one filter to another (or to a user-specified callback)
Definition: connection.h:80
message_filters::Synchronizer::Synchronizer
Synchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4)
Definition: synchronizer.h:181
boost::shared_ptr
message_filters::PolicyBase::M7Event
mpl::at_c< Events, 7 >::type M7Event
Definition: synchronizer.h:419
message_filters::Synchronizer::M4Event
mpl::at_c< Events, 4 >::type M4Event
Definition: synchronizer.h:151
message_filters::Synchronizer::M6Event
mpl::at_c< Events, 6 >::type M6Event
Definition: synchronizer.h:153
message_filters::Synchronizer::M3Event
mpl::at_c< Events, 3 >::type M3Event
Definition: synchronizer.h:150
message_filters::PolicyBase::M8Event
mpl::at_c< Events, 8 >::type M8Event
Definition: synchronizer.h:420
message_filters::PolicyBase
Definition: synchronizer.h:404
message_filters::PolicyBase::M2Event
mpl::at_c< Events, 2 >::type M2Event
Definition: synchronizer.h:414
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
message_filters::Synchronizer::cb
void cb(const typename mpl::at_c< Events, i >::type &evt)
Definition: synchronizer.h:420
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
message_filters::Synchronizer::disconnectAll
void disconnectAll()
Definition: synchronizer.h:411
message_filters::Synchronizer::M0Event
mpl::at_c< Events, 0 >::type M0Event
Definition: synchronizer.h:147
message_filters::PolicyBase::M1Event
mpl::at_c< Events, 1 >::type M1Event
Definition: synchronizer.h:413
message_filters::Synchronizer::getName
const std::string & getName()
Definition: synchronizer.h:390
message_filters::Synchronizer::M5Event
mpl::at_c< Events, 5 >::type M5Event
Definition: synchronizer.h:152
message_filters::Synchronizer::M8Event
mpl::at_c< Events, 8 >::type M8Event
Definition: synchronizer.h:155
message_filters::Synchronizer::registerCallback
Connection registerCallback(C &callback)
Definition: synchronizer.h:366
message_filters::Synchronizer::connectInput
void connectInput(F0 &f0, F1 &f1)
Definition: synchronizer.h:301
message_filters::Synchronizer::M5
mpl::at_c< Messages, 5 >::type M5
Definition: synchronizer.h:143
signal9.h
message_filters::Synchronizer::M1Event
mpl::at_c< Events, 1 >::type M1Event
Definition: synchronizer.h:148
message_filters::PolicyBase::M3Event
mpl::at_c< Events, 3 >::type M3Event
Definition: synchronizer.h:415
message_filters::Synchronizer::signal_
Signal signal_
Definition: synchronizer.h:427
message_filters::Synchronizer::M6
mpl::at_c< Messages, 6 >::type M6
Definition: synchronizer.h:144
message_filters::Signal9
Definition: signal9.h:176
message_filters::Synchronizer::Synchronizer
Synchronizer()
Definition: synchronizer.h:215
message_traits.h
message_filters::Synchronizer::name_
std::string name_
Definition: synchronizer.h:431
message_filters::Synchronizer::M7Event
mpl::at_c< Events, 7 >::type M7Event
Definition: synchronizer.h:154
message_filters::Synchronizer::input_connections_
Connection input_connections_[MAX_MESSAGES]
Definition: synchronizer.h:429
message_filters::Synchronizer::Events
Policy::Events Events
Definition: synchronizer.h:136
message_filters::Synchronizer::~Synchronizer
~Synchronizer()
Definition: synchronizer.h:290
message_filters::PolicyBase::M5Event
mpl::at_c< Events, 5 >::type M5Event
Definition: synchronizer.h:417
connection.h
null_types.h
message_filters::PolicyBase::Messages
mpl::vector< M0, M1, M2, M3, M4, M5, M6, M7, M8 > Messages
Definition: synchronizer.h:406
message_filters::Synchronizer::getPolicy
Policy * getPolicy()
Definition: synchronizer.h:399
message_filters::Synchronizer::M8
mpl::at_c< Messages, 8 >::type M8
Definition: synchronizer.h:146
message_filters::PolicyBase::Signal
Signal9< M0, M1, M2, M3, M4, M5, M6, M7, M8 > Signal
Definition: synchronizer.h:407
message_filters::Synchronizer::MAX_MESSAGES
static const uint8_t MAX_MESSAGES
Definition: synchronizer.h:157
message_filters::Synchronizer::M2Event
mpl::at_c< Events, 2 >::type M2Event
Definition: synchronizer.h:149
message_filters::Synchronizer::M0
mpl::at_c< Messages, 0 >::type M0
Definition: synchronizer.h:138
message_filters::Synchronizer::M1
mpl::at_c< Messages, 1 >::type M1
Definition: synchronizer.h:139
message_filters::Synchronizer::M7
mpl::at_c< Messages, 7 >::type M7
Definition: synchronizer.h:145
message_filters::Synchronizer::M3
mpl::at_c< Messages, 3 >::type M3
Definition: synchronizer.h:141
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
message_filters::PolicyBase::M0Event
mpl::at_c< Events, 0 >::type M0Event
Definition: synchronizer.h:412
message_filters::Synchronizer::signal
void signal(const M0Event &e0, const M1Event &e1, const M2Event &e2, const M3Event &e3, const M4Event &e4, const M5Event &e5, const M6Event &e6, const M7Event &e7, const M8Event &e8)
Definition: synchronizer.h:393
message_filters::Synchronizer::Messages
Policy::Messages Messages
Definition: synchronizer.h:135
message_event.h
message_filters::PolicyBase::M4Event
mpl::at_c< Events, 4 >::type M4Event
Definition: synchronizer.h:416
message_filters::Synchronizer::M2
mpl::at_c< Messages, 2 >::type M2
Definition: synchronizer.h:140
message_filters::PolicyBase::M6Event
mpl::at_c< Events, 6 >::type M6Event
Definition: synchronizer.h:418
message_filters::Synchronizer::init
void init()
Definition: synchronizer.h:295
ros::MessageEvent
message_filters::Synchronizer::queue_size_
uint32_t queue_size_
Definition: synchronizer.h:425
message_filters::Synchronizer::setName
void setName(const std::string &name)
Definition: synchronizer.h:389
message_filters::Connection::disconnect
void disconnect()
disconnects this connection
Definition: connection.cpp:84


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