43   std::vector<std::string> joints;
    44   if (!robot_hw_nh.
getParam(
"joints", joints)) {
return false;}
    47   size_t nb_joints = joints.size();
    55   for (
size_t i = 0; i < nb_joints; i++)
    87                                const std::list<hardware_interface::ControllerInfo>& stop_list)
    89   for (std::list<hardware_interface::ControllerInfo>::const_iterator it = start_list.begin(); it != start_list.end(); ++it)
    91     if (it->claimed_resources.empty())
    95     for (std::vector<hardware_interface::InterfaceResources>::const_iterator res_it = it->claimed_resources.begin(); res_it != it->claimed_resources.end(); ++res_it)
    97       std::vector<std::string> r_hw_ifaces = this->
getNames();
    99       std::vector<std::string>::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), res_it->hardware_interface);
   100       if (if_name == r_hw_ifaces.end()) 
   106       std::vector<std::string> r_hw_iface_resources = this->
getInterfaceResources(res_it->hardware_interface);
   107       for (std::set<std::string>::const_iterator ctrl_res = res_it->resources.begin(); ctrl_res != res_it->resources.end(); ++ctrl_res)
   109         std::vector<std::string>::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), *ctrl_res);
   110         if (res_name == r_hw_iface_resources.end()) 
   122                           const std::list<hardware_interface::ControllerInfo>& stop_list)
   124   for (std::list<hardware_interface::ControllerInfo>::const_iterator it = start_list.begin(); it != start_list.end(); ++it)
   126     if (it->claimed_resources.empty())
   130     for (std::vector<hardware_interface::InterfaceResources>::const_iterator res_it = it->claimed_resources.begin(); res_it != it->claimed_resources.end(); ++res_it)
   132       std::vector<std::string> r_hw_ifaces = this->
getNames();
   134       std::vector<std::string>::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), res_it->hardware_interface);
   135       if (if_name == r_hw_ifaces.end()) 
   140       std::vector<std::string> r_hw_iface_resources = this->
getInterfaceResources(res_it->hardware_interface);
   141       for (std::set<std::string>::const_iterator ctrl_res = res_it->resources.begin(); ctrl_res != res_it->resources.end(); ++ctrl_res)
   143         std::vector<std::string>::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), *ctrl_res);
   144         if (res_name == r_hw_iface_resources.end()) 
 void registerInterface(T *iface)
hardware_interface::VelocityJointInterface vj_interface_
virtual bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
std::vector< double > joint_position_
std::vector< std::string > getNames() const 
std::vector< std::string > joint_name_
hardware_interface::EffortJointInterface ej_interface_
std::vector< double > joint_velocity_
std::vector< double > joint_velocity_command_
hardware_interface::JointStateInterface js_interface_
void registerHandle(const JointStateHandle &handle)
void read(const ros::Time &time, const ros::Duration &period)
JointStateHandle getHandle(const std::string &name)
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
std::vector< double > joint_effort_command_
bool getParam(const std::string &key, std::string &s) const 
std::vector< std::string > getInterfaceResources(std::string iface_type) const 
void write(const ros::Time &time, const ros::Duration &period)
#define ROS_ERROR_STREAM(args)
virtual void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
std::vector< double > joint_effort_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)