File tree Expand file tree Collapse file tree 3 files changed +25
-0
lines changed
include/combined_robot_hw
hardware_interface/include/hardware_interface Expand file tree Collapse file tree 3 files changed +25
-0
lines changed Original file line number Diff line number Diff 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+
103108protected:
104109 ros::NodeHandle root_nh_;
105110 ros::NodeHandle robot_hw_nh_;
Original file line number Diff line number Diff 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)
Original file line number Diff line number Diff 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
168174typedef std::shared_ptr<RobotHW> RobotHWSharedPtr;
You can’t perform that action at this time.
0 commit comments