Skip to content

Commit a708bcf

Browse files
committed
Part3 WIP Migrate transmission tests to actuatorToJoint, jointToActuator
1 parent 8357c0c commit a708bcf

File tree

3 files changed

+225
-225
lines changed

3 files changed

+225
-225
lines changed

transmission_interface/test/differential_transmission_test.cpp

Lines changed: 84 additions & 84 deletions
Original file line numberDiff line numberDiff line change
@@ -118,54 +118,54 @@ TEST(PreconditionsTest, AssertionTriggering)
118118
vector<double>(2, 1.0));
119119

120120
// Data with invalid pointers should trigger an assertion
121-
EXPECT_DEATH(trans.actuatorToJointEffort(a_bad_data, j_bad_data), ".*");
122-
EXPECT_DEATH(trans.actuatorToJointEffort(a_good_data, j_bad_data), ".*");
123-
EXPECT_DEATH(trans.actuatorToJointEffort(a_bad_data, j_good_data), ".*");
121+
EXPECT_DEATH(trans.actuatorToJoint((EffortActuatorData)a_bad_data, j_bad_data), ".*");
122+
EXPECT_DEATH(trans.actuatorToJoint((EffortActuatorData)a_good_data, j_bad_data), ".*");
123+
EXPECT_DEATH(trans.actuatorToJoint((EffortActuatorData)a_bad_data, j_good_data), ".*");
124124

125-
EXPECT_DEATH(trans.actuatorToJointVelocity(a_bad_data, j_bad_data), ".*");
126-
EXPECT_DEATH(trans.actuatorToJointVelocity(a_good_data, j_bad_data), ".*");
127-
EXPECT_DEATH(trans.actuatorToJointVelocity(a_bad_data, j_good_data), ".*");
125+
EXPECT_DEATH(trans.actuatorToJoint((VelocityActuatorData)a_bad_data, j_bad_data), ".*");
126+
EXPECT_DEATH(trans.actuatorToJoint((VelocityActuatorData)a_good_data, j_bad_data), ".*");
127+
EXPECT_DEATH(trans.actuatorToJoint((VelocityActuatorData)a_bad_data, j_good_data), ".*");
128128

129-
EXPECT_DEATH(trans.actuatorToJointPosition(a_bad_data, j_bad_data), ".*");
130-
EXPECT_DEATH(trans.actuatorToJointPosition(a_good_data, j_bad_data), ".*");
131-
EXPECT_DEATH(trans.actuatorToJointPosition(a_bad_data, j_good_data), ".*");
129+
EXPECT_DEATH(trans.actuatorToJoint((PositionActuatorData)a_bad_data, j_bad_data), ".*");
130+
EXPECT_DEATH(trans.actuatorToJoint((PositionActuatorData)a_good_data, j_bad_data), ".*");
131+
EXPECT_DEATH(trans.actuatorToJoint((PositionActuatorData)a_bad_data, j_good_data), ".*");
132132

133-
EXPECT_DEATH(trans.jointToActuatorEffort(j_bad_data, a_bad_data), ".*");
134-
EXPECT_DEATH(trans.jointToActuatorEffort(j_good_data, a_bad_data), ".*");
135-
EXPECT_DEATH(trans.jointToActuatorEffort(j_bad_data, a_good_data), ".*");
133+
EXPECT_DEATH(trans.jointToActuator((EffortJointData)j_bad_data, a_bad_data), ".*");
134+
EXPECT_DEATH(trans.jointToActuator((EffortJointData)j_good_data, a_bad_data), ".*");
135+
EXPECT_DEATH(trans.jointToActuator((EffortJointData)j_bad_data, a_good_data), ".*");
136136

