Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Issue #1235: improve transmission tests (backport #1238) #1242

Merged
merged 1 commit into from
Dec 22, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,12 @@
#include "transmission_interface/differential_transmission_loader.hpp"
#include "transmission_interface/transmission_loader.hpp"

using testing::DoubleNear;
using testing::SizeIs;

// Floating-point value comparison threshold
const double EPS = 1e-5;

class TransmissionPluginLoader
{
public:
Expand Down Expand Up @@ -113,16 +117,16 @@ TEST(DifferentialTransmissionLoaderTest, FullSpec)

const std::vector<double> & actuator_reduction =
differential_transmission->get_actuator_reduction();
EXPECT_EQ(50.0, actuator_reduction[0]);
EXPECT_EQ(-50.0, actuator_reduction[1]);
EXPECT_THAT(50.0, DoubleNear(actuator_reduction[0], EPS));
EXPECT_THAT(-50.0, DoubleNear(actuator_reduction[1], EPS));

const std::vector<double> & joint_reduction = differential_transmission->get_joint_reduction();
EXPECT_EQ(2.0, joint_reduction[0]);
EXPECT_EQ(-2.0, joint_reduction[1]);
EXPECT_THAT(2.0, DoubleNear(joint_reduction[0], EPS));
EXPECT_THAT(-2.0, DoubleNear(joint_reduction[1], EPS));

const std::vector<double> & joint_offset = differential_transmission->get_joint_offset();
EXPECT_EQ(0.5, joint_offset[0]);
EXPECT_EQ(-0.5, joint_offset[1]);
EXPECT_THAT(0.5, DoubleNear(joint_offset[0], EPS));
EXPECT_THAT(-0.5, DoubleNear(joint_offset[1], EPS));
}

TEST(DifferentialTransmissionLoaderTest, only_mech_red_specified)
Expand Down Expand Up @@ -184,16 +188,16 @@ TEST(DifferentialTransmissionLoaderTest, only_mech_red_specified)

const std::vector<double> & actuator_reduction =
differential_transmission->get_actuator_reduction();
EXPECT_EQ(50.0, actuator_reduction[0]);
EXPECT_EQ(-50.0, actuator_reduction[1]);
EXPECT_THAT(50.0, DoubleNear(actuator_reduction[0], EPS));
EXPECT_THAT(-50.0, DoubleNear(actuator_reduction[1], EPS));

const std::vector<double> & joint_reduction = differential_transmission->get_joint_reduction();
EXPECT_EQ(1.0, joint_reduction[0]);
EXPECT_EQ(1.0, joint_reduction[1]);
EXPECT_THAT(1.0, DoubleNear(joint_reduction[0], EPS));
EXPECT_THAT(1.0, DoubleNear(joint_reduction[1], EPS));

const std::vector<double> & joint_offset = differential_transmission->get_joint_offset();
EXPECT_EQ(0.0, joint_offset[0]);
EXPECT_EQ(0.0, joint_offset[1]);
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
}

TEST(SimpleTransmissionLoaderTest, offset_and_mech_red_not_specified)
Expand Down Expand Up @@ -247,16 +251,16 @@ TEST(SimpleTransmissionLoaderTest, offset_and_mech_red_not_specified)

const std::vector<double> & actuator_reduction =
differential_transmission->get_actuator_reduction();
EXPECT_EQ(1.0, actuator_reduction[0]);
EXPECT_EQ(1.0, actuator_reduction[1]);
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[0], EPS));
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[1], EPS));

const std::vector<double> & joint_reduction = differential_transmission->get_joint_reduction();
EXPECT_EQ(1.0, joint_reduction[0]);
EXPECT_EQ(1.0, joint_reduction[1]);
EXPECT_THAT(1.0, DoubleNear(joint_reduction[0], EPS));
EXPECT_THAT(1.0, DoubleNear(joint_reduction[1], EPS));

const std::vector<double> & joint_offset = differential_transmission->get_joint_offset();
EXPECT_EQ(0.0, joint_offset[0]);
EXPECT_EQ(0.0, joint_offset[1]);
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
}

