Skip to content
Closed
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
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,12 @@ class CombinedRobotHW : public hardware_interface::RobotHW
*/
virtual void write(const ros::Time& time, const ros::Duration& period);

/**
* Checks whether the robot HW requires to reset controllers
*
*/
virtual bool isResetRequired();

protected:
ros::NodeHandle root_nh_;
ros::NodeHandle robot_hw_nh_;
Expand Down
12 changes: 12 additions & 0 deletions combined_robot_hw/src/combined_robot_hw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,6 +195,18 @@ namespace combined_robot_hw
}
}

bool CombinedRobotHW::isResetRequired()
{
// Call the isResetRequired method of the single RobotHW objects.
std::vector<hardware_interface::RobotHWSharedPtr>::iterator robot_hw;
for (robot_hw = robot_hw_list_.begin(); robot_hw != robot_hw_list_.end(); ++robot_hw)
{
if((*robot_hw)->isResetRequired())
return true;
}
return false;
}

void CombinedRobotHW::filterControllerList(const std::list<hardware_interface::ControllerInfo>& list,
std::list<hardware_interface::ControllerInfo>& filtered_list,
hardware_interface::RobotHWSharedPtr robot_hw)
Expand Down
20 changes: 20 additions & 0 deletions hardware_interface/include/hardware_interface/robot_hw.h
Original file line number Diff line number Diff line change
Expand Up @@ -175,6 +175,26 @@ class RobotHW : public InterfaceManager
* \param period The time passed since the last call to \ref write
*/
virtual void write(const ros::Time& /*time*/, const ros::Duration& /*period*/) {}

/**
* Each robot HW might require to reset controllers, rising reset_ to true, this
* method returns true if that is the case
*/
virtual bool isResetRequired()
{
if(reset_once_)
{
reset_once_ = false;
return true;
}
else
{
return false;
}
}

protected:
bool reset_once_;
};

typedef std::shared_ptr<RobotHW> RobotHWSharedPtr;
Expand Down