signal1.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2010, 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_SIGNAL1_H
36 #define MESSAGE_FILTERS_SIGNAL1_H
37 
38 #include <boost/noncopyable.hpp>
39 
40 #include "connection.h"
41 #include <ros/message_event.h>
42 #include <ros/parameter_adapter.h>
43 
44 #include <boost/bind.hpp>
45 #include <boost/thread/mutex.hpp>
46 
47 namespace message_filters
48 {
49 template<class M>
51 {
52 public:
53  virtual ~CallbackHelper1() {}
54 
55  virtual void call(const ros::MessageEvent<M const>& event, bool nonconst_need_copy) = 0;
56 
58 };
59 
60 template<typename P, typename M>
62 {
63 public:
65  typedef boost::function<void(typename Adapter::Parameter)> Callback;
66  typedef typename Adapter::Event Event;
67 
68  CallbackHelper1T(const Callback& cb)
69  : callback_(cb)
70  {
71  }
72 
73  virtual void call(const ros::MessageEvent<M const>& event, bool nonconst_force_copy)
74  {
75  Event my_event(event, nonconst_force_copy || event.nonConstWillCopy());
76  callback_(Adapter::getParameter(my_event));
77  }
78 
79 private:
80  Callback callback_;
81 };
82 
83 template<class M>
84 class Signal1
85 {
87  typedef std::vector<CallbackHelper1Ptr> V_CallbackHelper1;
88 
89 public:
90  template<typename P>
91  CallbackHelper1Ptr addCallback(const boost::function<void(P)>& callback)
92  {
93  CallbackHelper1T<P, M>* helper = new CallbackHelper1T<P, M>(callback);
94 
95  boost::mutex::scoped_lock lock(mutex_);
96  callbacks_.push_back(CallbackHelper1Ptr(helper));
97  return callbacks_.back();
98  }
99 
100  void removeCallback(const CallbackHelper1Ptr& helper)
101  {
102  boost::mutex::scoped_lock lock(mutex_);
103  typename V_CallbackHelper1::iterator it = std::find(callbacks_.begin(), callbacks_.end(), helper);
104  if (it != callbacks_.end())
105  {
106  callbacks_.erase(it);
107  }
108  }
109 
110  void call(const ros::MessageEvent<M const>& event)
111  {
112  boost::mutex::scoped_lock lock(mutex_);
113  bool nonconst_force_copy = callbacks_.size() > 1;
114  typename V_CallbackHelper1::iterator it = callbacks_.begin();
115  typename V_CallbackHelper1::iterator end = callbacks_.end();
116  for (; it != end; ++it)
117  {
118  const CallbackHelper1Ptr& helper = *it;
119  helper->call(event, nonconst_force_copy);
120  }
121  }
122 
123 private:
124  boost::mutex mutex_;
125  V_CallbackHelper1 callbacks_;
126 };
127 
128 } // message_filters
129 
130 #endif // MESSAGE_FILTERS_SIGNAL1_H
131 
132 
void removeCallback(const CallbackHelper1Ptr &helper)
Definition: signal1.h:100
V_CallbackHelper1 callbacks_
Definition: signal1.h:125
CallbackHelper1T(const Callback &cb)
Definition: signal1.h:68
bool nonConstWillCopy() const
boost::shared_ptr< CallbackHelper1< M > > CallbackHelper1Ptr
Definition: signal1.h:86
void call(const ros::MessageEvent< M const > &event)
Definition: signal1.h:110
boost::mutex mutex_
Definition: signal1.h:124
boost::shared_ptr< CallbackHelper1< M > > Ptr
Definition: signal1.h:57
virtual void call(const ros::MessageEvent< M const > &event, bool nonconst_need_copy)=0
CallbackHelper1Ptr addCallback(const boost::function< void(P)> &callback)
Definition: signal1.h:91
boost::function< void(typename Adapter::Parameter)> Callback
Definition: signal1.h:65
std::vector< CallbackHelper1Ptr > V_CallbackHelper1
Definition: signal1.h:87
ros::ParameterAdapter< P > Adapter
Definition: signal1.h:64
virtual void call(const ros::MessageEvent< M const > &event, bool nonconst_force_copy)
Definition: signal1.h:73


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