Skip to content

Commit 875fb78

Browse files
authored
Improve transmission tests (#1238) (#1241)
1 parent bf921d9 commit 875fb78

6 files changed

+106
-92
lines changed

transmission_interface/test/differential_transmission_loader_test.cpp

Lines changed: 34 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -26,8 +26,12 @@
2626
#include "transmission_interface/differential_transmission_loader.hpp"
2727
#include "transmission_interface/transmission_loader.hpp"
2828

29+
using testing::DoubleNear;
2930
using testing::SizeIs;
3031

32+
// Floating-point value comparison threshold
33+
const double EPS = 1e-5;
34+
3135
class TransmissionPluginLoader
3236
{
3337
public:
@@ -113,16 +117,16 @@ TEST(DifferentialTransmissionLoaderTest, FullSpec)
113117

114118
const std::vector<double> & actuator_reduction =
115119
differential_transmission->get_actuator_reduction();
116-
EXPECT_EQ(50.0, actuator_reduction[0]);
117-
EXPECT_EQ(-50.0, actuator_reduction[1]);
120+
EXPECT_THAT(50.0, DoubleNear(actuator_reduction[0], EPS));
121+
EXPECT_THAT(-50.0, DoubleNear(actuator_reduction[1], EPS));
118122

119123
const std::vector<double> & joint_reduction = differential_transmission->get_joint_reduction();
120-
EXPECT_EQ(2.0, joint_reduction[0]);
121-
EXPECT_EQ(-2.0, joint_reduction[1]);
124+
EXPECT_THAT(2.0, DoubleNear(joint_reduction[0], EPS));
125+
EXPECT_THAT(-2.0, DoubleNear(joint_reduction[1], EPS));
122126

123127
const std::vector<double> & joint_offset = differential_transmission->get_joint_offset();
124-
EXPECT_EQ(0.5, joint_offset[0]);
125-
EXPECT_EQ(-0.5, joint_offset[1]);
128+
EXPECT_THAT(0.5, DoubleNear(joint_offset[0], EPS));
129+
EXPECT_THAT(-0.5, DoubleNear(joint_offset[1], EPS));
126130
}
127131

128132
TEST(DifferentialTransmissionLoaderTest, only_mech_red_specified)
@@ -184,16 +188,16 @@ TEST(DifferentialTransmissionLoaderTest, only_mech_red_specified)
184188

185189
const std::vector<double> & actuator_reduction =
186190
differential_transmission->get_actuator_reduction();
187-
EXPECT_EQ(50.0, actuator_reduction[0]);
188-
EXPECT_EQ(-50.0, actuator_reduction[1]);
191+
EXPECT_THAT(50.0, DoubleNear(actuator_reduction[0], EPS));
192+
EXPECT_THAT(-50.0, DoubleNear(actuator_reduction[1], EPS));
189193

190194
const std::vector<double> & joint_reduction = differential_transmission->get_joint_reduction();
191-
EXPECT_EQ(1.0, joint_reduction[0]);
192-
EXPECT_EQ(1.0, joint_reduction[1]);
195+
EXPECT_THAT(1.0, DoubleNear(joint_reduction[0], EPS));
196+
EXPECT_THAT(1.0, DoubleNear(joint_reduction[1], EPS));
193197

194198
const std::vector<double> & joint_offset = differential_transmission->get_joint_offset();
195-
EXPECT_EQ(0.0, joint_offset[0]);
196-
EXPECT_EQ(0.0, joint_offset[1]);
199+
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
200+
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
197201
}
198202

199203
TEST(SimpleTransmissionLoaderTest, offset_and_mech_red_not_specified)
@@ -247,16 +251,16 @@ TEST(SimpleTransmissionLoaderTest, offset_and_mech_red_not_specified)
247251

248252
const std::vector<double> & actuator_reduction =
249253
differential_transmission->get_actuator_reduction();
250-
EXPECT_EQ(1.0, actuator_reduction[0]);
251-
EXPECT_EQ(1.0, actuator_reduction[1]);
254+
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[0], EPS));
255+
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[1], EPS));
252256

