34     robot_hw_loader_(
"hardware_interface", 
"hardware_interface::RobotHW")
    42     std::vector<std::string> robots;
    43     std::string param_name = 
"robot_hardware";
    44     if (!robot_hw_nh.
getParam(param_name, robots))
    50     std::vector<std::string>::iterator it;
    51     for (it = robots.begin(); it != robots.end(); it++)
    62                              const std::list<hardware_interface::ControllerInfo>& stop_list)
    65     std::vector<hardware_interface::RobotHWSharedPtr>::iterator robot_hw;
    68       std::list<hardware_interface::ControllerInfo> filtered_start_list;
    69       std::list<hardware_interface::ControllerInfo> filtered_stop_list;
    75       if (!(*robot_hw)->prepareSwitch(filtered_start_list, filtered_stop_list))
    82                         const std::list<hardware_interface::ControllerInfo>& stop_list)
    85     std::vector<hardware_interface::RobotHWSharedPtr>::iterator robot_hw;
    88       std::list<hardware_interface::ControllerInfo> filtered_start_list;
    89       std::list<hardware_interface::ControllerInfo> filtered_stop_list;
    95       (*robot_hw)->doSwitch(filtered_start_list, filtered_stop_list);
   101     ROS_DEBUG(
"Will load robot HW '%s'", name.c_str());
   109     catch(std::exception &e)
   111       ROS_ERROR(
"Exception thrown while constructing nodehandle for robot HW with name '%s':\n%s", name.c_str(), e.what());
   116       ROS_ERROR(
"Exception thrown while constructing nodehandle for robot HW with name '%s'", name.c_str());
   122     if (c_nh.getParam(
"type", type))
   124       ROS_DEBUG(
"Constructing robot HW '%s' of type '%s'", name.c_str(), type.c_str());
   128         for(
size_t i=0; i < cur_types.size(); i++)
   130           if (type == cur_types[i])
   136       catch (
const std::runtime_error &ex)
   138         ROS_ERROR(
"Could not load class %s: %s", type.c_str(), ex.what());
   143       ROS_ERROR(
"Could not load robot HW '%s' because the type was not specified. Did you load the robot HW configuration on the parameter server (namespace: '%s')?", name.c_str(), c_nh.getNamespace().c_str());
   150       ROS_ERROR(
"Could not load robot HW '%s' because robot HW type '%s' does not exist.",  name.c_str(), type.c_str());
   155     ROS_DEBUG(
"Initializing robot HW '%s'", name.c_str());
   159       initialized = robot_hw->init(
root_nh_, c_nh);
   161     catch(std::exception &e)
   163       ROS_ERROR(
"Exception thrown while initializing robot HW %s.\n%s", name.c_str(), e.what());
   168       ROS_ERROR(
"Exception thrown while initializing robot HW %s", name.c_str());
   174       ROS_ERROR(
"Initializing robot HW '%s' failed", name.c_str());
   177     ROS_DEBUG(
"Initialized robot HW '%s' successful", name.c_str());
   183     ROS_DEBUG(
"Successfully load robot HW '%s'", name.c_str());
   190     std::vector<hardware_interface::RobotHWSharedPtr>::iterator robot_hw;
   193       (*robot_hw)->read(time, period);
   201     std::vector<hardware_interface::RobotHWSharedPtr>::iterator robot_hw;
   204       (*robot_hw)->write(time, period);
   209                                              std::list<hardware_interface::ControllerInfo>& filtered_list,
   212     filtered_list.clear();
   213     for (std::list<hardware_interface::ControllerInfo>::const_iterator it = list.begin(); it != list.end(); ++it)
   216       filtered_controller.
name = it->name;
   217       filtered_controller.
type = it->type;
   219       if (it->claimed_resources.empty())
   221         filtered_list.push_back(filtered_controller);
   224       for (std::vector<hardware_interface::InterfaceResources>::const_iterator res_it = it->claimed_resources.begin(); res_it != it->claimed_resources.end(); ++res_it)
   228         std::vector<std::string> r_hw_ifaces = robot_hw->getNames();
   230         std::vector<std::string>::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), filtered_iface_resources.
hardware_interface);
   231         if (if_name == r_hw_ifaces.end()) 
   236         std::vector<std::string> r_hw_iface_resources = robot_hw->getInterfaceResources(filtered_iface_resources.
hardware_interface);
   237         std::set<std::string> filtered_resources;
   238         for (std::set<std::string>::const_iterator ctrl_res = res_it->resources.begin(); ctrl_res != res_it->resources.end(); ++ctrl_res)
   240           std::vector<std::string>::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), *ctrl_res);
   241           if (res_name != r_hw_iface_resources.end())
   243             filtered_resources.insert(*ctrl_res);
   246         filtered_iface_resources.
resources = filtered_resources;
   249       filtered_list.push_back(filtered_controller);
 
std::vector< hardware_interface::RobotHWSharedPtr > robot_hw_list_
pluginlib::ClassLoader< hardware_interface::RobotHW > robot_hw_loader_
void registerInterfaceManager(InterfaceManager *iface_man)
virtual bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
std::set< std::string > resources
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
The init function is called to initialize the RobotHW from a non-realtime thread. ...
virtual bool loadRobotHW(const std::string &name)
std::vector< InterfaceResources > claimed_resources
std::vector< std::string > getDeclaredClasses()
virtual void read(const ros::Time &time, const ros::Duration &period)
const std::string & getNamespace() const 
virtual void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
ros::NodeHandle robot_hw_nh_
bool getParam(const std::string &key, std::string &s) const 
virtual void write(const ros::Time &time, const ros::Duration &period)
#define ROS_ERROR_STREAM(args)
std::string hardware_interface
void filterControllerList(const std::list< hardware_interface::ControllerInfo > &list, std::list< hardware_interface::ControllerInfo > &filtered_list, hardware_interface::RobotHWSharedPtr robot_hw)
Filters the start and stop lists so that they only contain the controllers and resources that corresp...