From d7f9031394e7b17ea12731f191b9fd6620fa0989 Mon Sep 17 00:00:00 2001 From: Wolfgang Merkt Date: Wed, 12 Oct 2022 17:53:11 +0100 Subject: [PATCH 1/3] Address inconsistent override warning --- .../include/socketcan_interface/socketcan.h | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/socketcan_interface/include/socketcan_interface/socketcan.h b/socketcan_interface/include/socketcan_interface/socketcan.h index 691ff5da9..10dd7868f 100644 --- a/socketcan_interface/include/socketcan_interface/socketcan.h +++ b/socketcan_interface/include/socketcan_interface/socketcan.h @@ -47,7 +47,7 @@ class SocketCANInterface : public AsioDriver Date: Thu, 13 Oct 2022 17:13:38 +0100 Subject: [PATCH 2/3] [socketcan_interface] Address inconsistent missing overrides --- socketcan_interface/include/socketcan_interface/threading.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/socketcan_interface/include/socketcan_interface/threading.h b/socketcan_interface/include/socketcan_interface/threading.h index 58a796ce9..62eb45c2f 100644 --- a/socketcan_interface/include/socketcan_interface/threading.h +++ b/socketcan_interface/include/socketcan_interface/threading.h @@ -49,7 +49,7 @@ template class ThreadedInterface : public WrappedInte } } public: - [[deprecated("provide settings explicitly")]] virtual bool init(const std::string &device, bool loopback) override { + [[deprecated("provide settings explicitly")]] bool init(const std::string &device, bool loopback) override { #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wdeprecated-declarations" if(!thread_ && WrappedInterface::init(device, loopback)){ @@ -60,7 +60,7 @@ template class ThreadedInterface : public WrappedInte return WrappedInterface::getState().isReady(); #pragma GCC diagnostic pop } - virtual bool init(const std::string &device, bool loopback, SettingsConstSharedPtr settings) override { + bool init(const std::string &device, bool loopback, SettingsConstSharedPtr settings) override { if(!thread_ && WrappedInterface::init(device, loopback, settings)){ StateWaiter waiter(this); thread_.reset(new boost::thread(&ThreadedInterface::run_thread, this)); @@ -69,7 +69,7 @@ template class ThreadedInterface : public WrappedInte return WrappedInterface::getState().isReady(); } - virtual void shutdown(){ + void shutdown() override{ WrappedInterface::shutdown(); shutdown_internal(); } From cde1e49e00aed36af004c27e031db68ced19ca66 Mon Sep 17 00:00:00 2001 From: Wolfgang Merkt Date: Thu, 13 Oct 2022 17:18:23 +0100 Subject: [PATCH 3/3] [canopen_motor_node] Address deprecated filter_chain.h header Backwards compatible with melodic --- canopen_motor_node/include/canopen_motor_node/handle_layer.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/canopen_motor_node/include/canopen_motor_node/handle_layer.h b/canopen_motor_node/include/canopen_motor_node/handle_layer.h index 931ef37a0..13617609a 100644 --- a/canopen_motor_node/include/canopen_motor_node/handle_layer.h +++ b/canopen_motor_node/include/canopen_motor_node/handle_layer.h @@ -7,7 +7,12 @@ #include #include #include +#include // for ROS_VERSION_MINIMUM +#if ROS_VERSION_MINIMUM(1, 15, 0) +#include +#else #include +#endif #include #include #include