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

Unit Test Determinism #88

Merged
merged 3 commits into from
Nov 5, 2020
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
5 changes: 0 additions & 5 deletions rct_image_tools/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -56,11 +56,6 @@ target_link_libraries(${PROJECT_NAME}_test
rct::rct_optimizations
)

# Interface library to expose test image directory
add_library(${PROJECT_NAME}_images INTERFACE)
target_link_libraries(${PROJECT_NAME}_images INTERFACE)
target_compile_definitions(${PROJECT_NAME}_images INTERFACE TEST_SUPPORT_DIR="${CMAKE_CURRENT_SOURCE_DIR}/test/images/")

if(RCT_BUILD_TESTS)
enable_testing()
rct_add_run_tests_target()
Expand Down
2 changes: 1 addition & 1 deletion rct_image_tools/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,13 @@ add_executable(${PROJECT_NAME}_charuco_test charuco_test.cpp)
target_link_libraries(${PROJECT_NAME}_charuco_test
PRIVATE
${PROJECT_NAME}
${PROJECT_NAME}_images
GTest::GTest
GTest::Main
)
rct_gtest_discover_tests(${PROJECT_NAME}_charuco_test)
add_dependencies(${PROJECT_NAME}_charuco_test ${PROJECT_NAME})
add_dependencies(run_tests ${PROJECT_NAME}_charuco_test)
target_compile_definitions(${PROJECT_NAME}_charuco_test PUBLIC TEST_SUPPORT_DIR="${CMAKE_CURRENT_SOURCE_DIR}/images/")

# Install the test executables so they can be run independently later if needed
install(
Expand Down
9 changes: 6 additions & 3 deletions rct_optimizations/include/rct_optimizations/dh_chain.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,8 @@ struct DHTransform

DHTransform(const Eigen::Vector4d& params_, DHJointType type_, const std::string& name_);

DHTransform(const Eigen::Vector4d& params_, DHJointType type_, const std::string& name_, std::size_t random_seed);

/**
* @brief Creates the homogoneous transformation from the previous link to the current link
* @param joint_value - The joint value to apply when caluclating the transform
Expand Down Expand Up @@ -114,6 +116,8 @@ struct DHTransform
double min = -M_PI;
/** @brief Label for this transform */
std::string name;
/** @brief Seed for random number generator */
const std::size_t random_seed;
};