253257
const std::vector<double> & joint_reduction = differential_transmission->get_joint_reduction();
254-
EXPECT_EQ(1.0, joint_reduction[0]);
255-
EXPECT_EQ(1.0, joint_reduction[1]);
258+
EXPECT_THAT(1.0, DoubleNear(joint_reduction[0], EPS));
259+
EXPECT_THAT(1.0, DoubleNear(joint_reduction[1], EPS));
256260

257261
const std::vector<double> & joint_offset = differential_transmission->get_joint_offset();
258-
EXPECT_EQ(0.0, joint_offset[0]);
259-
EXPECT_EQ(0.0, joint_offset[1]);
262+
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
263+
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
260264
}
261265

262266
TEST(DifferentialTransmissionLoaderTest, mechanical_reduction_not_a_number)
@@ -319,16 +323,16 @@ TEST(DifferentialTransmissionLoaderTest, mechanical_reduction_not_a_number)
319323
// default kicks in for ill-defined values
320324
const std::vector<double> & actuator_reduction =
321325
differential_transmission->get_actuator_reduction();
322-
EXPECT_EQ(1.0, actuator_reduction[0]);
323-
EXPECT_EQ(1.0, actuator_reduction[1]);
326+
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[0], EPS));
327+
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[1], EPS));
324328

325329
const std::vector<double> & joint_reduction = differential_transmission->get_joint_reduction();
326-
EXPECT_EQ(1.0, joint_reduction[0]);
327-
EXPECT_EQ(1.0, joint_reduction[1]);
330+
EXPECT_THAT(1.0, DoubleNear(joint_reduction[0], EPS));
331+
EXPECT_THAT(1.0, DoubleNear(joint_reduction[1], EPS));
328332

329333
const std::vector<double> & joint_offset = differential_transmission->get_joint_offset();
330-
EXPECT_EQ(0.0, joint_offset[0]);
331-
EXPECT_EQ(0.0, joint_offset[1]);
334+
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
335+
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
332336
}
333337

334338
TEST(DifferentialTransmissionLoaderTest, offset_ill_defined)
@@ -393,17 +397,17 @@ TEST(DifferentialTransmissionLoaderTest, offset_ill_defined)
393397
// default kicks in for ill-defined values
394398
const std::vector<double> & actuator_reduction =
395399
differential_transmission->get_actuator_reduction();
396-
EXPECT_EQ(50.0, actuator_reduction[0]);
397-
EXPECT_EQ(-50.0, actuator_reduction[1]);
400+
EXPECT_THAT(50.0, DoubleNear(actuator_reduction[0], EPS));
401+
EXPECT_THAT(-50.0, DoubleNear(actuator_reduction[1], EPS));
398402

399403
const std::vector<double> & joint_reduction = differential_transmission->get_joint_reduction();
400-
EXPECT_EQ(2.0, joint_reduction[0]);
401-
EXPECT_EQ(-2.0, joint_reduction[1]);
404+
EXPECT_THAT(2.0, DoubleNear(joint_reduction[0], EPS));
405+
EXPECT_THAT(-2.0, DoubleNear(joint_reduction[1], EPS));
402406

403407
// default kicks in for ill-defined values
404408
const std::vector<double> & joint_offset = differential_transmission->get_joint_offset();
405-
EXPECT_EQ(0.0, joint_offset[0]);
406-
EXPECT_EQ(0.0, joint_offset[1]);
409+
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
410+
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
407411
}
408412

409413
TEST(DifferentialTransmissionLoaderTest, mech_red_invalid_value)

transmission_interface/test/differential_transmission_test.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ using transmission_interface::DifferentialTransmission;
2929
using transmission_interface::Exception;
3030
using transmission_interface::JointHandle;
3131
// Floating-point value comparison threshold
32-
const double EPS = 1e-6;
32+
const double EPS = 1e-5;
3333