137-
EXPECT_DEATH(trans.jointToActuatorVelocity(j_bad_data, a_bad_data), ".*");
138-
EXPECT_DEATH(trans.jointToActuatorVelocity(j_good_data, a_bad_data), ".*");
139-
EXPECT_DEATH(trans.jointToActuatorVelocity(j_bad_data, a_good_data), ".*");
137+
EXPECT_DEATH(trans.jointToActuator((VelocityJointData)j_bad_data, a_bad_data), ".*");
138+
EXPECT_DEATH(trans.jointToActuator((VelocityJointData)j_good_data, a_bad_data), ".*");
139+
EXPECT_DEATH(trans.jointToActuator((VelocityJointData)j_bad_data, a_good_data), ".*");
140140

141-
EXPECT_DEATH(trans.jointToActuatorPosition(j_bad_data, a_bad_data), ".*");
142-
EXPECT_DEATH(trans.jointToActuatorPosition(j_good_data, a_bad_data), ".*");
143-
EXPECT_DEATH(trans.jointToActuatorPosition(j_bad_data, a_good_data), ".*");
141+
EXPECT_DEATH(trans.jointToActuator((PositionJointData)j_bad_data, a_bad_data), ".*");
142+
EXPECT_DEATH(trans.jointToActuator((PositionJointData)j_good_data, a_bad_data), ".*");
143+
EXPECT_DEATH(trans.jointToActuator((PositionJointData)j_bad_data, a_good_data), ".*");
144144

145145
// Wrong parameter sizes should trigger an assertion
146-
EXPECT_DEATH(trans.actuatorToJointEffort(a_bad_size, j_bad_size), ".*");
147-
EXPECT_DEATH(trans.actuatorToJointEffort(a_good_data, j_bad_size), ".*");
148-
EXPECT_DEATH(trans.actuatorToJointEffort(a_bad_size, j_good_data), ".*");
146+
EXPECT_DEATH(trans.actuatorToJoint((EffortActuatorData)a_bad_size, j_bad_size), ".*");
147+
EXPECT_DEATH(trans.actuatorToJoint((EffortActuatorData)a_good_data, j_bad_size), ".*");
148+
EXPECT_DEATH(trans.actuatorToJoint((EffortActuatorData)a_bad_size, j_good_data), ".*");
149149

150-
EXPECT_DEATH(trans.actuatorToJointVelocity(a_bad_size, j_bad_size), ".*");
151-
EXPECT_DEATH(trans.actuatorToJointVelocity(a_good_data, j_bad_size), ".*");
152-
EXPECT_DEATH(trans.actuatorToJointVelocity(a_bad_size, j_good_data), ".*");
150+
EXPECT_DEATH(trans.actuatorToJoint((VelocityActuatorData)a_bad_size, j_bad_size), ".*");
151+
EXPECT_DEATH(trans.actuatorToJoint((VelocityActuatorData)a_good_data, j_bad_size), ".*");
152+
EXPECT_DEATH(trans.actuatorToJoint((VelocityActuatorData)a_bad_size, j_good_data), ".*");
153153

154-
EXPECT_DEATH(trans.actuatorToJointPosition(a_bad_size, j_bad_size), ".*");
155-
EXPECT_DEATH(trans.actuatorToJointPosition(a_good_data, j_bad_size), ".*");
156-
EXPECT_DEATH(trans.actuatorToJointPosition(a_bad_size, j_good_data), ".*");
154+
EXPECT_DEATH(trans.actuatorToJoint((PositionActuatorData)a_bad_size, j_bad_size), ".*");
155+
EXPECT_DEATH(trans.actuatorToJoint((PositionActuatorData)a_good_data, j_bad_size), ".*");
156+
EXPECT_DEATH(trans.actuatorToJoint((PositionActuatorData)a_bad_size, j_good_data), ".*");
157157

158-
EXPECT_DEATH(trans.jointToActuatorEffort(j_bad_size, a_bad_size), ".*");
159-
EXPECT_DEATH(trans.jointToActuatorEffort(j_good_data, a_bad_size), ".*");
160-
EXPECT_DEATH(trans.jointToActuatorEffort(j_bad_size, a_good_data), ".*");
158+
EXPECT_DEATH(trans.jointToActuator((EffortJointData)j_bad_size, a_bad_size), ".*");
159+
EXPECT_DEATH(trans.jointToActuator((EffortJointData)j_good_data, a_bad_size), ".*");
160+
EXPECT_DEATH(trans.jointToActuator((EffortJointData)j_bad_size, a_good_data), ".*");
161161

