101 const std::list<hardware_interface::ControllerInfo>& )
103 for (
const auto& controller : start_list)
105 if (controller.claimed_resources.empty())
109 for (
const auto& res_it : controller.claimed_resources)
111 std::vector<std::string> r_hw_ifaces = this->
getNames();
113 std::vector<std::string>::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), res_it.hardware_interface);
114 if (if_name == r_hw_ifaces.end())
117 std::cout << res_it.hardware_interface;
121 std::vector<std::string> r_hw_iface_resources = this->
getInterfaceResources(res_it.hardware_interface);
122 for (
const auto& resource : res_it.resources)
124 std::vector<std::string>::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), resource);
125 if (res_name == r_hw_iface_resources.end())
128 std::cout << resource;
138 const std::list<hardware_interface::ControllerInfo>& )
140 for (
const auto& controller : start_list)
142 if (controller.claimed_resources.empty())
146 for (
const auto& claimed_resource : controller.claimed_resources)
148 std::vector<std::string> r_hw_ifaces = this->
getNames();
150 std::vector<std::string>::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), claimed_resource.hardware_interface);
151 if (if_name == r_hw_ifaces.end())
156 std::vector<std::string> r_hw_iface_resources = this->
getInterfaceResources(claimed_resource.hardware_interface);
157 for (
const auto& resource : claimed_resource.resources)
159 std::vector<std::string>::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), resource);
160 if (res_name == r_hw_iface_resources.end())
void registerInterface(T *iface)
hardware_interface::VelocityJointInterface vj_interface_
hardware_interface::JointStateInterface js_interface_
bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
std::vector< double > joint_velocity_
std::vector< double > joint_velocity_command_
std::vector< std::string > getInterfaceResources(std::string iface_type) const
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
void write(const ros::Time &time, const ros::Duration &period) override
std::vector< std::string > joint_name_
std::vector< double > joint_effort_command_
void read(const ros::Time &time, const ros::Duration &period) override
std::vector< std::string > getNames() const
void registerHandle(const JointStateHandle &handle)
JointStateHandle getHandle(const std::string &name)
std::vector< double > joint_effort_
void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
std::vector< double > joint_position_
#define ROS_ERROR_STREAM(args)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
hardware_interface::EffortJointInterface ej_interface_