From 94b25d77f0fc8f91f629c4deaf364cbc349e1e45 Mon Sep 17 00:00:00 2001
From: Chris Lalancette <clalancette@gmail.com>
Date: Tue, 18 Jun 2024 19:09:02 +0000
Subject: [PATCH] Revert "Adding explicit constructors (#129)"

This reverts commit aea0e9ffcdeef43c1244a413a1f5ac2ffb78d082.
---
 include/message_filters/message_event.h              |  2 +-
 include/message_filters/pass_through.h               |  2 +-
 include/message_filters/signal1.h                    |  2 +-
 include/message_filters/signal9.h                    |  2 +-
 .../message_filters/sync_policies/approximate_time.h |  2 +-
 include/message_filters/sync_policies/exact_time.h   |  2 +-
 include/message_filters/synchronizer.h               |  2 +-
 include/message_filters/time_synchronizer.h          |  2 +-
 test/test_approximate_time_policy.cpp                | 12 ++++++------
 test/test_exact_time_policy.cpp                      | 12 ++++--------
 test/test_simple.cpp                                 |  2 +-
 11 files changed, 19 insertions(+), 23 deletions(-)

diff --git a/include/message_filters/message_event.h b/include/message_filters/message_event.h
index b36c527..c0c92b8 100644
--- a/include/message_filters/message_event.h
+++ b/include/message_filters/message_event.h
@@ -118,7 +118,7 @@ class MessageEvent
   /**
    * \todo Make this explicit in ROS 2.0.  Keep as auto-converting for now to maintain backwards compatibility in some places (message_filters)
    */
-  explicit MessageEvent(const ConstMessagePtr & message)
+  MessageEvent(const ConstMessagePtr & message)  // NOLINT(runtime/explicit)
   {
     init(message, rclcpp::Clock().now(), true, message_filters::DefaultMessageCreator<Message>());
   }
diff --git a/include/message_filters/pass_through.h b/include/message_filters/pass_through.h
index ad1aa92..14d8fc3 100644
--- a/include/message_filters/pass_through.h
+++ b/include/message_filters/pass_through.h
@@ -53,7 +53,7 @@ class PassThrough : public SimpleFilter<M>
 
 
   template<typename F>
-  explicit PassThrough(F & f)
+  PassThrough(F & f)  // NOLINT(runtime/explicit)
   {
     connectInput(f);
   }
diff --git a/include/message_filters/signal1.h b/include/message_filters/signal1.h
index 5d22d99..4ea243d 100644
--- a/include/message_filters/signal1.h
+++ b/include/message_filters/signal1.h
@@ -59,7 +59,7 @@ class CallbackHelper1T : public CallbackHelper1<M>
   typedef std::function<void (typename Adapter::Parameter)> Callback;
   typedef typename Adapter::Event Event;
 
-  explicit CallbackHelper1T(const Callback & cb)
+  CallbackHelper1T(const Callback & cb)  // NOLINT(runtime/explicit)
   : callback_(cb)
   {
   }
diff --git a/include/message_filters/signal9.h b/include/message_filters/signal9.h
index d63539a..ad01494 100644
--- a/include/message_filters/signal9.h
+++ b/include/message_filters/signal9.h
@@ -107,7 +107,7 @@ class CallbackHelper9T
       typename A5::Parameter, typename A6::Parameter, typename A7::Parameter,
       typename A8::Parameter)> Callback;
 
-  explicit CallbackHelper9T(const Callback & cb)
+  CallbackHelper9T(const Callback & cb)  // NOLINT(runtime/explicit)
   : callback_(cb)
   {
   }
diff --git a/include/message_filters/sync_policies/approximate_time.h b/include/message_filters/sync_policies/approximate_time.h
index f451552..931cc23 100644
--- a/include/message_filters/sync_policies/approximate_time.h
+++ b/include/message_filters/sync_policies/approximate_time.h
@@ -109,7 +109,7 @@ struct ApproximateTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
   typedef std::tuple<M0Vector, M1Vector, M2Vector, M3Vector, M4Vector, M5Vector, M6Vector, M7Vector,
       M8Vector> VectorTuple;
 
-  explicit ApproximateTime(uint32_t queue_size)
+  ApproximateTime(uint32_t queue_size)  // NOLINT(runtime/explicit)
   : parent_(0)
     , queue_size_(queue_size)
     , num_non_empty_deques_(0)
diff --git a/include/message_filters/sync_policies/exact_time.h b/include/message_filters/sync_policies/exact_time.h
index 8ff4204..def90cc 100644
--- a/include/message_filters/sync_policies/exact_time.h
+++ b/include/message_filters/sync_policies/exact_time.h
@@ -70,7 +70,7 @@ struct ExactTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
   typedef typename Super::M8Event M8Event;
   typedef Events Tuple;
 
-  explicit ExactTime(uint32_t queue_size)
+  ExactTime(uint32_t queue_size)  // NOLINT(runtime/explicit)
   : parent_(0)
     , queue_size_(queue_size)
   {
diff --git a/include/message_filters/synchronizer.h b/include/message_filters/synchronizer.h
index fa16056..0e7f679 100644
--- a/include/message_filters/synchronizer.h
+++ b/include/message_filters/synchronizer.h
@@ -204,7 +204,7 @@ class Synchronizer : public noncopyable, public Policy
     init();
   }
 