/**
Expand All @@ -122,8 +126,7 @@ struct DHTransform
class DHChain
{
public:
DHChain(std::vector<DHTransform> transforms,
const Eigen::Isometry3d& base_offset = Eigen::Isometry3d::Identity());
DHChain(std::vector<DHTransform> transforms, const Eigen::Isometry3d& base_offset = Eigen::Isometry3d::Identity());

DHChain(const DHChain& rhs, const Eigen::MatrixX4d& dh_offsets);

Expand Down Expand Up @@ -154,7 +157,7 @@ class DHChain
Isometry3<T> getFK(const Eigen::Matrix<T, Eigen::Dynamic, 1>& joint_values,
const Eigen::Matrix<T, Eigen::Dynamic, 4>& offsets) const
{
if (joint_values.size() > dof())
if (static_cast<std::size_t>(joint_values.size()) > dof())
{
std::stringstream ss;
ss << "Joint values size (" << joint_values.size() << ") is larger than the chain DoF (" << dof() << ")";
Expand Down
12 changes: 9 additions & 3 deletions rct_optimizations/src/rct_optimizations/dh_chain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,22 +5,28 @@ namespace rct_optimizations
{
// DH Transform

DHTransform::DHTransform(const Eigen::Vector4d &params_, DHJointType type_)
: DHTransform(params_, type_, "joint")
DHTransform::DHTransform(const Eigen::Vector4d& params_, DHJointType type_)
: DHTransform(params_, type_, "joint", std::random_device{}())
{
}

DHTransform::DHTransform(const Eigen::Vector4d &params_, DHJointType type_, const std::string& name_)
: DHTransform(params_, type_, name_, std::random_device{}())
{
}

DHTransform::DHTransform(const Eigen::Vector4d& params_, DHJointType type_, const std::string& name_, std::size_t random_seed_)
: params(params_)
, type(type_)
, name(name_)
, random_seed(random_seed_)
{
}

double DHTransform::createRandomJointValue() const
{
// Create a static random number generator so that this object does not get continuously re-instantiated
static std::mt19937 mt_rand = std::mt19937(std::random_device{}());
static std::mt19937 mt_rand = std::mt19937(random_seed);

// Create a new uniform distribution object with the current min and max values
std::uniform_real_distribution<double> dist(min, max);
Expand Down
4 changes: 2 additions & 2 deletions rct_optimizations/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,9 @@ add_library(${PROJECT_NAME}_test_support
src/observation_creator.cpp
src/dh_chain_observation_creator.cpp
src/utilities.cpp)

target_link_libraries(${PROJECT_NAME}_test_support ${PROJECT_NAME})
target_include_directories(${PROJECT_NAME}_test_support PUBLIC include)
target_compile_definitions(${PROJECT_NAME}_test_support PUBLIC RCT_RANDOM_SEED=0)

# The actual tests...

Expand Down Expand Up @@ -50,7 +50,7 @@ add_dependencies(run_tests ${PROJECT_NAME}_extrinsic_hand_eye_dh_chain_tests)
# Covariance
# The expectations for the covariance matrices of these tests tends to be flaky due to random number generation, so let's only build but not run these tests
add_executable(${PROJECT_NAME}_covariance_tests covariance_utest.cpp)
target_link_libraries(${PROJECT_NAME}_covariance_tests PRIVATE ${PROJECT_NAME} GTest::GTest GTest::Main)
target_link_libraries(${PROJECT_NAME}_covariance_tests PRIVATE ${PROJECT_NAME} ${PROJECT_NAME}_test_support GTest::GTest GTest::Main)
add_dependencies(${PROJECT_NAME}_covariance_tests ${PROJECT_NAME})

# Homography
Expand Down
6 changes: 4 additions & 2 deletions rct_optimizations/test/covariance_utest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,16 +8,18 @@
#include <rct_optimizations/covariance_analysis.h>
#include <rct_optimizations/circle_fit.h>

static std::mt19937 RAND_GEN(RCT_RANDOM_SEED);

template <typename T>
T perturb_normal(T val, T std_dev)
{
return std::bind(std::normal_distribution<T>{val, std_dev}, std::mt19937(std::random_device{}()))();
return std::bind(std::normal_distribution<T>{val, std_dev}, RAND_GEN)();
}

template <typename T>
T perturb_random(T mean, T offset)
{
return std::bind(std::uniform_real_distribution<T>{mean - offset, mean + offset}, std::mt19937(std::random_device{}()))();
return std::bind(std::uniform_real_distribution<T>{mean - offset, mean + offset}, RAND_GEN)();
}

class CircleFitUnit : public ::testing::Test
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,8 +88,7 @@ class DHChainCalTest : public ::testing::Test
EXPECT_EQ(problem.target_chain.dof(), result.target_chain_dh_offsets.rows());

// Test the result by moving the robot around to a lot of positions and seeing of the results match
DHChain optimized_chain = test::createChain(problem.camera_chain.getDHTable() + result.camera_chain_dh_offsets,
problem.camera_chain.getJointTypes());
DHChain optimized_chain(problem.camera_chain, result.camera_chain_dh_offsets);

std::cout << "original chain:\n" << problem.camera_chain.getDHTable().matrix() << std::endl << std::endl;
std::cout << "optimized chain:\n" << optimized_chain.getDHTable().matrix() << std::endl << std::endl;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,8 +93,7 @@ class DHChainMeasurementTest : public ::testing::Test
EXPECT_EQ(problem.target_chain.dof(), result.target_chain_dh_offsets.rows());

// Test the result by moving the robot around to a lot of positions and seeing of the results match
DHChain optimized_chain = test::createChain(problem.camera_chain.getDHTable() + result.camera_chain_dh_offsets,
problem.camera_chain.getJointTypes());
DHChain optimized_chain(problem.camera_chain, result.camera_chain_dh_offsets);

std::cout << "true chain:\n" << camera_chain_truth.getDHTable().matrix() << std::endl << std::endl;
std::cout << "optimized chain:\n" << optimized_chain.getDHTable().matrix() << std::endl << std::endl;
Expand Down
2 changes: 1 addition & 1 deletion rct_optimizations/test/dh_parameter_utest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ TEST(DHChain, NoisyFKTest)
DHChain robot = test::createABBIRB2400();

// Create random gaussian-distributed DH offsets
std::mt19937 mt_rand(std::random_device{}());
std::mt19937 mt_rand(RCT_RANDOM_SEED);
std::uniform_real_distribution<double> dist(-0.01, 0.01);

Eigen::MatrixX4d dh_offsets = Eigen::MatrixX4d(robot.dof(), 4).unaryExpr([&](float) { return dist(mt_rand); });
Expand Down
2 changes: 1 addition & 1 deletion rct_optimizations/test/homography_utest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ TEST_F(HomographyTest, NoisyCorrespondences)
true));

// Add Gaussian noise to the image features
std::mt19937 mt_rand(std::random_device{}());
std::mt19937 mt_rand(RCT_RANDOM_SEED);
const double stdev = 1.0;
std::normal_distribution<double> dist(0.0, stdev);
for (Correspondence2D3D &corr : correspondence_set)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,15 +73,6 @@ Eigen::Isometry3d perturbPose(const Eigen::Isometry3d &pose,
double spatial_noise,
double angle_noise);


/**
* @brief Creates a DH chain form
* @param dh
* @param joint_types
* @return
*/
DHChain createChain(const Eigen::MatrixXd &dh, const std::vector<DHJointType> &joint_types);