3434
TEST(PreconditionsTest, ExceptionThrowing)
3535
{
@@ -79,12 +79,12 @@ TEST(PreconditionsTest, AccessorValidation)
7979

8080
EXPECT_EQ(2u, trans.num_actuators());
8181
EXPECT_EQ(2u, trans.num_joints());
82-
EXPECT_EQ(2.0, trans.get_actuator_reduction()[0]);
83-
EXPECT_EQ(-2.0, trans.get_actuator_reduction()[1]);
84-
EXPECT_EQ(4.0, trans.get_joint_reduction()[0]);
85-
EXPECT_EQ(-4.0, trans.get_joint_reduction()[1]);
86-
EXPECT_EQ(1.0, trans.get_joint_offset()[0]);
87-
EXPECT_EQ(-1.0, trans.get_joint_offset()[1]);
82+
EXPECT_THAT(2.0, DoubleNear(trans.get_actuator_reduction()[0], EPS));
83+
EXPECT_THAT(-2.0, DoubleNear(trans.get_actuator_reduction()[1], EPS));
84+
EXPECT_THAT(4.0, DoubleNear(trans.get_joint_reduction()[0], EPS));
85+
EXPECT_THAT(-4.0, DoubleNear(trans.get_joint_reduction()[1], EPS));
86+
EXPECT_THAT(1.0, DoubleNear(trans.get_joint_offset()[0], EPS));
87+
EXPECT_THAT(-1.0, DoubleNear(trans.get_joint_offset()[1], EPS));
8888
}
8989

9090
void testConfigureWithBadHandles(std::string interface_name)

transmission_interface/test/four_bar_linkage_transmission_loader_test.cpp

Lines changed: 34 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -26,8 +26,12 @@
2626
#include "transmission_interface/four_bar_linkage_transmission_loader.hpp"
2727
#include "transmission_interface/transmission_loader.hpp"
2828

29+
using testing::DoubleNear;
2930
using testing::SizeIs;
3031

32+
// Floating-point value comparison threshold
33+
const double EPS = 1e-5;
34+
3135
class TransmissionPluginLoader
3236
{
3337
public:
@@ -113,17 +117,17 @@ TEST(FourBarLinkageTransmissionLoaderTest, FullSpec)
113117

114118
const std::vector<double> & actuator_reduction =
115119
four_bar_linkage_transmission->get_actuator_reduction();
116-
EXPECT_EQ(50.0, actuator_reduction[0]);
117-
EXPECT_EQ(-50.0, actuator_reduction[1]);
120+
EXPECT_THAT(50.0, DoubleNear(actuator_reduction[0], EPS));
121+
EXPECT_THAT(-50.0, DoubleNear(actuator_reduction[1], EPS));
118122

119123
const std::vector<double> & joint_reduction =
120124
four_bar_linkage_transmission->get_joint_reduction();
121-
EXPECT_EQ(2.0, joint_reduction[0]);
122-
EXPECT_EQ(-2.0, joint_reduction[1]);
125+
EXPECT_THAT(2.0, DoubleNear(joint_reduction[0], EPS));
126+
EXPECT_THAT(-2.0, DoubleNear(joint_reduction[1], EPS));
123127

124128
const std::vector<double> & joint_offset = four_bar_linkage_transmission->get_joint_offset();
125-
EXPECT_EQ(0.5, joint_offset[0]);
126-
EXPECT_EQ(-0.5, joint_offset[1]);
129+
EXPECT_THAT(0.5, DoubleNear(joint_offset[0], EPS));
130+
EXPECT_THAT(-0.5, DoubleNear(joint_offset[1], EPS));
127131
}
128132

129133
TEST(FourBarLinkageTransmissionLoaderTest, only_mech_red_specified)
@@ -185,17 +189,17 @@ TEST(FourBarLinkageTransmissionLoaderTest, only_mech_red_specified)
185189

