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

Prepare switch jade #218

Merged
merged 3 commits into from
Nov 19, 2015
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
2 changes: 1 addition & 1 deletion controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -471,7 +471,7 @@ bool ControllerManager::switchController(const std::vector<std::string>& start_c
return false;
}

if (!robot_hw_->canSwitch(start_list, stop_list))
if (!robot_hw_->prepareSwitch(start_list, stop_list))
{
ROS_ERROR("Could not switch controllers. The hardware interface combination for the requested controllers is unfeasible.");
stop_request_.clear();
Expand Down
10 changes: 5 additions & 5 deletions controller_manager/test/hwi_switch_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ class SwitchBot : public hardware_interface::RobotHW
if(can_switch) interfaces_.insert(hardware_interface::internal::demangledTypeName<Interface>() );
iface.registerHandle(typename Interface::ResourceHandleType(jsh_, &dummy_));
}
bool canSwitch(const std::string &n) const
bool prepareSwitch(const std::string &n)
{
if(interfaces_.find(n) == interfaces_.end()) return false;
return n >= current_;
Expand Down Expand Up @@ -135,11 +135,11 @@ class SwitchBot : public hardware_interface::RobotHW

}

virtual bool canSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list) const
virtual bool prepareSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list)
{

if(!RobotHW::canSwitch(start_list, stop_list))
if(!RobotHW::prepareSwitch(start_list, stop_list))
{
ROS_ERROR("Something is wrong with RobotHW");
return false;
Expand Down Expand Up @@ -171,7 +171,7 @@ class SwitchBot : public hardware_interface::RobotHW
// per joint check
try
{
if(!joints_.at(*res_it)->canSwitch(iface_res.hardware_interface))
if(!joints_.at(*res_it)->prepareSwitch(iface_res.hardware_interface))
{
ROS_ERROR_STREAM("Cannot switch " << *res_it << " to " << iface_res.hardware_interface);
return false;
Expand Down
12 changes: 7 additions & 5 deletions hardware_interface/include/hardware_interface/robot_hw.h
Original file line number Diff line number Diff line change
Expand Up @@ -116,16 +116,18 @@ class RobotHW : public InterfaceManager

/**
* 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. Start and stop list are disjoint.
* This is just a check, the actual switch is done in doSwitch()
* 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 canSwitch(const std::list<ControllerInfo>& /*start_list*/, const std::list<ControllerInfo>& /*stop_list*/) const { return true; }
virtual bool prepareSwitch(const std::list<ControllerInfo>& start_list,
const std::list<ControllerInfo>& stop_list) { return true; }

/**
* Perform (in non-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 canSwitch() beforehand.
* Start and stop list are disjoint. The feasability was checked in prepareSwitch() beforehand.
*/
virtual void doSwitch(const std::list<ControllerInfo>& /*start_list*/, const std::list<ControllerInfo>& /*stop_list*/) {}
virtual void doSwitch(const std::list<ControllerInfo>& /*start_list*/,
const std::list<ControllerInfo>& /*stop_list*/) {}
};

}
Expand Down