TEST(DifferentialTransmissionLoaderTest, mechanical_reduction_not_a_number)
Expand Down Expand Up @@ -319,16 +323,16 @@ TEST(DifferentialTransmissionLoaderTest, mechanical_reduction_not_a_number)
// default kicks in for ill-defined values
const std::vector<double> & actuator_reduction =
differential_transmission->get_actuator_reduction();
EXPECT_EQ(1.0, actuator_reduction[0]);
EXPECT_EQ(1.0, actuator_reduction[1]);
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[0], EPS));
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[1], EPS));

const std::vector<double> & joint_reduction = differential_transmission->get_joint_reduction();
EXPECT_EQ(1.0, joint_reduction[0]);
EXPECT_EQ(1.0, joint_reduction[1]);
EXPECT_THAT(1.0, DoubleNear(joint_reduction[0], EPS));
EXPECT_THAT(1.0, DoubleNear(joint_reduction[1], EPS));

const std::vector<double> & joint_offset = differential_transmission->get_joint_offset();
EXPECT_EQ(0.0, joint_offset[0]);
EXPECT_EQ(0.0, joint_offset[1]);
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
}

TEST(DifferentialTransmissionLoaderTest, offset_ill_defined)
Expand Down Expand Up @@ -393,17 +397,17 @@ TEST(DifferentialTransmissionLoaderTest, offset_ill_defined)
// default kicks in for ill-defined values
const std::vector<double> & actuator_reduction =
differential_transmission->get_actuator_reduction();
EXPECT_EQ(50.0, actuator_reduction[0]);
EXPECT_EQ(-50.0, actuator_reduction[1]);
EXPECT_THAT(50.0, DoubleNear(actuator_reduction[0], EPS));
EXPECT_THAT(-50.0, DoubleNear(actuator_reduction[1], EPS));

const std::vector<double> & joint_reduction = differential_transmission->get_joint_reduction();
EXPECT_EQ(2.0, joint_reduction[0]);
EXPECT_EQ(-2.0, joint_reduction[1]);
EXPECT_THAT(2.0, DoubleNear(joint_reduction[0], EPS));
EXPECT_THAT(-2.0, DoubleNear(joint_reduction[1], EPS));

// default kicks in for ill-defined values
const std::vector<double> & joint_offset = differential_transmission->get_joint_offset();
EXPECT_EQ(0.0, joint_offset[0]);
EXPECT_EQ(0.0, joint_offset[1]);
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
}

TEST(DifferentialTransmissionLoaderTest, mech_red_invalid_value)
Expand Down
14 changes: 7 additions & 7 deletions transmission_interface/test/differential_transmission_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ using transmission_interface::DifferentialTransmission;
using transmission_interface::Exception;
using transmission_interface::JointHandle;
// Floating-point value comparison threshold
const double EPS = 1e-6;
const double EPS = 1e-5;

TEST(PreconditionsTest, ExceptionThrowing)
{
Expand Down Expand Up @@ -79,12 +79,12 @@ TEST(PreconditionsTest, AccessorValidation)

EXPECT_EQ(2u, trans.num_actuators());
EXPECT_EQ(2u, trans.num_joints());
EXPECT_EQ(2.0, trans.get_actuator_reduction()[0]);
EXPECT_EQ(-2.0, trans.get_actuator_reduction()[1]);
EXPECT_EQ(4.0, trans.get_joint_reduction()[0]);
EXPECT_EQ(-4.0, trans.get_joint_reduction()[1]);
EXPECT_EQ(1.0, trans.get_joint_offset()[0]);
EXPECT_EQ(-1.0, trans.get_joint_offset()[1]);
EXPECT_THAT(2.0, DoubleNear(trans.get_actuator_reduction()[0], EPS));
EXPECT_THAT(-2.0, DoubleNear(trans.get_actuator_reduction()[1], EPS));
EXPECT_THAT(4.0, DoubleNear(trans.get_joint_reduction()[0], EPS));
EXPECT_THAT(-4.0, DoubleNear(trans.get_joint_reduction()[1], EPS));
EXPECT_THAT(1.0, DoubleNear(trans.get_joint_offset()[0], EPS));
EXPECT_THAT(-1.0, DoubleNear(trans.get_joint_offset()[1], EPS));
}