186190
const std::vector<double> & actuator_reduction =
187191
four_bar_linkage_transmission->get_actuator_reduction();
188-
EXPECT_EQ(50.0, actuator_reduction[0]);
189-
EXPECT_EQ(-50.0, actuator_reduction[1]);
192+
EXPECT_THAT(50.0, DoubleNear(actuator_reduction[0], EPS));
193+
EXPECT_THAT(-50.0, DoubleNear(actuator_reduction[1], EPS));
190194

191195
const std::vector<double> & joint_reduction =
192196
four_bar_linkage_transmission->get_joint_reduction();
193-
EXPECT_EQ(1.0, joint_reduction[0]);
194-
EXPECT_EQ(1.0, joint_reduction[1]);
197+
EXPECT_THAT(1.0, DoubleNear(joint_reduction[0], EPS));
198+
EXPECT_THAT(1.0, DoubleNear(joint_reduction[1], EPS));
195199

196200
const std::vector<double> & joint_offset = four_bar_linkage_transmission->get_joint_offset();
197-
EXPECT_EQ(0.0, joint_offset[0]);
198-
EXPECT_EQ(0.0, joint_offset[1]);
201+
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
202+
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
199203
}
200204

201205
TEST(DifferentialTransmissionLoaderTest, offset_and_mech_red_not_specified)
@@ -249,17 +253,17 @@ TEST(DifferentialTransmissionLoaderTest, offset_and_mech_red_not_specified)
249253

250254
const std::vector<double> & actuator_reduction =
251255
four_bar_linkage_transmission->get_actuator_reduction();
252-
EXPECT_EQ(1.0, actuator_reduction[0]);
253-
EXPECT_EQ(1.0, actuator_reduction[1]);
256+
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[0], EPS));
257+
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[1], EPS));
254258

255259
const std::vector<double> & joint_reduction =
256260
four_bar_linkage_transmission->get_joint_reduction();
257-
EXPECT_EQ(1.0, joint_reduction[0]);
258-
EXPECT_EQ(1.0, joint_reduction[1]);
261+
EXPECT_THAT(1.0, DoubleNear(joint_reduction[0], EPS));
262+
EXPECT_THAT(1.0, DoubleNear(joint_reduction[1], EPS));
259263

260264
const std::vector<double> & joint_offset = four_bar_linkage_transmission->get_joint_offset();
261-
EXPECT_EQ(0.0, joint_offset[0]);
262-
EXPECT_EQ(0.0, joint_offset[1]);
265+
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
266+
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
263267
}
264268

265269
TEST(FourBarLinkageTransmissionLoaderTest, mechanical_reduction_not_a_number)
@@ -322,17 +326,17 @@ TEST(FourBarLinkageTransmissionLoaderTest, mechanical_reduction_not_a_number)
322326
// default kicks in for ill-defined values
323327
const std::vector<double> & actuator_reduction =
324328
four_bar_linkage_transmission->get_actuator_reduction();
325-
EXPECT_EQ(1.0, actuator_reduction[0]);
326-
EXPECT_EQ(1.0, actuator_reduction[1]);
329+
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[0], EPS));
330+
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[1], EPS));
327331

328332
const std::vector<double> & joint_reduction =
329333
four_bar_linkage_transmission->get_joint_reduction();
330-
EXPECT_EQ(1.0, joint_reduction[0]);
331-
EXPECT_EQ(1.0, joint_reduction[1]);
334+
EXPECT_THAT(1.0, DoubleNear(joint_reduction[0], EPS));
335+
EXPECT_THAT(1.0, DoubleNear(joint_reduction[1], EPS));
332336

333337
const std::vector<double> & joint_offset = four_bar_linkage_transmission->get_joint_offset();
334-
EXPECT_EQ(0.0, joint_offset[0]);
335-
EXPECT_EQ(0.0, joint_offset[1]);
338+
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
339+
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
336340
}
337341

