simple_filter.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, 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_SIMPLE_FILTER_H
36 #define MESSAGE_FILTERS_SIMPLE_FILTER_H
37 
38 #include <boost/noncopyable.hpp>
39 
40 #include "connection.h"
41 #include "signal1.h"
42 #include <ros/message_event.h>
44 
45 #include <boost/bind.hpp>
46 
47 #include <string>
48 
49 namespace message_filters
50 {
51 
59 template<class M>
60 class SimpleFilter : public boost::noncopyable
61 {
62 public:
64  typedef boost::function<void(const MConstPtr&)> Callback;
66  typedef boost::function<void(const EventType&)> EventCallback;
67 
72  template<typename C>
73  Connection registerCallback(const C& callback)
74  {
75  typename CallbackHelper1<M>::Ptr helper = signal_.addCallback(Callback(callback));
76  return Connection(boost::bind(&Signal::removeCallback, &signal_, helper));
77  }
78 
83  template<typename P>
84  Connection registerCallback(const boost::function<void(P)>& callback)
85  {
86  return Connection(boost::bind(&Signal::removeCallback, &signal_, signal_.addCallback(callback)));
87  }
88 
93  template<typename P>
94  Connection registerCallback(void(*callback)(P))
95  {
96  typename CallbackHelper1<M>::Ptr helper = signal_.template addCallback<P>(boost::bind(callback, _1));
97  return Connection(boost::bind(&Signal::removeCallback, &signal_, helper));
98  }
99 
104  template<typename T, typename P>
105  Connection registerCallback(void(T::*callback)(P), T* t)
106  {
107  typename CallbackHelper1<M>::Ptr helper = signal_.template addCallback<P>(boost::bind(callback, t, _1));
108  return Connection(boost::bind(&Signal::removeCallback, &signal_, helper));
109  }
110 
114  void setName(const std::string& name) { name_ = name; }
118  const std::string& getName() { return name_; }
119 
120 protected:
124  void signalMessage(const MConstPtr& msg)
125  {
126  ros::MessageEvent<M const> event(msg);
127 
128  signal_.call(event);
129  }
130 
135  {
136  signal_.call(event);
137  }
138 
139 private:
141 
142  Signal signal_;
143 
144  std::string name_;
145 };
146 
147 }
148 
149 #endif
150 
Connection registerCallback(void(*callback)(P))
Register a callback to be called when this filter has passed.
Definition: simple_filter.h:94
void removeCallback(const CallbackHelper1Ptr &helper)
Definition: signal1.h:100
void signalMessage(const MConstPtr &msg)
Call all registered callbacks, passing them the specified message.
void signalMessage(const ros::MessageEvent< M const > &event)
Call all registered callbacks, passing them the specified message.
void call(const ros::MessageEvent< M const > &event)
Definition: signal1.h:110
ros::MessageEvent< M const > EventType
Definition: simple_filter.h:65
const std::string & getName()
Get the name of this filter. For debugging use.
void setName(const std::string &name)
Set the name of this filter. For debugging use.
boost::function< void(const MConstPtr &)> Callback
Definition: simple_filter.h:64
CallbackHelper1Ptr addCallback(const boost::function< void(P)> &callback)
Definition: signal1.h:91
Connection registerCallback(const boost::function< void(P)> &callback)
Register a callback to be called when this filter has passed.
Definition: simple_filter.h:84
Convenience base-class for simple filters which output a single message.
Definition: simple_filter.h:60
boost::function< void(const EventType &)> EventCallback
Definition: simple_filter.h:66
boost::shared_ptr< M const > MConstPtr
Definition: simple_filter.h:63
Connection registerCallback(void(T::*callback)(P), T *t)
Register a callback to be called when this filter has passed.
Encapsulates a connection from one filter to another (or to a user-specified callback) ...
Definition: connection.h:48
Connection registerCallback(const C &callback)
Register a callback to be called when this filter has passed.
Definition: simple_filter.h:73


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