162-
EXPECT_DEATH(trans.jointToActuatorVelocity(j_bad_size, a_bad_size), ".*");
163-
EXPECT_DEATH(trans.jointToActuatorVelocity(j_good_data, a_bad_size), ".*");
164-
EXPECT_DEATH(trans.jointToActuatorVelocity(j_bad_size, a_good_data), ".*");
162+
EXPECT_DEATH(trans.jointToActuator((VelocityJointData)j_bad_size, a_bad_size), ".*");
163+
EXPECT_DEATH(trans.jointToActuator((VelocityJointData)j_good_data, a_bad_size), ".*");
164+
EXPECT_DEATH(trans.jointToActuator((VelocityJointData)j_bad_size, a_good_data), ".*");
165165

166-
EXPECT_DEATH(trans.jointToActuatorPosition(j_bad_size, a_bad_size), ".*");
167-
EXPECT_DEATH(trans.jointToActuatorPosition(j_good_data, a_bad_size), ".*");
168-
EXPECT_DEATH(trans.jointToActuatorPosition(j_bad_size, a_good_data), ".*");
166+
EXPECT_DEATH(trans.jointToActuator((PositionJointData)j_bad_size, a_bad_size), ".*");
167+
EXPECT_DEATH(trans.jointToActuator((PositionJointData)j_good_data, a_bad_size), ".*");
168+
EXPECT_DEATH(trans.jointToActuator((PositionJointData)j_bad_size, a_good_data), ".*");
169169
}
170170
#endif // NDEBUG
171171

