Skip to content

Commit

Permalink
Remove 'using' keyword in message_filters (#106)
Browse files Browse the repository at this point in the history
* Remove using namespace std.

* Remove using namespace message_filters.

Signed-off-by: Chris Lalancette <[email protected]>
Co-authored-by: Tomoya Fujita <[email protected]>
  • Loading branch information
clalancette and fujitatomoya authored Dec 8, 2023
1 parent 33231ea commit ba5029f
Show file tree
Hide file tree
Showing 12 changed files with 340 additions and 408 deletions.
57 changes: 27 additions & 30 deletions test/msg_cache_unittest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,15 +34,14 @@

#include <gtest/gtest.h>

#include <rclcpp/rclcpp.hpp>
#include <memory>
#include <functional>
#include <memory>
#include <vector>

#include <rclcpp/rclcpp.hpp>
#include "message_filters/cache.h"
#include "message_filters/message_traits.h"

using namespace std ;
using namespace message_filters ;

struct Header
{
rclcpp::Time stamp ;
Expand Down Expand Up @@ -70,27 +69,24 @@ struct TimeStamp<Msg>
}
}


void fillCacheEasy(Cache<Msg>& cache, unsigned int start, unsigned int end)

void fillCacheEasy(message_filters::Cache<Msg>& cache, unsigned int start, unsigned int end)
{
for (unsigned int i=start; i < end; i++)
{
Msg* msg = new Msg ;
msg->data = i ;
msg->header.stamp= rclcpp::Time(i*10, 0) ;
for (unsigned int i = start; i < end; i++) {
Msg * msg = new Msg;
msg->data = i;
msg->header.stamp = rclcpp::Time(i * 10, 0);

std::shared_ptr<Msg const> msg_ptr(msg) ;
cache.add(msg_ptr) ;
std::shared_ptr<Msg const> msg_ptr(msg);
cache.add(msg_ptr);
}
}

TEST(Cache, easyInterval)
{
Cache<Msg> cache(10) ;
fillCacheEasy(cache, 0, 5) ;
message_filters::Cache<Msg> cache(10);
fillCacheEasy(cache, 0, 5);

vector<std::shared_ptr<Msg const> > interval_data = cache.getInterval(rclcpp::Time(5, 0), rclcpp::Time(35, 0)) ;
std::vector<std::shared_ptr<Msg const> > interval_data = cache.getInterval(rclcpp::Time(5, 0), rclcpp::Time(35, 0));

ASSERT_EQ(interval_data.size(), (unsigned int) 3) ;
EXPECT_EQ(interval_data[0]->data, 1) ;
Expand All @@ -109,10 +105,10 @@ TEST(Cache, easyInterval)

TEST(Cache, easySurroundingInterval)
{
Cache<Msg> cache(10);
message_filters::Cache<Msg> cache(10);
fillCacheEasy(cache, 1, 6);

vector<std::shared_ptr<Msg const> > interval_data;
std::vector<std::shared_ptr<Msg const> > interval_data;
interval_data = cache.getSurroundingInterval(rclcpp::Time(15,0), rclcpp::Time(35,0)) ;
ASSERT_EQ(interval_data.size(), (unsigned int) 4);
EXPECT_EQ(interval_data[0]->data, 1);
Expand Down Expand Up @@ -147,15 +143,15 @@ std::shared_ptr<Msg const> buildMsg(int32_t seconds, int data)

TEST(Cache, easyUnsorted)
{
Cache<Msg> cache(10) ;
message_filters::Cache<Msg> cache(10);

cache.add(buildMsg(10, 1)) ;
cache.add(buildMsg(30, 3)) ;
cache.add(buildMsg(70, 7)) ;
cache.add(buildMsg( 5, 0)) ;
cache.add(buildMsg(20, 2)) ;

vector<std::shared_ptr<Msg const> > interval_data = cache.getInterval(rclcpp::Time(3, 0), rclcpp::Time(15, 0)) ;
std::vector<std::shared_ptr<Msg const> > interval_data = cache.getInterval(rclcpp::Time(3, 0), rclcpp::Time(15, 0));

ASSERT_EQ(interval_data.size(), (unsigned int) 2) ;
EXPECT_EQ(interval_data[0]->data, 0) ;
Expand All @@ -174,8 +170,8 @@ TEST(Cache, easyUnsorted)

TEST(Cache, easyElemBeforeAfter)
{
Cache<Msg> cache(10) ;
std::shared_ptr<Msg const> elem_ptr ;
message_filters::Cache<Msg> cache(10);
std::shared_ptr<Msg const> elem_ptr;

fillCacheEasy(cache, 5, 10) ;

Expand All @@ -195,29 +191,30 @@ TEST(Cache, easyElemBeforeAfter)
struct EventHelper
{
public:
void cb(const MessageEvent<Msg const>& evt)
void cb(const message_filters::MessageEvent<Msg const> & evt)
{
event_ = evt;
}

MessageEvent<Msg const> event_;
message_filters::MessageEvent<Msg const> event_;
};

TEST(Cache, eventInEventOut)
{
Cache<Msg> c0(10);
Cache<Msg> c1(c0, 10);
message_filters::Cache<Msg> c0(10);
message_filters::Cache<Msg> c1(c0, 10);
EventHelper h;
c1.registerCallback(&EventHelper::cb, &h);

MessageEvent<Msg const> evt(std::make_shared<Msg const>(), rclcpp::Time(4, 0));
message_filters::MessageEvent<Msg const> evt(std::make_shared<Msg const>(), rclcpp::Time(4, 0));
c0.add(evt);

EXPECT_EQ(h.event_.getReceiptTime(), evt.getReceiptTime());
EXPECT_EQ(h.event_.getMessage(), evt.getMessage());
}

int main(int argc, char **argv){
int main(int argc, char **argv)
{
testing::InitGoogleTest(&argc, argv);
rclcpp::init(argc, argv);
return RUN_ALL_TESTS();
Expand Down
29 changes: 14 additions & 15 deletions test/test_approximate_epsilon_time_policy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,9 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#include <functional>
#include <memory>
#include <utility>
#include <vector>

#include <gtest/gtest.h>
Expand All @@ -42,16 +45,11 @@
#include "message_filters/sync_policies/approximate_epsilon_time.h"
#include "message_filters/message_traits.h"

using namespace std::placeholders;
using namespace message_filters;
using namespace message_filters::sync_policies;

struct Header
{
rclcpp::Time stamp;
};


struct Msg
{
Header header;
Expand Down Expand Up @@ -98,9 +96,9 @@ class ApproximateEpsilonTimeSynchronizerTest
const std::vector<TimePair> &output,
uint32_t queue_size, rclcpp::Duration epsilon) :
input_(input), output_(output), output_position_(0), sync_(
ApproximateEpsilonTime<Msg, Msg>{queue_size, epsilon})
message_filters::sync_policies::ApproximateEpsilonTime<Msg, Msg>{queue_size, epsilon})
{
sync_.registerCallback(std::bind(&ApproximateEpsilonTimeSynchronizerTest::callback, this, _1, _2));
sync_.registerCallback(std::bind(&ApproximateEpsilonTimeSynchronizerTest::callback, this, std::placeholders::_1, std::placeholders::_2));
}

void callback(const MsgConstPtr& p, const MsgConstPtr& q)
Expand Down Expand Up @@ -136,10 +134,10 @@ class ApproximateEpsilonTimeSynchronizerTest
}

private:
const std::vector<TimeAndTopic> &input_;
const std::vector<TimePair> &output_;
const std::vector<TimeAndTopic> & input_;
const std::vector<TimePair> & output_;
unsigned int output_position_;
typedef Synchronizer<ApproximateEpsilonTime<Msg, Msg> > Sync2;
typedef message_filters::Synchronizer<message_filters::sync_policies::ApproximateEpsilonTime<Msg, Msg>> Sync2;
public:
Sync2 sync_;
};
Expand All @@ -157,10 +155,10 @@ TEST(ApproxTimeSync, ExactMatch) {

input.push_back(TimeAndTopic(t,0)); // a
input.push_back(TimeAndTopic(t,1)); // A
input.push_back(TimeAndTopic(t+s*3,0)); // b
input.push_back(TimeAndTopic(t+s*3,1)); // B
input.push_back(TimeAndTopic(t+s*6,0)); // c
input.push_back(TimeAndTopic(t+s*6,1)); // C
input.push_back(TimeAndTopic(t+s*3,0)); // b
input.push_back(TimeAndTopic(t+s*3,1)); // B
input.push_back(TimeAndTopic(t+s*6,0)); // c
input.push_back(TimeAndTopic(t+s*6,1)); // C
output.push_back(TimePair(t, t));
output.push_back(TimePair(t+s*3, t+s*3));
output.push_back(TimePair(t+s*6, t+s*6));
Expand Down Expand Up @@ -225,7 +223,8 @@ TEST(ApproxTimeSync, ImperfectMatch) {
sync_test.run();
}

int main(int argc, char **argv) {
int main(int argc, char **argv)
{
testing::InitGoogleTest(&argc, argv);
rclcpp::init(argc, argv);

Expand Down
59 changes: 24 additions & 35 deletions test/test_approximate_time_policy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,38 +33,37 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#include <functional>
#include <memory>
#include <vector>

#include <gtest/gtest.h>
#include <rclcpp/rclcpp.hpp>
#include "message_filters/synchronizer.h"
#include "message_filters/sync_policies/approximate_time.h"
#include "message_filters/message_traits.h"
#include <vector>

using namespace std::placeholders;
using namespace message_filters;
using namespace message_filters::sync_policies;

struct Header
{
rclcpp::Time stamp;
};


struct Msg
{
Header header;
int data;
};
typedef std::shared_ptr<Msg> MsgPtr;
typedef std::shared_ptr<Msg const> MsgConstPtr;

namespace message_filters
{
namespace message_traits
{
template<>
struct TimeStamp<Msg>
{
static rclcpp::Time value(const Msg& m)
static rclcpp::Time value(const Msg & m)
{
return m.header.stamp;
}
Expand Down Expand Up @@ -94,18 +93,16 @@ class ApproximateTimeSynchronizerTest
{
public:

ApproximateTimeSynchronizerTest(const std::vector<TimeAndTopic> &input,
const std::vector<TimePair> &output,
ApproximateTimeSynchronizerTest(const std::vector<TimeAndTopic> & input,
const std::vector<TimePair> & output,
uint32_t queue_size) :
input_(input), output_(output), output_position_(0), sync_(queue_size)
{
sync_.registerCallback(std::bind(&ApproximateTimeSynchronizerTest::callback, this, _1, _2));
sync_.registerCallback(std::bind(&ApproximateTimeSynchronizerTest::callback, this, std::placeholders::_1, std::placeholders::_2));
}

void callback(const MsgConstPtr& p, const MsgConstPtr& q)
void callback(const MsgConstPtr & p, const MsgConstPtr & q)
{
//printf("Call_back called\n");
//printf("Call back: <%f, %f>\n", p->header.stamp.toSec(), q->header.stamp.toSec());
ASSERT_TRUE(p);
ASSERT_TRUE(q);
ASSERT_LT(output_position_, output_.size());
Expand All @@ -116,30 +113,25 @@ class ApproximateTimeSynchronizerTest

void run()
{
for (unsigned int i = 0; i < input_.size(); i++)
{
if (input_[i].second == 0)
{
for (size_t i = 0; i < input_.size(); i++) {
if (input_[i].second == 0) {
MsgPtr p(std::make_shared<Msg>());
p->header.stamp = input_[i].first;
sync_.add<0>(p);
}
else
{
} else {
MsgPtr q(std::make_shared<Msg>());
q->header.stamp = input_[i].first;
sync_.add<1>(q);
}
}
//printf("Done running test\n");
EXPECT_EQ(output_.size(), output_position_);
}

private:
const std::vector<TimeAndTopic> &input_;
const std::vector<TimePair> &output_;
const std::vector<TimeAndTopic> & input_;
const std::vector<TimePair> & output_;
unsigned int output_position_;
typedef Synchronizer<ApproximateTime<Msg, Msg> > Sync2;
typedef message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<Msg, Msg>> Sync2;
public:
Sync2 sync_;
};
Expand All @@ -152,18 +144,16 @@ class ApproximateTimeSynchronizerTestQuad
{
public:

ApproximateTimeSynchronizerTestQuad(const std::vector<TimeAndTopic> &input,
const std::vector<TimeQuad> &output,
ApproximateTimeSynchronizerTestQuad(const std::vector<TimeAndTopic> & input,
const std::vector<TimeQuad> & output,
uint32_t queue_size) :
input_(input), output_(output), output_position_(0), sync_(queue_size)
{
sync_.registerCallback(std::bind(&ApproximateTimeSynchronizerTestQuad::callback, this, _1, _2, _3, _4));
sync_.registerCallback(std::bind(&ApproximateTimeSynchronizerTestQuad::callback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4));
}

void callback(const MsgConstPtr& p, const MsgConstPtr& q, const MsgConstPtr& r, const MsgConstPtr& s)
void callback(const MsgConstPtr & p, const MsgConstPtr & q, const MsgConstPtr & r, const MsgConstPtr & s)
{
//printf("Call_back called\n");
//printf("Call back: <%f, %f>\n", p->header.stamp.toSec(), q->header.stamp.toSec());
ASSERT_TRUE(p);
ASSERT_TRUE(q);
ASSERT_TRUE(r);
Expand All @@ -178,8 +168,7 @@ class ApproximateTimeSynchronizerTestQuad

void run()
{
for (unsigned int i = 0; i < input_.size(); i++)
{
for (size_t i = 0; i < input_.size(); i++) {
MsgPtr p(std::make_shared<Msg>());
p->header.stamp = input_[i].first;
switch (input_[i].second)
Expand All @@ -198,15 +187,14 @@ class ApproximateTimeSynchronizerTestQuad
break;
}
}
//printf("Done running test\n");
EXPECT_EQ(output_.size(), output_position_);
}

private:
const std::vector<TimeAndTopic> &input_;
const std::vector<TimeQuad> &output_;
unsigned int output_position_;
typedef Synchronizer<ApproximateTime<Msg, Msg, Msg, Msg> > Sync4;
typedef message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<Msg, Msg, Msg, Msg> > Sync4;
public:
Sync4 sync_;
};
Expand Down Expand Up @@ -534,7 +522,8 @@ TEST(ApproxTimeSync, RateBound) {
}


int main(int argc, char **argv) {
int main(int argc, char **argv)
{
testing::InitGoogleTest(&argc, argv);
rclcpp::init(argc, argv);

Expand Down
Loading

0 comments on commit ba5029f

Please sign in to comment.