time_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_TIME_SYNCHRONIZER_H
36 #define MESSAGE_FILTERS_TIME_SYNCHRONIZER_H
37 
38 #include "synchronizer.h"
40 
41 #include <boost/shared_ptr.hpp>
42 
43 #include <ros/message_event.h>
44 
45 namespace message_filters
46 {
47 namespace mpl = boost::mpl;
48 
83 template<class M0, class M1, class M2 = NullType, class M3 = NullType, class M4 = NullType,
84  class M5 = NullType, class M6 = NullType, class M7 = NullType, class M8 = NullType>
85 class TimeSynchronizer : public Synchronizer<sync_policies::ExactTime<M0, M1, M2, M3, M4, M5, M6, M7, M8> >
86 {
87 public:
99 
100  using Base::add;
101  using Base::connectInput;
103  using Base::setName;
104  using Base::getName;
106  typedef typename Base::M0Event M0Event;
107  typedef typename Base::M1Event M1Event;
108  typedef typename Base::M2Event M2Event;
109  typedef typename Base::M3Event M3Event;
110  typedef typename Base::M4Event M4Event;
111  typedef typename Base::M5Event M5Event;
112  typedef typename Base::M6Event M6Event;
113  typedef typename Base::M7Event M7Event;
114  typedef typename Base::M8Event M8Event;
115 
116  template<class F0, class F1>
117  TimeSynchronizer(F0& f0, F1& f1, uint32_t queue_size)
118  : Base(Policy(queue_size))
119  {
120  connectInput(f0, f1);
121  }
122 
123  template<class F0, class F1, class F2>
124  TimeSynchronizer(F0& f0, F1& f1, F2& f2, uint32_t queue_size)
125  : Base(Policy(queue_size))
126  {
127  connectInput(f0, f1, f2);
128  }
129 
130  template<class F0, class F1, class F2, class F3>
131  TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, uint32_t queue_size)
132  : Base(Policy(queue_size))
133  {
134  connectInput(f0, f1, f2, f3);
135  }
136 
137  template<class F0, class F1, class F2, class F3, class F4>
138  TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, uint32_t queue_size)
139  : Base(Policy(queue_size))
140  {
141  connectInput(f0, f1, f2, f3, f4);
142  }
143 
144  template<class F0, class F1, class F2, class F3, class F4, class F5>
145  TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, uint32_t queue_size)
146  : Base(Policy(queue_size))
147  {
148  connectInput(f0, f1, f2, f3, f4, f5);
149  }
150 
151  template<class F0, class F1, class F2, class F3, class F4, class F5, class F6>
152  TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, uint32_t queue_size)
153  : Base(Policy(queue_size))
154  {
155  connectInput(f0, f1, f2, f3, f4, f5, f6);
156  }
157 
158  template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7>
159  TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, F7& f7, uint32_t queue_size)
160  : Base(Policy(queue_size))
161  {
162  connectInput(f0, f1, f2, f3, f4, f5, f6, f7);
163  }
164 
165  template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7, class F8>
166  TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, F7& f7, F8& f8, uint32_t queue_size)
167  : Base(Policy(queue_size))
168  {
169  connectInput(f0, f1, f2, f3, f4, f5, f6, f7, f8);
170  }
171 
172  TimeSynchronizer(uint32_t queue_size)
173  : Base(Policy(queue_size))
174  {
175  }
176 
178  // For backwards compatibility
180  void add0(const M0ConstPtr& msg)
181  {
182  this->template add<0>(M0Event(msg));
183  }
184 
185  void add1(const M1ConstPtr& msg)
186  {
187  this->template add<1>(M1Event(msg));
188  }
189 
190  void add2(const M2ConstPtr& msg)
191  {
192  this->template add<2>(M2Event(msg));
193  }
194 
195  void add3(const M3ConstPtr& msg)
196  {
197  this->template add<3>(M3Event(msg));
198  }
199 
200  void add4(const M4ConstPtr& msg)
201  {
202  this->template add<4>(M4Event(msg));
203  }
204 
205  void add5(const M5ConstPtr& msg)
206  {
207  this->template add<5>(M5Event(msg));
208  }
209 
210  void add6(const M6ConstPtr& msg)
211  {
212  this->template add<6>(M6Event(msg));
213  }
214 
215  void add7(const M7ConstPtr& msg)
216  {
217  this->template add<7>(M7Event(msg));
218  }
219 
220  void add8(const M8ConstPtr& msg)
221  {
222  this->template add<8>(M8Event(msg));
223  }
224 };
225 
226 }
227 
228 #endif // MESSAGE_FILTERS_TIME_SYNCHRONIZER_H
boost::shared_ptr< M6 const > M6ConstPtr
void add1(const M1ConstPtr &msg)
void setName(const std::string &name)
Definition: synchronizer.h:325
boost::shared_ptr< M7 const > M7ConstPtr
void add(const boost::shared_ptr< typename mpl::at_c< Messages, i >::type const > &msg)
Definition: synchronizer.h:340
boost::shared_ptr< M8 const > M8ConstPtr
TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, uint32_t queue_size)
boost::shared_ptr< M2 const > M2ConstPtr
mpl::at_c< Events, 6 >::type M6Event
Definition: synchronizer.h:89
TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7, uint32_t queue_size)
void add3(const M3ConstPtr &msg)
TimeSynchronizer(F0 &f0, F1 &f1, uint32_t queue_size)
mpl::at_c< Events, 7 >::type M7Event
Definition: synchronizer.h:90
void add5(const M5ConstPtr &msg)
TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, uint32_t queue_size)
mpl::at_c< Events, 3 >::type M3Event
Definition: synchronizer.h:86
mpl::at_c< Events, 5 >::type M5Event
Definition: synchronizer.h:88
const std::string & getName()
Definition: synchronizer.h:326
boost::shared_ptr< M3 const > M3ConstPtr
void add4(const M4ConstPtr &msg)
Connection registerDropCallback(const C &callback)
Definition: exact_time.h:134
void add2(const M2ConstPtr &msg)
boost::shared_ptr< M5 const > M5ConstPtr
sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > Policy
Connection registerCallback(C &callback)
Definition: synchronizer.h:302
boost::shared_ptr< M1 const > M1ConstPtr
void add0(const M0ConstPtr &msg)
TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, uint32_t queue_size)
boost::shared_ptr< M0 const > M0ConstPtr
mpl::at_c< Events, 0 >::type M0Event
Definition: synchronizer.h:83
void add8(const M8ConstPtr &msg)
void add7(const M7ConstPtr &msg)
TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, uint32_t queue_size)
void connectInput(F0 &f0, F1 &f1)
Definition: synchronizer.h:237
void add6(const M6ConstPtr &msg)
boost::shared_ptr< M4 const > M4ConstPtr
mpl::at_c< Events, 4 >::type M4Event
Definition: synchronizer.h:87
mpl::at_c< Events, 1 >::type M1Event
Definition: synchronizer.h:84
TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, uint32_t queue_size)
mpl::at_c< Events, 8 >::type M8Event
Definition: synchronizer.h:91
Synchronizes up to 9 messages by their timestamps.
mpl::at_c< Events, 2 >::type M2Event
Definition: synchronizer.h:85
TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7, F8 &f8, uint32_t queue_size)


message_filters
Author(s): Josh Faust, Vijay Pradeep, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:42