Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00027
00028 #ifndef HARDWARE_INTERFACE_ROBOT_HW_H
00029 #define HARDWARE_INTERFACE_ROBOT_HW_H
00030
00031 #include <list>
00032 #include <map>
00033 #include <typeinfo>
00034 #include <hardware_interface/internal/demangle_symbol.h>
00035 #include <hardware_interface/internal/interface_manager.h>
00036 #include <hardware_interface/hardware_interface.h>
00037 #include <hardware_interface/controller_info.h>
00038 #include <ros/console.h>
00039
00040 namespace hardware_interface
00041 {
00042
00056 class RobotHW : public InterfaceManager
00057 {
00058 public:
00059 RobotHW()
00060 {
00061
00062 }
00063
00073 virtual bool checkForConflict(const std::list<ControllerInfo>& info) const
00074 {
00075
00076 typedef std::map<std::string, std::list<ControllerInfo> > ResourceMap;
00077 ResourceMap resource_map;
00078 for (std::list<ControllerInfo>::const_iterator info_it = info.begin(); info_it != info.end(); ++info_it)
00079 for (std::set<std::string>::const_iterator resource_it = info_it->resources.begin(); resource_it != info_it->resources.end(); ++resource_it)
00080 resource_map[*resource_it].push_back(*info_it);
00081
00082 bool in_conflict = false;
00083 for (ResourceMap::iterator it = resource_map.begin(); it != resource_map.end(); ++it)
00084 {
00085 if (it->second.size() > 1)
00086 {
00087 std::string controller_list;
00088 for (std::list<ControllerInfo>::const_iterator controller_it = it->second.begin(); controller_it != it->second.end(); ++controller_it)
00089 controller_list += controller_it->name + ", ";
00090 ROS_WARN("Resource conflict on [%s]. Controllers = [%s]", it->first.c_str(), controller_list.c_str());
00091 in_conflict = true;
00092 }
00093 }
00094
00095 return in_conflict;
00096 }
00106 virtual bool canSwitch(const std::list<ControllerInfo>& ,
00107 const std::list<ControllerInfo>& ) const { return true; }
00108
00114 virtual bool prepareSwitch(const std::list<ControllerInfo>& start_list,
00115 const std::list<ControllerInfo>& stop_list) { return canSwitch(start_list, stop_list); }
00116
00121 virtual void doSwitch(const std::list<ControllerInfo>& ,
00122 const std::list<ControllerInfo>& ) {}
00123 };
00124
00125 typedef boost::shared_ptr<RobotHW> RobotHWSharedPtr;
00126
00127 }
00128
00129 #endif
00130