338342
TEST(FourBarLinkageTransmissionLoaderTest, offset_ill_defined)
@@ -397,18 +401,18 @@ TEST(FourBarLinkageTransmissionLoaderTest, offset_ill_defined)
397401
// default kicks in for ill-defined values
398402
const std::vector<double> & actuator_reduction =
399403
four_bar_linkage_transmission->get_actuator_reduction();
400-
EXPECT_EQ(50.0, actuator_reduction[0]);
401-
EXPECT_EQ(-50.0, actuator_reduction[1]);
404+
EXPECT_THAT(50.0, DoubleNear(actuator_reduction[0], EPS));
405+
EXPECT_THAT(-50.0, DoubleNear(actuator_reduction[1], EPS));
402406

403407
const std::vector<double> & joint_reduction =
404408
four_bar_linkage_transmission->get_joint_reduction();
405-
EXPECT_EQ(2.0, joint_reduction[0]);
406-
EXPECT_EQ(-2.0, joint_reduction[1]);
409+
EXPECT_THAT(2.0, DoubleNear(joint_reduction[0], EPS));
410+
EXPECT_THAT(-2.0, DoubleNear(joint_reduction[1], EPS));
407411

408412
// default kicks in for ill-defined values
409413
const std::vector<double> & joint_offset = four_bar_linkage_transmission->get_joint_offset();
410-
EXPECT_EQ(0.0, joint_offset[0]);
411-
EXPECT_EQ(0.0, joint_offset[1]);
414+
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
415+
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
412416
}
413417

414418
TEST(FourBarLinkageTransmissionLoaderTest, mech_red_invalid_value)

transmission_interface/test/four_bar_linkage_transmission_test.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ using transmission_interface::FourBarLinkageTransmission;
3333
using transmission_interface::JointHandle;
3434

3535
// Floating-point value comparison threshold
36-
const double EPS = 1e-6;
36+
const double EPS = 1e-5;
3737

3838
TEST(PreconditionsTest, ExceptionThrowing)
3939
{
@@ -83,12 +83,12 @@ TEST(PreconditionsTest, AccessorValidation)
8383

8484
EXPECT_EQ(2u, trans.num_actuators());
8585
EXPECT_EQ(2u, trans.num_joints());
86-
EXPECT_EQ(2.0, trans.get_actuator_reduction()[0]);
87-
EXPECT_EQ(-2.0, trans.get_actuator_reduction()[1]);
88-
EXPECT_EQ(4.0, trans.get_joint_reduction()[0]);
89-
EXPECT_EQ(-4.0, trans.get_joint_reduction()[1]);
90-
EXPECT_EQ(1.0, trans.get_joint_offset()[0]);
91-
EXPECT_EQ(-1.0, trans.get_joint_offset()[1]);
86+
EXPECT_THAT(2.0, DoubleNear(trans.get_actuator_reduction()[0], EPS));
87+
EXPECT_THAT(-2.0, DoubleNear(trans.get_actuator_reduction()[1], EPS));
88+
EXPECT_THAT(4.0, DoubleNear(trans.get_joint_reduction()[0], EPS));
89+
EXPECT_THAT(-4.0, DoubleNear(trans.get_joint_reduction()[1], EPS));
90+
EXPECT_THAT(1.0, DoubleNear(trans.get_joint_offset()[0], EPS));
91+
EXPECT_THAT(-1.0, DoubleNear(trans.get_joint_offset()[1], EPS));
9292
}
9393

9494
void testConfigureWithBadHandles(std::string interface_name)

transmission_interface/test/simple_transmission_loader_test.cpp

Lines changed: 13 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -26,8 +26,12 @@
2626
#include "transmission_interface/simple_transmission_loader.hpp"
2727
#include "transmission_interface/transmission_loader.hpp"
2828

29+
using testing::DoubleNear;
2930
using testing::SizeIs;
3031

