From aea0e9ffcdeef43c1244a413a1f5ac2ffb78d082 Mon Sep 17 00:00:00 2001 From: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Date: Mon, 10 Jun 2024 04:38:32 -0400 Subject: [PATCH] Adding explicit constructors (#129) Signed-off-by: CursedRock17 --- 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, 23 insertions(+), 19 deletions(-) diff --git a/include/message_filters/message_event.h b/include/message_filters/message_event.h index c0c92b8..b36c527 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) */ - MessageEvent(const ConstMessagePtr & message) // NOLINT(runtime/explicit) + explicit MessageEvent(const ConstMessagePtr & message) { init(message, rclcpp::Clock().now(), true, message_filters::DefaultMessageCreator()); } diff --git a/include/message_filters/pass_through.h b/include/message_filters/pass_through.h index 14d8fc3..ad1aa92 100644 --- a/include/message_filters/pass_through.h +++ b/include/message_filters/pass_through.h @@ -53,7 +53,7 @@ class PassThrough : public SimpleFilter template - PassThrough(F & f) // NOLINT(runtime/explicit) + explicit PassThrough(F & f) { connectInput(f); } diff --git a/include/message_filters/signal1.h b/include/message_filters/signal1.h index 4ea243d..5d22d99 100644 --- a/include/message_filters/signal1.h +++ b/include/message_filters/signal1.h @@ -59,7 +59,7 @@ class CallbackHelper1T : public CallbackHelper1 typedef std::function Callback; typedef typename Adapter::Event Event; - CallbackHelper1T(const Callback & cb) // NOLINT(runtime/explicit) + explicit CallbackHelper1T(const Callback & cb) : callback_(cb) { } diff --git a/include/message_filters/signal9.h b/include/message_filters/signal9.h index ad01494..d63539a 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; - CallbackHelper9T(const Callback & cb) // NOLINT(runtime/explicit) + explicit CallbackHelper9T(const Callback & cb) : callback_(cb) { } diff --git a/include/message_filters/sync_policies/approximate_time.h b/include/message_filters/sync_policies/approximate_time.h index 931cc23..f451552 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 typedef std::tuple VectorTuple; - ApproximateTime(uint32_t queue_size) // NOLINT(runtime/explicit) + explicit ApproximateTime(uint32_t queue_size) : 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 def90cc..8ff4204 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 typedef typename Super::M8Event M8Event; typedef Events Tuple; - ExactTime(uint32_t queue_size) // NOLINT(runtime/explicit) + explicit ExactTime(uint32_t queue_size) : parent_(0) , queue_size_(queue_size) { diff --git a/include/message_filters/synchronizer.h b/include/message_filters/synchronizer.h index 0e7f679..fa16056 100644 --- a/include/message_filters/synchronizer.h +++ b/include/message_filters/synchronizer.h @@ -204,7 +204,7 @@ class Synchronizer : public noncopyable, public Policy init(); } - Synchronizer(const Policy & policy) // NOLINT(runtime/explicit) + explicit Synchronizer(const Policy & policy) : Policy(policy) { init(); diff --git a/include/message_filters/time_synchronizer.h b/include/message_filters/time_synchronizer.h index f74c236..19aff61 100644 --- a/include/message_filters/time_synchronizer.h +++ b/include/message_filters/time_synchronizer.h @@ -169,7 +169,7 @@ class TimeSynchronizer : public Synchronizer & input, const std::vector & output, uint32_t queue_size) - : input_(input), output_(output), output_position_(0), sync_(queue_size) + : input_(input), output_(output), output_position_(0), sync_(Policy2(queue_size)) { sync_.registerCallback( std::bind( @@ -129,8 +129,8 @@ class ApproximateTimeSynchronizerTest const std::vector & input_; const std::vector & output_; unsigned int output_position_; - typedef message_filters::Synchronizer> Sync2; + typedef message_filters::sync_policies::ApproximateTime Policy2; + typedef message_filters::Synchronizer Sync2; public: Sync2 sync_; @@ -147,7 +147,7 @@ class ApproximateTimeSynchronizerTestQuad const std::vector & input, const std::vector & output, uint32_t queue_size) - : input_(input), output_(output), output_position_(0), sync_(queue_size) + : input_(input), output_(output), output_position_(0), sync_(Policy4(queue_size)) { sync_.registerCallback( std::bind( @@ -199,8 +199,8 @@ class ApproximateTimeSynchronizerTestQuad const std::vector & input_; const std::vector & output_; unsigned int output_position_; - typedef message_filters::Synchronizer> Sync4; + typedef message_filters::sync_policies::ApproximateTime Policy4; + typedef message_filters::Synchronizer Sync4; public: Sync4 sync_; diff --git a/test/test_exact_time_policy.cpp b/test/test_exact_time_policy.cpp index 9d90374..2d303a2 100644 --- a/test/test_exact_time_policy.cpp +++ b/test/test_exact_time_policy.cpp @@ -96,7 +96,8 @@ typedef message_filters::Synchronizer Sync3; ////////////////////////////////////////////////////////////////////////////////////////////////// TEST(ExactTime, multipleTimes) { - Sync3 sync(2); + Policy3 p(2); + Sync3 sync(p); Helper h; sync.registerCallback(std::bind(&Helper::cb, &h)); MsgPtr m(std::make_shared()); @@ -117,7 +118,8 @@ TEST(ExactTime, multipleTimes) TEST(ExactTime, queueSize) { - Sync3 sync(1); + Policy3 p(1); + Sync3 sync(p); Helper h; sync.registerCallback(std::bind(&Helper::cb, &h)); MsgPtr m(std::make_shared()); @@ -143,7 +145,8 @@ TEST(ExactTime, queueSize) TEST(ExactTime, dropCallback) { - Sync2 sync(1); + Policy2 p(1); + Sync2 sync(p); Helper h; sync.registerCallback(std::bind(&Helper::cb, &h)); sync.getPolicy()->registerDropCallback(std::bind(&Helper::dropcb, &h)); @@ -174,7 +177,8 @@ struct EventHelper TEST(ExactTime, eventInEventOut) { - Sync2 sync(2); + Policy2 p(2); + Sync2 sync(p); EventHelper h; sync.registerCallback(&EventHelper::callback, &h); message_filters::MessageEvent evt(std::make_shared(), rclcpp::Time(4, 0)); diff --git a/test/test_simple.cpp b/test/test_simple.cpp index 287d271..0e6f498 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::cb3, &h, std::placeholders::_1)); + f.registerCallback(std::bind(&Helper::cb0, &h, std::placeholders::_1)); } int main(int argc, char ** argv)