Skip to content

Commit 73b4483

Browse files
committed
Add method to check for error in robotHW component
1 parent 7202777 commit 73b4483

File tree

3 files changed

+25
-0
lines changed

3 files changed

+25
-0
lines changed

combined_robot_hw/include/combined_robot_hw/combined_robot_hw.h

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -100,6 +100,11 @@ class CombinedRobotHW : public hardware_interface::RobotHW
100100
*/
101101
virtual void write(const ros::Time& time, const ros::Duration& period);
102102

103+
/**
104+
* Checks whether the robot HW components have errors
105+
*/
106+
virtual bool hasError();
107+
103108
protected:
104109
ros::NodeHandle root_nh_;
105110
ros::NodeHandle robot_hw_nh_;

combined_robot_hw/src/combined_robot_hw.cpp

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -205,6 +205,20 @@ namespace combined_robot_hw
205205
}
206206
}
207207

208+
bool CombinedRobotHW::hasError()
209+
{
210+
// Call the hasError method of the single RobotHW objects.
211+
std::vector<hardware_interface::RobotHWSharedPtr>::iterator robot_hw;
212+
for (robot_hw = robot_hw_list_.begin(); robot_hw != robot_hw_list_.end(); ++robot_hw)
213+
{
214+
if ((*robot_hw)->hasError())
215+
{
216+
return true;
217+
}
218+
}
219+
return false;
220+
}
221+
208222
void CombinedRobotHW::filterControllerList(const std::list<hardware_interface::ControllerInfo>& list,
209223
std::list<hardware_interface::ControllerInfo>& filtered_list,
210224
hardware_interface::RobotHWSharedPtr robot_hw)

hardware_interface/include/hardware_interface/robot_hw.h

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -163,6 +163,12 @@ class RobotHW : public InterfaceManager
163163
* \param period The time passed since the last call to \ref write
164164
*/
165165
virtual void write(const ros::Time& time, const ros::Duration& period) {}
166+
167+
/**
168+
* Check whether the robot HW has encountered an error
169+
*/
170+
virtual bool hasError() { return false; };
171+
166172
};
167173

168174
typedef std::shared_ptr<RobotHW> RobotHWSharedPtr;

0 commit comments

Comments
 (0)