32+
// Floating-point value comparison threshold
33+
const double EPS = 1e-5;
34+
3135
class TransmissionPluginLoader
3236
{
3337
public:
@@ -229,8 +233,8 @@ TEST(SimpleTransmissionLoaderTest, FullSpec)
229233
transmission_interface::SimpleTransmission * simple_transmission =
230234
dynamic_cast<transmission_interface::SimpleTransmission *>(transmission.get());
231235
ASSERT_TRUE(nullptr != simple_transmission);
232-
EXPECT_EQ(325.949, simple_transmission->get_actuator_reduction());
233-
EXPECT_EQ(0.0, simple_transmission->get_joint_offset());
236+
EXPECT_THAT(325.949, DoubleNear(simple_transmission->get_actuator_reduction(), EPS));
237+
EXPECT_THAT(0.0, DoubleNear(simple_transmission->get_joint_offset(), EPS));
234238
}
235239

236240
TEST(SimpleTransmissionLoaderTest, only_mech_red_specified)
@@ -275,8 +279,8 @@ TEST(SimpleTransmissionLoaderTest, only_mech_red_specified)
275279
transmission_interface::SimpleTransmission * simple_transmission =
276280
dynamic_cast<transmission_interface::SimpleTransmission *>(transmission.get());
277281
ASSERT_TRUE(nullptr != simple_transmission);
278-
EXPECT_EQ(50.0, simple_transmission->get_actuator_reduction());
279-
EXPECT_EQ(0.0, simple_transmission->get_joint_offset());
282+
EXPECT_THAT(50.0, DoubleNear(simple_transmission->get_actuator_reduction(), EPS));
283+
EXPECT_THAT(0.0, DoubleNear(simple_transmission->get_joint_offset(), EPS));
280284
}
281285

282286
TEST(SimpleTransmissionLoaderTest, offset_and_mech_red_not_specified)
@@ -317,8 +321,8 @@ TEST(SimpleTransmissionLoaderTest, offset_and_mech_red_not_specified)
317321
transmission_interface::SimpleTransmission * simple_transmission =
318322
dynamic_cast<transmission_interface::SimpleTransmission *>(transmission.get());
319323
ASSERT_TRUE(nullptr != simple_transmission);
320-
EXPECT_EQ(1.0, simple_transmission->get_actuator_reduction());
321-
EXPECT_EQ(0.0, simple_transmission->get_joint_offset());
324+
EXPECT_THAT(1.0, DoubleNear(simple_transmission->get_actuator_reduction(), EPS));
325+
EXPECT_THAT(0.0, DoubleNear(simple_transmission->get_joint_offset(), EPS));
322326
}
323327

324328
TEST(SimpleTransmissionLoaderTest, mechanical_reduction_not_a_number)
@@ -360,7 +364,7 @@ TEST(SimpleTransmissionLoaderTest, mechanical_reduction_not_a_number)
360364
dynamic_cast<transmission_interface::SimpleTransmission *>(transmission.get());
361365
ASSERT_TRUE(nullptr != simple_transmission);
362366
// default kicks in for ill-defined values
363-
EXPECT_EQ(1.0, simple_transmission->get_actuator_reduction());
367+
EXPECT_THAT(1.0, DoubleNear(simple_transmission->get_actuator_reduction(), EPS));
364368
}
365369

366370
TEST(SimpleTransmissionLoaderTest, offset_ill_defined)
@@ -403,8 +407,8 @@ TEST(SimpleTransmissionLoaderTest, offset_ill_defined)
403407
dynamic_cast<transmission_interface::SimpleTransmission *>(transmission.get());
404408
ASSERT_TRUE(nullptr != simple_transmission);
405409
// default kicks in for ill-defined values
406-
EXPECT_EQ(0.0, simple_transmission->get_joint_offset());
407-
EXPECT_EQ(50.0, simple_transmission->get_actuator_reduction());
410+
EXPECT_THAT(0.0, DoubleNear(simple_transmission->get_joint_offset(), EPS));
411+
EXPECT_THAT(50.0, DoubleNear(simple_transmission->get_actuator_reduction(), EPS));
408412
}
409413

410414
TEST(SimpleTransmissionLoaderTest, mech_red_invalid_value)

0 commit comments

Comments
 (0)