-  explicit Synchronizer(const Policy & policy)
+  Synchronizer(const Policy & policy)  // NOLINT(runtime/explicit)
   : Policy(policy)
   {
     init();
diff --git a/include/message_filters/time_synchronizer.h b/include/message_filters/time_synchronizer.h
index 19aff61..f74c236 100644
--- a/include/message_filters/time_synchronizer.h
+++ b/include/message_filters/time_synchronizer.h
@@ -169,7 +169,7 @@ class TimeSynchronizer : public Synchronizer<sync_policies::ExactTime<M0, M1, M2
     connectInput(f0, f1, f2, f3, f4, f5, f6, f7, f8);
   }
 
-  explicit TimeSynchronizer(uint32_t queue_size)
+  TimeSynchronizer(uint32_t queue_size)  // NOLINT(runtime/explicit)
   : Base(Policy(queue_size))
   {
   }
diff --git a/test/test_approximate_time_policy.cpp b/test/test_approximate_time_policy.cpp
index 8f46126..e778c5f 100644
--- a/test/test_approximate_time_policy.cpp
+++ b/test/test_approximate_time_policy.cpp
@@ -91,7 +91,7 @@ class ApproximateTimeSynchronizerTest
     const std::vector<TimeAndTopic> & input,
     const std::vector<TimePair> & output,
     uint32_t queue_size)
-  : input_(input), output_(output), output_position_(0), sync_(Policy2(queue_size))
+  : input_(input), output_(output), output_position_(0), sync_(queue_size)
   {
     sync_.registerCallback(
       std::bind(
@@ -129,8 +129,8 @@ class ApproximateTimeSynchronizerTest
   const std::vector<TimeAndTopic> & input_;
   const std::vector<TimePair> & output_;
   unsigned int output_position_;
-  typedef message_filters::sync_policies::ApproximateTime<Msg, Msg> Policy2;
-  typedef message_filters::Synchronizer<Policy2> Sync2;
+  typedef message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<Msg,
+      Msg>> Sync2;
 
 public:
   Sync2 sync_;
@@ -147,7 +147,7 @@ class ApproximateTimeSynchronizerTestQuad
     const std::vector<TimeAndTopic> & input,
     const std::vector<TimeQuad> & output,
     uint32_t queue_size)
-  : input_(input), output_(output), output_position_(0), sync_(Policy4(queue_size))
+  : input_(input), output_(output), output_position_(0), sync_(queue_size)
   {
     sync_.registerCallback(
       std::bind(
@@ -199,8 +199,8 @@ class ApproximateTimeSynchronizerTestQuad
   const std::vector<TimeAndTopic> & input_;
   const std::vector<TimeQuad> & output_;
   unsigned int output_position_;
-  typedef message_filters::sync_policies::ApproximateTime<Msg, Msg, Msg, Msg> Policy4;
-  typedef message_filters::Synchronizer<Policy4> Sync4;
+  typedef message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<Msg,
+      Msg, Msg, Msg>> Sync4;
 
 public:
   Sync4 sync_;
diff --git a/test/test_exact_time_policy.cpp b/test/test_exact_time_policy.cpp
index 2d303a2..9d90374 100644
--- a/test/test_exact_time_policy.cpp
+++ b/test/test_exact_time_policy.cpp
@@ -96,8 +96,7 @@ typedef message_filters::Synchronizer<Policy3> Sync3;
 //////////////////////////////////////////////////////////////////////////////////////////////////
 TEST(ExactTime, multipleTimes)
 {
-  Policy3 p(2);
-  Sync3 sync(p);
+  Sync3 sync(2);
   Helper h;
   sync.registerCallback(std::bind(&Helper::cb, &h));
   MsgPtr m(std::make_shared<Msg>());
@@ -118,8 +117,7 @@ TEST(ExactTime, multipleTimes)
 
 TEST(ExactTime, queueSize)
 {
-  Policy3 p(1);
-  Sync3 sync(p);
+  Sync3 sync(1);
   Helper h;
   sync.registerCallback(std::bind(&Helper::cb, &h));
   MsgPtr m(std::make_shared<Msg>());
@@ -145,8 +143,7 @@ TEST(ExactTime, queueSize)
 
 TEST(ExactTime, dropCallback)
 {
-  Policy2 p(1);
-  Sync2 sync(p);
+  Sync2 sync(1);
   Helper h;
   sync.registerCallback(std::bind(&Helper::cb, &h));
   sync.getPolicy()->registerDropCallback(std::bind(&Helper::dropcb, &h));
@@ -177,8 +174,7 @@ struct EventHelper
 
 TEST(ExactTime, eventInEventOut)
 {
-  Policy2 p(2);
-  Sync2 sync(p);
+  Sync2 sync(2);
   EventHelper h;
   sync.registerCallback(&EventHelper::callback, &h);
   message_filters::MessageEvent<Msg const> evt(std::make_shared<Msg>(), rclcpp::Time(4, 0));
diff --git a/test/test_simple.cpp b/test/test_simple.cpp
index 0e6f498..287d271 100644
--- a/test/test_simple.cpp
+++ b/test/test_simple.cpp
@@ -145,7 +145,7 @@ TEST(SimpleFilter, oldRegisterWithNewFilter)
 {
   OldFilter f;
   Helper h;
-  f.registerCallback(std::bind(&Helper::cb0, &h, std::placeholders::_1));
+  f.registerCallback(std::bind(&Helper::cb3, &h, std::placeholders::_1));
 }
 
 int main(int argc, char ** argv)