6 const std::map<std::string, std::shared_ptr<franka_gazebo::Joint>>& joints,
7 const std::string& arm_id)
9 for (
const auto& joint : joints) {
21 [](
const auto& resource) {
22 return ControllerVerifier::determineControlMethod(resource.hardware_interface);
39 if (not
areFingerJoints(claimed_resource.resources) or claimed_resource.resources.size() != 2) {
44 if (not control_method) {
47 if (control_method.value() ==
EFFORT) {
62 return std::all_of(resources.begin(), resources.end(), [
this](
const std::string& joint_name) {
63 return std::find_if(joint_names_.begin(), joint_names_.end(),
64 [&joint_name, this](const std::string& joint) {
66 if (joint.find(arm_id_ +
"_finger_joint") != std::string::npos) {
69 return joint == joint_name;
74 bool ControllerVerifier::areFingerJoints(
const std::set<std::string>& resources)
const {
75 return std::all_of(resources.begin(), resources.end(), [
this](
const std::string& joint_name) {
76 return joint_name.find(arm_id_ +
"_finger_joint") != std::string::npos;
80 boost::optional<ControlMethod> ControllerVerifier::determineControlMethod(
82 if (
hardware_interface.find(
"hardware_interface::PositionJointInterface") != std::string::npos) {
85 if (
hardware_interface.find(
"hardware_interface::VelocityJointInterface") != std::string::npos) {
88 if (
hardware_interface.find(
"hardware_interface::EffortJointInterface") != std::string::npos) {