void testConfigureWithBadHandles(std::string interface_name)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,12 @@
#include "transmission_interface/four_bar_linkage_transmission_loader.hpp"
#include "transmission_interface/transmission_loader.hpp"

using testing::DoubleNear;
using testing::SizeIs;

// Floating-point value comparison threshold
const double EPS = 1e-5;

class TransmissionPluginLoader
{
public:
Expand Down Expand Up @@ -113,17 +117,17 @@ TEST(FourBarLinkageTransmissionLoaderTest, FullSpec)

const std::vector<double> & actuator_reduction =
four_bar_linkage_transmission->get_actuator_reduction();
EXPECT_EQ(50.0, actuator_reduction[0]);
EXPECT_EQ(-50.0, actuator_reduction[1]);
EXPECT_THAT(50.0, DoubleNear(actuator_reduction[0], EPS));
EXPECT_THAT(-50.0, DoubleNear(actuator_reduction[1], EPS));

const std::vector<double> & joint_reduction =
four_bar_linkage_transmission->get_joint_reduction();
EXPECT_EQ(2.0, joint_reduction[0]);
EXPECT_EQ(-2.0, joint_reduction[1]);
EXPECT_THAT(2.0, DoubleNear(joint_reduction[0], EPS));
EXPECT_THAT(-2.0, DoubleNear(joint_reduction[1], EPS));

const std::vector<double> & joint_offset = four_bar_linkage_transmission->get_joint_offset();
EXPECT_EQ(0.5, joint_offset[0]);
EXPECT_EQ(-0.5, joint_offset[1]);
EXPECT_THAT(0.5, DoubleNear(joint_offset[0], EPS));
EXPECT_THAT(-0.5, DoubleNear(joint_offset[1], EPS));
}

TEST(FourBarLinkageTransmissionLoaderTest, only_mech_red_specified)
Expand Down Expand Up @@ -185,17 +189,17 @@ TEST(FourBarLinkageTransmissionLoaderTest, only_mech_red_specified)

const std::vector<double> & actuator_reduction =
four_bar_linkage_transmission->get_actuator_reduction();
EXPECT_EQ(50.0, actuator_reduction[0]);
EXPECT_EQ(-50.0, actuator_reduction[1]);
EXPECT_THAT(50.0, DoubleNear(actuator_reduction[0], EPS));
EXPECT_THAT(-50.0, DoubleNear(actuator_reduction[1], EPS));

const std::vector<double> & joint_reduction =
four_bar_linkage_transmission->get_joint_reduction();
EXPECT_EQ(1.0, joint_reduction[0]);
EXPECT_EQ(1.0, joint_reduction[1]);
EXPECT_THAT(1.0, DoubleNear(joint_reduction[0], EPS));
EXPECT_THAT(1.0, DoubleNear(joint_reduction[1], EPS));

const std::vector<double> & joint_offset = four_bar_linkage_transmission->get_joint_offset();
EXPECT_EQ(0.0, joint_offset[0]);
EXPECT_EQ(0.0, joint_offset[1]);
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
}

TEST(DifferentialTransmissionLoaderTest, offset_and_mech_red_not_specified)
Expand Down Expand Up @@ -249,17 +253,17 @@ TEST(DifferentialTransmissionLoaderTest, offset_and_mech_red_not_specified)

const std::vector<double> & actuator_reduction =
four_bar_linkage_transmission->get_actuator_reduction();
EXPECT_EQ(1.0, actuator_reduction[0]);
EXPECT_EQ(1.0, actuator_reduction[1]);
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[0], EPS));
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[1], EPS));

const std::vector<double> & joint_reduction =
four_bar_linkage_transmission->get_joint_reduction();
EXPECT_EQ(1.0, joint_reduction[0]);
EXPECT_EQ(1.0, joint_reduction[1]);
EXPECT_THAT(1.0, DoubleNear(joint_reduction[0], EPS));
EXPECT_THAT(1.0, DoubleNear(joint_reduction[1], EPS));

const std::vector<double> & joint_offset = four_bar_linkage_transmission->get_joint_offset();
EXPECT_EQ(0.0, joint_offset[0]);
EXPECT_EQ(0.0, joint_offset[1]);
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
}

