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 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 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(); }