39 std::vector<std::string> joints;
40 if (!robot_hw_nh.
getParam(
"joints", joints)) {
return false;}
43 size_t nb_joints = joints.size();
51 for (
size_t i = 0; i < nb_joints; i++)
83 const std::list<hardware_interface::ControllerInfo>& )
85 for (
const auto& controller : start_list)
87 if (controller.name ==
"ctrl_without_my_robot_hw_2_resources")
89 ROS_ERROR_STREAM(
"Controller should have been filtered out: " << controller.name);
93 if (controller.name ==
"ctrl_without_my_robot_hw_2_resources_in_one_of_two_ifaces")
95 if (controller.claimed_resources.size() > 1)
102 if (controller.claimed_resources.empty())
106 for (
const auto& res_it : controller.claimed_resources)
108 std::vector<std::string> r_hw_ifaces = this->
getNames();
110 std::vector<std::string>::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), res_it.hardware_interface);
111 if (if_name == r_hw_ifaces.end())
117 std::vector<std::string> r_hw_iface_resources = this->
getInterfaceResources(res_it.hardware_interface);
118 for (
const auto& resource : res_it.resources)
120 std::vector<std::string>::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), resource);
121 if (res_name == r_hw_iface_resources.end())
133 const std::list<hardware_interface::ControllerInfo>& )
135 for (
const auto& controller : start_list)
137 if (controller.name ==
"ctrl_without_my_robot_hw_2_resources")
142 if (controller.name ==
"ctrl_without_my_robot_hw_2_resources_in_one_of_two_ifaces")
144 if (controller.claimed_resources.size() > 1)
150 if (controller.claimed_resources.empty())
154 for (
const auto& claimed_resource : controller.claimed_resources)
156 std::vector<std::string> r_hw_ifaces = this->
getNames();
158 std::vector<std::string>::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), claimed_resource.hardware_interface);
159 if (if_name == r_hw_ifaces.end())
164 std::vector<std::string> r_hw_iface_resources = this->
getInterfaceResources(claimed_resource.hardware_interface);
165 for (
const auto& resource : claimed_resource.resources)
167 std::vector<std::string>::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), resource);
168 if (res_name == r_hw_iface_resources.end())
void registerInterface(T *iface)
void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
hardware_interface::VelocityJointInterface vj_interface_
std::vector< double > joint_position_
std::vector< std::string > joint_name_
hardware_interface::EffortJointInterface ej_interface_
void read(const ros::Time &time, const ros::Duration &period) override
std::vector< double > joint_velocity_
std::vector< std::string > getInterfaceResources(std::string iface_type) const
std::vector< double > joint_velocity_command_
bool getParam(const std::string &key, std::string &s) const
hardware_interface::JointStateInterface js_interface_
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
std::vector< std::string > getNames() const
void registerHandle(const JointStateHandle &handle)
JointStateHandle getHandle(const std::string &name)
std::vector< double > joint_effort_command_
void write(const ros::Time &time, const ros::Duration &period) override
#define ROS_ERROR_STREAM(args)
bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
std::vector< double > joint_effort_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)