TEST(FourBarLinkageTransmissionLoaderTest, mechanical_reduction_not_a_number)
Expand Down Expand Up @@ -322,17 +326,17 @@ TEST(FourBarLinkageTransmissionLoaderTest, mechanical_reduction_not_a_number)
// default kicks in for ill-defined values
const std::vector<double> & actuator_reduction =
four_bar_linkage_transmission->get_actuator_reduction();
EXPECT_EQ(1.0, actuator_reduction[0]);
EXPECT_EQ(1.0, actuator_reduction[1]);
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[0], EPS));
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[1], EPS));

const std::vector<double> & joint_reduction =
four_bar_linkage_transmission->get_joint_reduction();
EXPECT_EQ(1.0, joint_reduction[0]);
EXPECT_EQ(1.0, joint_reduction[1]);
EXPECT_THAT(1.0, DoubleNear(joint_reduction[0], EPS));
EXPECT_THAT(1.0, DoubleNear(joint_reduction[1], EPS));

const std::vector<double> & joint_offset = four_bar_linkage_transmission->get_joint_offset();
EXPECT_EQ(0.0, joint_offset[0]);
EXPECT_EQ(0.0, joint_offset[1]);
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
}

TEST(FourBarLinkageTransmissionLoaderTest, offset_ill_defined)
Expand Down Expand Up @@ -397,18 +401,18 @@ TEST(FourBarLinkageTransmissionLoaderTest, offset_ill_defined)
// default kicks in for ill-defined values
const std::vector<double> & actuator_reduction =
four_bar_linkage_transmission->get_actuator_reduction();
EXPECT_EQ(50.0, actuator_reduction[0]);
EXPECT_EQ(-50.0, actuator_reduction[1]);
EXPECT_THAT(50.0, DoubleNear(actuator_reduction[0], EPS));
EXPECT_THAT(-50.0, DoubleNear(actuator_reduction[1], EPS));

const std::vector<double> & joint_reduction =
four_bar_linkage_transmission->get_joint_reduction();
EXPECT_EQ(2.0, joint_reduction[0]);
EXPECT_EQ(-2.0, joint_reduction[1]);
EXPECT_THAT(2.0, DoubleNear(joint_reduction[0], EPS));
EXPECT_THAT(-2.0, DoubleNear(joint_reduction[1], EPS));

// default kicks in for ill-defined values
const std::vector<double> & joint_offset = four_bar_linkage_transmission->get_joint_offset();
EXPECT_EQ(0.0, joint_offset[0]);
EXPECT_EQ(0.0, joint_offset[1]);
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
}

TEST(FourBarLinkageTransmissionLoaderTest, mech_red_invalid_value)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ using transmission_interface::FourBarLinkageTransmission;
using transmission_interface::JointHandle;

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

TEST(PreconditionsTest, ExceptionThrowing)
{
Expand Down Expand Up @@ -83,12 +83,12 @@ TEST(PreconditionsTest, AccessorValidation)

EXPECT_EQ(2u, trans.num_actuators());
EXPECT_EQ(2u, trans.num_joints());
EXPECT_EQ(2.0, trans.get_actuator_reduction()[0]);
EXPECT_EQ(-2.0, trans.get_actuator_reduction()[1]);
EXPECT_EQ(4.0, trans.get_joint_reduction()[0]);
EXPECT_EQ(-4.0, trans.get_joint_reduction()[1]);
EXPECT_EQ(1.0, trans.get_joint_offset()[0]);
EXPECT_EQ(-1.0, trans.get_joint_offset()[1]);
EXPECT_THAT(2.0, DoubleNear(trans.get_actuator_reduction()[0], EPS));
EXPECT_THAT(-2.0, DoubleNear(trans.get_actuator_reduction()[1], EPS));
EXPECT_THAT(4.0, DoubleNear(trans.get_joint_reduction()[0], EPS));
EXPECT_THAT(-4.0, DoubleNear(trans.get_joint_reduction()[1], EPS));
EXPECT_THAT(1.0, DoubleNear(trans.get_joint_offset()[0], EPS));
EXPECT_THAT(-1.0, DoubleNear(trans.get_joint_offset()[1], EPS));
}

