105 const std::list<hardware_interface::ControllerInfo>& stop_list)
107 for (std::list<hardware_interface::ControllerInfo>::const_iterator it = start_list.begin(); it != start_list.end(); ++it)
109 if (it->claimed_resources.empty())
113 for (std::vector<hardware_interface::InterfaceResources>::const_iterator res_it = it->claimed_resources.begin(); res_it != it->claimed_resources.end(); ++res_it)
115 std::vector<std::string> r_hw_ifaces = this->
getNames();
117 std::vector<std::string>::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), res_it->hardware_interface);
118 if (if_name == r_hw_ifaces.end())
121 std::cout << res_it->hardware_interface;
125 std::vector<std::string> r_hw_iface_resources = this->
getInterfaceResources(res_it->hardware_interface);
126 for (std::set<std::string>::const_iterator ctrl_res = res_it->resources.begin(); ctrl_res != res_it->resources.end(); ++ctrl_res)
128 std::vector<std::string>::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), *ctrl_res);
129 if (res_name == r_hw_iface_resources.end())
132 std::cout << (*ctrl_res);
142 const std::list<hardware_interface::ControllerInfo>& stop_list)
144 for (std::list<hardware_interface::ControllerInfo>::const_iterator it = start_list.begin(); it != start_list.end(); ++it)
146 if (it->claimed_resources.empty())
150 for (std::vector<hardware_interface::InterfaceResources>::const_iterator res_it = it->claimed_resources.begin(); res_it != it->claimed_resources.end(); ++res_it)
152 std::vector<std::string> r_hw_ifaces = this->
getNames();
154 std::vector<std::string>::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), res_it->hardware_interface);
155 if (if_name == r_hw_ifaces.end())
160 std::vector<std::string> r_hw_iface_resources = this->
getInterfaceResources(res_it->hardware_interface);
161 for (std::set<std::string>::const_iterator ctrl_res = res_it->resources.begin(); ctrl_res != res_it->resources.end(); ++ctrl_res)
163 std::vector<std::string>::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), *ctrl_res);
164 if (res_name == r_hw_iface_resources.end())
void registerInterface(T *iface)
hardware_interface::VelocityJointInterface vj_interface_
virtual void write(const ros::Time &time, const ros::Duration &period)
hardware_interface::JointStateInterface js_interface_
std::vector< double > joint_velocity_
virtual bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
std::vector< std::string > getNames() const
std::vector< double > joint_velocity_command_
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
std::vector< std::string > joint_name_
std::vector< double > joint_effort_command_
void registerHandle(const JointStateHandle &handle)
virtual void read(const ros::Time &time, const ros::Duration &period)
JointStateHandle getHandle(const std::string &name)
std::vector< double > joint_effort_
std::vector< double > joint_position_
std::vector< std::string > getInterfaceResources(std::string iface_type) const
virtual void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
#define ROS_ERROR_STREAM(args)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
hardware_interface::EffortJointInterface ej_interface_