Skip to content

Commit

Permalink
Merge pull request #217 from ros-controls/prepare-switch
Browse files Browse the repository at this point in the history
Prepare switch
  • Loading branch information
adolfo-rt committed Nov 13, 2015
2 parents b1a758c + d19eeac commit a5067ae
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 3 deletions.
2 changes: 1 addition & 1 deletion controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -472,7 +472,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
15 changes: 13 additions & 2 deletions hardware_interface/include/hardware_interface/robot_hw.h
Original file line number Diff line number Diff line change
Expand Up @@ -101,14 +101,25 @@ 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()
* @deprecated: Implement prepareSwitch() instead
*/
virtual bool canSwitch(const std::list<ControllerInfo>& /*start_list*/, const std::list<ControllerInfo>& /*stop_list*/) const { return true; }
virtual bool canSwitch(const std::list<ControllerInfo>& /*start_list*/,
const std::list<ControllerInfo>& /*stop_list*/) const { return true; }

/**
* 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<ControllerInfo>& start_list,
const std::list<ControllerInfo>& stop_list) { return canSwitch(start_list, stop_list); }

/**
* 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.
*/
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

0 comments on commit a5067ae

Please sign in to comment.