@@ -232,48 +232,48 @@ class BlackBoxTest : public TransmissionSetup
232232
{
233233
// Effort interface
234234
{
235-
ActuatorData a_data;
235+
EffortActuatorData a_data;
236236
a_data.effort = a_vec;
237237
*a_data.effort[0] = ref_val[0];
238238
*a_data.effort[1] = ref_val[1];
239239

240-
JointData j_data;
240+
EffortJointData j_data;
241241
j_data.effort = j_vec;
242242

243-
trans.actuatorToJointEffort(a_data, j_data);
244-
trans.jointToActuatorEffort(j_data, a_data);
243+
trans.actuatorToJoint(a_data, j_data);
244+
trans.jointToActuator(j_data, a_data);
245245
EXPECT_NEAR(ref_val[0], *a_data.effort[0], EPS);
246246
EXPECT_NEAR(ref_val[1], *a_data.effort[1], EPS);
247247
}
248248

249249
// Velocity interface
250250
{
251-
ActuatorData a_data;
251+
VelocityActuatorData a_data;
252252
a_data.velocity = a_vec;
253253
*a_data.velocity[0] = ref_val[0];
254254
*a_data.velocity[1] = ref_val[1];
255255

256-
JointData j_data;
256+
VelocityJointData j_data;
257257
j_data.velocity = j_vec;
258258

259-
trans.actuatorToJointVelocity(a_data, j_data);
260-
trans.jointToActuatorVelocity(j_data, a_data);
259+
trans.actuatorToJoint(a_data, j_data);
260+
trans.jointToActuator(j_data, a_data);
261261
EXPECT_NEAR(ref_val[0], *a_data.velocity[0], EPS);
262262
EXPECT_NEAR(ref_val[1], *a_data.velocity[1], EPS);
263263
}
264264

265265
// Position interface
266266
{
267-
ActuatorData a_data;
267+
PositionActuatorData a_data;
268268
a_data.position = a_vec;
269269
*a_data.position[0] = ref_val[0];
270270
*a_data.position[1] = ref_val[1];
271271

272-
JointData j_data;
272+
PositionJointData j_data;
273273
j_data.position = j_vec;
274274

275-
trans.actuatorToJointPosition(a_data, j_data);
276-
trans.jointToActuatorPosition(j_data, a_data);
275+
trans.actuatorToJoint(a_data, j_data);
276+
trans.jointToActuator(j_data, a_data);
277277
EXPECT_NEAR(ref_val[0], *a_data.position[0], EPS);
278278
EXPECT_NEAR(ref_val[1], *a_data.position[1], EPS);
279279
}
@@ -342,39 +342,39 @@ TEST_F(WhiteBoxTest, DontMoveJoints)
342342

343343
// Effort interface
344344
{
345-
ActuatorData a_data;
345+
EffortActuatorData a_data;
346346
a_data.effort = a_vec;
347347

348-
JointData j_data;
348+
EffortJointData j_data;
349349
j_data.effort = j_vec;
350350

351-
trans.actuatorToJointEffort(a_data, j_data);
351+
trans.actuatorToJoint(a_data, j_data);
352352
EXPECT_NEAR(0.0, *j_data.effort[0], EPS);
353353
EXPECT_NEAR(0.0, *j_data.effort[1], EPS);
354354
}
355355

356356
// Velocity interface
357357
{
358-
ActuatorData a_data;
358+
VelocityActuatorData a_data;
359359
a_data.velocity = a_vec;
360360

361-
JointData j_data;
361+
VelocityJointData j_data;
362362
j_data.velocity = j_vec;
363363

364-
trans.actuatorToJointVelocity(a_data, j_data);
364+
trans.actuatorToJoint(a_data, j_data);
365365
EXPECT_NEAR(0.0, *j_data.velocity[0], EPS);
366366
EXPECT_NEAR(0.0, *j_data.velocity[1], EPS);
367367
}
368368

369369
// Position interface
370370
{
371-
ActuatorData a_data;
371+
PositionActuatorData a_data;
372372
a_data.position = a_vec;
373373

374-
JointData j_data;
374+
PositionJointData j_data;
375375
j_data.position = j_vec;
376376

377-
trans.actuatorToJointPosition(a_data, j_data);
377+
trans.actuatorToJoint(a_data, j_data);
378378
EXPECT_NEAR(joint_offset[0], *j_data.position[0], EPS);
379379
EXPECT_NEAR(joint_offset[1], *j_data.position[1], EPS);
380380
}
@@ -393,39 +393,39 @@ TEST_F(WhiteBoxTest, MoveFirstJointOnly)
393393

394394
// Effort interface
395395
{
396-
ActuatorData a_data;
396+
EffortActuatorData a_data;
397397
a_data.effort = a_vec;
398398

399-
JointData j_data;
399+
EffortJointData j_data;
400400
j_data.effort = j_vec;
401401

402-
trans.actuatorToJointEffort(a_data, j_data);
402+
trans.actuatorToJoint(a_data, j_data);
403403
EXPECT_NEAR(400.0, *j_data.effort[0], EPS);
404404
EXPECT_NEAR(0.0, *j_data.effort[1], EPS);
405405
}
406406

407407
// Velocity interface
408408
{
409-
ActuatorData a_data;
409+
VelocityActuatorData a_data;
410410
a_data.velocity = a_vec;
411411

412-
JointData j_data;
412+
VelocityJointData j_data;
413413
j_data.velocity = j_vec;
414414

415-
trans.actuatorToJointVelocity(a_data, j_data);
415+
trans.actuatorToJoint(a_data, j_data);
416416
EXPECT_NEAR(0.5, *j_data.velocity[0], EPS);
417417
EXPECT_NEAR(0.0, *j_data.velocity[1], EPS);
418418
}
419419

420420
// Position interface
421421
{
422-
ActuatorData a_data;
422+
PositionActuatorData a_data;
423423
a_data.position = a_vec;
424424

425-
JointData j_data;
425+
PositionJointData j_data;
426426
j_data.position = j_vec;
427427

428-
trans.actuatorToJointPosition(a_data, j_data);
428+
trans.actuatorToJoint(a_data, j_data);
429429
EXPECT_NEAR(0.5, *j_data.position[0], EPS);
430430
EXPECT_NEAR(0.0, *j_data.position[1], EPS);
431431
}
@@ -444,39 +444,39 @@ TEST_F(WhiteBoxTest, MoveSecondJointOnly)
444444

445445
// Effort interface
446446
{
447-
ActuatorData a_data;
447+
EffortActuatorData a_data;
448448
a_data.effort = a_vec;
449449

450-
JointData j_data;
450+
EffortJointData j_data;
451451
j_data.effort = j_vec;
452452

453-
trans.actuatorToJointEffort(a_data, j_data);
453+
trans.actuatorToJoint(a_data, j_data);
454454
EXPECT_NEAR(0.0, *j_data.effort[0], EPS);
455455
EXPECT_NEAR(400.0, *j_data.effort[1], EPS);
456456
}
457457

458458
// Velocity interface
459459
{
460-
ActuatorData a_data;
460+
VelocityActuatorData a_data;
461461
a_data.velocity = a_vec;
462462

463-
JointData j_data;
463+
VelocityJointData j_data;
464464
j_data.velocity = j_vec;
465465

466-
trans.actuatorToJointVelocity(a_data, j_data);
466+
trans.actuatorToJoint(a_data, j_data);
467467
EXPECT_NEAR(0.0, *j_data.velocity[0], EPS);
468468
EXPECT_NEAR(0.5, *j_data.velocity[1], EPS);
469469
}
470470

471471
// Position interface
472472
{
473-
ActuatorData a_data;
473+
PositionActuatorData a_data;
474474
a_data.position = a_vec;
475475

476-
JointData j_data;
476+
PositionJointData j_data;
477477
j_data.position = j_vec;
478478

479-
trans.actuatorToJointPosition(a_data, j_data);
479+
trans.actuatorToJoint(a_data, j_data);
480480
EXPECT_NEAR(0.0, *j_data.position[0], EPS);
481481
EXPECT_NEAR(0.5, *j_data.position[1], EPS);
482482
}
@@ -507,39 +507,39 @@ TEST_F(WhiteBoxTest, MoveBothJoints)
507507

508508
// Effort interface
509509
{
510-
ActuatorData a_data;
510+
EffortActuatorData a_data;
511511
a_data.effort = a_vec;
512512

513-
JointData j_data;
513+
EffortJointData j_data;
514514
j_data.effort = j_vec;
515515

516-
trans.actuatorToJointEffort(a_data, j_data);
516+
trans.actuatorToJoint(a_data, j_data);
517517
EXPECT_NEAR(140.0, *j_data.effort[0], EPS);
518518
EXPECT_NEAR(520.0, *j_data.effort[1], EPS);
519519
}
520520

521521
// Velocity interface
522522
{
523-
ActuatorData a_data;
523+
VelocityActuatorData a_data;
524524
a_data.velocity = a_vec;
525525

526-
JointData j_data;
526+
VelocityJointData j_data;
527527
j_data.velocity = j_vec;
528528

529-
trans.actuatorToJointVelocity(a_data, j_data);
529+
trans.actuatorToJoint(a_data, j_data);
530530
EXPECT_NEAR(-0.01250, *j_data.velocity[0], EPS);
531531
EXPECT_NEAR( 0.06875, *j_data.velocity[1], EPS);
532532
}
533533

534534
// Position interface
535535
{
536-
ActuatorData a_data;
536+
PositionActuatorData a_data;
537537
a_data.position = a_vec;
538538

539-
JointData j_data;
539+
PositionJointData j_data;
540540
j_data.position = j_vec;
541541

542-
trans.actuatorToJointPosition(a_data, j_data);
542+
trans.actuatorToJoint(a_data, j_data);
543543
EXPECT_NEAR(-2.01250, *j_data.position[0], EPS);
544544
EXPECT_NEAR( 4.06875, *j_data.position[1], EPS);
545545
}

0 commit comments

Comments
 (0)