Skip to content

Commit

Permalink
Merge pull request #472 from wxmerkt/melodic-devel
Browse files Browse the repository at this point in the history
Address inconsistent override warning
  • Loading branch information
hsd-dev authored Nov 22, 2022
2 parents d86360e + cde1e49 commit 21a9888
Show file tree
Hide file tree
Showing 3 changed files with 13 additions and 8 deletions.
5 changes: 5 additions & 0 deletions canopen_motor_node/include/canopen_motor_node/handle_layer.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,12 @@
#include <atomic>
#include <functional>
#include <boost/thread/mutex.hpp>
#include <ros/common.h> // for ROS_VERSION_MINIMUM
#if ROS_VERSION_MINIMUM(1, 15, 0)
#include <filters/filter_chain.hpp>
#else
#include <filters/filter_chain.h>
#endif
#include <hardware_interface/joint_command_interface.h>
#include <hardware_interface/joint_state_interface.h>
#include <joint_limits_interface/joint_limits_interface.h>
Expand Down
10 changes: 5 additions & 5 deletions socketcan_interface/include/socketcan_interface/socketcan.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ class SocketCANInterface : public AsioDriver<boost::asio::posix::stream_descript
: loopback_(false), sc_(-1), error_mask_(0), fatal_error_mask_(0)
{}

virtual bool doesLoopBack() const{
bool doesLoopBack() const override{
return loopback_;
}

Expand Down Expand Up @@ -82,14 +82,14 @@ class SocketCANInterface : public AsioDriver<boost::asio::posix::stream_descript
return init(device, loopback, error_mask, fatal_error_mask);
}

virtual bool recover(){
bool recover() override{
if(!getState().isReady()){
shutdown();
return init(device_, loopback_, error_mask_, fatal_error_mask_);
}
return getState().isReady();
}
virtual bool translateError(unsigned int internal_error, std::string & str){
bool translateError(unsigned int internal_error, std::string & str) override{

bool ret = false;
if(!internal_error){
Expand Down Expand Up @@ -205,12 +205,12 @@ class SocketCANInterface : public AsioDriver<boost::asio::posix::stream_descript
return getState().isReady();
}

virtual void triggerReadSome(){
void triggerReadSome() override{
boost::mutex::scoped_lock lock(send_mutex_);
socket_.async_read_some(boost::asio::buffer(&frame_, sizeof(frame_)), boost::bind( &SocketCANInterface::readFrame,this, boost::asio::placeholders::error));
}

virtual bool enqueue(const Frame & msg){
bool enqueue(const Frame & msg) override{
boost::mutex::scoped_lock lock(send_mutex_); //TODO: timed try lock

can_frame frame = {0};
Expand Down
6 changes: 3 additions & 3 deletions socketcan_interface/include/socketcan_interface/threading.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ template<typename WrappedInterface> 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)){
Expand All @@ -60,7 +60,7 @@ template<typename WrappedInterface> 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));
Expand All @@ -69,7 +69,7 @@ template<typename WrappedInterface> class ThreadedInterface : public WrappedInte
return WrappedInterface::getState().isReady();
}

virtual void shutdown(){
void shutdown() override{
WrappedInterface::shutdown();
shutdown_internal();
}
Expand Down

0 comments on commit 21a9888

Please sign in to comment.