* Move PassThrough filter to its own header

* Fix TimeSynchronizer's connecting constructors and add test for it
This commit is contained in:
Josh Faust 2010-03-15 22:46:55 +00:00
parent 3cf9ee07b0
commit 9d6aca1ff1
4 changed files with 121 additions and 59 deletions

View File

@ -36,56 +36,12 @@
#define MESSAGE_FILTERS_CHAIN_H
#include "simple_filter.h"
#include "pass_through.h"
#include <vector>
namespace message_filters
{
/**
* \brief Simple passthrough filter. What comes in goes out immediately.
*/
template<typename M>
class PassThrough : public SimpleFilter<M>
{
public:
typedef boost::shared_ptr<M const> MConstPtr;
typedef ros::MessageEvent<M const> EventType;
PassThrough()
{
}
template<typename F>
PassThrough(F& f)
{
connectInput(f);
}
template<class F>
void connectInput(F& f)
{
incoming_connection_.disconnect();
incoming_connection_ = f.registerCallback(typename SimpleFilter<M>::EventCallback(boost::bind(&PassThrough::cb, this, _1)));
}
void add(const MConstPtr& msg)
{
add(EventType(msg));
}
void add(const EventType& evt)
{
signalMessage(evt);
}
private:
void cb(const EventType& evt)
{
add(evt);
}
Connection incoming_connection_;
};
/**
* \brief Base class for Chain, allows you to store multiple chains in the same container. Provides filter retrieval

View File

@ -0,0 +1,93 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2010, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
#ifndef MESSAGE_FILTERS_PASSTHROUGH_H
#define MESSAGE_FILTERS_PASSTHROUGH_H
#include "simple_filter.h"
#include <vector>
namespace message_filters
{
/**
* \brief Simple passthrough filter. What comes in goes out immediately.
*/
template<typename M>
class PassThrough : public SimpleFilter<M>
{
public:
typedef boost::shared_ptr<M const> MConstPtr;
typedef ros::MessageEvent<M const> EventType;
PassThrough()
{
}
template<typename F>
PassThrough(F& f)
{
connectInput(f);
}
template<class F>
void connectInput(F& f)
{
incoming_connection_.disconnect();
incoming_connection_ = f.registerCallback(typename SimpleFilter<M>::EventCallback(boost::bind(&PassThrough::cb, this, _1)));
}
void add(const MConstPtr& msg)
{
add(EventType(msg));
}
void add(const EventType& evt)
{
signalMessage(evt);
}
private:
void cb(const EventType& evt)
{
add(evt);
}
Connection incoming_connection_;
};
} // namespace message_filters
#endif // MESSAGE_FILTERS_PASSTHROUGH_H

View File

@ -35,22 +35,11 @@
#ifndef MESSAGE_FILTERS_TIME_SYNCHRONIZER_H
#define MESSAGE_FILTERS_TIME_SYNCHRONIZER_H
#include <boost/tuple/tuple.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/function.hpp>
#include <boost/thread/mutex.hpp>
#include <boost/signals.hpp>
#include <boost/bind.hpp>
#include <boost/type_traits/is_same.hpp>
#include <boost/noncopyable.hpp>
#include <boost/mpl/and.hpp>
#include <boost/mpl/equal_to.hpp>
#include <roslib/Header.h>
#include "synchronizer.h"
#include "sync_exact_time.h"
#include <ros/message_traits.h>
#include <boost/shared_ptr.hpp>
#include <ros/message_event.h>
namespace message_filters
@ -127,48 +116,56 @@ public:
TimeSynchronizer(F0& f0, F1& f1, uint32_t queue_size)
: Base(Policy(queue_size))
{
connectInput(f0, f1);
}
template<class F0, class F1, class F2>
TimeSynchronizer(F0& f0, F1& f1, F2& f2, uint32_t queue_size)
: Base(Policy(queue_size))
{
connectInput(f0, f1, f2);
}
template<class F0, class F1, class F2, class F3>
TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, uint32_t queue_size)
: Base(Policy(queue_size))
{
connectInput(f0, f1, f2, f3);
}
template<class F0, class F1, class F2, class F3, class F4>
TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, uint32_t queue_size)
: Base(Policy(queue_size))
{
connectInput(f0, f1, f2, f3, f4);
}
template<class F0, class F1, class F2, class F3, class F4, class F5>
TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, uint32_t queue_size)
: Base(Policy(queue_size))
{
connectInput(f0, f1, f2, f3, f4, f5);
}
template<class F0, class F1, class F2, class F3, class F4, class F5, class F6>
TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, uint32_t queue_size)
: Base(Policy(queue_size))
{
connectInput(f0, f1, f2, f3, f4, f5, f6);
}
template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7>
TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, F7& f7, uint32_t queue_size)
: Base(Policy(queue_size))
{
connectInput(f0, f1, f2, f3, f4, f5, f6, f7);
}
template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7, class F8>
TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, F7& f7, F8& f8, uint32_t queue_size)
: Base(Policy(queue_size))
{
connectInput(f0, f1, f2, f3, f4, f5, f6, f7, f8);
}
TimeSynchronizer(uint32_t queue_size)

View File

@ -36,6 +36,7 @@
#include "ros/time.h"
#include "message_filters/time_synchronizer.h"
#include "message_filters/pass_through.h"
using namespace message_filters;
@ -520,6 +521,21 @@ TEST(TimeSynchronizer, eventInEventOut)
ASSERT_EQ(h.e2_.getReceiptTime(), evt.getReceiptTime());
}
TEST(TimeSynchronizer, connectConstructor)
{
PassThrough<Msg> pt1, pt2;
TimeSynchronizer<Msg, Msg> sync(pt1, pt2, 1);
Helper h;
sync.registerCallback(boost::bind(&Helper::cb, &h));
MsgPtr m(new Msg);
m->header.stamp = ros::Time::now();
pt1.add(m);
ASSERT_EQ(h.count_, 0);
pt2.add(m);
ASSERT_EQ(h.count_, 1);
}
//TEST(TimeSynchronizer, connectToSimple)
int main(int argc, char **argv){