/**
* @brief Creates a DH parameter-based robot representation of an ABB IRB2400
* @return
Expand Down
6 changes: 3 additions & 3 deletions rct_optimizations/test/noise_qualification_utest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ TEST(NoiseTest, QuatMeanTest)
Eigen::Quaterniond q_mean(1, 0, 0, 0);

// Make a lot of quaternions randomly oriented about the x-axis
std::mt19937 mt_rand(std::random_device{}());
std::mt19937 mt_rand(RCT_RANDOM_SEED);
double stdev = M_PI / 8.0;
std::normal_distribution<double> dist(0.0, stdev);

Expand All @@ -47,7 +47,7 @@ class NoiseQualification2D : public ::testing::Test
: target(TARGET_ROWS, TARGET_COLS, SPACING)
, camera(test::makeKinectCamera())
, target_to_camera(Eigen::Isometry3d::Identity())
, mt_rand(std::random_device{}())
, mt_rand(RCT_RANDOM_SEED)
{
// Put the camera over the center of the target facing normal to the target
double x = static_cast<double>(TARGET_ROWS - 1) * SPACING / 2.0;
Expand Down Expand Up @@ -212,7 +212,7 @@ class NoiseQualification3D : public ::testing::Test
NoiseQualification3D()
: target(test::Target(TARGET_ROWS, TARGET_COLS, SPACING))
, target_to_camera(Eigen::Isometry3d::Identity())
, mt_rand(std::random_device{}())
, mt_rand(RCT_RANDOM_SEED)
{
// Put the camera over the center of the target facing normal to the target
double x = static_cast<double>(TARGET_ROWS - 1) * SPACING / 2.0;
Expand Down
40 changes: 11 additions & 29 deletions rct_optimizations/test/src/utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ Camera makeKinectCamera()

Eigen::Isometry3d perturbPose(const Eigen::Isometry3d& pose, double spatial_noise, double angle_noise)
{
auto mt_rand = std::mt19937(std::random_device{}());
auto mt_rand = std::mt19937(RCT_RANDOM_SEED);

auto spatial_dist = std::bind(std::uniform_real_distribution<double>{-spatial_noise, spatial_noise}, mt_rand);
auto angle_dist = std::bind(std::uniform_real_distribution<double>{-angle_noise, angle_noise}, mt_rand);
Expand All @@ -40,21 +40,6 @@ Eigen::Isometry3d perturbPose(const Eigen::Isometry3d& pose, double spatial_nois
return new_pose;
}

DHChain createChain(const Eigen::MatrixXd &dh, const std::vector<DHJointType> &joint_types)
{
if (dh.rows() != joint_types.size())
throw OptimizationException("DH table rows does not match joint types size");

std::vector<DHTransform> joints;
joints.reserve(joint_types.size());
for (std::size_t i = 0; i < joint_types.size(); ++i)
{
joints.push_back(DHTransform(dh.row(i), joint_types.at(i)));
}

return DHChain(joints);
}

DHChain createABBIRB2400()
{
std::vector<DHTransform> transforms;
Expand All @@ -69,12 +54,12 @@ DHChain createABBIRB2400()
p5 << 0.0, 0.0, 0.0, -M_PI / 2.0;
p6 << 0.085, M_PI, 0.0, 0.0;

transforms.emplace_back(p1, DHJointType::REVOLUTE, "j1");
transforms.emplace_back(p2, DHJointType::REVOLUTE, "j2");
transforms.emplace_back(p3, DHJointType::REVOLUTE, "j3");
transforms.emplace_back(p4, DHJointType::REVOLUTE, "j4");
transforms.emplace_back(p5, DHJointType::REVOLUTE, "j5");
transforms.emplace_back(p6, DHJointType::REVOLUTE, "j6");
transforms.emplace_back(p1, DHJointType::REVOLUTE, "j1", RCT_RANDOM_SEED);
transforms.emplace_back(p2, DHJointType::REVOLUTE, "j2", RCT_RANDOM_SEED);
transforms.emplace_back(p3, DHJointType::REVOLUTE, "j3", RCT_RANDOM_SEED);
transforms.emplace_back(p4, DHJointType::REVOLUTE, "j4", RCT_RANDOM_SEED);
transforms.emplace_back(p5, DHJointType::REVOLUTE, "j5", RCT_RANDOM_SEED);
transforms.emplace_back(p6, DHJointType::REVOLUTE, "j6", RCT_RANDOM_SEED);

return DHChain(transforms);
}
Expand All @@ -90,14 +75,14 @@ DHChain createTwoAxisPositioner()

// Add the first DH transform
{
DHTransform t(p1, DHJointType::REVOLUTE, "j1");
DHTransform t(p1, DHJointType::REVOLUTE, "j1", RCT_RANDOM_SEED);
t.max = M_PI;
t.min = -M_PI;
transforms.push_back(t);
}
// Add the second DH transform
{
DHTransform dh_transform(p2, DHJointType::REVOLUTE, "j2");
DHTransform dh_transform(p2, DHJointType::REVOLUTE, "j2", RCT_RANDOM_SEED);
dh_transform.max = 2.0 * M_PI;
dh_transform.min = -2.0 * M_PI;
transforms.push_back(dh_transform);
Expand All @@ -113,7 +98,7 @@ DHChain createTwoAxisPositioner()

DHChain perturbDHChain(const DHChain &in, const double stddev)
{
std::mt19937 mt_rand(std::random_device{}());
std::mt19937 mt_rand(RCT_RANDOM_SEED);
std::normal_distribution<double> norm(0.0, stddev);

// Get the joint types and nominal DH table
Expand All @@ -127,13 +112,10 @@ DHChain perturbDHChain(const DHChain &in, const double stddev)
transforms.reserve(joint_types.size());
for (std::size_t i = 0; i < joint_types.size(); ++i)
{
transforms.emplace_back(dh.row(i), joint_types[i], "j" + std::to_string(i + 1));
transforms.emplace_back(dh.row(i), joint_types[i], "j" + std::to_string(i + 1), RCT_RANDOM_SEED);
}
return DHChain(transforms, in.getBaseOffset());
}

} // namespace test
} // namespace rct_optimizations