resource_helpers.cpp
Go to the documentation of this file.
1 // Copyright (c) 2017 Franka Emika GmbH
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
4 
5 #include <ros/console.h>
6 
7 namespace franka_hw {
8 
9 bool findArmIdInResourceId(const std::string& resource_id, std::string* arm_id) {
10  size_t position = resource_id.rfind("_joint");
11  if (position != std::string::npos && position > 0) {
12  *arm_id = resource_id.substr(0, position);
13  return true;
14  }
15  position = resource_id.rfind("_robot");
16  if (position != std::string::npos && position > 0) {
17  *arm_id = resource_id.substr(0, position);
18  return true;
19  }
20  return false;
21 }
22 
23 ResourceWithClaimsMap getResourceMap(const std::list<hardware_interface::ControllerInfo>& info) {
24  ResourceWithClaimsMap resource_map;
25  for (auto& item : info) {
26  const std::vector<hardware_interface::InterfaceResources>& c_res = item.claimed_resources;
27  for (auto& resource_set : c_res) {
28  const std::set<std::string>& iface_resources = resource_set.resources;
29  for (auto& resource : iface_resources) {
30  std::vector<std::string> claiming_controller(3);
31  claiming_controller[0] = item.name;
32  claiming_controller[1] = item.type;
33  claiming_controller[2] = resource_set.hardware_interface;
34  resource_map[resource].push_back(claiming_controller);
35  }
36  }
37  }
38  return resource_map;
39 }
40 
41 bool getArmClaimedMap(ResourceWithClaimsMap& resource_map, ArmClaimedMap& arm_claim_map) {
42  std::string current_arm_id;
43 
44  // check for conflicts between joint and cartesian level for each arm.
45  // Valid claims are torque claims on joint level in combination with either
46  // 7 non-torque claims on joint_level or one claim on cartesian level.
47  for (auto map_it = resource_map.begin(); map_it != resource_map.end(); map_it++) {
48  if (!findArmIdInResourceId(map_it->first, &current_arm_id)) {
49  ROS_ERROR_STREAM("Resource conflict: Could not find arm_id in resource "
50  << map_it->first << ". Name joints as '<robot_arm_id>_joint<jointnumber>'");
51  return false;
52  }
53  ResourceClaims new_claim;
54  for (auto claimed_by : map_it->second) {
55  if (claimed_by[2] == "hardware_interface::EffortJointInterface") {
56  new_claim.joint_torque_claims++;
57  } else if (claimed_by[2] == "hardware_interface::PositionJointInterface") {
58  new_claim.joint_position_claims++;
59  } else if (claimed_by[2] == "hardware_interface::VelocityJointInterface") {
60  new_claim.joint_velocity_claims++;
61  } else if (claimed_by[2] == "franka_hw::FrankaPoseCartesianInterface") {
62  new_claim.cartesian_pose_claims++;
63  } else if (claimed_by[2] == "franka_hw::FrankaVelocityCartesianInterface") {
64  new_claim.cartesian_velocity_claims++;
65  } else {
66  return false;
67  }
68  }
69  arm_claim_map[current_arm_id].joint_position_claims += new_claim.joint_position_claims;
70  arm_claim_map[current_arm_id].joint_velocity_claims += new_claim.joint_velocity_claims;
71  arm_claim_map[current_arm_id].joint_torque_claims += new_claim.joint_torque_claims;
72  arm_claim_map[current_arm_id].cartesian_velocity_claims += new_claim.cartesian_velocity_claims;
73  arm_claim_map[current_arm_id].cartesian_pose_claims += new_claim.cartesian_pose_claims;
74  }
75  return true;
76 }
77 
78 ControlMode getControlMode(const std::string& arm_id, ArmClaimedMap& arm_claim_map) {
79  ControlMode control_mode = ControlMode::None;
80  if (arm_claim_map[arm_id].joint_position_claims > 0 &&
81  arm_claim_map[arm_id].joint_velocity_claims == 0 &&
82  arm_claim_map[arm_id].joint_torque_claims == 0 &&
83  arm_claim_map[arm_id].cartesian_pose_claims == 0 &&
84  arm_claim_map[arm_id].cartesian_velocity_claims == 0) {
85  control_mode = ControlMode::JointPosition;
86  } else if (arm_claim_map[arm_id].joint_position_claims == 0 &&
87  arm_claim_map[arm_id].joint_velocity_claims > 0 &&
88  arm_claim_map[arm_id].joint_torque_claims == 0 &&
89  arm_claim_map[arm_id].cartesian_pose_claims == 0 &&
90  arm_claim_map[arm_id].cartesian_velocity_claims == 0) {
91  control_mode = ControlMode::JointVelocity;
92  } else if (arm_claim_map[arm_id].joint_position_claims == 0 &&
93  arm_claim_map[arm_id].joint_velocity_claims == 0 &&
94  arm_claim_map[arm_id].joint_torque_claims > 0 &&
95  arm_claim_map[arm_id].cartesian_pose_claims == 0 &&
96  arm_claim_map[arm_id].cartesian_velocity_claims == 0) {
97  control_mode = ControlMode::JointTorque;
98  } else if (arm_claim_map[arm_id].joint_position_claims == 0 &&
99  arm_claim_map[arm_id].joint_velocity_claims == 0 &&
100  arm_claim_map[arm_id].joint_torque_claims == 0 &&
101  arm_claim_map[arm_id].cartesian_pose_claims > 0 &&
102  arm_claim_map[arm_id].cartesian_velocity_claims == 0) {
103  control_mode = ControlMode::CartesianPose;
104  } else if (arm_claim_map[arm_id].joint_position_claims == 0 &&
105  arm_claim_map[arm_id].joint_velocity_claims == 0 &&
106  arm_claim_map[arm_id].joint_torque_claims == 0 &&
107  arm_claim_map[arm_id].cartesian_pose_claims == 0 &&
108  arm_claim_map[arm_id].cartesian_velocity_claims > 0) {
109  control_mode = ControlMode::CartesianVelocity;
110  } else if (arm_claim_map[arm_id].joint_position_claims > 0 &&
111  arm_claim_map[arm_id].joint_velocity_claims == 0 &&
112  arm_claim_map[arm_id].joint_torque_claims > 0 &&
113  arm_claim_map[arm_id].cartesian_pose_claims == 0 &&
114  arm_claim_map[arm_id].cartesian_velocity_claims == 0) {
116  } else if (arm_claim_map[arm_id].joint_position_claims == 0 &&
117  arm_claim_map[arm_id].joint_velocity_claims > 0 &&
118  arm_claim_map[arm_id].joint_torque_claims > 0 &&
119  arm_claim_map[arm_id].cartesian_pose_claims == 0 &&
120  arm_claim_map[arm_id].cartesian_velocity_claims == 0) {
122  } else if (arm_claim_map[arm_id].joint_position_claims == 0 &&
123  arm_claim_map[arm_id].joint_velocity_claims == 0 &&
124  arm_claim_map[arm_id].joint_torque_claims > 0 &&
125  arm_claim_map[arm_id].cartesian_pose_claims > 0 &&
126  arm_claim_map[arm_id].cartesian_velocity_claims == 0) {
128  } else if (arm_claim_map[arm_id].joint_position_claims == 0 &&
129  arm_claim_map[arm_id].joint_velocity_claims == 0 &&
130  arm_claim_map[arm_id].joint_torque_claims > 0 &&
131  arm_claim_map[arm_id].cartesian_pose_claims == 0 &&
132  arm_claim_map[arm_id].cartesian_velocity_claims > 0) {
134  }
135  return control_mode;
136 }
137 
139  for (const auto& resource : resource_map) {
140  if (resource.second.size() > 2) {
141  ROS_ERROR_STREAM("Resource conflict: " << resource.first
142  << " is claimed with more than two command interfaces "
143  "which is not supported.");
144  return true;
145  }
146  uint8_t torque_claims = 0;
147  uint8_t other_claims = 0;
148  if (resource.second.size() == 2) {
149  for (const auto& claimed_by : resource.second) {
150  if (claimed_by.at(2) == "hardware_interface::EffortJointInterface") {
151  torque_claims++;
152  } else {
153  other_claims++;
154  }
155  }
156  if (torque_claims != 1) {
157  ROS_ERROR_STREAM("Resource conflict: "
158  << resource.first
159  << " is claimed with a combination of two interfaces that is not "
160  "supported.");
161  return true;
162  }
163  }
164  }
165  return false;
166 }
167 
169  const std::string& arm_id) {
170  // check for conflicts between joint and cartesian level for each arm.
171  if (arm_claim_map.find(arm_id) != arm_claim_map.end()) {
172  if ((arm_claim_map.at(arm_id).cartesian_velocity_claims +
173  arm_claim_map.at(arm_id).cartesian_pose_claims >
174  0 &&
175  arm_claim_map.at(arm_id).joint_position_claims +
176  arm_claim_map.at(arm_id).joint_velocity_claims >
177  0)) {
179  "Resource conflict: Invalid combination of claims on joint AND cartesian level on arm "
180  << arm_id << " which is not supported.");
181  return true;
182  }
183  }
184  return false;
185 }
186 
187 bool partiallyClaimsArmJoints(const ArmClaimedMap& arm_claim_map, const std::string& arm_id) {
188  // Valid claims are torque claims on joint level in combination with either
189  // 7 non-torque claims on joint_level or one claim on cartesian level.
190  if (arm_claim_map.find(arm_id) != arm_claim_map.end()) {
191  if ((arm_claim_map.at(arm_id).joint_position_claims > 0 &&
192  arm_claim_map.at(arm_id).joint_position_claims != 7) ||
193  (arm_claim_map.at(arm_id).joint_velocity_claims > 0 &&
194  arm_claim_map.at(arm_id).joint_velocity_claims != 7) ||
195  (arm_claim_map.at(arm_id).joint_torque_claims > 0 &&
196  arm_claim_map.at(arm_id).joint_torque_claims != 7)) {
197  ROS_ERROR_STREAM("Resource conflict: Partially claiming joints of arm "
198  << arm_id
199  << " is not supported. Make sure to claim all 7 joints of the robot.");
200  return true;
201  }
202  }
203  return false;
204 }
205 
206 bool hasTrajectoryClaim(const ArmClaimedMap& arm_claim_map, const std::string& arm_id) {
207  if (arm_claim_map.find(arm_id) != arm_claim_map.end()) {
208  if (arm_claim_map.at(arm_id).joint_position_claims +
209  arm_claim_map.at(arm_id).joint_velocity_claims +
210  arm_claim_map.at(arm_id).cartesian_velocity_claims +
211  arm_claim_map.at(arm_id).cartesian_pose_claims >
212  0) {
213  return true;
214  }
215  }
216  return false;
217 }
218 
219 } // namespace franka_hw
std::string arm_id
bool getArmClaimedMap(ResourceWithClaimsMap &resource_map, ArmClaimedMap &arm_claim_map)
bool hasConflictingJointAndCartesianClaim(const ArmClaimedMap &arm_claim_map, const std::string &arm_id)
ControlMode getControlMode(const std::string &arm_id, ArmClaimedMap &arm_claim_map)
std::map< std::string, ResourceClaims > ArmClaimedMap
bool findArmIdInResourceId(const std::string &resource_id, std::string *arm_id)
std::map< std::string, std::vector< std::vector< std::string >>> ResourceWithClaimsMap
bool hasTrajectoryClaim(const ArmClaimedMap &arm_claim_map, const std::string &arm_id)
bool partiallyClaimsArmJoints(const ArmClaimedMap &arm_claim_map, const std::string &arm_id)
#define ROS_ERROR_STREAM(args)
ResourceWithClaimsMap getResourceMap(const std::list< hardware_interface::ControllerInfo > &info)
bool hasConflictingMultiClaim(const ResourceWithClaimsMap &resource_map)


franka_hw
Author(s): Franka Emika GmbH
autogenerated on Fri Oct 23 2020 03:47:05