Skip to content

Commit

Permalink
Add common::testing module
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <michael@openrobotics.org>
  • Loading branch information
mjcarroll committed Feb 23, 2022
1 parent ce7cb4a commit 6c0ac04
Show file tree
Hide file tree
Showing 15 changed files with 758 additions and 1 deletion.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ configure_file("${PROJECT_SOURCE_DIR}/cppcheck.suppress.in"
${PROJECT_BINARY_DIR}/cppcheck.suppress)

ign_configure_build(QUIT_IF_BUILD_ERRORS
COMPONENTS av events graphics profiler)
COMPONENTS av events graphics profiler testing)

#============================================================================
# Create package information
Expand Down
Empty file.
109 changes: 109 additions & 0 deletions testing/include/ignition/common/testing/AutoLogFixture.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,109 @@
/*
* Copyright (C) 2022 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef IGNITION_COMMON_TESTING_AUTOLOGFIXTURE_HH_
#define IGNITION_COMMON_TESTING_AUTOLOGFIXTURE_HH_

#include <gtest/gtest.h>

#include <memory>
#include <string>

#include "ignition/common/Console.hh"
#include "ignition/common/Filesystem.hh"
#include "ignition/common/TempDirectory.hh"
#include "ignition/common/Util.hh"

namespace ignition::common::testing
{
/// \brief A utility class that stores test logs in ~/.ignition/test_logs.
/// This functionality is needed to keep all the log information reported
/// by ignition during continuous integration. Without this, debugging
/// failing tests is significantly more difficult.
class AutoLogFixture : public ::testing::Test
{
/// \brief Setup the test fixture. This gets called by gtest.
protected: virtual void SetUp()
{
const ::testing::TestInfo *const testInfo =
::testing::UnitTest::GetInstance()->current_test_info();

std::string testName = testInfo->name();
std::string testCaseName = testInfo->test_case_name();
this->logFilename = testCaseName + "_" + testName + ".log";

this->temp = std::make_unique<TempDirectory>(
"test", "ign_common", true);
ASSERT_TRUE(this->temp->Valid());
common::setenv(IGN_HOMEDIR, this->temp->Path());

// Initialize Console
ignLogInit(common::joinPaths(this->temp->Path(), "test_logs"),
this->logFilename);

ignition::common::Console::SetVerbosity(4);

// Read the full path to the log directory.
this->logDirectory = ignLogDirectory();
}

/// \brief Get a string with the full log file path.
/// \return The full log file path as a string.
protected: std::string FullLogPath() const
{
return ignition::common::joinPaths(
this->logDirectory, this->logFilename);
}

/// \brief Get a string with all the log content loaded from the disk.
/// \return A string with all the log content.
protected: std::string LogContent() const
{
std::string loggedString;
// Open the log file, and read back the string
std::ifstream ifs(this->FullLogPath().c_str(), std::ios::in);

while (!ifs.eof())
{
std::string line;
std::getline(ifs, line);
loggedString += line;
}
return loggedString;
}

/// \brief Default destructor.
public: virtual ~AutoLogFixture()
{
ignLogClose();
EXPECT_TRUE(ignition::common::unsetenv(IGN_HOMEDIR));
}

/// \brief String with the full path of the logfile
private: std::string logFilename;

/// \brief String with the full path to log directory
private: std::string logDirectory;

/// \brief String with the base path to log directory
private: std::string logBasePath;

/// \brief Temporary directory to run test in
private: std::unique_ptr<common::TempDirectory> temp;
};
} // namespace ignition::common::testing

#endif // IGNITION_COMMON_TESTING_AUTOLOGFIXTURE_HH_
37 changes: 37 additions & 0 deletions testing/include/ignition/common/testing/BazelTestPaths.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
/*
* Copyright (C) 2022 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef IGNITION_COMMON_TESTING_BAZELTESTPATHS_HH_
#define IGNITION_COMMON_TESTING_BAZELTESTPATHS_HH_

#include <string>

#include "ignition/common/testing/TestPaths.hh"

namespace ignition::common::testing
{

class BazelTestPaths: public TestPaths
{
public: using TestPaths::TestPaths;
public: ~BazelTestPaths() override;
public: bool ProjectSourcePath(std::string &_sourceDir) override;
public: bool TestTmpPath(std::string &_tmpDir) override;
};

} // namespace ignition::common::testing

#endif // IGNITION_COMMON_TESTING_AUTOLOGFIXTURE_HH_
2 changes: 2 additions & 0 deletions testing/include/ignition/common/testing/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@

ign_install_all_headers(COMPONENT testing)
37 changes: 37 additions & 0 deletions testing/include/ignition/common/testing/CMakeTestPaths.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
/*
* Copyright (C) 2022 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef IGNITION_COMMON_TESTING_CMAKETESTPATHS_HH_
#define IGNITION_COMMON_TESTING_CMAKETESTPATHS_HH_

#include <string>

#include "ignition/common/testing/TestPaths.hh"

namespace ignition::common::testing
{

class CMakeTestPaths: public TestPaths
{
public: using TestPaths::TestPaths;
public: ~CMakeTestPaths() override;
public: bool ProjectSourcePath(std::string &_sourceDir) override;
public: bool TestTmpPath(std::string &_tmpDir) override;
};

} // namespace ignition::common::testing

#endif // IGNITION_COMMON_TESTING_CMAKETESTPATHS_HH_
118 changes: 118 additions & 0 deletions testing/include/ignition/common/testing/TestPaths.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,118 @@
/*
* Copyright (C) 2022 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef IGNITION_COMMON_TESTING_TESTPATHS_HH_
#define IGNITION_COMMON_TESTING_TESTPATHS_HH_

#include <memory>
#include <string>

#include "ignition/common/Filesystem.hh"
#include "ignition/common/TempDirectory.hh"
#include "ignition/common/Util.hh"

#ifndef TESTING_PROJECT_SOURCE_DIR
#define TESTING_PROJECT_SOURCE_DIR ""
#endif

namespace ignition::common::testing
{

//////////////////////////////////////////////////
constexpr char kTestingProjectSourceDir[] = TESTING_PROJECT_SOURCE_DIR;

//////////////////////////////////////////////////
enum class BuildType
{
kUnknown,
kCMake,
kBazel
};

//////////////////////////////////////////////////
class TestPaths
{
public: explicit TestPaths(const std::string &_projectSourcePath =
kTestingProjectSourceDir);
public: virtual ~TestPaths() = 0;
public: virtual bool ProjectSourcePath(std::string &_sourceDir) = 0;
public: virtual bool TestTmpPath(std::string &_tmpDir) = 0;

protected: std::string projectSourcePath;
};

//////////////////////////////////////////////////
std::shared_ptr<ignition::common::TempDirectory>
MakeTestTempDirectoryImpl(const std::string &_projectSourcePath,
const std::string &_prefix = "test",
const std::string &_subDir = "ignition",
bool _cleanup = true);


//////////////////////////////////////////////////
inline std::shared_ptr<ignition::common::TempDirectory>
MakeTestTempDirectory(const std::string &_prefix = "test",
const std::string &_subDir = "ignition",
bool _cleanup = true)
{
return MakeTestTempDirectoryImpl(kTestingProjectSourceDir,
_prefix,
_subDir,
_cleanup);
}

//////////////////////////////////////////////////
BuildType
TestBuildType(
const std::string &_projectSourcePath = kTestingProjectSourceDir);

//////////////////////////////////////////////////
std::unique_ptr<TestPaths>
TestPathFactory(
const std::string &_projectSourcePath = kTestingProjectSourceDir);

//////////////////////////////////////////////////
template <typename... Args>
std::string SourceFile(Args const &... args)
{
auto testPaths = TestPathFactory(kTestingProjectSourceDir);
assert(nullptr != testPaths);

std::string dataDir;
testPaths->ProjectSourcePath(dataDir);
return common::joinPaths(dataDir, args...);
}

//////////////////////////////////////////////////
template <typename... Args>
std::string TestFile(Args const &... args)
{
return SourceFile("test", args...);
}

//////////////////////////////////////////////////
template <typename... Args>
std::string TempPath(Args const &... args)
{
auto testPaths = TestPathFactory(kTestingProjectSourceDir);
std::string dataDir;
testPaths->TestTmpPath(dataDir);
return common::joinPaths(dataDir, args...);
}

} // namespace ignition::common::testing

#endif // IGNITION_COMMON_TESTING_TESTPATHS_HH_
59 changes: 59 additions & 0 deletions testing/include/ignition/common/testing/Utils.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
/*
* Copyright (C) 2022 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef IGNITION_COMMON_TESTING_UTILS_HH_
#define IGNITION_COMMON_TESTING_UTILS_HH_

#include <climits>
#include <cstdint>
#include <fstream>
#include <random>
#include <string>

namespace ignition::common::testing
{

/// \brief Get a random number based on an integer converted to string.
/// \return A random integer converted to string.
std::string getRandomNumber(int32_t _min = 0, int32_t _max = INT_MAX)
{
// Initialize random number generator.
uint32_t seed = std::random_device {}();
std::mt19937 randGenerator(seed);

// Create a random number based on an integer converted to string.
std::uniform_int_distribution<int32_t> d(_min, _max);

return std::to_string(d(randGenerator));
}

/////////////////////////////////////////////////
bool create_new_empty_file(const std::string &_filename)
{
try
{
std::fstream fs(_filename, std::ios::out);
}
catch(...)
{
return false;
}
return true;
}

} // namespace ignition::common::testing

#endif // IGNITION_COMMON_TESTING_TESTPATHS_HH_
Loading

0 comments on commit 6c0ac04

Please sign in to comment.