void testConfigureWithBadHandles(std::string interface_name)
Expand Down
22 changes: 13 additions & 9 deletions transmission_interface/test/simple_transmission_loader_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,12 @@
#include "transmission_interface/simple_transmission_loader.hpp"
#include "transmission_interface/transmission_loader.hpp"

using testing::DoubleNear;
using testing::SizeIs;

// Floating-point value comparison threshold
const double EPS = 1e-5;

class TransmissionPluginLoader
{
public:
Expand Down Expand Up @@ -229,8 +233,8 @@ TEST(SimpleTransmissionLoaderTest, FullSpec)
transmission_interface::SimpleTransmission * simple_transmission =
dynamic_cast<transmission_interface::SimpleTransmission *>(transmission.get());
ASSERT_TRUE(nullptr != simple_transmission);
EXPECT_EQ(325.949, simple_transmission->get_actuator_reduction());
EXPECT_EQ(0.0, simple_transmission->get_joint_offset());
EXPECT_THAT(325.949, DoubleNear(simple_transmission->get_actuator_reduction(), EPS));
EXPECT_THAT(0.0, DoubleNear(simple_transmission->get_joint_offset(), EPS));
}

TEST(SimpleTransmissionLoaderTest, only_mech_red_specified)
Expand Down Expand Up @@ -275,8 +279,8 @@ TEST(SimpleTransmissionLoaderTest, only_mech_red_specified)
transmission_interface::SimpleTransmission * simple_transmission =
dynamic_cast<transmission_interface::SimpleTransmission *>(transmission.get());
ASSERT_TRUE(nullptr != simple_transmission);
EXPECT_EQ(50.0, simple_transmission->get_actuator_reduction());
EXPECT_EQ(0.0, simple_transmission->get_joint_offset());
EXPECT_THAT(50.0, DoubleNear(simple_transmission->get_actuator_reduction(), EPS));
EXPECT_THAT(0.0, DoubleNear(simple_transmission->get_joint_offset(), EPS));
}

TEST(SimpleTransmissionLoaderTest, offset_and_mech_red_not_specified)
Expand Down Expand Up @@ -317,8 +321,8 @@ TEST(SimpleTransmissionLoaderTest, offset_and_mech_red_not_specified)
transmission_interface::SimpleTransmission * simple_transmission =
dynamic_cast<transmission_interface::SimpleTransmission *>(transmission.get());
ASSERT_TRUE(nullptr != simple_transmission);
EXPECT_EQ(1.0, simple_transmission->get_actuator_reduction());
EXPECT_EQ(0.0, simple_transmission->get_joint_offset());
EXPECT_THAT(1.0, DoubleNear(simple_transmission->get_actuator_reduction(), EPS));
EXPECT_THAT(0.0, DoubleNear(simple_transmission->get_joint_offset(), EPS));
}

TEST(SimpleTransmissionLoaderTest, mechanical_reduction_not_a_number)
Expand Down Expand Up @@ -360,7 +364,7 @@ TEST(SimpleTransmissionLoaderTest, mechanical_reduction_not_a_number)
dynamic_cast<transmission_interface::SimpleTransmission *>(transmission.get());
ASSERT_TRUE(nullptr != simple_transmission);
// default kicks in for ill-defined values
EXPECT_EQ(1.0, simple_transmission->get_actuator_reduction());
EXPECT_THAT(1.0, DoubleNear(simple_transmission->get_actuator_reduction(), EPS));
}

TEST(SimpleTransmissionLoaderTest, offset_ill_defined)
Expand Down Expand Up @@ -403,8 +407,8 @@ TEST(SimpleTransmissionLoaderTest, offset_ill_defined)
dynamic_cast<transmission_interface::SimpleTransmission *>(transmission.get());
ASSERT_TRUE(nullptr != simple_transmission);
// default kicks in for ill-defined values
EXPECT_EQ(0.0, simple_transmission->get_joint_offset());
EXPECT_EQ(50.0, simple_transmission->get_actuator_reduction());
EXPECT_THAT(0.0, DoubleNear(simple_transmission->get_joint_offset(), EPS));
EXPECT_THAT(50.0, DoubleNear(simple_transmission->get_actuator_reduction(), EPS));
}

TEST(SimpleTransmissionLoaderTest, mech_red_invalid_value)
Expand Down
Loading
Loading