@@ -233,73 +233,73 @@ TEST_F(ResourceManagerTest, resource_claiming)
233
233
// Activate components to get all interfaces available
234
234
activate_components (rm);
235
235
236
- const auto key = " joint1/position" ;
237
- EXPECT_TRUE (rm.command_interface_is_available (key ));
238
- EXPECT_FALSE (rm.command_interface_is_claimed (key ));
236
+ const auto command_interface = " joint1/position" ;
237
+ EXPECT_TRUE (rm.command_interface_is_available (command_interface ));
238
+ EXPECT_FALSE (rm.command_interface_is_claimed (command_interface ));
239
239
240
240
{
241
- auto position_command_interface = rm.claim_command_interface (key );
242
- EXPECT_TRUE (rm.command_interface_is_available (key ));
243
- EXPECT_TRUE (rm.command_interface_is_claimed (key ));
241
+ auto position_command_interface = rm.claim_command_interface (command_interface );
242
+ EXPECT_TRUE (rm.command_interface_is_available (command_interface ));
243
+ EXPECT_TRUE (rm.command_interface_is_claimed (command_interface ));
244
244
{
245
- EXPECT_ANY_THROW (rm.claim_command_interface (key ));
246
- EXPECT_TRUE (rm.command_interface_is_available (key ));
245
+ EXPECT_ANY_THROW (rm.claim_command_interface (command_interface ));
246
+ EXPECT_TRUE (rm.command_interface_is_available (command_interface ));
247
247
}
248
248
}
249
- EXPECT_TRUE (rm.command_interface_is_available (key ));
250
- EXPECT_FALSE (rm.command_interface_is_claimed (key ));
249
+ EXPECT_TRUE (rm.command_interface_is_available (command_interface ));
250
+ EXPECT_FALSE (rm.command_interface_is_claimed (command_interface ));
251
251
252
252
// command interfaces can only be claimed once
253
- for (const auto & key :
253
+ for (const auto & interface_key :
254
254
{" joint1/position" , " joint1/position" , " joint1/position" , " joint2/velocity" ,
255
255
" joint3/velocity" })
256
256
{
257
257
{
258
- auto interface = rm.claim_command_interface (key );
259
- EXPECT_TRUE (rm.command_interface_is_available (key ));
260
- EXPECT_TRUE (rm.command_interface_is_claimed (key ));
258
+ auto interface = rm.claim_command_interface (interface_key );
259
+ EXPECT_TRUE (rm.command_interface_is_available (interface_key ));
260
+ EXPECT_TRUE (rm.command_interface_is_claimed (interface_key ));
261
261
{
262
- EXPECT_ANY_THROW (rm.claim_command_interface (key ));
263
- EXPECT_TRUE (rm.command_interface_is_available (key ));
262
+ EXPECT_ANY_THROW (rm.claim_command_interface (interface_key ));
263
+ EXPECT_TRUE (rm.command_interface_is_available (interface_key ));
264
264
}
265
265
}
266
- EXPECT_TRUE (rm.command_interface_is_available (key ));
267
- EXPECT_FALSE (rm.command_interface_is_claimed (key ));
266
+ EXPECT_TRUE (rm.command_interface_is_available (interface_key ));
267
+ EXPECT_FALSE (rm.command_interface_is_claimed (interface_key ));
268
268
}
269
269
270
270
// TODO(destogl): This claim test is not true.... can not be...
271
271
// state interfaces can be claimed multiple times
272
- for (const auto & key :
272
+ for (const auto & interface_key :
273
273
{" joint1/position" , " joint1/velocity" , " sensor1/velocity" , " joint2/position" ,
274
274
" joint3/position" })
275
275
{
276
276
{
277
- EXPECT_TRUE (rm.state_interface_is_available (key ));
278
- auto interface = rm.claim_state_interface (key );
277
+ EXPECT_TRUE (rm.state_interface_is_available (interface_key ));
278
+ auto interface = rm.claim_state_interface (interface_key );
279
279
{
280
- EXPECT_TRUE (rm.state_interface_is_available (key ));
281
- EXPECT_NO_THROW (rm.claim_state_interface (key ));
280
+ EXPECT_TRUE (rm.state_interface_is_available (interface_key ));
281
+ EXPECT_NO_THROW (rm.claim_state_interface (interface_key ));
282
282
}
283
283
}
284
284
}
285
285
286
286
std::vector<hardware_interface::LoanedCommandInterface> interfaces;
287
287
const auto interface_names = {" joint1/position" , " joint2/velocity" , " joint3/velocity" };
288
- for (const auto & key : interface_names)
288
+ for (const auto & interface : interface_names)
289
289
{
290
- EXPECT_TRUE (rm.command_interface_is_available (key ));
291
- interfaces.emplace_back (rm.claim_command_interface (key ));
290
+ EXPECT_TRUE (rm.command_interface_is_available (interface ));
291
+ interfaces.emplace_back (rm.claim_command_interface (interface ));
292
292
}
293
- for (const auto & key : interface_names)
293
+ for (const auto & interface : interface_names)
294
294
{
295
- EXPECT_TRUE (rm.command_interface_is_available (key ));
296
- EXPECT_TRUE (rm.command_interface_is_claimed (key ));
295
+ EXPECT_TRUE (rm.command_interface_is_available (interface ));
296
+ EXPECT_TRUE (rm.command_interface_is_claimed (interface ));
297
297
}
298
298
interfaces.clear ();
299
- for (const auto & key : interface_names)
299
+ for (const auto & interface : interface_names)
300
300
{
301
- EXPECT_TRUE (rm.command_interface_is_available (key ));
302
- EXPECT_FALSE (rm.command_interface_is_claimed (key ));
301
+ EXPECT_TRUE (rm.command_interface_is_available (interface ));
302
+ EXPECT_FALSE (rm.command_interface_is_claimed (interface ));
303
303
}
304
304
}
305
305
0 commit comments