Skip to content

Commit

Permalink
Revert "Adding explicit constructors (#129)" (#132)
Browse files Browse the repository at this point in the history
This reverts commit aea0e9f.
  • Loading branch information
clalancette authored Jun 26, 2024
1 parent d220e48 commit 8be7422
Show file tree
Hide file tree
Showing 11 changed files with 19 additions and 23 deletions.
2 changes: 1 addition & 1 deletion include/message_filters/message_event.h
Original file line number Diff line number Diff line change
Expand Up @@ -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>());
}
Expand Down
2 changes: 1 addition & 1 deletion include/message_filters/pass_through.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ class PassThrough : public SimpleFilter<M>


template<typename F>
explicit PassThrough(F & f)
PassThrough(F & f) // NOLINT(runtime/explicit)
{
connectInput(f);
}
Expand Down
2 changes: 1 addition & 1 deletion include/message_filters/signal1.h
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
}
Expand Down
2 changes: 1 addition & 1 deletion include/message_filters/signal9.h
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
}
Expand Down
2 changes: 1 addition & 1 deletion include/message_filters/sync_policies/approximate_time.h
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion include/message_filters/sync_policies/exact_time.h
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand Down
2 changes: 1 addition & 1 deletion include/message_filters/synchronizer.h
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
2 changes: 1 addition & 1 deletion include/message_filters/time_synchronizer.h
Original file line number Diff line number Diff line change
Expand Up @@ -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))
{
}
Expand Down
12 changes: 6 additions & 6 deletions test/test_approximate_time_policy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down Expand Up @@ -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_;
Expand All @@ -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(
Expand Down Expand Up @@ -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_;
Expand Down
12 changes: 4 additions & 8 deletions test/test_exact_time_policy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>());
Expand All @@ -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>());
Expand All @@ -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));
Expand Down Expand Up @@ -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));
Expand Down
2 changes: 1 addition & 1 deletion test/test_simple.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down

0 comments on commit 8be7422

Please sign in to comment.