Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add function specifiers and modernize constructors #430

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 7 additions & 8 deletions combined_robot_hw/include/combined_robot_hw/combined_robot_hw.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,6 @@ namespace combined_robot_hw
class CombinedRobotHW : public hardware_interface::RobotHW
{
public:
virtual ~CombinedRobotHW(){}
bmagyar marked this conversation as resolved.
Show resolved Hide resolved

/** \brief The init function is called to initialize the RobotHW from a
* non-realtime thread.
Expand All @@ -64,39 +63,39 @@ 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;


/**
* Check (in non-realtime) if given controllers could be started and stopped from the current state of the 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<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list);
bool prepareSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& 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<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list);
void doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list) override;

/**
* Reads data from the robot HW
*
* \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
*
* \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_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list);
virtual void doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& 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<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list) override;
void doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list) override;

protected:

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list);
virtual void doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& 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<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list) override;
void doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list) override;

protected:

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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:

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list);
virtual void doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& 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<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list) override;
void doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list) override;

protected:

Expand Down
4 changes: 0 additions & 4 deletions combined_robot_hw_tests/src/my_robot_hw_1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
4 changes: 0 additions & 4 deletions combined_robot_hw_tests/src/my_robot_hw_2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
5 changes: 0 additions & 5 deletions combined_robot_hw_tests/src/my_robot_hw_3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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)

4 changes: 0 additions & 4 deletions combined_robot_hw_tests/src/my_robot_hw_4.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
15 changes: 4 additions & 11 deletions controller_interface/include/controller_interface/controller.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,6 @@ template <class T>
class Controller: public virtual ControllerBase
{
public:
Controller() {}
virtual ~Controller<T>(){}

/** \brief The init function is called to initialize the controller from a
* non-realtime thread with a pointer to the hardware interface, itself,
Expand Down Expand Up @@ -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){
Expand Down Expand Up @@ -137,11 +135,6 @@ class Controller: public virtual ControllerBase
{
return hardware_interface::internal::demangledTypeName<T>();
}

private:
Controller<T>(const Controller<T> &c);
Controller<T>& operator =(const Controller<T> &c);

};

}
Original file line number Diff line number Diff line change
Expand Up @@ -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
*\{*/
Expand Down Expand Up @@ -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<ControllerBase> ControllerBaseSharedPtr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
*\{*/
Expand Down Expand Up @@ -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){
Expand Down Expand Up @@ -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
7 changes: 0 additions & 7 deletions controller_interface/test/controller_base_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,13 +43,6 @@ using ::testing::Return;
class ControllerMock : public controller_interface::ControllerBase
{
public:
ControllerMock() : controller_interface::ControllerBase()
{
}

~ControllerMock()
{
}

void initializeState()
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string> getDeclaredClasses()
std::vector<std::string> getDeclaredClasses() override
{
return controller_loader_->getDeclaredClasses();
}

void reload()
void reload() override
{
controller_loader_.reset(new pluginlib::ClassLoader<T>(package_, base_class_) );
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string> getDeclaredClasses() = 0;
virtual void reload() = 0;
const std::string& getName() { return name_; }
virtual ~ControllerLoaderInterface() { }

private:
const std::string name_;

};

typedef std::shared_ptr<ControllerLoaderInterface> ControllerLoaderInterfaceSharedPtr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
*\{*/
Expand Down
4 changes: 0 additions & 4 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand Down
Loading