diff --git a/combined_robot_hw/include/combined_robot_hw/combined_robot_hw.h b/combined_robot_hw/include/combined_robot_hw/combined_robot_hw.h index 720689c9c..d1e1d343e 100644 --- a/combined_robot_hw/include/combined_robot_hw/combined_robot_hw.h +++ b/combined_robot_hw/include/combined_robot_hw/combined_robot_hw.h @@ -52,7 +52,6 @@ namespace combined_robot_hw class CombinedRobotHW : public hardware_interface::RobotHW { public: - virtual ~CombinedRobotHW(){} /** \brief The init function is called to initialize the RobotHW from a * non-realtime thread. @@ -64,7 +63,7 @@ class CombinedRobotHW : public hardware_interface::RobotHW * * \returns True if initialization was successful */ - virtual bool init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh); + bool init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh) override; /** @@ -72,15 +71,15 @@ class CombinedRobotHW : public hardware_interface::RobotHW * with regard to necessary hardware interface switches and prepare the switching. Start and stop list are disjoint. * This handles the check and preparation, the actual switch is commited in doSwitch() */ - virtual bool prepareSwitch(const std::list& start_list, - const std::list& stop_list); + bool prepareSwitch(const std::list& start_list, + const std::list& stop_list) override; /** * Perform (in realtime) all necessary hardware interface switches in order to start and stop the given controllers. * Start and stop list are disjoint. The feasability was checked in prepareSwitch() beforehand. */ - virtual void doSwitch(const std::list& start_list, - const std::list& stop_list); + void doSwitch(const std::list& start_list, + const std::list& stop_list) override; /** * Reads data from the robot HW @@ -88,7 +87,7 @@ class CombinedRobotHW : public hardware_interface::RobotHW * \param time The current time * \param period The time passed since the last call to \ref read */ - virtual void read(const ros::Time& time, const ros::Duration& period); + void read(const ros::Time& time, const ros::Duration& period) override; /** * Writes data to the robot HW @@ -96,7 +95,7 @@ class CombinedRobotHW : public hardware_interface::RobotHW * \param time The current time * \param period The time passed since the last call to \ref write */ - virtual void write(const ros::Time& time, const ros::Duration& period); + void write(const ros::Time& time, const ros::Duration& period) override; protected: ros::NodeHandle root_nh_; diff --git a/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_1.h b/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_1.h index e84e8a241..b4425712c 100644 --- a/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_1.h +++ b/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_1.h @@ -38,15 +38,13 @@ namespace combined_robot_hw_tests class MyRobotHW1 : public hardware_interface::RobotHW { public: - MyRobotHW1(); - virtual ~MyRobotHW1(){}; - virtual bool init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh); - virtual void read(const ros::Time& time, const ros::Duration& period); - virtual void write(const ros::Time& time, const ros::Duration& period); - virtual bool prepareSwitch(const std::list& start_list, - const std::list& stop_list); - virtual void doSwitch(const std::list& start_list, - const std::list& stop_list); + bool init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh) override; + void read(const ros::Time& time, const ros::Duration& period) override; + void write(const ros::Time& time, const ros::Duration& period) override; + bool prepareSwitch(const std::list& start_list, + const std::list& stop_list) override; + void doSwitch(const std::list& start_list, + const std::list& stop_list) override; protected: diff --git a/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_2.h b/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_2.h index 961d22141..51e1fbeaa 100644 --- a/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_2.h +++ b/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_2.h @@ -38,15 +38,13 @@ namespace combined_robot_hw_tests class MyRobotHW2 : public hardware_interface::RobotHW { public: - MyRobotHW2(); - virtual ~MyRobotHW2(){}; - virtual bool init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh); - void read(const ros::Time& time, const ros::Duration& period); - void write(const ros::Time& time, const ros::Duration& period); - virtual bool prepareSwitch(const std::list& start_list, - const std::list& stop_list); - virtual void doSwitch(const std::list& start_list, - const std::list& stop_list); + bool init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh) override; + void read(const ros::Time& time, const ros::Duration& period) override; + void write(const ros::Time& time, const ros::Duration& period) override; + bool prepareSwitch(const std::list& start_list, + const std::list& stop_list) override; + void doSwitch(const std::list& start_list, + const std::list& stop_list) override; protected: diff --git a/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_3.h b/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_3.h index 18da60b3c..28ebb6dd7 100644 --- a/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_3.h +++ b/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_3.h @@ -38,11 +38,9 @@ namespace combined_robot_hw_tests class MyRobotHW3 : public hardware_interface::RobotHW { public: - MyRobotHW3(); - virtual ~MyRobotHW3(){}; - virtual bool init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh); - void read(const ros::Time& time, const ros::Duration& period); - void write(const ros::Time& time, const ros::Duration& period); + bool init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh) override; + void read(const ros::Time& time, const ros::Duration& period) override; + void write(const ros::Time& time, const ros::Duration& period) override; protected: diff --git a/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_4.h b/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_4.h index 0e2909753..0925726ab 100644 --- a/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_4.h +++ b/combined_robot_hw_tests/include/combined_robot_hw_tests/my_robot_hw_4.h @@ -38,15 +38,13 @@ namespace combined_robot_hw_tests class MyRobotHW4 : public hardware_interface::RobotHW { public: - MyRobotHW4(); - virtual ~MyRobotHW4(){}; - virtual bool init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh); - void read(const ros::Time& time, const ros::Duration& period); - void write(const ros::Time& time, const ros::Duration& period); - virtual bool prepareSwitch(const std::list& start_list, - const std::list& stop_list); - virtual void doSwitch(const std::list& start_list, - const std::list& stop_list); + bool init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh) override; + void read(const ros::Time& time, const ros::Duration& period) override; + void write(const ros::Time& time, const ros::Duration& period) override; + bool prepareSwitch(const std::list& start_list, + const std::list& stop_list) override; + void doSwitch(const std::list& start_list, + const std::list& stop_list) override; protected: diff --git a/combined_robot_hw_tests/src/my_robot_hw_1.cpp b/combined_robot_hw_tests/src/my_robot_hw_1.cpp index 2ab9239af..b465f881c 100644 --- a/combined_robot_hw_tests/src/my_robot_hw_1.cpp +++ b/combined_robot_hw_tests/src/my_robot_hw_1.cpp @@ -32,10 +32,6 @@ namespace combined_robot_hw_tests { -MyRobotHW1::MyRobotHW1() -{ -} - bool MyRobotHW1::init(ros::NodeHandle& /*root_nh*/, ros::NodeHandle &/*robot_hw_nh*/) { using namespace hardware_interface; diff --git a/combined_robot_hw_tests/src/my_robot_hw_2.cpp b/combined_robot_hw_tests/src/my_robot_hw_2.cpp index 823122de3..a256a6cce 100644 --- a/combined_robot_hw_tests/src/my_robot_hw_2.cpp +++ b/combined_robot_hw_tests/src/my_robot_hw_2.cpp @@ -32,10 +32,6 @@ namespace combined_robot_hw_tests { -MyRobotHW2::MyRobotHW2() -{ -} - bool MyRobotHW2::init(ros::NodeHandle& /*root_nh*/, ros::NodeHandle &robot_hw_nh) { using namespace hardware_interface; diff --git a/combined_robot_hw_tests/src/my_robot_hw_3.cpp b/combined_robot_hw_tests/src/my_robot_hw_3.cpp index e84aa859d..ed4008a23 100644 --- a/combined_robot_hw_tests/src/my_robot_hw_3.cpp +++ b/combined_robot_hw_tests/src/my_robot_hw_3.cpp @@ -31,10 +31,6 @@ namespace combined_robot_hw_tests { -MyRobotHW3::MyRobotHW3() -{ -} - bool MyRobotHW3::init(ros::NodeHandle& /*root_nh*/, ros::NodeHandle &robot_hw_nh) { using namespace hardware_interface; @@ -91,4 +87,3 @@ void MyRobotHW3::write(const ros::Time& /*time*/, const ros::Duration& /*period* } PLUGINLIB_EXPORT_CLASS( combined_robot_hw_tests::MyRobotHW3, hardware_interface::RobotHW) - diff --git a/combined_robot_hw_tests/src/my_robot_hw_4.cpp b/combined_robot_hw_tests/src/my_robot_hw_4.cpp index b31d6c15f..8fe88bb67 100644 --- a/combined_robot_hw_tests/src/my_robot_hw_4.cpp +++ b/combined_robot_hw_tests/src/my_robot_hw_4.cpp @@ -31,10 +31,6 @@ namespace combined_robot_hw_tests { -MyRobotHW4::MyRobotHW4() -{ -} - bool MyRobotHW4::init(ros::NodeHandle& /*root_nh*/, ros::NodeHandle &/*robot_hw_nh*/) { using namespace hardware_interface; diff --git a/controller_interface/include/controller_interface/controller.h b/controller_interface/include/controller_interface/controller.h index 846f1c738..2a865db50 100644 --- a/controller_interface/include/controller_interface/controller.h +++ b/controller_interface/include/controller_interface/controller.h @@ -52,8 +52,6 @@ template class Controller: public virtual ControllerBase { public: - Controller() {} - virtual ~Controller(){} /** \brief The init function is called to initialize the controller from a * non-realtime thread with a pointer to the hardware interface, itself, @@ -95,10 +93,10 @@ class Controller: public virtual ControllerBase * can extract the correct interface from \c robot_hw. * */ - virtual bool initRequest(hardware_interface::RobotHW* robot_hw, - ros::NodeHandle& root_nh, - ros::NodeHandle& controller_nh, - ClaimedResources& claimed_resources) + bool initRequest(hardware_interface::RobotHW* robot_hw, + ros::NodeHandle& root_nh, + ros::NodeHandle& controller_nh, + ClaimedResources& claimed_resources) override { // check if construction finished cleanly if (state_ != CONSTRUCTED){ @@ -137,11 +135,6 @@ class Controller: public virtual ControllerBase { return hardware_interface::internal::demangledTypeName(); } - -private: - Controller(const Controller &c); - Controller& operator =(const Controller &c); - }; } diff --git a/controller_interface/include/controller_interface/controller_base.h b/controller_interface/include/controller_interface/controller_base.h index 0681b5231..ee40bc4dc 100644 --- a/controller_interface/include/controller_interface/controller_base.h +++ b/controller_interface/include/controller_interface/controller_base.h @@ -48,8 +48,12 @@ namespace controller_interface class ControllerBase { public: - ControllerBase() {} - virtual ~ControllerBase(){} + ControllerBase() = default; + virtual ~ControllerBase() = default; + ControllerBase(const ControllerBase&) = delete; + ControllerBase& operator=(const ControllerBase&) = delete; + ControllerBase(ControllerBase&&) = delete; + ControllerBase& operator=(ControllerBase&&) = delete; /** \name Real-Time Safe Functions *\{*/ @@ -238,12 +242,6 @@ class ControllerBase /// The current execution state of the controller enum {CONSTRUCTED, INITIALIZED, RUNNING, STOPPED, WAITING, ABORTED} state_ = {CONSTRUCTED}; - - -private: - ControllerBase(const ControllerBase &c); - ControllerBase& operator =(const ControllerBase &c); - }; typedef std::shared_ptr ControllerBaseSharedPtr; diff --git a/controller_interface/include/controller_interface/multi_interface_controller.h b/controller_interface/include/controller_interface/multi_interface_controller.h index f96aa0833..43fb05023 100644 --- a/controller_interface/include/controller_interface/multi_interface_controller.h +++ b/controller_interface/include/controller_interface/multi_interface_controller.h @@ -155,10 +155,7 @@ class MultiInterfaceController: public virtual ControllerBase * If set to false (the default), all requested interfaces are required. */ MultiInterfaceController(bool allow_optional_interfaces = false) - : allow_optional_interfaces_(allow_optional_interfaces) - {} - - virtual ~MultiInterfaceController() {} + : allow_optional_interfaces_(allow_optional_interfaces) {} /** \name Non Real-Time Safe Functions *\{*/ @@ -245,10 +242,10 @@ class MultiInterfaceController: public virtual ControllerBase * \returns True if initialization was successful and the controller * is ready to be started. */ - virtual bool initRequest(hardware_interface::RobotHW* robot_hw, - ros::NodeHandle& root_nh, - ros::NodeHandle& controller_nh, - ClaimedResources& claimed_resources) + bool initRequest(hardware_interface::RobotHW* robot_hw, + ros::NodeHandle& root_nh, + ros::NodeHandle& controller_nh, + ClaimedResources& claimed_resources) override { // check if construction finished cleanly if (state_ != CONSTRUCTED){ @@ -340,10 +337,6 @@ class MultiInterfaceController: public virtual ControllerBase /** Flag to indicate if hardware interfaces are considered optional (i.e. non-required). */ bool allow_optional_interfaces_; - -private: - MultiInterfaceController(const MultiInterfaceController& c); - MultiInterfaceController& operator =(const MultiInterfaceController& c); }; } // namespace diff --git a/controller_interface/test/controller_base_test.cpp b/controller_interface/test/controller_base_test.cpp index 1191f33b5..becacc7eb 100644 --- a/controller_interface/test/controller_base_test.cpp +++ b/controller_interface/test/controller_base_test.cpp @@ -43,13 +43,6 @@ using ::testing::Return; class ControllerMock : public controller_interface::ControllerBase { public: - ControllerMock() : controller_interface::ControllerBase() - { - } - - ~ControllerMock() - { - } void initializeState() { diff --git a/controller_manager/include/controller_manager/controller_loader.h b/controller_manager/include/controller_manager/controller_loader.h index b2d292a18..86c494947 100644 --- a/controller_manager/include/controller_manager/controller_loader.h +++ b/controller_manager/include/controller_manager/controller_loader.h @@ -56,17 +56,17 @@ class ControllerLoader : public ControllerLoaderInterface reload(); } - controller_interface::ControllerBaseSharedPtr createInstance(const std::string& lookup_name) + controller_interface::ControllerBaseSharedPtr createInstance(const std::string& lookup_name) override { return controller_loader_->createUniqueInstance(lookup_name); } - std::vector getDeclaredClasses() + std::vector getDeclaredClasses() override { return controller_loader_->getDeclaredClasses(); } - void reload() + void reload() override { controller_loader_.reset(new pluginlib::ClassLoader(package_, base_class_) ); } diff --git a/controller_manager/include/controller_manager/controller_loader_interface.h b/controller_manager/include/controller_manager/controller_loader_interface.h index cff4faf90..a4c2de89a 100644 --- a/controller_manager/include/controller_manager/controller_loader_interface.h +++ b/controller_manager/include/controller_manager/controller_loader_interface.h @@ -45,15 +45,16 @@ namespace controller_manager class ControllerLoaderInterface { public: - ControllerLoaderInterface(const std::string& name) : name_(name) { } + ControllerLoaderInterface(const std::string& name) : name_(name) {} + virtual ~ControllerLoaderInterface() = default; + virtual controller_interface::ControllerBaseSharedPtr createInstance(const std::string& lookup_name) = 0; virtual std::vector getDeclaredClasses() = 0; virtual void reload() = 0; const std::string& getName() { return name_; } - virtual ~ControllerLoaderInterface() { } + private: const std::string name_; - }; typedef std::shared_ptr ControllerLoaderInterfaceSharedPtr; diff --git a/controller_manager/include/controller_manager/controller_manager.h b/controller_manager/include/controller_manager/controller_manager.h index e4541b8b5..471f47a50 100644 --- a/controller_manager/include/controller_manager/controller_manager.h +++ b/controller_manager/include/controller_manager/controller_manager.h @@ -75,7 +75,7 @@ class ControllerManager{ */ ControllerManager(hardware_interface::RobotHW *robot_hw, const ros::NodeHandle& nh=ros::NodeHandle()); - virtual ~ControllerManager(); + virtual ~ControllerManager() = default; /** \name Real-Time Safe Functions *\{*/ diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 441e3d878..2f5406f0d 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -62,10 +62,6 @@ ControllerManager::ControllerManager(hardware_interface::RobotHW *robot_hw, cons } -ControllerManager::~ControllerManager() -{} - - // Must be realtime safe. void ControllerManager::update(const ros::Time& time, const ros::Duration& period, bool reset_controllers) { diff --git a/controller_manager/test/hwi_switch_test.cpp b/controller_manager/test/hwi_switch_test.cpp index 11d65d075..54a752ed1 100644 --- a/controller_manager/test/hwi_switch_test.cpp +++ b/controller_manager/test/hwi_switch_test.cpp @@ -137,8 +137,8 @@ class SwitchBot : public hardware_interface::RobotHW } - virtual bool prepareSwitch(const std::list& start_list, - const std::list& stop_list) + bool prepareSwitch(const std::list& start_list, + const std::list& stop_list) override { if(!RobotHW::prepareSwitch(start_list, stop_list)) @@ -188,7 +188,7 @@ class SwitchBot : public hardware_interface::RobotHW } return !(j_pe_e && j_ve_v); // check inter-joint hardware interface conflict } - virtual void doSwitch(const std::list &start_list, const std::list &stop_list) + void doSwitch(const std::list &start_list, const std::list &stop_list) override { RobotHW::doSwitch(start_list, stop_list); // check if member is defined @@ -236,11 +236,11 @@ class DummyControllerLoader: public controller_manager::ControllerLoaderInterfac const std::string type_name; public: DummyController(const std::string &name) : type_name(name) {} - virtual void update(const ros::Time& /*time*/, const ros::Duration& /*period*/) {} - virtual bool initRequest(hardware_interface::RobotHW* /*hw*/, - ros::NodeHandle& /*root_nh*/, - ros::NodeHandle& controller_nh, - ClaimedResources& claimed_resources) + void update(const ros::Time& /*time*/, const ros::Duration& /*period*/) override {} + bool initRequest(hardware_interface::RobotHW* /*hw*/, + ros::NodeHandle& /*root_nh*/, + ros::NodeHandle& controller_nh, + ClaimedResources& claimed_resources) override { std::vector joints; if(!controller_nh.getParam("joints", joints)) @@ -272,11 +272,11 @@ class DummyControllerLoader: public controller_manager::ControllerLoaderInterfac add("PositionJointInterface"); add("VelocityJointInterface"); } - virtual controller_interface::ControllerBaseSharedPtr createInstance(const std::string& lookup_name) + controller_interface::ControllerBaseSharedPtr createInstance(const std::string& lookup_name) override { return controller_interface::ControllerBaseSharedPtr(new DummyController(classes.at(lookup_name))); } - virtual std::vector getDeclaredClasses() + std::vector getDeclaredClasses() override { std::vector v; for (const auto& declared_class : classes) @@ -285,7 +285,7 @@ class DummyControllerLoader: public controller_manager::ControllerLoaderInterfac } return v; } - virtual void reload() {} + void reload() override {} }; void update(controller_manager::ControllerManager &cm, const ros::TimerEvent& e) diff --git a/controller_manager/test/hwi_update_test.cpp b/controller_manager/test/hwi_update_test.cpp index 3636be781..515060f0d 100644 --- a/controller_manager/test/hwi_update_test.cpp +++ b/controller_manager/test/hwi_update_test.cpp @@ -51,13 +51,6 @@ using ::testing::Return; class RobotHWMock : public hardware_interface::RobotHW { public: - RobotHWMock() - { - } - - ~RobotHWMock() - { - } MOCK_METHOD2(init, bool(ros::NodeHandle &, ros::NodeHandle &)); MOCK_CONST_METHOD1(checkForConflict, @@ -75,13 +68,7 @@ class RobotHWMock : public hardware_interface::RobotHW class ControllerLoaderMock : public controller_manager::ControllerLoaderInterface { public: - ControllerLoaderMock() : ControllerLoaderInterface("ControllerLoaderMock") - { - } - - ~ControllerLoaderMock() - { - } + ControllerLoaderMock() : ControllerLoaderInterface("ControllerLoaderMock") {} MOCK_METHOD1(createInstance, controller_interface::ControllerBaseSharedPtr(const std::string &)); @@ -92,13 +79,6 @@ class ControllerLoaderMock : public controller_manager::ControllerLoaderInterfac class ControllerMock : public controller_interface::ControllerBase { public: - ControllerMock() - { - } - - ~ControllerMock() - { - } void initializeState() { @@ -117,7 +97,7 @@ class ControllerMock : public controller_interface::ControllerBase class ControllerManagerTest : public ::testing::Test { public: - void SetUp() + void SetUp() override { prepareMocks(); loadControllers(); diff --git a/controller_manager_tests/include/controller_manager_tests/effort_test_controller.h b/controller_manager_tests/include/controller_manager_tests/effort_test_controller.h index 46271e8f3..55c3266a4 100644 --- a/controller_manager_tests/include/controller_manager_tests/effort_test_controller.h +++ b/controller_manager_tests/include/controller_manager_tests/effort_test_controller.h @@ -40,13 +40,11 @@ namespace controller_manager_tests class EffortTestController: public controller_interface::Controller { public: - EffortTestController(){} - using controller_interface::Controller::init; - bool init(hardware_interface::EffortJointInterface* hw, ros::NodeHandle& /*n*/); - void starting(const ros::Time& /*time*/); - void update(const ros::Time& /*time*/, const ros::Duration& /*period*/); - void stopping(const ros::Time& /*time*/); + bool init(hardware_interface::EffortJointInterface* hw, ros::NodeHandle& /*n*/) override; + void starting(const ros::Time& /*time*/) override; + void update(const ros::Time& /*time*/, const ros::Duration& /*period*/) override; + void stopping(const ros::Time& /*time*/) override; private: std::vector joint_effort_commands_; diff --git a/controller_manager_tests/include/controller_manager_tests/extensible_controllers.h b/controller_manager_tests/include/controller_manager_tests/extensible_controllers.h index 7c98083b0..848a4805e 100644 --- a/controller_manager_tests/include/controller_manager_tests/extensible_controllers.h +++ b/controller_manager_tests/include/controller_manager_tests/extensible_controllers.h @@ -43,9 +43,9 @@ class ExtensibleController : public virtual BaseControllerInterface { public: bool init(hardware_interface::RobotHW* robot_hw, - ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh); + ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh) override; virtual int helper(); - void update(const ros::Time&, const ros::Duration&); + void update(const ros::Time&, const ros::Duration&) override; }; /** @@ -58,10 +58,10 @@ class DerivedController : public ExtensibleController, public DerivedControllerI { public: bool initRequest(hardware_interface::RobotHW* hw, ros::NodeHandle& nh, ros::NodeHandle& pnh, - controller_interface::ControllerBase::ClaimedResources& cr); + controller_interface::ControllerBase::ClaimedResources& cr) override; bool init(hardware_interface::RobotHW* robot_hw, - ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh); - virtual int helper(); + ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh) override; + int helper() override; }; } // namespace controller_manager_tests diff --git a/controller_manager_tests/include/controller_manager_tests/my_dummy_controller.h b/controller_manager_tests/include/controller_manager_tests/my_dummy_controller.h index 5d06a7458..75fa5aa8f 100644 --- a/controller_manager_tests/include/controller_manager_tests/my_dummy_controller.h +++ b/controller_manager_tests/include/controller_manager_tests/my_dummy_controller.h @@ -37,25 +37,16 @@ namespace controller_manager_tests { -class MyDummyInterface : public hardware_interface::HardwareInterface -{ -public: - MyDummyInterface() - { - - } -}; +class MyDummyInterface : public hardware_interface::HardwareInterface {}; class MyDummyController : public controller_interface::Controller { public: - MyDummyController() { } - using controller_interface::Controller::init; - bool init(MyDummyInterface* /*hw*/, ros::NodeHandle& /*n*/) { return true; } - void starting(const ros::Time& /*time*/) { } - void update(const ros::Time& /*time*/, const ros::Duration& /*period*/) { } - void stopping(const ros::Time& /*time*/) { } + bool init(MyDummyInterface* /*hw*/, ros::NodeHandle& /*n*/) override { return true; } + void starting(const ros::Time& /*time*/) override { } + void update(const ros::Time& /*time*/, const ros::Duration& /*period*/) override { } + void stopping(const ros::Time& /*time*/) override { } }; } diff --git a/controller_manager_tests/include/controller_manager_tests/pos_eff_controller.h b/controller_manager_tests/include/controller_manager_tests/pos_eff_controller.h index 281dcbaa2..9c9a259f0 100644 --- a/controller_manager_tests/include/controller_manager_tests/pos_eff_controller.h +++ b/controller_manager_tests/include/controller_manager_tests/pos_eff_controller.h @@ -40,12 +40,10 @@ class PosEffController : public hardware_interface::EffortJointInterface> { public: - PosEffController() {} - - bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle &n); - void starting(const ros::Time& time); - void update(const ros::Time& time, const ros::Duration& period); - void stopping(const ros::Time& time); + bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle &n) override; + void starting(const ros::Time& time) override; + void update(const ros::Time& time, const ros::Duration& period) override; + void stopping(const ros::Time& time) override; private: std::vector pos_cmd_; diff --git a/controller_manager_tests/include/controller_manager_tests/pos_eff_opt_controller.h b/controller_manager_tests/include/controller_manager_tests/pos_eff_opt_controller.h index f03d86323..9fc17a3ff 100644 --- a/controller_manager_tests/include/controller_manager_tests/pos_eff_opt_controller.h +++ b/controller_manager_tests/include/controller_manager_tests/pos_eff_opt_controller.h @@ -45,10 +45,10 @@ class PosEffOptController : public : controller_interface::MultiInterfaceController (true) {} - bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle &n); - void starting(const ros::Time& time); - void update(const ros::Time& time, const ros::Duration& period); - void stopping(const ros::Time& time); + bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle &n) override; + void starting(const ros::Time& time) override; + void update(const ros::Time& time, const ros::Duration& period) override; + void stopping(const ros::Time& time) override; private: std::vector pos_cmd_; diff --git a/controller_manager_tests/include/controller_manager_tests/vel_eff_controller.h b/controller_manager_tests/include/controller_manager_tests/vel_eff_controller.h index ae316f52e..ccf85855d 100644 --- a/controller_manager_tests/include/controller_manager_tests/vel_eff_controller.h +++ b/controller_manager_tests/include/controller_manager_tests/vel_eff_controller.h @@ -40,12 +40,10 @@ class VelEffController : public hardware_interface::EffortJointInterface> { public: - VelEffController() {} - - bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle &n); - void starting(const ros::Time& time); - void update(const ros::Time& time, const ros::Duration& period); - void stopping(const ros::Time& time); + bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle &n) override; + void starting(const ros::Time& time) override; + void update(const ros::Time& time, const ros::Duration& period) override; + void stopping(const ros::Time& time) override; private: std::vector vel_cmd_; diff --git a/hardware_interface/include/hardware_interface/actuator_command_interface.h b/hardware_interface/include/hardware_interface/actuator_command_interface.h index 889bd3800..9395f63b1 100644 --- a/hardware_interface/include/hardware_interface/actuator_command_interface.h +++ b/hardware_interface/include/hardware_interface/actuator_command_interface.h @@ -40,7 +40,7 @@ namespace hardware_interface class ActuatorHandle : public ActuatorStateHandle { public: - ActuatorHandle() {} + ActuatorHandle() = default; /** * \param as This actuator's state handle diff --git a/hardware_interface/include/hardware_interface/actuator_state_interface.h b/hardware_interface/include/hardware_interface/actuator_state_interface.h index 79dd5c86d..22f455190 100644 --- a/hardware_interface/include/hardware_interface/actuator_state_interface.h +++ b/hardware_interface/include/hardware_interface/actuator_state_interface.h @@ -45,7 +45,7 @@ namespace hardware_interface class ActuatorStateHandle { public: - ActuatorStateHandle() {} + ActuatorStateHandle() = default; /** * \param name The name of the actuator diff --git a/hardware_interface/include/hardware_interface/force_torque_sensor_interface.h b/hardware_interface/include/hardware_interface/force_torque_sensor_interface.h index e6e63eed7..c9d12ba55 100644 --- a/hardware_interface/include/hardware_interface/force_torque_sensor_interface.h +++ b/hardware_interface/include/hardware_interface/force_torque_sensor_interface.h @@ -40,7 +40,7 @@ namespace hardware_interface class ForceTorqueSensorHandle { public: - ForceTorqueSensorHandle() {} + ForceTorqueSensorHandle() = default; /** * \param name The name of the sensor diff --git a/hardware_interface/include/hardware_interface/hardware_interface.h b/hardware_interface/include/hardware_interface/hardware_interface.h index c8443cc25..9c37ba6e7 100644 --- a/hardware_interface/include/hardware_interface/hardware_interface.h +++ b/hardware_interface/include/hardware_interface/hardware_interface.h @@ -46,7 +46,7 @@ namespace hardware_interface{ class HardwareInterface { public: - virtual ~HardwareInterface() {} + virtual ~HardwareInterface() = default; /** \name Resource management *\{**/ @@ -71,17 +71,8 @@ class HardwareInterface class HardwareInterfaceException: public std::exception { public: - HardwareInterfaceException(const std::string& message) - : msg(message) {} - - virtual ~HardwareInterfaceException() throw() {} - - virtual const char* what() const throw() - { - return msg.c_str(); - } - - + HardwareInterfaceException(const std::string& message) : msg(message) {} + const char* what() const noexcept override {return msg.c_str();} private: std::string msg; }; diff --git a/hardware_interface/include/hardware_interface/imu_sensor_interface.h b/hardware_interface/include/hardware_interface/imu_sensor_interface.h index ecdfca1df..b3612e90e 100644 --- a/hardware_interface/include/hardware_interface/imu_sensor_interface.h +++ b/hardware_interface/include/hardware_interface/imu_sensor_interface.h @@ -46,7 +46,8 @@ class ImuSensorHandle public: struct Data { - Data() {}; + // Note: User-provided constructor required due to a defect in the standard. See https://stackoverflow.com/a/17436088/1932358 + Data() {} std::string name; ///< The name of the sensor std::string frame_id; ///< The reference frame to which this sensor is associated diff --git a/hardware_interface/include/hardware_interface/interface_resources.h b/hardware_interface/include/hardware_interface/interface_resources.h index 8b5a4a80f..558b19cf0 100644 --- a/hardware_interface/include/hardware_interface/interface_resources.h +++ b/hardware_interface/include/hardware_interface/interface_resources.h @@ -41,7 +41,7 @@ namespace hardware_interface */ struct InterfaceResources { - InterfaceResources() {} + InterfaceResources() = default; InterfaceResources(const std::string& hw_iface, const std::set& res) : hardware_interface(hw_iface), diff --git a/hardware_interface/include/hardware_interface/internal/resource_manager.h b/hardware_interface/include/hardware_interface/internal/resource_manager.h index f6a208432..2620baa5c 100644 --- a/hardware_interface/include/hardware_interface/internal/resource_manager.h +++ b/hardware_interface/include/hardware_interface/internal/resource_manager.h @@ -52,7 +52,7 @@ namespace hardware_interface class ResourceManagerBase { public: - virtual ~ResourceManagerBase() {} + virtual ~ResourceManagerBase() = default; }; /** @@ -73,8 +73,6 @@ class ResourceManager : public ResourceManagerBase /** \name Non Real-Time Safe Functions *\{*/ - virtual ~ResourceManager() {} - /** \return Vector of resource names registered to this interface. */ std::vector getNames() const { diff --git a/hardware_interface/include/hardware_interface/joint_command_interface.h b/hardware_interface/include/hardware_interface/joint_command_interface.h index 82a52d562..849a54e52 100644 --- a/hardware_interface/include/hardware_interface/joint_command_interface.h +++ b/hardware_interface/include/hardware_interface/joint_command_interface.h @@ -42,7 +42,7 @@ namespace hardware_interface class JointHandle : public JointStateHandle { public: - JointHandle() {} + JointHandle() = default; /** * \param js This joint's state handle diff --git a/hardware_interface/include/hardware_interface/joint_mode_interface.h b/hardware_interface/include/hardware_interface/joint_mode_interface.h index 7c6928d67..563f101aa 100644 --- a/hardware_interface/include/hardware_interface/joint_mode_interface.h +++ b/hardware_interface/include/hardware_interface/joint_mode_interface.h @@ -62,8 +62,7 @@ namespace hardware_interface class JointModeHandle { public: - - JointModeHandle() {} + JointModeHandle() = default; /** \param mode Which mode to start in */ JointModeHandle(std::string name, JointCommandModes* mode) diff --git a/hardware_interface/include/hardware_interface/joint_state_interface.h b/hardware_interface/include/hardware_interface/joint_state_interface.h index 5c51d4377..18c76c35f 100644 --- a/hardware_interface/include/hardware_interface/joint_state_interface.h +++ b/hardware_interface/include/hardware_interface/joint_state_interface.h @@ -45,7 +45,7 @@ namespace hardware_interface class JointStateHandle { public: - JointStateHandle() {} + JointStateHandle() = default; /** * \param name The name of the joint diff --git a/hardware_interface/include/hardware_interface/posvel_command_interface.h b/hardware_interface/include/hardware_interface/posvel_command_interface.h index 24678356d..05a3759cd 100644 --- a/hardware_interface/include/hardware_interface/posvel_command_interface.h +++ b/hardware_interface/include/hardware_interface/posvel_command_interface.h @@ -42,7 +42,7 @@ namespace hardware_interface class PosVelJointHandle : public JointStateHandle { public: - PosVelJointHandle() {} + PosVelJointHandle() = default; /** * \param js This joint's state handle diff --git a/hardware_interface/include/hardware_interface/posvelacc_command_interface.h b/hardware_interface/include/hardware_interface/posvelacc_command_interface.h index 37b91aad8..8030f2273 100644 --- a/hardware_interface/include/hardware_interface/posvelacc_command_interface.h +++ b/hardware_interface/include/hardware_interface/posvelacc_command_interface.h @@ -42,7 +42,7 @@ namespace hardware_interface class PosVelAccJointHandle : public PosVelJointHandle { public: - PosVelAccJointHandle() {} + PosVelAccJointHandle() = default; /** * \param js This joint's state handle diff --git a/hardware_interface/include/hardware_interface/robot_hw.h b/hardware_interface/include/hardware_interface/robot_hw.h index a70340898..1c339994b 100644 --- a/hardware_interface/include/hardware_interface/robot_hw.h +++ b/hardware_interface/include/hardware_interface/robot_hw.h @@ -58,15 +58,7 @@ namespace hardware_interface class RobotHW : public InterfaceManager { public: - RobotHW() - { - - } - - virtual ~RobotHW() - { - - } + virtual ~RobotHW() = default; /** \brief The init function is called to initialize the RobotHW from a * non-realtime thread. diff --git a/joint_limits_interface/include/joint_limits_interface/joint_limits_interface.h b/joint_limits_interface/include/joint_limits_interface/joint_limits_interface.h index f2f4720b8..c4f0c90c0 100644 --- a/joint_limits_interface/include/joint_limits_interface/joint_limits_interface.h +++ b/joint_limits_interface/include/joint_limits_interface/joint_limits_interface.h @@ -160,7 +160,7 @@ class PositionJointSaturationHandle class PositionJointSoftLimitsHandle { public: - PositionJointSoftLimitsHandle() {} + PositionJointSoftLimitsHandle() = default; PositionJointSoftLimitsHandle(const hardware_interface::JointHandle& jh, const JointLimits& limits, @@ -316,7 +316,7 @@ class EffortJointSaturationHandle class EffortJointSoftLimitsHandle { public: - EffortJointSoftLimitsHandle() {} + EffortJointSoftLimitsHandle() = default; EffortJointSoftLimitsHandle(const hardware_interface::JointHandle& jh, const JointLimits& limits, @@ -402,7 +402,7 @@ class EffortJointSoftLimitsHandle class VelocityJointSaturationHandle { public: - VelocityJointSaturationHandle() {} + VelocityJointSaturationHandle() = default; VelocityJointSaturationHandle(const hardware_interface::JointHandle& jh, const JointLimits& limits) : jh_(jh) diff --git a/joint_limits_interface/include/joint_limits_interface/joint_limits_interface_exception.h b/joint_limits_interface/include/joint_limits_interface/joint_limits_interface_exception.h index 0e71969c9..b5aeb4bff 100644 --- a/joint_limits_interface/include/joint_limits_interface/joint_limits_interface_exception.h +++ b/joint_limits_interface/include/joint_limits_interface/joint_limits_interface_exception.h @@ -28,6 +28,9 @@ #pragma once +#include +#include + namespace joint_limits_interface { @@ -35,16 +38,8 @@ namespace joint_limits_interface class JointLimitsInterfaceException: public std::exception { public: - JointLimitsInterfaceException(const std::string& message) - : msg(message) {} - - virtual ~JointLimitsInterfaceException() throw() {} - - virtual const char* what() const throw() - { - return msg.c_str(); - } - + JointLimitsInterfaceException(const std::string& message) : msg(message) {} + const char* what() const noexcept override {return msg.c_str();} private: std::string msg; }; diff --git a/transmission_interface/include/transmission_interface/bidirectional_effort_joint_interface_provider.h b/transmission_interface/include/transmission_interface/bidirectional_effort_joint_interface_provider.h index 290a74a07..caa820fbd 100644 --- a/transmission_interface/include/transmission_interface/bidirectional_effort_joint_interface_provider.h +++ b/transmission_interface/include/transmission_interface/bidirectional_effort_joint_interface_provider.h @@ -38,9 +38,8 @@ namespace transmission_interface class BiDirectionalEffortJointInterfaceProvider : public EffortJointInterfaceProvider { protected: - bool registerTransmission(TransmissionLoaderData& loader_data, - TransmissionHandleData& handle_data); + TransmissionHandleData& handle_data) override; }; } // namespace diff --git a/transmission_interface/include/transmission_interface/bidirectional_position_joint_interface_provider.h b/transmission_interface/include/transmission_interface/bidirectional_position_joint_interface_provider.h index 4f0d40b1f..454ff8cd8 100644 --- a/transmission_interface/include/transmission_interface/bidirectional_position_joint_interface_provider.h +++ b/transmission_interface/include/transmission_interface/bidirectional_position_joint_interface_provider.h @@ -38,9 +38,8 @@ namespace transmission_interface class BiDirectionalPositionJointInterfaceProvider : public PositionJointInterfaceProvider { protected: - bool registerTransmission(TransmissionLoaderData& loader_data, - TransmissionHandleData& handle_data); + TransmissionHandleData& handle_data) override; }; } // namespace diff --git a/transmission_interface/include/transmission_interface/bidirectional_velocity_joint_interface_provider.h b/transmission_interface/include/transmission_interface/bidirectional_velocity_joint_interface_provider.h index 7814ca41e..1a823bf7d 100644 --- a/transmission_interface/include/transmission_interface/bidirectional_velocity_joint_interface_provider.h +++ b/transmission_interface/include/transmission_interface/bidirectional_velocity_joint_interface_provider.h @@ -38,9 +38,8 @@ namespace transmission_interface class BiDirectionalVelocityJointInterfaceProvider : public VelocityJointInterfaceProvider { protected: - bool registerTransmission(TransmissionLoaderData& loader_data, - TransmissionHandleData& handle_data); + TransmissionHandleData& handle_data) override; }; } // namespace diff --git a/transmission_interface/include/transmission_interface/differential_transmission.h b/transmission_interface/include/transmission_interface/differential_transmission.h index 7a198544c..e2c1c24c4 100644 --- a/transmission_interface/include/transmission_interface/differential_transmission.h +++ b/transmission_interface/include/transmission_interface/differential_transmission.h @@ -147,7 +147,7 @@ class DifferentialTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void actuatorToJointEffort(const ActuatorData& act_data, - JointData& jnt_data); + JointData& jnt_data) override; /** * \brief Transform \e velocity variables from actuator to joint space. @@ -157,7 +157,7 @@ class DifferentialTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void actuatorToJointVelocity(const ActuatorData& act_data, - JointData& jnt_data); + JointData& jnt_data) override; /** * \brief Transform \e position variables from actuator to joint space. @@ -167,7 +167,7 @@ class DifferentialTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void actuatorToJointPosition(const ActuatorData& act_data, - JointData& jnt_data); + JointData& jnt_data) override; /** * \brief Transform \e absolute encoder values from actuator to joint space. @@ -177,7 +177,7 @@ class DifferentialTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void actuatorToJointAbsolutePosition(const ActuatorData& act_data, - JointData& jnt_data); + JointData& jnt_data) override; /** * \brief Transform \e torque sensor values from actuator to joint space. @@ -187,7 +187,7 @@ class DifferentialTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void actuatorToJointTorqueSensor(const ActuatorData& act_data, - JointData& jnt_data); + JointData& jnt_data) override; /** * \brief Transform \e effort variables from joint to actuator space. @@ -197,7 +197,7 @@ class DifferentialTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void jointToActuatorEffort(const JointData& jnt_data, - ActuatorData& act_data); + ActuatorData& act_data) override; /** * \brief Transform \e velocity variables from joint to actuator space. @@ -207,7 +207,7 @@ class DifferentialTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void jointToActuatorVelocity(const JointData& jnt_data, - ActuatorData& act_data); + ActuatorData& act_data) override; /** * \brief Transform \e position variables from joint to actuator space. @@ -217,12 +217,12 @@ class DifferentialTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void jointToActuatorPosition(const JointData& jnt_data, - ActuatorData& act_data); + ActuatorData& act_data) override; - std::size_t numActuators() const {return 2;} - std::size_t numJoints() const {return 2;} - bool hasActuatorToJointAbsolutePosition() const {return true;} - bool hasActuatorToJointTorqueSensor() const {return true;} + std::size_t numActuators() const override {return 2;} + std::size_t numJoints() const override {return 2;} + bool hasActuatorToJointAbsolutePosition() const override {return true;} + bool hasActuatorToJointTorqueSensor() const override {return true;} const std::vector& getActuatorReduction() const {return act_reduction_;} const std::vector& getJointReduction() const {return jnt_reduction_;} diff --git a/transmission_interface/include/transmission_interface/differential_transmission_loader.h b/transmission_interface/include/transmission_interface/differential_transmission_loader.h index 37d01cbfb..2cbcb3545 100644 --- a/transmission_interface/include/transmission_interface/differential_transmission_loader.h +++ b/transmission_interface/include/transmission_interface/differential_transmission_loader.h @@ -45,7 +45,7 @@ namespace transmission_interface class DifferentialTransmissionLoader : public TransmissionLoader { public: - TransmissionSharedPtr load(const TransmissionInfo& transmission_info); + TransmissionSharedPtr load(const TransmissionInfo& transmission_info) override; private: static bool getActuatorConfig(const TransmissionInfo& transmission_info, diff --git a/transmission_interface/include/transmission_interface/effort_joint_interface_provider.h b/transmission_interface/include/transmission_interface/effort_joint_interface_provider.h index 0b88add6b..6fedfe872 100644 --- a/transmission_interface/include/transmission_interface/effort_joint_interface_provider.h +++ b/transmission_interface/include/transmission_interface/effort_joint_interface_provider.h @@ -44,20 +44,20 @@ class EffortJointInterfaceProvider : public JointStateInterfaceProvider bool updateJointInterfaces(const TransmissionInfo& transmission_info, hardware_interface::RobotHW* robot_hw, JointInterfaces& joint_interfaces, - RawJointDataMap& raw_joint_data_map); + RawJointDataMap& raw_joint_data_map) override; protected: bool getJointCommandData(const TransmissionInfo& transmission_info, const RawJointDataMap& raw_joint_data_map, - JointData& jnt_cmd_data); + JointData& jnt_cmd_data) override; bool getActuatorCommandData(const TransmissionInfo& transmission_info, hardware_interface::RobotHW* robot_hw, - ActuatorData& act_cmd_data); + ActuatorData& act_cmd_data) override; bool registerTransmission(TransmissionLoaderData& loader_data, - TransmissionHandleData& handle_data); + TransmissionHandleData& handle_data) override; }; } // namespace diff --git a/transmission_interface/include/transmission_interface/four_bar_linkage_transmission.h b/transmission_interface/include/transmission_interface/four_bar_linkage_transmission.h index 95c7d9a03..1cdb6d52a 100644 --- a/transmission_interface/include/transmission_interface/four_bar_linkage_transmission.h +++ b/transmission_interface/include/transmission_interface/four_bar_linkage_transmission.h @@ -135,7 +135,7 @@ class FourBarLinkageTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void actuatorToJointEffort(const ActuatorData& act_data, - JointData& jnt_data); + JointData& jnt_data) override; /** * \brief Transform \e velocity variables from actuator to joint space. @@ -145,7 +145,7 @@ class FourBarLinkageTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void actuatorToJointVelocity(const ActuatorData& act_data, - JointData& jnt_data); + JointData& jnt_data) override; /** * \brief Transform \e position variables from actuator to joint space. @@ -155,7 +155,7 @@ class FourBarLinkageTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void actuatorToJointPosition(const ActuatorData& act_data, - JointData& jnt_data); + JointData& jnt_data) override; /** * \brief Transform \e absolute encoder values from actuator to joint space. @@ -165,7 +165,7 @@ class FourBarLinkageTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void actuatorToJointAbsolutePosition(const ActuatorData& act_data, - JointData& jnt_data); + JointData& jnt_data) override; /** * \brief Transform \e torque sensor values from actuator to joint space. @@ -174,7 +174,7 @@ class FourBarLinkageTransmission : public Transmission * \pre Actuator, joint position and torque sensor vectors must have the same size. */ void actuatorToJointTorqueSensor(const ActuatorData& act_data, - JointData& jnt_data); + JointData& jnt_data) override; /** * \brief Transform \e effort variables from joint to actuator space. @@ -184,7 +184,7 @@ class FourBarLinkageTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void jointToActuatorEffort(const JointData& jnt_data, - ActuatorData& act_data); + ActuatorData& act_data) override; /** * \brief Transform \e velocity variables from joint to actuator space. @@ -194,7 +194,7 @@ class FourBarLinkageTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void jointToActuatorVelocity(const JointData& jnt_data, - ActuatorData& act_data); + ActuatorData& act_data) override; /** * \brief Transform \e position variables from joint to actuator space. @@ -204,12 +204,12 @@ class FourBarLinkageTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void jointToActuatorPosition(const JointData& jnt_data, - ActuatorData& act_data); + ActuatorData& act_data) override; - std::size_t numActuators() const {return 2;} - std::size_t numJoints() const {return 2;} - bool hasActuatorToJointAbsolutePosition() const {return true;} - bool hasActuatorToJointTorqueSensor() const {return true;} + std::size_t numActuators() const override {return 2;} + std::size_t numJoints() const override {return 2;} + bool hasActuatorToJointAbsolutePosition() const override {return true;} + bool hasActuatorToJointTorqueSensor() const override {return true;} const std::vector& getActuatorReduction() const {return act_reduction_;} const std::vector& getJointReduction() const {return jnt_reduction_;} diff --git a/transmission_interface/include/transmission_interface/four_bar_linkage_transmission_loader.h b/transmission_interface/include/transmission_interface/four_bar_linkage_transmission_loader.h index a8c2f4783..c4b66229e 100644 --- a/transmission_interface/include/transmission_interface/four_bar_linkage_transmission_loader.h +++ b/transmission_interface/include/transmission_interface/four_bar_linkage_transmission_loader.h @@ -45,7 +45,7 @@ namespace transmission_interface class FourBarLinkageTransmissionLoader : public TransmissionLoader { public: - TransmissionSharedPtr load(const TransmissionInfo& transmission_info); + TransmissionSharedPtr load(const TransmissionInfo& transmission_info) override; private: static bool getActuatorConfig(const TransmissionInfo& transmission_info, diff --git a/transmission_interface/include/transmission_interface/joint_state_interface_provider.h b/transmission_interface/include/transmission_interface/joint_state_interface_provider.h index 8f28f0a54..ecf0d5139 100644 --- a/transmission_interface/include/transmission_interface/joint_state_interface_provider.h +++ b/transmission_interface/include/transmission_interface/joint_state_interface_provider.h @@ -43,27 +43,27 @@ class JointStateInterfaceProvider : public RequisiteProvider bool updateJointInterfaces(const TransmissionInfo& transmission_info, hardware_interface::RobotHW* robot_hw, JointInterfaces& joint_interfaces, - RawJointDataMap& raw_joint_data_map); + RawJointDataMap& raw_joint_data_map) override; protected: bool getJointStateData(const TransmissionInfo& transmission_info, const RawJointDataMap& raw_joint_data_map, - JointData& jnt_state_data); + JointData& jnt_state_data) override; bool getJointCommandData(const TransmissionInfo& /*transmission_info*/, const RawJointDataMap& /*raw_joint_data_map*/, - JointData& /*jnt_cmd_data*/) {return true;} + JointData& /*jnt_cmd_data*/) override {return true;} bool getActuatorStateData(const TransmissionInfo& transmission_info, hardware_interface::RobotHW* robot_hw, - ActuatorData& act_state_data); + ActuatorData& act_state_data) override; bool getActuatorCommandData(const TransmissionInfo& /*transmission_info*/, hardware_interface::RobotHW* /*robot_hw*/, - ActuatorData& /*act_cmd_data*/) {return true;} + ActuatorData& /*act_cmd_data*/) override {return true;} bool registerTransmission(TransmissionLoaderData& loader_data, - TransmissionHandleData& handle_data); + TransmissionHandleData& handle_data) override; }; } // namespace diff --git a/transmission_interface/include/transmission_interface/position_joint_interface_provider.h b/transmission_interface/include/transmission_interface/position_joint_interface_provider.h index 734843ea3..4db28eb88 100644 --- a/transmission_interface/include/transmission_interface/position_joint_interface_provider.h +++ b/transmission_interface/include/transmission_interface/position_joint_interface_provider.h @@ -44,20 +44,20 @@ class PositionJointInterfaceProvider : public JointStateInterfaceProvider bool updateJointInterfaces(const TransmissionInfo& transmission_info, hardware_interface::RobotHW* robot_hw, JointInterfaces& joint_interfaces, - RawJointDataMap& raw_joint_data_map); + RawJointDataMap& raw_joint_data_map) override; protected: bool getJointCommandData(const TransmissionInfo& transmission_info, const RawJointDataMap& raw_joint_data_map, - JointData& jnt_cmd_data); + JointData& jnt_cmd_data) override; bool getActuatorCommandData(const TransmissionInfo& transmission_info, hardware_interface::RobotHW* robot_hw, - ActuatorData& act_cmd_data); + ActuatorData& act_cmd_data) override; bool registerTransmission(TransmissionLoaderData& loader_data, - TransmissionHandleData& handle_data); + TransmissionHandleData& handle_data) override; }; } // namespace diff --git a/transmission_interface/include/transmission_interface/simple_transmission.h b/transmission_interface/include/transmission_interface/simple_transmission.h index dad72f15a..c47c6a5d9 100644 --- a/transmission_interface/include/transmission_interface/simple_transmission.h +++ b/transmission_interface/include/transmission_interface/simple_transmission.h @@ -111,7 +111,7 @@ class SimpleTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void actuatorToJointEffort(const ActuatorData& act_data, - JointData& jnt_data); + JointData& jnt_data) override; /** * \brief Transform \e velocity variables from actuator to joint space. @@ -121,7 +121,7 @@ class SimpleTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void actuatorToJointVelocity(const ActuatorData& act_data, - JointData& jnt_data); + JointData& jnt_data) override; /** * \brief Transform \e position variables from actuator to joint space. @@ -131,13 +131,13 @@ class SimpleTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void actuatorToJointPosition(const ActuatorData& act_data, - JointData& jnt_data); + JointData& jnt_data) override; void actuatorToJointAbsolutePosition(const ActuatorData& act_data, - JointData& jnt_data); + JointData& jnt_data) override; void actuatorToJointTorqueSensor(const ActuatorData& act_data, - JointData& jnt_data); + JointData& jnt_data) override; /** * \brief Transform \e effort variables from joint to actuator space. @@ -147,7 +147,7 @@ class SimpleTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void jointToActuatorEffort(const JointData& jnt_data, - ActuatorData& act_data); + ActuatorData& act_data) override; /** * \brief Transform \e velocity variables from joint to actuator space. @@ -157,7 +157,7 @@ class SimpleTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void jointToActuatorVelocity(const JointData& jnt_data, - ActuatorData& act_data); + ActuatorData& act_data) override; /** * \brief Transform \e position variables from joint to actuator space. @@ -167,12 +167,12 @@ class SimpleTransmission : public Transmission * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. */ void jointToActuatorPosition(const JointData& jnt_data, - ActuatorData& act_data); + ActuatorData& act_data) override; - std::size_t numActuators() const {return 1;} - std::size_t numJoints() const {return 1;} - bool hasActuatorToJointAbsolutePosition() const {return true;} - bool hasActuatorToJointTorqueSensor() const {return true;} + std::size_t numActuators() const override {return 1;} + std::size_t numJoints() const override {return 1;} + bool hasActuatorToJointAbsolutePosition() const override {return true;} + bool hasActuatorToJointTorqueSensor() const override {return true;} double getActuatorReduction() const {return reduction_;} double getJointOffset() const {return jnt_offset_;} diff --git a/transmission_interface/include/transmission_interface/simple_transmission_loader.h b/transmission_interface/include/transmission_interface/simple_transmission_loader.h index b17ee34c9..12d49687a 100644 --- a/transmission_interface/include/transmission_interface/simple_transmission_loader.h +++ b/transmission_interface/include/transmission_interface/simple_transmission_loader.h @@ -43,7 +43,7 @@ class SimpleTransmissionLoader : public TransmissionLoader { public: - TransmissionSharedPtr load(const TransmissionInfo& transmission_info); + TransmissionSharedPtr load(const TransmissionInfo& transmission_info) override; }; } // namespace diff --git a/transmission_interface/include/transmission_interface/transmission.h b/transmission_interface/include/transmission_interface/transmission.h index 572ec0eab..9702f9b0e 100644 --- a/transmission_interface/include/transmission_interface/transmission.h +++ b/transmission_interface/include/transmission_interface/transmission.h @@ -91,7 +91,7 @@ struct JointData class Transmission { public: - virtual ~Transmission() {} + virtual ~Transmission() = default; /** * \brief Transform \e effort variables from actuator to joint space. diff --git a/transmission_interface/include/transmission_interface/transmission_interface_exception.h b/transmission_interface/include/transmission_interface/transmission_interface_exception.h index 9fa0e8868..36bad326e 100644 --- a/transmission_interface/include/transmission_interface/transmission_interface_exception.h +++ b/transmission_interface/include/transmission_interface/transmission_interface_exception.h @@ -29,6 +29,7 @@ #include +#include namespace transmission_interface { @@ -37,8 +38,7 @@ class TransmissionInterfaceException: public std::exception { public: TransmissionInterfaceException(const std::string& message) : msg(message) {} - virtual ~TransmissionInterfaceException() throw() {} - virtual const char* what() const throw() {return msg.c_str();} + const char* what() const noexcept override {return msg.c_str();} private: std::string msg; }; diff --git a/transmission_interface/include/transmission_interface/transmission_interface_loader.h b/transmission_interface/include/transmission_interface/transmission_interface_loader.h index 21f379dfb..2e912f965 100644 --- a/transmission_interface/include/transmission_interface/transmission_interface_loader.h +++ b/transmission_interface/include/transmission_interface/transmission_interface_loader.h @@ -128,8 +128,7 @@ struct TransmissionLoaderData class RequisiteProvider // TODO: There must be a more descriptive name for this class! { public: - - virtual ~RequisiteProvider() {} + virtual ~RequisiteProvider() = default; /** * \brief Update a robot's joint interfaces with joint information contained in a transmission. diff --git a/transmission_interface/include/transmission_interface/transmission_loader.h b/transmission_interface/include/transmission_interface/transmission_loader.h index 8f007dd28..7edb63277 100644 --- a/transmission_interface/include/transmission_interface/transmission_loader.h +++ b/transmission_interface/include/transmission_interface/transmission_loader.h @@ -61,8 +61,7 @@ namespace transmission_interface class TransmissionLoader { public: - - virtual ~TransmissionLoader() {} + virtual ~TransmissionLoader() = default; virtual TransmissionSharedPtr load(const TransmissionInfo& transmission_info) = 0; diff --git a/transmission_interface/include/transmission_interface/velocity_joint_interface_provider.h b/transmission_interface/include/transmission_interface/velocity_joint_interface_provider.h index 2712edcee..af0b16219 100644 --- a/transmission_interface/include/transmission_interface/velocity_joint_interface_provider.h +++ b/transmission_interface/include/transmission_interface/velocity_joint_interface_provider.h @@ -44,20 +44,20 @@ class VelocityJointInterfaceProvider : public JointStateInterfaceProvider bool updateJointInterfaces(const TransmissionInfo& transmission_info, hardware_interface::RobotHW* robot_hw, JointInterfaces& joint_interfaces, - RawJointDataMap& raw_joint_data_map); + RawJointDataMap& raw_joint_data_map) override; protected: bool getJointCommandData(const TransmissionInfo& transmission_info, const RawJointDataMap& raw_joint_data_map, - JointData& jnt_cmd_data); + JointData& jnt_cmd_data) override; bool getActuatorCommandData(const TransmissionInfo& transmission_info, hardware_interface::RobotHW* robot_hw, - ActuatorData& act_cmd_data); + ActuatorData& act_cmd_data) override; bool registerTransmission(TransmissionLoaderData& loader_data, - TransmissionHandleData& handle_data); + TransmissionHandleData& handle_data) override; }; } // namespace