From 07e916143501395127a79229ffc060428a5539c6 Mon Sep 17 00:00:00 2001 From: Bi0T1N <28802083+Bi0T1N@users.noreply.github.com> Date: Tue, 7 Feb 2023 22:00:59 +0100 Subject: [PATCH 01/23] Cherry-pick the python3 embedSdf script and tests (#884) These won't be used as part of the cmake build on this branch, but are useful for generating the same file from bazel. Co-authored-by: Bi0T1N Co-authored-by: Michael Carroll Signed-off-by: Michael Carroll --- sdf/CMakeLists.txt | 4 +- sdf/embedSdf.py | 151 +++++++++++++++++++++++++++++++++++++++++++++ src/SDF_TEST.cc | 56 +++++++++++++++++ 3 files changed, 209 insertions(+), 2 deletions(-) create mode 100644 sdf/embedSdf.py diff --git a/sdf/CMakeLists.txt b/sdf/CMakeLists.txt index 127458d91..e4b6a78e0 100644 --- a/sdf/CMakeLists.txt +++ b/sdf/CMakeLists.txt @@ -20,8 +20,8 @@ execute_process( OUTPUT_FILE "${PROJECT_BINARY_DIR}/src/EmbeddedSdf.cc" ) -# Generate aggregated SDF description files for use by the sdformat.org -# website. If the description files change, the generated full*.sdf files need +# Generate aggregated SDF description files for use by the sdformat.org +# website. If the description files change, the generated full*.sdf files need # to be removed before running this target. if (GZ_PROGRAM) diff --git a/sdf/embedSdf.py b/sdf/embedSdf.py new file mode 100644 index 000000000..b89607fa6 --- /dev/null +++ b/sdf/embedSdf.py @@ -0,0 +1,151 @@ +#!/usr/bin/env python3 +import inspect +from pathlib import Path, PurePosixPath + +""""Script for generating a C++ file that contains the content from all SDF files""" + +# The list of supported SDF specification versions. This will let us drop +# versions without removing the directories. +SUPPORTED_SDF_VERSIONS = ['1.10', '1.9', '1.8', '1.7', '1.6', '1.5', '1.4', '1.3', '1.2'] + +# The list of supported SDF conversions. This list includes versions that +# a user can convert an existing SDF version to. +SUPPORTED_SDF_CONVERSIONS = ['1.10', '1.9', '1.8', '1.7', '1.6', '1.5', '1.4', '1.3'] + +# whitespace indentation for C++ code +INDENTATION = ' ' +# newline character +NEWLINE = '\n' + +def get_copyright_notice() -> str: + """ + Provides the copyrigt notice for the C++ file + + :returns: copyright notice + """ + res = inspect.cleandoc(""" + /* + * Copyright 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. + * + */ + """) + return res + 2*NEWLINE + + +def get_file_header_prolog() -> str: + """ + Provides the include statement, namespace and variable declaration of the C++ file + + :returns: prolog of the C++ file + """ + res = inspect.cleandoc(""" + #include "EmbeddedSdf.hh" + + namespace sdf + { + inline namespace SDF_VERSION_NAMESPACE + { + ///////////////////////////////////////////////// + const std::map &GetEmbeddedSdf() + { + static const std::map result { + """) + return res + NEWLINE + + +def embed_sdf_content(arg_path: str, arg_file_content: str) -> str: + """ + Generates a string pair with the folder and filename as well as the content of the file + + :param arg_path: Foldername and filename of the SDF + :param arg_file_content: Content of the provided file + :returns: raw string literal mapping pair for the std::map + """ + res = [] + res.append('// NOLINT') + res.append('{') + res.append(f'"{arg_path}",') + res.append('R"__sdf_literal__(') + res.append(f'{arg_file_content}') + res.append(')__sdf_literal__"') + res.append('},') + res.append('') + return NEWLINE.join(res) + + +def get_map_content(arg_pathlist: Path) -> str: + """ + Generates a string pair with the folder and filename as well as the content + of the file in ascending order + + :param arg_pathlist: Foldername and all filenames inside it + :returns: mapping pairs for the std::map + """ + map_str = '' + files = [] + for path in arg_pathlist: + # dir separator is hardcoded to '/' in C++ mapping + posix_path = PurePosixPath(path) + files.append(str(posix_path)) + # get ascending order + files.sort() + for file in files: + with Path(file).open() as f: + content = f.read() + map_str += embed_sdf_content(file, content) + return map_str + + +def get_file_header_epilog() -> str: + """ + Provides the return statement and the closing brackets of the C++ file + + :returns: epilog of the C++ file + """ + res = inspect.cleandoc(""" + }; + + return result; + } + + } + } // namespace sdf + + """) + return NEWLINE + res + + +if __name__ == "__main__": + copyright = get_copyright_notice() + prolog = get_file_header_prolog() + + map_str = "" + for sdf_version in SUPPORTED_SDF_VERSIONS: + pathlist = Path(sdf_version).glob('*.sdf') + map_str += get_map_content(pathlist) + + for sdf_conversion in SUPPORTED_SDF_CONVERSIONS: + pathlist = Path(sdf_conversion).glob('*.convert') + map_str += get_map_content(pathlist) + + # remove the last comma + map_str = map_str[:-2] + + epilog = get_file_header_epilog() + + output = copyright + prolog + map_str + epilog + + # output to stdin so that CMake can read it and create the appropriate file + print(output) diff --git a/src/SDF_TEST.cc b/src/SDF_TEST.cc index ca14549df..315343e12 100644 --- a/src/SDF_TEST.cc +++ b/src/SDF_TEST.cc @@ -21,6 +21,9 @@ #include #include +#include "test_config.hh" +#include "test_utils.hh" + #include "sdf/sdf.hh" class SDFUpdateFixture @@ -559,6 +562,59 @@ TEST(SDF, Version) EXPECT_STREQ(SDF_VERSION, sdf::SDF::Version().c_str()); } +///////////////////////////////////////////////// +TEST(SDF, EmbeddedSpec) +{ + std::string result; + + result = sdf::SDF::EmbeddedSpec("actor.sdf", false); + EXPECT_NE(result.find(""), std::string::npos); + EXPECT_NE(result.find(""), + std::string::npos); + result = sdf::SDF::EmbeddedSpec("actor.sdf", true); + EXPECT_NE(result.find(""), std::string::npos); + EXPECT_NE(result.find(""), + std::string::npos); + + result = sdf::SDF::EmbeddedSpec("root.sdf", false); + EXPECT_NE(result.find("SDFormat base element"), std::string::npos); + EXPECT_NE(result.find("name=\"version\" type=\"string\""), std::string::npos); + result = sdf::SDF::EmbeddedSpec("root.sdf", true); + EXPECT_NE(result.find("SDFormat base element"), std::string::npos); + EXPECT_NE(result.find("name=\"version\" type=\"string\""), std::string::npos); +} + +TEST(SDF, EmbeddedSpecNonExistent) +{ + std::string result; + + // Capture sdferr output + std::stringstream stderr_buffer; + sdf::testing::RedirectConsoleStream redir( + sdf::Console::Instance()->GetMsgStream(), &stderr_buffer); +#ifdef _WIN32 + sdf::Console::Instance()->SetQuiet(false); + sdf::testing::ScopeExit revertSetQuiet( + [] + { + sdf::Console::Instance()->SetQuiet(true); + }); +#endif + + result = sdf::SDF::EmbeddedSpec("unavailable.sdf", false); + EXPECT_NE(stderr_buffer.str().find("Unable to find SDF filename"), + std::string::npos); + EXPECT_NE(stderr_buffer.str().find("with version"), std::string::npos); + EXPECT_TRUE(result.empty()); + + // clear the contents of the buffer + stderr_buffer.str(""); + + result = sdf::SDF::EmbeddedSpec("unavailable.sdf", true); + EXPECT_TRUE(stderr_buffer.str().empty()); + EXPECT_TRUE(result.empty()); +} + ///////////////////////////////////////////////// TEST(SDF, FilePath) { From 09d69f4d341d7e6d59ec2a99c2bb7f4aebcf7832 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 16 Feb 2023 11:11:19 -0600 Subject: [PATCH 02/23] Improvements to embedSdf script Signed-off-by: Michael Carroll --- sdf/CMakeLists.txt | 25 +++++-- sdf/embedSdf.py | 168 +++++++++++++++++++++++++++++---------------- 2 files changed, 130 insertions(+), 63 deletions(-) diff --git a/sdf/CMakeLists.txt b/sdf/CMakeLists.txt index e4b6a78e0..6e6fbe7f8 100644 --- a/sdf/CMakeLists.txt +++ b/sdf/CMakeLists.txt @@ -12,13 +12,28 @@ add_subdirectory(1.10) add_custom_target(schema) add_dependencies(schema schema1_10) +# Optionally use the python script (default in sdf14+) +if (EMBEDSDF_PY) + if (NOT Python3_Interpreter_FOUND) + gz_build_error("Python is required to generate the C++ file with the SDF content") + endif() + # Generate the EmbeddedSdf.cc file, which contains all the supported SDF # descriptions in a map of strings. The parser.cc file uses EmbeddedSdf.hh. -execute_process( - COMMAND ${RUBY} ${CMAKE_SOURCE_DIR}/sdf/embedSdf.rb - WORKING_DIRECTORY "${CMAKE_SOURCE_DIR}/sdf" - OUTPUT_FILE "${PROJECT_BINARY_DIR}/src/EmbeddedSdf.cc" -) + execute_process( + COMMAND ${Python3_EXECUTABLE} ${CMAKE_SOURCE_DIR}/sdf/embedSdf.py + --output-file "${PROJECT_BINARY_DIR}/src/EmbeddedSdf.cc" + WORKING_DIRECTORY "${CMAKE_SOURCE_DIR}/sdf" + OUTPUT_FILE "${PROJECT_BINARY_DIR}/src/EmbeddedSdf.cc" + ) +else() + execute_process( + COMMAND ${RUBY} ${CMAKE_SOURCE_DIR}/sdf/embedSdf.py + WORKING_DIRECTORY "${CMAKE_SOURCE_DIR}/sdf" + OUTPUT_FILE "${PROJECT_BINARY_DIR}/src/EmbeddedSdf.cc" + ) +endif() + # Generate aggregated SDF description files for use by the sdformat.org # website. If the description files change, the generated full*.sdf files need diff --git a/sdf/embedSdf.py b/sdf/embedSdf.py index b89607fa6..292958712 100644 --- a/sdf/embedSdf.py +++ b/sdf/embedSdf.py @@ -1,29 +1,49 @@ #!/usr/bin/env python3 +""" +Script for generating a C++ file that contains the content from all SDF files +""" + +from typing import List, Optional + +import argparse import inspect -from pathlib import Path, PurePosixPath +import sys +from pathlib import Path -""""Script for generating a C++ file that contains the content from all SDF files""" # The list of supported SDF specification versions. This will let us drop # versions without removing the directories. -SUPPORTED_SDF_VERSIONS = ['1.10', '1.9', '1.8', '1.7', '1.6', '1.5', '1.4', '1.3', '1.2'] +SUPPORTED_SDF_VERSIONS = [ + "1.10", + "1.9", + "1.8", + "1.7", + "1.6", + "1.5", + "1.4", + "1.3", + "1.2", +] # The list of supported SDF conversions. This list includes versions that # a user can convert an existing SDF version to. -SUPPORTED_SDF_CONVERSIONS = ['1.10', '1.9', '1.8', '1.7', '1.6', '1.5', '1.4', '1.3'] +SUPPORTED_SDF_CONVERSIONS = ["1.10", "1.9", "1.8", "1.7", "1.6", "1.5", "1.4", "1.3"] # whitespace indentation for C++ code -INDENTATION = ' ' +INDENTATION = " " + # newline character -NEWLINE = '\n' +NEWLINE = "\n" + def get_copyright_notice() -> str: """ - Provides the copyrigt notice for the C++ file + Provides the copyright notice for the C++ file :returns: copyright notice """ - res = inspect.cleandoc(""" + res = inspect.cleandoc( + """ /* * Copyright 2022 Open Source Robotics Foundation * @@ -40,8 +60,9 @@ def get_copyright_notice() -> str: * limitations under the License. * */ - """) - return res + 2*NEWLINE + """ + ) + return res + 2 * NEWLINE def get_file_header_prolog() -> str: @@ -50,7 +71,8 @@ def get_file_header_prolog() -> str: :returns: prolog of the C++ file """ - res = inspect.cleandoc(""" + res = inspect.cleandoc( + """ #include "EmbeddedSdf.hh" namespace sdf @@ -61,60 +83,39 @@ def get_file_header_prolog() -> str: const std::map &GetEmbeddedSdf() { static const std::map result { - """) + """ + ) return res + NEWLINE def embed_sdf_content(arg_path: str, arg_file_content: str) -> str: """ - Generates a string pair with the folder and filename as well as the content of the file + Generates a string pair with the folder and filename + as well as the content of the file :param arg_path: Foldername and filename of the SDF :param arg_file_content: Content of the provided file :returns: raw string literal mapping pair for the std::map """ res = [] - res.append('// NOLINT') - res.append('{') + res.append("// NOLINT") + res.append("{") res.append(f'"{arg_path}",') res.append('R"__sdf_literal__(') - res.append(f'{arg_file_content}') + res.append(f"{arg_file_content}") res.append(')__sdf_literal__"') - res.append('},') - res.append('') + res.append("}") return NEWLINE.join(res) -def get_map_content(arg_pathlist: Path) -> str: - """ - Generates a string pair with the folder and filename as well as the content - of the file in ascending order - - :param arg_pathlist: Foldername and all filenames inside it - :returns: mapping pairs for the std::map - """ - map_str = '' - files = [] - for path in arg_pathlist: - # dir separator is hardcoded to '/' in C++ mapping - posix_path = PurePosixPath(path) - files.append(str(posix_path)) - # get ascending order - files.sort() - for file in files: - with Path(file).open() as f: - content = f.read() - map_str += embed_sdf_content(file, content) - return map_str - - def get_file_header_epilog() -> str: """ Provides the return statement and the closing brackets of the C++ file :returns: epilog of the C++ file """ - res = inspect.cleandoc(""" + res = inspect.cleandoc( + """ }; return result; @@ -123,29 +124,80 @@ def get_file_header_epilog() -> str: } } // namespace sdf - """) + """ + ) return NEWLINE + res -if __name__ == "__main__": - copyright = get_copyright_notice() +def write_output(file_content: str, output_filename: str) -> None: + """ + Print the content of the EmbeddedSdf.cc to a file + """ + copyright_notice = get_copyright_notice() prolog = get_file_header_prolog() + epilog = get_file_header_epilog() + output_content = copyright_notice + prolog + file_content + epilog - map_str = "" - for sdf_version in SUPPORTED_SDF_VERSIONS: - pathlist = Path(sdf_version).glob('*.sdf') - map_str += get_map_content(pathlist) + with open(output_filename, "w", encoding="utf8") as output_file: + output_file.write(output_content) - for sdf_conversion in SUPPORTED_SDF_CONVERSIONS: - pathlist = Path(sdf_conversion).glob('*.convert') - map_str += get_map_content(pathlist) - # remove the last comma - map_str = map_str[:-2] +def collect_file_locations() -> List[Path]: + paths: List[Path] = [] - epilog = get_file_header_epilog() + for sdf_version in SUPPORTED_SDF_VERSIONS: + paths.extend(Path(sdf_version).glob("*.sdf")) + for sdf_conversion in SUPPORTED_SDF_CONVERSIONS: + paths.extend(Path(sdf_conversion).glob("*.convert")) + return paths + + +def generate_map_content(paths: List[Path], relative_to: Optional[str] = None) -> str: + ''' + Generate the EmbeddedSdf.cc content + ''' + content = [] + for path in paths: + with open(path, "r", encoding="utf8") as input_sdf: + file_content = input_sdf.read() + + # Strip relative path if requested + if relative_to is not None: + path = path.relative_to(relative_to) + content.append(embed_sdf_content(str(path), file_content)) + return ",".join(content) + + +def main(args=None) -> int: + ''' + Main entrypoint + ''' + if args is None: + args = sys.argv[1:] + + parser = argparse.ArgumentParser() + + parser.add_argument( + "--sdf-root", + default=None, + help="Directory containing sdf description files for each version", + ) + parser.add_argument( + "--input-files", nargs="*", help="List of input files to be embedded" + ) + parser.add_argument( + "--output-file", help="File to output embeddedsdf.cc content to" + ) + + args = parser.parse_args(args) + if not args.input_files or len(args.input_files) == 0: + paths = collect_file_locations() + else: + paths = [Path(f) for f in args.input_files] + content = generate_map_content(paths, args.sdf_root) + write_output(content, args.output_file) + return 0 - output = copyright + prolog + map_str + epilog - # output to stdin so that CMake can read it and create the appropriate file - print(output) +if __name__ == "__main__": + sys.exit(main()) From a82e65f562eb58985715115a2865eb6e1185c2e5 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 16 Feb 2023 12:58:16 -0600 Subject: [PATCH 03/23] Update sdf/CMakeLists.txt Signed-off-by: Michael Carroll Co-authored-by: Addisu Z. Taddese --- sdf/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sdf/CMakeLists.txt b/sdf/CMakeLists.txt index 6e6fbe7f8..983e7804b 100644 --- a/sdf/CMakeLists.txt +++ b/sdf/CMakeLists.txt @@ -28,7 +28,7 @@ if (EMBEDSDF_PY) ) else() execute_process( - COMMAND ${RUBY} ${CMAKE_SOURCE_DIR}/sdf/embedSdf.py + COMMAND ${RUBY} ${CMAKE_SOURCE_DIR}/sdf/embedSdf.rb WORKING_DIRECTORY "${CMAKE_SOURCE_DIR}/sdf" OUTPUT_FILE "${PROJECT_BINARY_DIR}/src/EmbeddedSdf.cc" ) From 7553e0fca1318e6eb1e323b4520f894df4e145e0 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Wed, 15 Feb 2023 15:56:11 -0600 Subject: [PATCH 04/23] Update bazel files Signed-off-by: Michael Carroll --- BUILD.bazel | 151 +++++++++ include/sdf/config.hh.in | 5 + src/CMakeLists.txt | 7 + src/SDF.cc | 13 +- src/gz_TEST.cc | 302 ++++++++++++------ src/parser_TEST.cc | 5 +- test/BUILD.bazel | 57 ++++ test/integration/CMakeLists.txt | 19 +- test/integration/converter.cc | 2 +- test/integration/default_elements.cc | 16 +- test/integration/frame.cc | 3 +- test/integration/nested_model.cc | 4 +- .../nested_multiple_elements_error.cc | 8 +- test/integration/schema_test.cc | 4 +- test/integration/toml_parser.hh | 2 +- test/test_config.hh.in | 38 ++- 16 files changed, 487 insertions(+), 149 deletions(-) create mode 100644 BUILD.bazel create mode 100644 test/BUILD.bazel diff --git a/BUILD.bazel b/BUILD.bazel new file mode 100644 index 000000000..365854e05 --- /dev/null +++ b/BUILD.bazel @@ -0,0 +1,151 @@ +load( + "@gz//bazel/skylark:build_defs.bzl", + "GZ_FEATURES", + "GZ_ROOT", + "GZ_VISIBILITY", + "gz_configure_header", + "gz_export_header", + "gz_include_header", +) +load("@gz//bazel/skylark:gz_py.bzl", "gz_py_binary") + +package( + default_visibility = GZ_VISIBILITY, + features = GZ_FEATURES, +) + +licenses(["notice"]) # Apache-2.0 + +exports_files(["LICENSE"]) + +gz_configure_header( + name = "config", + src = "include/sdf/config.hh.in", + cmakelists = ["CMakeLists.txt"], + defines = { + "CMAKE_INSTALL_FULL_DATAROOTDIR": "", + }, + package = "sdformat", +) + +gz_py_binary( + name = "embed_sdf", + srcs = ["sdf/embedSdf.py"], +) + +genrule( + name = "embed_sdf_genrule", + srcs = glob([ + "sdf/**/*.sdf", + "sdf/**/*.convert", + ]), + outs = ["EmbeddedSdf.cc"], + cmd = "$(execpath :embed_sdf) --output-file $@ --sdf-root ./sdformat/sdf --input-files $(SRCS)", # noqa + tools = [":embed_sdf"], +) + +public_headers_no_gen = glob([ + "include/sdf/*.h", + "include/sdf/*.hh", +]) + +private_headers = glob(["src/*.hh"]) + +sources = glob( + ["src/*.cc"], + exclude = [ + "src/*_TEST.cc", + "src/gz.cc", + ], +) + +gz_export_header( + name = "include/sdf/Export.hh", + export_base = "GZ_SDFORMAT", + lib_name = "sdf", + visibility = ["//visibility:private"], +) + +gz_include_header( + name = "sdformat_hh_genrule", + out = "include/sdformat.hh", + hdrs = public_headers_no_gen + [ + "include/sdf/config.hh", + "include/sdf/Export.hh", + ], +) + +public_headers = public_headers_no_gen + [ + "include/sdf/Export.hh", + "include/sdf/config.hh", + "include/sdformat.hh", +] + +cc_library( + name = "urdf", + srcs = [ + "src/urdf/urdf_parser/joint.cpp", + "src/urdf/urdf_parser/link.cpp", + "src/urdf/urdf_parser/model.cpp", + "src/urdf/urdf_parser/pose.cpp", + "src/urdf/urdf_parser/twist.cpp", + "src/urdf/urdf_parser/urdf_model_state.cpp", + "src/urdf/urdf_parser/urdf_sensor.cpp", + "src/urdf/urdf_parser/world.cpp", + ], + hdrs = glob( + ["src/urdf/**/*.h"], + ), + copts = ["-Wno-unknown-pragmas"], + includes = ["src/urdf"], + deps = [ + "@tinyxml2", + ], +) + +cc_library( + name = "sdformat", + srcs = sources + private_headers + ["EmbeddedSdf.cc"], + hdrs = public_headers, + includes = [ + "include", + "src", + ], + defines = [ + 'SDF_SHARE_PATH=\\".\\"', + 'SDF_VERSION_PATH=\\"sdformat\\"', + ], + deps = [ + ":urdf", + GZ_ROOT + "math", + GZ_ROOT + "utils", + "@tinyxml2", + ], +) + +test_sources = glob( + ["src/*_TEST.cc"], + exclude = ["src/gz_TEST.cc"], +) + +[cc_test( + name = src.replace("/", "_").replace(".cc", "").replace("src_", ""), + srcs = [src], + data = [ + "sdf", + GZ_ROOT + "sdformat/test:integration", + GZ_ROOT + "sdformat/test:sdf", + ], + env = { + "GZ_BAZEL": "1", + "GZ_BAZEL_PATH": "sdformat", + }, + deps = [ + ":sdformat", + GZ_ROOT + "sdformat/test:test_utils", + "@gtest", + "@gtest//:gtest_main", + ], +) for src in test_sources] + +exports_files(["sdf"]) diff --git a/include/sdf/config.hh.in b/include/sdf/config.hh.in index d1b3db532..7b128ebad 100644 --- a/include/sdf/config.hh.in +++ b/include/sdf/config.hh.in @@ -47,7 +47,12 @@ #cmakedefine SDFORMAT_DISABLE_CONSOLE_LOGFILE 1 +#ifndef SDF_SHARE_PATH #define SDF_SHARE_PATH "${CMAKE_INSTALL_FULL_DATAROOTDIR}/" +#endif + +#ifndef SDF_VERSION_PATH #define SDF_VERSION_PATH "${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${SDF_MAJOR_VERSION}/${SDF_PKG_VERSION}" +#endif #endif // #ifndef SDF_CONFIG_HH_ diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index feab8e716..fbf8cd0cf 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -61,6 +61,13 @@ if (BUILD_TESTING) XmlUtils.cc) endif() + if (TARGET UNIT_gz_TEST) + target_compile_definitions(UNIT_gz_TEST PRIVATE + -DGZ_PATH="${GZ_PROGRAM}" + -DGZ_CONFIG_PATH="${CMAKE_BINARY_DIR}/test/conf" + -DGZ_TEST_LIBRARY_PATH="${PROJECT_BINARY_DIR}/src") + endif() + if (TARGET UNIT_FrameSemantics_TEST) target_sources(UNIT_FrameSemantics_TEST PRIVATE FrameSemantics.cc Utils.cc) target_link_libraries(UNIT_FrameSemantics_TEST TINYXML2::TINYXML2) diff --git a/src/SDF.cc b/src/SDF.cc index 395119a01..c28ba4400 100644 --- a/src/SDF.cc +++ b/src/SDF.cc @@ -43,6 +43,15 @@ inline namespace SDF_VERSION_NAMESPACE // returns the version string when possible. std::string SDF::version = SDF_VERSION; // NOLINT(runtime/string) +std::string sdfSharePath() +{ +#ifdef SDF_SHARE_PATH + if (std::string(SDF_SHARE_PATH) != "/") + return SDF_SHARE_PATH; +#endif + return ""; +} + ///////////////////////////////////////////////// void setFindCallback(std::function _cb) { @@ -98,14 +107,14 @@ std::string findFile(const std::string &_filename, bool _searchLocalPath, } // Next check the install path. - std::string path = sdf::filesystem::append(SDF_SHARE_PATH, filename); + std::string path = sdf::filesystem::append(sdfSharePath(), filename); if (sdf::filesystem::exists(path)) { return path; } // Next check the versioned install path. - path = sdf::filesystem::append(SDF_SHARE_PATH, + path = sdf::filesystem::append(sdfSharePath(), "sdformat" SDF_MAJOR_VERSION_STR, sdf::SDF::Version(), filename); if (sdf::filesystem::exists(path)) diff --git a/src/gz_TEST.cc b/src/gz_TEST.cc index 9d4bde234..ce91a7cf7 100644 --- a/src/gz_TEST.cc +++ b/src/gz_TEST.cc @@ -22,6 +22,7 @@ #include #include +#include #include "sdf/Error.hh" #include "sdf/Filesystem.hh" @@ -70,12 +71,10 @@ std::string custom_exec_str(std::string _cmd) ///////////////////////////////////////////////// TEST(checkUnrecognizedElements, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) { - std::string pathBase = PROJECT_SOURCE_PATH; - pathBase += "/test/sdf"; - // Check an SDFormat file with unrecognized elements { - std::string path = pathBase +"/unrecognized_elements.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "unrecognized_elements.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf -k " + path + SdfVersion()); @@ -100,7 +99,8 @@ TEST(checkUnrecognizedElements, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDFormat file with unrecognized elements with XML namespaces { - std::string path = pathBase +"/unrecognized_elements_with_namespace.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "unrecognized_elements_with_namespace.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf -k " + path + SdfVersion()); @@ -118,12 +118,10 @@ TEST(checkUnrecognizedElements, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) ///////////////////////////////////////////////// TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) { - std::string pathBase = PROJECT_SOURCE_PATH; - pathBase += "/test/sdf"; - // Check a good SDF file { - std::string path = pathBase +"/box_plane_low_friction_test.world"; + const auto path = + sdf::testing::TestFile("sdf", "box_plane_low_friction_test.world"); // Check box_plane_low_friction_test.world std::string output = @@ -133,7 +131,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check a bad SDF file { - std::string path = pathBase +"/box_bad_test.world"; + const auto path = + sdf::testing::TestFile("sdf", "box_bad_test.world"); // Check box_bad_test.world std::string output = @@ -145,7 +144,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with sibling elements of the same type (world) // that have duplicate names. { - std::string path = pathBase +"/world_duplicate.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "world_duplicate.world"); // Check world_duplicate.sdf std::string output = @@ -157,7 +157,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with sibling elements of different types (model, light) // that have duplicate names. { - std::string path = pathBase +"/world_sibling_same_names.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "world_sibling_same_names.sdf"); // Check world_sibling_same_names.sdf std::string output = @@ -167,7 +168,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) } // Check an SDF world file is allowed to have duplicate plugin names { - std::string path = pathBase +"/world_duplicate_plugins.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "world_duplicate_plugins.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf -k " + path + SdfVersion()); @@ -177,7 +179,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with sibling elements of the same type (link) // that have duplicate names. { - std::string path = pathBase +"/model_duplicate_links.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "model_duplicate_links.sdf"); // Check model_duplicate_links.sdf std::string output = @@ -189,7 +192,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with sibling elements of the same type (joint) // that have duplicate names. { - std::string path = pathBase +"/model_duplicate_joints.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "model_duplicate_joints.sdf"); // Check model_duplicate_joints.sdf std::string output = @@ -201,7 +205,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with sibling elements of different types (link, joint) // that have duplicate names. { - std::string path = pathBase +"/model_link_joint_same_name.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "model_link_joint_same_name.sdf"); // Check model_link_joint_same_name.sdf std::string output = @@ -212,7 +217,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF model file is allowed to have duplicate plugin names { - std::string path = pathBase +"/model_duplicate_plugins.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "model_link_duplicate_plugins.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf -k " + path + SdfVersion()); @@ -222,7 +228,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with sibling elements of the same type (collision) // that have duplicate names. { - std::string path = pathBase +"/link_duplicate_sibling_collisions.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "link_duplicate_sibling_collisions.sdf"); // Check link_duplicate_sibling_collisions.sdf std::string output = @@ -235,7 +243,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with sibling elements of the same type (visual) // that have duplicate names. { - std::string path = pathBase +"/link_duplicate_sibling_visuals.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "link_duplicate_sibling_visuals.sdf"); // Check link_duplicate_sibling_visuals.sdf std::string output = @@ -247,7 +257,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with cousin elements of the same type (collision) // that have duplicate names. This is a valid file. { - std::string path = pathBase +"/link_duplicate_cousin_collisions.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "link_duplicate_cousin_collisions.sdf"); // Check link_duplicate_cousin_collisions.sdf std::string output = @@ -258,7 +270,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with cousin elements of the same type (visual) // that have duplicate names. This is a valid file. { - std::string path = pathBase +"/link_duplicate_cousin_visuals.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "link_duplicate_cousin_visuals.sdf"); // Check link_duplicate_cousin_visuals.sdf std::string output = @@ -268,7 +282,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with a joint with an invalid child link. { - std::string path = pathBase +"/joint_invalid_child.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "joint_invalid_child.sdf"); // Check joint_invalid_child.sdf std::string output = @@ -281,7 +296,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with a joint with an invalid parent link. { - std::string path = pathBase +"/joint_invalid_parent.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "joint_invalid_parent.sdf"); // Check joint_invalid_parent.sdf std::string output = @@ -294,7 +310,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with a joint that names itself as the child frame. { - std::string path = pathBase +"/joint_invalid_self_child.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "joint_invalid_self_child.sdf"); // Check joint_invalid_self_child.sdf std::string output = @@ -306,7 +323,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with a joint that names itself as the parent frame. { - std::string path = pathBase +"/joint_invalid_self_parent.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "joint_invalid_self_parent.sdf"); // Check joint_invalid_self_parent.sdf std::string output = @@ -319,7 +337,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with a joint with identical parent and child. { - std::string path = pathBase +"/joint_invalid_parent_same_as_child.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "joint_invalid_parent_same_as_child.sdf"); // Check joint_invalid_parent_same_as_child.sdf std::string output = @@ -333,8 +353,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with a joint with parent parent frame that resolves // to the same value as the child. { - std::string path = - pathBase + "/joint_invalid_resolved_parent_same_as_child.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "joint_invalid_resolved_parent_same_as_child.sdf"); // Check joint_invalid_resolved_parent_same_as_child.sdf std::string output = @@ -347,7 +368,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with the world specified as a child link. { - std::string path = pathBase +"/joint_child_world.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "joint_child_world.sdf"); // Check joint_child_world.sdf std::string output = @@ -363,7 +385,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with the world specified as a parent link. // This is a valid file. { - std::string path = pathBase +"/joint_parent_world.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "joint_parent_world.sdf"); // Check joint_parent_world.sdf std::string output = @@ -374,7 +397,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with a frame specified as the joint child. // This is a valid file. { - std::string path = pathBase +"/joint_child_frame.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "joint_child_frame.sdf"); // Check joint_child_frame.sdf std::string output = @@ -385,7 +409,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with a frame specified as the joint parent. // This is a valid file. { - std::string path = pathBase +"/joint_parent_frame.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "joint_parent_frame.sdf"); // Check joint_parent_frame.sdf std::string output = @@ -396,7 +421,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with the infinite values for joint axis limits. // This is a valid file. { - std::string path = pathBase +"/joint_axis_infinite_limits.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "joint_axis_infinite_limits.sdf"); // Check joint_axis_infinite_limits.sdf std::string output = @@ -407,7 +433,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with the second link specified as the canonical link. // This is a valid file. { - std::string path = pathBase +"/model_canonical_link.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "model_canonical_link.sdf"); // Check model_canonical_link.sdf std::string output = @@ -417,7 +444,8 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with an invalid link specified as the canonical link. { - std::string path = pathBase +"/model_invalid_canonical_link.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "model_invalid_canonical_link.sdf"); // Check model_invalid_canonical_link.sdf std::string output = @@ -429,7 +457,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with an invalid model without links. { - std::string path = pathBase +"/model_without_links.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_without_links.sdf"); // Check model_without_links.sdf std::string output = @@ -440,7 +470,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with a nested model. { - std::string path = pathBase +"/nested_model.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "nested_model.sdf"); // Check nested_model.sdf std::string output = @@ -450,7 +482,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with a model that has a nested canonical link. { - std::string path = pathBase +"/nested_canonical_link.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "nested_canonical_link.sdf"); // Check nested_canonical_link.sdf std::string output = @@ -462,7 +496,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // that is explicitly specified by //model/@canonical_link using :: // syntax. { - std::string path = pathBase +"/nested_explicit_canonical_link.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "nested_explicit_canonical_link.sdf"); // Check nested_explicit_canonical_link.sdf std::string output = @@ -472,7 +508,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with a model that a nested model without a link. { - std::string path = pathBase +"/nested_without_links_invalid.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "nested_without_links_invalid.sdf"); // Check nested_without_links_invalid.sdf std::string output = @@ -483,7 +521,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an invalid SDF file that uses reserved names. { - std::string path = pathBase +"/model_invalid_reserved_names.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "nested_invalid_reserved_names.sdf"); // Check model_invalid_reserved_names.sdf std::string output = @@ -509,7 +549,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check that validity checks are disabled inside elements { - std::string path = pathBase +"/ignore_sdf_in_plugin.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "ignore_sdf_in_plugin.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf -k " + path + SdfVersion()); @@ -518,7 +560,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check that validity checks are disabled inside namespaced elements { - std::string path = pathBase +"/ignore_sdf_in_namespaced_elements.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "ignore_sdf_in_namespaced_elements.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf -k " + path + SdfVersion()); @@ -528,7 +572,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with model frames using the attached_to attribute. // This is a valid file. { - std::string path = pathBase +"/model_frame_attached_to.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_frame_attached_to.sdf"); // Check model_frame_attached_to.sdf std::string output = @@ -539,7 +585,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with model frames attached_to joints. // This is a valid file. { - std::string path = pathBase +"/model_frame_attached_to_joint.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_frame_attached_to_joint.sdf"); // Check model_frame_attached_to_joint.sdf std::string output = @@ -550,7 +598,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with model frames attached_to a nested model. // This is a valid file. { - std::string path = pathBase +"/model_frame_attached_to_nested_model.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_frame_attached_to_nested_model.sdf"); // Check model_frame_attached_to_nested_model.sdf std::string output = @@ -560,7 +610,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with model frames with invalid attached_to attributes. { - std::string path = pathBase +"/model_frame_invalid_attached_to.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_frame_invalid_attached_to.sdf"); // Check model_frame_invalid_attached_to.sdf std::string output = @@ -578,7 +630,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with a cycle in its FrameAttachedTo graph { - std::string path = pathBase +"/model_frame_invalid_attached_to_cycle.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_frame_invalid_attached_to_cycle.sdf"); // Check model_frame_invalid_attached_to_cycle.sdf std::string output = @@ -596,7 +650,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with model frames using the attached_to attribute. // This is a valid file. { - std::string path = pathBase +"/world_frame_attached_to.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "world_frame_attached_to.sdf"); // Check world_frame_attached_to.sdf std::string output = @@ -606,7 +662,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with world frames with invalid attached_to attributes. { - std::string path = pathBase +"/world_frame_invalid_attached_to.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "world_frame_invalid_attached_to.sdf"); // Check world_frame_invalid_attached_to.sdf std::string output = @@ -626,7 +684,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with links using the relative_to attribute. // This is a valid file. { - std::string path = pathBase +"/model_link_relative_to.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_link_relative_to.sdf"); // Check model_link_relative_to.sdf std::string output = @@ -636,7 +696,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with model links with invalid relative_to attributes. { - std::string path = pathBase +"/model_invalid_link_relative_to.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_invalid_link_relative_to.sdf"); // Check model_invalid_link_relative_to.sdf std::string output = @@ -655,7 +717,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with nested_models using the relative_to attribute. // This is a valid file. { - std::string path = pathBase +"/model_nested_model_relative_to.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_nested_model_relative_to.sdf"); // Check model_nested_model_relative_to.sdf std::string output = @@ -667,7 +731,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // parent or child frames. // This is a valid file. { - std::string path = pathBase +"/joint_nested_parent_child.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "joint_nested_parent_child.sdf"); // Check model_nested_model_relative_to.sdf std::string output = @@ -678,7 +744,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with joints using the relative_to attribute. // This is a valid file. { - std::string path = pathBase +"/model_joint_relative_to.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_joint_relative_to.sdf"); // Check model_joint_relative_to.sdf std::string output = @@ -688,7 +756,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with model joints with invalid relative_to attributes. { - std::string path = pathBase +"/model_invalid_joint_relative_to.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_invalid_joint_relative_to.sdf"); // Check model_invalid_joint_relative_to.sdf std::string output = @@ -707,7 +777,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with model frames using the relative_to attribute. // This is a valid file. { - std::string path = pathBase +"/model_frame_relative_to.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_frame_relative_to.sdf"); // Check model_frame_relative_to.sdf std::string output = @@ -718,7 +790,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with model frames relative_to joints. // This is a valid file. { - std::string path = pathBase +"/model_frame_relative_to_joint.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_frame_relative_to_joint.sdf"); // Check model_frame_relative_to_joint.sdf std::string output = @@ -728,7 +802,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with model frames with invalid relative_to attributes. { - std::string path = pathBase +"/model_invalid_frame_relative_to.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_invalid_frame_relative_to.sdf"); // Check model_invalid_frame_relative_to.sdf std::string output = @@ -746,7 +822,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with a cycle in its PoseRelativeTo graph { - std::string path = pathBase +"/model_invalid_frame_relative_to_cycle.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_invalid_frame_relative_to_cycle.sdf"); // Check model_invalid_frame_relative_to_cycle.sdf std::string output = @@ -764,7 +842,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with model frames using the attached_to attribute. // This is a valid file. { - std::string path = pathBase +"/world_frame_relative_to.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "world_frame_relative_to.sdf"); // Check world_frame_relative_to.sdf std::string output = @@ -774,7 +854,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with world frames with invalid relative_to attributes. { - std::string path = pathBase +"/world_frame_invalid_relative_to.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "world_frame_invalid_relative_to.sdf"); // Check world_frame_invalid_relative_to.sdf std::string output = @@ -803,7 +885,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with an invalid frame specified as the placement_frame // attribute. { - std::string path = pathBase + "/model_invalid_placement_frame.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_invalid_placement_frame.sdf"); // Check model_invalid_placement_frame.sdf std::string output = @@ -816,7 +900,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF file with an valid nested model cross references { - std::string path = pathBase + "/nested_model_cross_references.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "nested_model_cross_references.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf -k " + path + SdfVersion()); @@ -825,7 +911,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF model file with an invalid usage of __root__ { - std::string path = pathBase + "/model_invalid_root_reference.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_invalid_root_reference.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf -k " + path + SdfVersion()); @@ -844,8 +932,11 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) { // Set SDF_PATH so that included models can be found gz::utils::setenv( - "SDF_PATH", sdf::testing::SourceFile("test", "integration", "model")); - std::string path = pathBase + "/world_invalid_root_reference.sdf"; + "SDF_PATH", sdf::testing::TestFile("integration", "model")); + + const auto path = + sdf::testing::TestFile("sdf", + "world_invalid_root_reference.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf -k " + path + SdfVersion()); @@ -892,7 +983,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) } // Check an SDF world file with an valid usage of __root__ { - std::string path = pathBase + "/world_valid_root_reference.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "world_valid_root_reference.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf -k " + path + SdfVersion()); @@ -900,7 +993,9 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) } // Check an SDF with an invalid relative frame at the top level model { - std::string path = pathBase + "/model_invalid_top_level_frame.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "model_invalid_top_level_frame.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf -k " + path + SdfVersion()); @@ -914,11 +1009,10 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) ///////////////////////////////////////////////// TEST(check_shapes_sdf, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) { - std::string pathBase = PROJECT_SOURCE_PATH; - pathBase += "/test/sdf"; - { - std::string path = pathBase +"/shapes.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "shapes.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf -k " + path + SdfVersion()); @@ -926,7 +1020,9 @@ TEST(check_shapes_sdf, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) } { - std::string path = pathBase +"/shapes_world.sdf"; + const auto path = + sdf::testing::TestFile("sdf", + "shapes_world.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf -k " + path + SdfVersion()); @@ -937,12 +1033,11 @@ TEST(check_shapes_sdf, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) ///////////////////////////////////////////////// TEST(check_model_sdf, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) { - std::string pathBase = PROJECT_SOURCE_PATH; - pathBase += "/test/integration/model/box"; - // Check a good SDF file by passing the absolute path { - std::string path = pathBase +"/model.sdf"; + const auto path = + sdf::testing::TestFile("integration", + "model", "box", "model.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf -k " + path + SdfVersion()); @@ -951,7 +1046,9 @@ TEST(check_model_sdf, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check a good SDF file from the same folder by passing a relative path { - std::string path = "model.sdf"; + const auto pathBase = sdf::testing::TestFile("integration", + "model", "box"); + const auto path = "model.sdf"; std::string output = custom_exec_str("cd " + pathBase + " && " + @@ -975,12 +1072,10 @@ TEST(describe, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) ///////////////////////////////////////////////// TEST(print, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) { - std::string pathBase = PROJECT_SOURCE_PATH; - pathBase += "/test/sdf"; - // Check a good SDF file { - std::string path = pathBase +"/box_plane_low_friction_test.world"; + const auto path = + sdf::testing::TestFile("sdf", "box_plane_low_friction_test.world"); sdf::SDFPtr sdf(new sdf::SDF()); EXPECT_TRUE(sdf::init(sdf)); EXPECT_TRUE(sdf::readFile(path, sdf)); @@ -993,7 +1088,8 @@ TEST(print, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check a bad SDF file { - std::string path = pathBase +"/box_bad_test.world"; + const auto path = + sdf::testing::TestFile("sdf", "box_bad_test.world"); // Check box_bad_test.world std::string output = @@ -1361,7 +1457,7 @@ TEST(print_includes_rotations_in_quaternions, { // Set SDF_PATH so that included models can be found gz::utils::setenv( - "SDF_PATH", sdf::testing::SourceFile("test", "integration", "model")); + "SDF_PATH", sdf::testing::TestFile("integration", "model")); const auto path = sdf::testing::TestFile( "sdf", "includes_rotations_in_quaternions.sdf"); @@ -1639,11 +1735,9 @@ TEST(print_snap_to_degrees_tolerance_too_high, ///////////////////////////////////////////////// TEST(GraphCmd, GZ_UTILS_TEST_DISABLED_ON_WIN32(WorldPoseRelativeTo)) { - const std::string pathBase = std::string(PROJECT_SOURCE_PATH) + "/test/sdf"; - // world pose relative_to graph const std::string path = - pathBase + "/world_relative_to_nested_reference.sdf"; + sdf::testing::TestFile("sdf", "world_relative_to_nested_reference.sdf"); const std::string output = custom_exec_str(GzCommand() + " sdf -g pose " + path + SdfVersion()); @@ -1690,8 +1784,9 @@ TEST(GraphCmd, GZ_UTILS_TEST_DISABLED_ON_WIN32(WorldPoseRelativeTo)) ///////////////////////////////////////////////// TEST(GraphCmd, GZ_UTILS_TEST_DISABLED_ON_WIN32(ModelPoseRelativeTo)) { - const std::string pathBase = std::string(PROJECT_SOURCE_PATH) + "/test/sdf"; - const std::string path = pathBase + "/model_relative_to_nested_reference.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "model_relative_to_nested_reference.sdf"); + const std::string output = custom_exec_str(GzCommand() + " sdf -g pose " + path + SdfVersion()); @@ -1766,8 +1861,8 @@ TEST(GraphCmd, GZ_UTILS_TEST_DISABLED_ON_WIN32(ModelPoseRelativeTo)) ///////////////////////////////////////////////// TEST(GraphCmd, GZ_UTILS_TEST_DISABLED_ON_WIN32(WorldFrameAttachedTo)) { - const std::string pathBase = std::string(PROJECT_SOURCE_PATH) + "/test/sdf"; - const std::string path = pathBase + "/world_nested_frame_attached_to.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "world_nested_frame_attached_to.sdf"); const std::string output = custom_exec_str(GzCommand() + " sdf -g frame " + path + SdfVersion()); @@ -1812,8 +1907,9 @@ TEST(GraphCmd, GZ_UTILS_TEST_DISABLED_ON_WIN32(WorldFrameAttachedTo)) ///////////////////////////////////////////////// TEST(GraphCmd, GZ_UTILS_TEST_DISABLED_ON_WIN32(ModelFrameAttachedTo)) { - const std::string pathBase = std::string(PROJECT_SOURCE_PATH) + "/test/sdf"; - const std::string path = pathBase + "/model_nested_frame_attached_to.sdf"; + const auto path = + sdf::testing::TestFile("sdf", "model_nested_frame_attached_to.sdf"); + const std::string output = custom_exec_str(GzCommand() + " sdf -g frame " + path + SdfVersion()); @@ -1863,9 +1959,6 @@ TEST(GraphCmd, GZ_UTILS_TEST_DISABLED_ON_WIN32(ModelFrameAttachedTo)) ///////////////////////////////////////////////// TEST(inertial_stats, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) { - std::string pathBase = PROJECT_SOURCE_PATH; - pathBase += "/test/sdf"; - std::string expectedOutput = "Inertial statistics for model: test_model\n" "---\n" @@ -1884,7 +1977,7 @@ TEST(inertial_stats, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check a good SDF file by passing the absolute path { - std::string path = pathBase +"/inertial_stats.sdf"; + const auto path = sdf::testing::TestFile("sdf", "inertial_stats.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf --inertial-stats " + @@ -1894,7 +1987,8 @@ TEST(inertial_stats, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check a good SDF file from the same folder by passing a relative path { - std::string path = "inertial_stats.sdf"; + const auto path = "inertial_stats.sdf"; + const auto pathBase = sdf::testing::TestFile("sdf"); std::string output = custom_exec_str("cd " + pathBase + " && " + @@ -1925,7 +2019,7 @@ TEST(inertial_stats, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an invalid SDF file by passing the absolute path { - std::string path = pathBase +"/inertial_invalid.sdf"; + const auto path = sdf::testing::TestFile("sdf", "inertial_invalid.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf --inertial-stats " + @@ -1937,7 +2031,8 @@ TEST(inertial_stats, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) "Error: Expected a model file but received a world file.\n"; // Check a valid world file. { - std::string path = pathBase +"/box_plane_low_friction_test.world"; + const auto path = + sdf::testing::TestFile("sdf", "box_plane_low_friction_test.world"); std::string output = custom_exec_str(GzCommand() + " sdf --inertial-stats " + @@ -1956,9 +2051,8 @@ TEST(HelpVsCompletionFlags, SDF) std::string helpOutput = custom_exec_str(GzCommand() + " sdf --help"); // Call the output function in the bash completion script - std::string scriptPath = PROJECT_SOURCE_PATH; - scriptPath = sdf::filesystem::append(scriptPath, "src", "cmd", - "sdf.bash_completion.sh"); + const auto scriptPath = + sdf::testing::SourceFile("src", "cmd", "sdf.bash_completion.sh"); // Equivalent to: // sh -c "bash -c \". /path/to/sdf.bash_completion.sh; _gz_sdf_flags\"" diff --git a/src/parser_TEST.cc b/src/parser_TEST.cc index 3e06c945a..9614e34e6 100644 --- a/src/parser_TEST.cc +++ b/src/parser_TEST.cc @@ -23,9 +23,9 @@ #include "sdf/Element.hh" #include "sdf/Console.hh" #include "sdf/Filesystem.hh" -#include "test_config.hh" #include +#include "test_config.hh" ///////////////////////////////////////////////// TEST(Parser, initStringTrim) @@ -840,7 +840,8 @@ int main(int argc, char **argv) { // temporarily set HOME std::string homeDir; - sdf::testing::TestSetHomePath(homeDir); + sdf::testing::TestTmpPath(homeDir); + gz::utils::setenv("HOME", homeDir); sdf::Console::Clear(); ::testing::InitGoogleTest(&argc, argv); diff --git a/test/BUILD.bazel b/test/BUILD.bazel new file mode 100644 index 000000000..2743e75f0 --- /dev/null +++ b/test/BUILD.bazel @@ -0,0 +1,57 @@ +load( + "@gz//bazel/skylark:build_defs.bzl", + "GZ_ROOT", + "cmake_configure_file", +) + +cmake_configure_file( + name = "config", + src = "test_config.hh.in", + out = "test_config.hh", + cmakelists = ["CMakeLists.txt"], + defines = [] +) + +cc_library( + name = "test_utils", + hdrs = ["test_utils.hh", "test_config.hh"], + includes = ["."], + visibility = ["//visibility:public"], +) + +integration_test_sources = glob( + ["integration/*.cc"], + exclude = [ + "integration/schema_test.cc", + "integration/element_memory_leak.cc", + ], +) + +[cc_test( + name = src.replace("/", "_").replace(".cc", "").replace("integration_", "INTEGRATION_"), + srcs = [ + src, + "integration/toml_parser.hh", + ], + data = [ + GZ_ROOT + "sdformat:sdf", + "integration", + "sdf", + ], + env = { + "GZ_BAZEL": "1", + "GZ_BAZEL_PATH": "sdformat", + }, + includes = ["integration"], + deps = [ + GZ_ROOT + "sdformat:sdformat", + ":test_utils", + "@gtest", + "@gtest//:gtest_main", + ], +) for src in integration_test_sources] + +exports_files([ + "sdf", + "integration", +]) diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index 0635cfdf3..09a504260 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -72,11 +72,22 @@ else() gz_build_warning("xmllint not found. schema_test won't be run") endif() -gz_build_tests(TYPE ${TEST_TYPE} SOURCES ${tests} INCLUDE_DIRS ${PROJECT_SOURCE_DIR}/test) +gz_build_tests(TYPE ${TEST_TYPE} + SOURCES ${tests} + INCLUDE_DIRS ${PROJECT_SOURCE_DIR}/test +) -if (EXISTS ${XMLLINT_EXE}) - # Need to run schema target (build .xsd files) before running schema_test - add_dependencies(${TEST_TYPE}_schema_test schema) + +if (TARGET ${TEST_TYPE}_schema_test) + target_compile_definitions(${TEST_TYPE}_schema_test + PRIVATE + -DSDF_ROOT_SCHEMA="${PROJECT_BINARY_DIR}/sdf/${SDF_PROTOCOL_VERSION}/root.xsd" + ) + + if (EXISTS ${XMLLINT_EXE}) + # Need to run schema target (build .xsd files) before running schema_test + add_dependencies(${TEST_TYPE}_schema_test schema) + endif() endif() # Test symbols having the right name on linux only diff --git a/test/integration/converter.cc b/test/integration/converter.cc index ec062d5ad..1509de722 100644 --- a/test/integration/converter.cc +++ b/test/integration/converter.cc @@ -156,7 +156,7 @@ void ParserStringConverter(const std::string &_version) TEST(ConverterIntegration, UnflattenConversion) { const std::string filename = - sdf::testing::SourceFile("test", "sdf", + sdf::testing::TestFile("sdf", "flattened_test_nested_model_with_frames.sdf"); sdf::SDFPtr sdf(new sdf::SDF()); diff --git a/test/integration/default_elements.cc b/test/integration/default_elements.cc index efad8d8ad..f07cee0c8 100644 --- a/test/integration/default_elements.cc +++ b/test/integration/default_elements.cc @@ -26,14 +26,14 @@ #include "sdf/Root.hh" #include "sdf/World.hh" #include "sdf/Filesystem.hh" + #include "test_config.hh" ////////////////////////////////////////////////// TEST(ExplicitlySetInFile, EmptyRoadSphCoords) { - const std::string testFile = - sdf::filesystem::append(PROJECT_SOURCE_PATH, "test", "sdf", - "empty_road_sph_coords.sdf"); + const auto testFile = + sdf::testing::TestFile("sdf", "empty_road_sph_coords.sdf"); sdf::Root root; sdf::Errors errors = root.Load(testFile); @@ -109,9 +109,8 @@ TEST(ExplicitlySetInFile, EmptyRoadSphCoords) ////////////////////////////////////////////////// TEST(ExplicitlySetInFile, EmptyAxis) { - const std::string testFile = - sdf::filesystem::append(PROJECT_SOURCE_PATH, "test", "sdf", - "empty_axis.sdf"); + const auto testFile = + sdf::testing::TestFile("sdf", "empty_axis.sdf"); sdf::Root root; sdf::Errors errors = root.Load(testFile); @@ -157,9 +156,8 @@ TEST(ExplicitlySetInFile, EmptyAxis) ////////////////////////////////////////////////// TEST(ExplicitlySetInFile, ToString) { - const std::string testFile = - sdf::filesystem::append(PROJECT_SOURCE_PATH, "test", "sdf", - "empty_road_sph_coords.sdf"); + const auto testFile = + sdf::testing::TestFile("sdf", "empty_road_sph_coords.sdf"); sdf::Root root; sdf::Errors errors = root.Load(testFile); diff --git a/test/integration/frame.cc b/test/integration/frame.cc index 9e0438273..1ed67cd3a 100644 --- a/test/integration/frame.cc +++ b/test/integration/frame.cc @@ -1299,8 +1299,7 @@ TEST(DOMFrame, WorldIncludeModel) TEST(Frame, IncludeFrameWithSubmodel) { const std::string MODEL_PATH = - sdf::filesystem::append(PROJECT_SOURCE_PATH, "test", "integration", - "model", "box_with_submodel"); + sdf::testing::TestFile("integration", "model", "box_with_submodel"); std::ostringstream stream; std::string version = SDF_VERSION; diff --git a/test/integration/nested_model.cc b/test/integration/nested_model.cc index ec9181c4e..0c63cbc43 100644 --- a/test/integration/nested_model.cc +++ b/test/integration/nested_model.cc @@ -623,7 +623,7 @@ TEST(NestedModel, NestedModelWithFramesDirectComparison) const std::string expectedSdfPath = sdf::testing::TestFile( "integration", "nested_model_with_frames_expected.sdf"); - std::fstream fs; + std::ifstream fs; fs.open(expectedSdfPath); EXPECT_TRUE(fs.is_open()); std::stringstream expected; @@ -779,7 +779,7 @@ TEST(NestedModel, TwoLevelNestedModelWithFramesDirectComparison) const std::string expectedSdfPath = sdf::testing::TestFile( "integration", "two_level_nested_model_with_frames_expected.sdf"); - std::fstream fs; + std::ifstream fs; fs.open(expectedSdfPath); EXPECT_TRUE(fs.is_open()); std::stringstream expected; diff --git a/test/integration/nested_multiple_elements_error.cc b/test/integration/nested_multiple_elements_error.cc index 46c0e975a..7831d2271 100644 --- a/test/integration/nested_multiple_elements_error.cc +++ b/test/integration/nested_multiple_elements_error.cc @@ -26,17 +26,17 @@ #include "sdf/Model.hh" #include "sdf/Root.hh" #include "sdf/World.hh" + #include "test_config.hh" const auto g_testPath = sdf::testing::TestFile(); -const auto g_modelsPath = - sdf::filesystem::append(g_testPath, "integration", "model"); -const auto g_sdfPath = sdf::filesystem::append(g_testPath, "sdf"); +const auto g_modelsPath = sdf::testing::TestFile("integration", "model"); +const auto g_sdfPath = sdf::testing::TestFile("sdf"); ///////////////////////////////////////////////// std::string findFileCb(const std::string &_input) { - return sdf::filesystem::append(g_testPath, "integration", "model", _input); + return sdf::filesystem::append(g_modelsPath, _input); } ////////////////////////////////////////////////// diff --git a/test/integration/schema_test.cc b/test/integration/schema_test.cc index 1fa5e5a8f..99a309fdb 100644 --- a/test/integration/schema_test.cc +++ b/test/integration/schema_test.cc @@ -31,9 +31,7 @@ class SDFSchemaGenerator : public testing::Test public: void runXMLlint(const std::string & model) { - const std::string sdfRootSchema = sdf::filesystem::append( - PROJECT_BINARY_DIR, "sdf", SDF_PROTOCOL_VERSION, "root.xsd"); - + const auto sdfRootSchema = sdf::filesystem::append(SDF_ROOT_SCHEMA); std::string xmllintCmd = "xmllint --noout --schema " + sdfRootSchema + " " + model; std::cout << "CMD[" << xmllintCmd << "]\n"; diff --git a/test/integration/toml_parser.hh b/test/integration/toml_parser.hh index f142aad7c..528563cab 100644 --- a/test/integration/toml_parser.hh +++ b/test/integration/toml_parser.hh @@ -135,7 +135,7 @@ struct Document: public Value Document parseToml(const std::string &_filePath, sdf::Errors &_errors) { - std::fstream fs; + std::ifstream fs; fs.open(_filePath); if (!fs.good()) { diff --git a/test/test_config.hh.in b/test/test_config.hh.in index a84d1cddd..f509cfc94 100644 --- a/test/test_config.hh.in +++ b/test/test_config.hh.in @@ -18,18 +18,25 @@ #ifndef SDF_TEST_CONFIG_HH_ #define SDF_TEST_CONFIG_HH_ -#define GZ_CONFIG_PATH "@CMAKE_BINARY_DIR@/test/conf" -#define GZ_PATH "@GZ_PROGRAM@" -#define GZ_TEST_LIBRARY_PATH "${PROJECT_BINARY_DIR}/src:"\ - "@GZ-MSGS_LIBRARY_DIRS@:" -#define PROJECT_SOURCE_PATH "${PROJECT_SOURCE_DIR}" -#define PROJECT_BINARY_DIR "${CMAKE_BINARY_DIR}" -#define SDF_PROTOCOL_VERSION "${SDF_PROTOCOL_VERSION}" -#define SDF_TMP_DIR "tmp-sdf/" - #include #include + +#cmakedefine PROJECT_SOURCE_DIR +#cmakedefine PROJECT_BINARY_DIR + +#ifdef PROJECT_SOURCE_DIR +constexpr const char* kProjectSourceDir = PROJECT_SOURCE_DIR; +#else +constexpr const char* kProjectSourceDir = ""; +#endif + +#ifdef PROJECT_BINARY_DIR +constexpr const char* kProjectBinaryDir = PROJECT_BINARY_DIR; +#else +constexpr const char* kProjectBinaryDir= ""; +#endif + namespace sdf { namespace testing @@ -41,17 +48,18 @@ namespace sdf /// \return True if directory is set correctly, false otherwise bool ProjectSourcePath(std::string &_sourceDir) { + std::string bazel_path; // Bazel builds set TEST_SRCDIR - if(gz::utils::env("TEST_SRCDIR", _sourceDir)) + if(gz::utils::env("TEST_SRCDIR", _sourceDir) && + gz::utils::env("GZ_BAZEL_PATH", bazel_path)) { _sourceDir = sdf::filesystem::append( - _sourceDir, "__main__", "sdformat"); + _sourceDir, "gz", bazel_path); return true; } else { - // CMake builds set PROJECT_SOURCE_PATH - _sourceDir = PROJECT_SOURCE_PATH; + _sourceDir = kProjectSourceDir; return true; } @@ -71,7 +79,7 @@ namespace sdf } else { - _tmpDir = sdf::filesystem::append(PROJECT_BINARY_DIR, SDF_TMP_DIR); + _tmpDir = sdf::filesystem::append(kProjectBinaryDir, "sdf-tmp"); return true; } } @@ -93,7 +101,7 @@ namespace sdf } else { - _homeDir = PROJECT_BINARY_DIR; + _homeDir = kProjectBinaryDir; // Set both for linux and windows return gz::utils::setenv("HOME", _homeDir) && gz::utils::setenv("HOMEPATH", _homeDir); From 607918fcdd12e0c75739bee7af724061c4ca72ba Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 16 Feb 2023 13:31:39 -0600 Subject: [PATCH 05/23] Lint Signed-off-by: Michael Carroll --- BUILD.bazel | 13 ++++++++----- test/BUILD.bazel | 15 +++++++++------ test/test_config.hh.in | 4 ++-- 3 files changed, 19 insertions(+), 13 deletions(-) diff --git a/BUILD.bazel b/BUILD.bazel index 365854e05..f346da326 100644 --- a/BUILD.bazel +++ b/BUILD.bazel @@ -8,6 +8,7 @@ load( "gz_include_header", ) load("@gz//bazel/skylark:gz_py.bzl", "gz_py_binary") +load("@gz//bazel/lint:lint.bzl", "add_lint_tests") package( default_visibility = GZ_VISIBILITY, @@ -40,7 +41,7 @@ genrule( "sdf/**/*.convert", ]), outs = ["EmbeddedSdf.cc"], - cmd = "$(execpath :embed_sdf) --output-file $@ --sdf-root ./sdformat/sdf --input-files $(SRCS)", # noqa + cmd = "$(execpath :embed_sdf) --output-file $@ --sdf-root ./sdformat/sdf --input-files $(SRCS)", # noqa tools = [":embed_sdf"], ) @@ -107,14 +108,14 @@ cc_library( name = "sdformat", srcs = sources + private_headers + ["EmbeddedSdf.cc"], hdrs = public_headers, + defines = [ + 'SDF_SHARE_PATH=\\".\\"', + 'SDF_VERSION_PATH=\\"sdformat\\"', + ], includes = [ "include", "src", ], - defines = [ - 'SDF_SHARE_PATH=\\".\\"', - 'SDF_VERSION_PATH=\\"sdformat\\"', - ], deps = [ ":urdf", GZ_ROOT + "math", @@ -149,3 +150,5 @@ test_sources = glob( ) for src in test_sources] exports_files(["sdf"]) + +add_lint_tests() diff --git a/test/BUILD.bazel b/test/BUILD.bazel index 2743e75f0..39d08fab8 100644 --- a/test/BUILD.bazel +++ b/test/BUILD.bazel @@ -5,16 +5,19 @@ load( ) cmake_configure_file( - name = "config", - src = "test_config.hh.in", - out = "test_config.hh", - cmakelists = ["CMakeLists.txt"], - defines = [] + name = "config", + src = "test_config.hh.in", + out = "test_config.hh", + cmakelists = ["CMakeLists.txt"], + defines = [], ) cc_library( name = "test_utils", - hdrs = ["test_utils.hh", "test_config.hh"], + hdrs = [ + "test_config.hh", + "test_utils.hh", + ], includes = ["."], visibility = ["//visibility:public"], ) diff --git a/test/test_config.hh.in b/test/test_config.hh.in index f509cfc94..989f2bba5 100644 --- a/test/test_config.hh.in +++ b/test/test_config.hh.in @@ -22,8 +22,8 @@ #include -#cmakedefine PROJECT_SOURCE_DIR -#cmakedefine PROJECT_BINARY_DIR +#cmakedefine PROJECT_SOURCE_DIR "@PROJECT_SOURCE_DIR@" +#cmakedefine PROJECT_BINARY_DIR "@PROJECT_BINARY_DIR@" #ifdef PROJECT_SOURCE_DIR constexpr const char* kProjectSourceDir = PROJECT_SOURCE_DIR; From 7b54dd3b61cb350f18cc041017cdefb1fc2d62fc Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Mon, 12 Jun 2023 20:49:13 +0000 Subject: [PATCH 06/23] Add utils back to parser Signed-off-by: Michael Carroll --- src/parser_TEST.cc | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/parser_TEST.cc b/src/parser_TEST.cc index bd7ff37cc..5b6cd659e 100644 --- a/src/parser_TEST.cc +++ b/src/parser_TEST.cc @@ -25,7 +25,9 @@ #include "sdf/Filesystem.hh" #include + #include "test_config.hh" +#include "test_utils.hh" ///////////////////////////////////////////////// TEST(Parser, initStringTrim) From 0deefe365fa80168a423e1f82242cef6a4fced43 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Wed, 9 Aug 2023 21:28:34 +0000 Subject: [PATCH 07/23] Fix gz_TEST Signed-off-by: Michael Carroll --- src/gz_TEST.cc | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/gz_TEST.cc b/src/gz_TEST.cc index 38cf851dd..f7fda467a 100644 --- a/src/gz_TEST.cc +++ b/src/gz_TEST.cc @@ -146,7 +146,7 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // that have duplicate names. { const auto path = - sdf::testing::TestFile("sdf", "world_duplicate.world"); + sdf::testing::TestFile("sdf", "world_duplicate.sdf"); // Check world_duplicate.sdf std::string output = @@ -219,7 +219,7 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) // Check an SDF model file is allowed to have duplicate plugin names { const auto path = - sdf::testing::TestFile("sdf", "model_link_duplicate_plugins.sdf"); + sdf::testing::TestFile("sdf", "model_duplicate_plugins.sdf"); std::string output = custom_exec_str(GzCommand() + " sdf -k " + path + SdfVersion()); @@ -524,7 +524,7 @@ TEST(check, GZ_UTILS_TEST_DISABLED_ON_WIN32(SDF)) { const auto path = sdf::testing::TestFile("sdf", - "nested_invalid_reserved_names.sdf"); + "model_invalid_reserved_names.sdf"); // Check model_invalid_reserved_names.sdf std::string output = From 51a49dea6c569751c8bdaa54a6c624c6994ca6bf Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Wed, 9 Aug 2023 21:28:57 +0000 Subject: [PATCH 08/23] Ignore pycache folders Signed-off-by: Michael Carroll --- .gitignore | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.gitignore b/.gitignore index 08e5eba3e..50e689128 100644 --- a/.gitignore +++ b/.gitignore @@ -3,3 +3,5 @@ build build_* *.*.sw? .vscode + +__pycache__ From c5b5828567250ba47a81ef6367be6962e91a1a96 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Wed, 9 Aug 2023 21:48:25 +0000 Subject: [PATCH 09/23] Fix parser_TEST Signed-off-by: Michael Carroll --- src/parser_TEST.cc | 8 ++++++++ test/test_config.hh.in | 1 + 2 files changed, 9 insertions(+) diff --git a/src/parser_TEST.cc b/src/parser_TEST.cc index 31790f709..44018a6fa 100644 --- a/src/parser_TEST.cc +++ b/src/parser_TEST.cc @@ -419,10 +419,18 @@ TEST(Parser, IncludesErrors) const auto path = sdf::testing::TestFile("sdf", "includes_missing_model.sdf"); + sdf::setFindCallback([&](const std::string &/*_file*/) + { + return ""; + }); + sdf::SDFPtr sdf(new sdf::SDF()); sdf::init(sdf); sdf::readFile(path, sdf); + + std::cout << buffer.str() << std::endl; + EXPECT_PRED2(sdf::testing::contains, buffer.str(), "Error Code " + std::to_string( diff --git a/test/test_config.hh.in b/test/test_config.hh.in index 989f2bba5..303eab375 100644 --- a/test/test_config.hh.in +++ b/test/test_config.hh.in @@ -80,6 +80,7 @@ namespace sdf else { _tmpDir = sdf::filesystem::append(kProjectBinaryDir, "sdf-tmp"); + sdf::filesystem::create_directory(_tmpDir); return true; } } From 0f6044a1b584dfe9a8caf11faeb1f753ecbe0401 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 10 Aug 2023 14:54:49 +0000 Subject: [PATCH 10/23] Bazel nits Signed-off-by: Michael Carroll --- BUILD.bazel | 7 ++++--- test/BUILD.bazel | 2 ++ 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/BUILD.bazel b/BUILD.bazel index a188adbfb..2e7934c4a 100644 --- a/BUILD.bazel +++ b/BUILD.bazel @@ -3,19 +3,19 @@ load( "GZ_FEATURES", "GZ_ROOT", "GZ_VISIBILITY", + "add_lint_tests", "gz_configure_header", "gz_export_header", "gz_include_header", + "gz_py_binary", ) -load("@gz//bazel/skylark:gz_py.bzl", "gz_py_binary") -load("@gz//bazel/lint:lint.bzl", "add_lint_tests") package( default_visibility = GZ_VISIBILITY, features = GZ_FEATURES, ) -licenses(["notice"]) # Apache-2.0 +licenses(["notice"]) exports_files(["LICENSE"]) @@ -32,6 +32,7 @@ gz_configure_header( gz_py_binary( name = "embed_sdf", srcs = ["sdf/embedSdf.py"], + main = "sdf/embedSdf.py", ) genrule( diff --git a/test/BUILD.bazel b/test/BUILD.bazel index 39d08fab8..2cd16e5cc 100644 --- a/test/BUILD.bazel +++ b/test/BUILD.bazel @@ -4,6 +4,8 @@ load( "cmake_configure_file", ) +licenses(["notice"]) + cmake_configure_file( name = "config", src = "test_config.hh.in", From c9a1b856d646fc8cebd41b9a6315e041f9537192 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 10 Aug 2023 16:11:46 +0000 Subject: [PATCH 11/23] Fix path logic Signed-off-by: Michael Carroll --- BUILD.bazel | 2 +- sdf/embedSdf.py | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/BUILD.bazel b/BUILD.bazel index 2e7934c4a..eaca4bd2b 100644 --- a/BUILD.bazel +++ b/BUILD.bazel @@ -42,7 +42,7 @@ genrule( "sdf/**/*.convert", ]), outs = ["EmbeddedSdf.cc"], - cmd = "$(execpath :embed_sdf) --output-file $@ --sdf-root ./sdformat/sdf --input-files $(SRCS)", # noqa + cmd = "$(execpath :embed_sdf) --output-file $@ --sdf-root sdformat/sdf --input-files $(SRCS)", # noqa tools = [":embed_sdf"], ) diff --git a/sdf/embedSdf.py b/sdf/embedSdf.py index 292958712..8e81054d2 100644 --- a/sdf/embedSdf.py +++ b/sdf/embedSdf.py @@ -160,10 +160,10 @@ def generate_map_content(paths: List[Path], relative_to: Optional[str] = None) - for path in paths: with open(path, "r", encoding="utf8") as input_sdf: file_content = input_sdf.read() - # Strip relative path if requested if relative_to is not None: - path = path.relative_to(relative_to) + _, relative_path = str(path).split(relative_to) + path = relative_path content.append(embed_sdf_content(str(path), file_content)) return ",".join(content) From cc8a96a94c048526d4b74274092e2a69d6875ef0 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 10 Aug 2023 16:17:24 +0000 Subject: [PATCH 12/23] Fix visibility Signed-off-by: Michael Carroll --- test/BUILD.bazel | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/test/BUILD.bazel b/test/BUILD.bazel index 2cd16e5cc..c2d87d12d 100644 --- a/test/BUILD.bazel +++ b/test/BUILD.bazel @@ -1,9 +1,17 @@ load( "@gz//bazel/skylark:build_defs.bzl", "GZ_ROOT", + "GZ_VISIBILITY", + "GZ_FEATURES", "cmake_configure_file", ) +package( + default_visibility = GZ_VISIBILITY, + features = GZ_FEATURES, +) + + licenses(["notice"]) cmake_configure_file( @@ -21,7 +29,10 @@ cc_library( "test_utils.hh", ], includes = ["."], - visibility = ["//visibility:public"], + deps = [ + GZ_ROOT + "utils:utils", + GZ_ROOT + "sdformat:sdformat" + ] ) integration_test_sources = glob( From 119cabd95e7a548884f96e396605e4ff66beb505 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 10 Aug 2023 17:10:15 +0000 Subject: [PATCH 13/23] Fix strings Signed-off-by: Michael Carroll --- include/sdf/Param.hh | 5 +++++ src/SDF.cc | 2 +- 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/include/sdf/Param.hh b/include/sdf/Param.hh index 29c5b90e5..dea9aa07a 100644 --- a/include/sdf/Param.hh +++ b/include/sdf/Param.hh @@ -85,6 +85,11 @@ namespace sdf : val(_val), precision(_precision) {} }; + // Template deduction guide for ParamVariant + template + ParamStreamer(const ParamVariant &_val, int _precision) + -> ParamStreamer; + template std::ostream& operator<<(std::ostream &os, ParamStreamer s) { diff --git a/src/SDF.cc b/src/SDF.cc index 74cf4825d..9943b679d 100644 --- a/src/SDF.cc +++ b/src/SDF.cc @@ -126,7 +126,7 @@ std::string findFile(const std::string &_filename, bool _searchLocalPath, // Next check the versioned install path. path = sdf::filesystem::append(sdfSharePath(), - "sdformat" SDF_MAJOR_VERSION_STR, + "sdformat" + std::string(SDF_MAJOR_VERSION_STR), sdf::SDF::Version(), filename); if (sdf::filesystem::exists(path)) { From 5c854ea6f7c7b459dbd54caaf63c817b16d2659d Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 10 Aug 2023 18:17:58 +0000 Subject: [PATCH 14/23] Use standard vars Signed-off-by: Michael Carroll --- include/sdf/config.hh.in | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/include/sdf/config.hh.in b/include/sdf/config.hh.in index 7b128ebad..cabba6081 100644 --- a/include/sdf/config.hh.in +++ b/include/sdf/config.hh.in @@ -52,7 +52,7 @@ #endif #ifndef SDF_VERSION_PATH -#define SDF_VERSION_PATH "${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${SDF_MAJOR_VERSION}/${SDF_PKG_VERSION}" -#endif +#define SDF_VERSION_PATH "${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/${SDF_PKG_VERSION}" +#endif #endif // #ifndef SDF_CONFIG_HH_ From a774176db096df317003c8851b58785e4c6d43a9 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 10 Aug 2023 18:34:23 +0000 Subject: [PATCH 15/23] Fix string conversions Signed-off-by: Michael Carroll --- src/Capsule_TEST.cc | 2 +- src/Cylinder_TEST.cc | 2 +- src/Plane_TEST.cc | 2 +- src/SDF_TEST.cc | 26 +++++++++++++------------- 4 files changed, 16 insertions(+), 16 deletions(-) diff --git a/src/Capsule_TEST.cc b/src/Capsule_TEST.cc index b24495966..f2a2993f2 100644 --- a/src/Capsule_TEST.cc +++ b/src/Capsule_TEST.cc @@ -154,7 +154,7 @@ TEST(DOMCapsule, Load) // Add a radius element sdf::ElementPtr radiusDesc(new sdf::Element()); radiusDesc->SetName("radius"); - radiusDesc->AddValue("double", "1.0", "1", "radius"); + radiusDesc->AddValue("double", "1.0", true, "radius"); sdf->AddElementDescription(radiusDesc); sdf::ElementPtr radiusElem = sdf->AddElement("radius"); radiusElem->Set(2.0); diff --git a/src/Cylinder_TEST.cc b/src/Cylinder_TEST.cc index efc7f302b..b1edb35a5 100644 --- a/src/Cylinder_TEST.cc +++ b/src/Cylinder_TEST.cc @@ -150,7 +150,7 @@ TEST(DOMCylinder, Load) // Add a radius element sdf::ElementPtr radiusDesc(new sdf::Element()); radiusDesc->SetName("radius"); - radiusDesc->AddValue("double", "1.0", "1", "radius"); + radiusDesc->AddValue("double", "1.0", true, "radius"); sdf->AddElementDescription(radiusDesc); sdf::ElementPtr radiusElem = sdf->AddElement("radius"); radiusElem->Set(2.0); diff --git a/src/Plane_TEST.cc b/src/Plane_TEST.cc index ea93941a0..81439ffed 100644 --- a/src/Plane_TEST.cc +++ b/src/Plane_TEST.cc @@ -145,7 +145,7 @@ TEST(DOMPlane, Load) // Add a normal element sdf::ElementPtr normalDesc(new sdf::Element()); normalDesc->SetName("normal"); - normalDesc->AddValue("vector3", "0 0 1", "1", "normal"); + normalDesc->AddValue("vector3", "0 0 1", true, "normal"); sdf->AddElementDescription(normalDesc); sdf::ElementPtr normalElem = sdf->AddElement("normal"); normalElem->Set({1, 0, 0}); diff --git a/src/SDF_TEST.cc b/src/SDF_TEST.cc index 43d2e4732..b9ead0e22 100644 --- a/src/SDF_TEST.cc +++ b/src/SDF_TEST.cc @@ -306,56 +306,56 @@ TEST(SDF, EmptyValues) elem.reset(new sdf::Element()); EXPECT_FALSE(elem->Get(emptyString)); - elem->AddValue("bool", "true", "0", "description"); + elem->AddValue("bool", "true", false, "description"); EXPECT_TRUE(elem->Get(emptyString)); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), 0); - elem->AddValue("int", "12", "0", "description"); + elem->AddValue("int", "12", false, "description"); EXPECT_EQ(elem->Get(emptyString), 12); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), static_cast(0)); - elem->AddValue("unsigned int", "123", "0", "description"); + elem->AddValue("unsigned int", "123", false, "description"); EXPECT_EQ(elem->Get(emptyString), static_cast(123)); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), '\0'); - elem->AddValue("char", "a", "0", "description"); + elem->AddValue("char", "a", false, "description"); EXPECT_EQ(elem->Get(emptyString), 'a'); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), ""); - elem->AddValue("string", "hello", "0", "description"); + elem->AddValue("string", "hello", false, "description"); EXPECT_EQ(elem->Get(emptyString), "hello"); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), gz::math::Vector2d()); - elem->AddValue("vector2d", "1 2", "0", "description"); + elem->AddValue("vector2d", "1 2", false, "description"); EXPECT_EQ(elem->Get(emptyString), gz::math::Vector2d(1, 2)); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), gz::math::Vector3d()); - elem->AddValue("vector3", "1 2 3", "0", "description"); + elem->AddValue("vector3", "1 2 3", false, "description"); EXPECT_EQ(elem->Get(emptyString), gz::math::Vector3d(1, 2, 3)); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), gz::math::Quaterniond()); - elem->AddValue("quaternion", "1 2 3", "0", "description"); + elem->AddValue("quaternion", "1 2 3", false, "description"); EXPECT_EQ(elem->Get(emptyString), gz::math::Quaterniond(-2.14159, 1.14159, -0.141593)); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), gz::math::Pose3d()); - elem->AddValue("pose", "1.0 2.0 3.0 4.0 5.0 6.0", "0", "description"); + elem->AddValue("pose", "1.0 2.0 3.0 4.0 5.0 6.0", false, "description"); EXPECT_EQ(elem->Get(emptyString).Pos(), gz::math::Pose3d(1, 2, 3, 4, 5, 6).Pos()); EXPECT_EQ(elem->Get(emptyString).Rot().Euler(), @@ -364,23 +364,23 @@ TEST(SDF, EmptyValues) elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), gz::math::Color()); - elem->AddValue("color", ".1 .2 .3 1.0", "0", "description"); + elem->AddValue("color", ".1 .2 .3 1.0", false, "description"); EXPECT_EQ(elem->Get(emptyString), gz::math::Color(.1f, .2f, .3f, 1.0f)); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), sdf::Time()); - elem->AddValue("time", "1 2", "0", "description"); + elem->AddValue("time", "1 2", false, "description"); EXPECT_EQ(elem->Get(emptyString), sdf::Time(1, 2)); elem.reset(new sdf::Element()); EXPECT_NEAR(elem->Get(emptyString), 0.0, 1e-6); - elem->AddValue("float", "12.34", "0", "description"); + elem->AddValue("float", "12.34", false, "description"); EXPECT_NEAR(elem->Get(emptyString), 12.34, 1e-6); elem.reset(new sdf::Element()); EXPECT_NEAR(elem->Get(emptyString), 0.0, 1e-6); - elem->AddValue("double", "12.34", "0", "description"); + elem->AddValue("double", "12.34", false, "description"); EXPECT_NEAR(elem->Get(emptyString), 12.34, 1e-6); } From 17d12ecd178e67f3b243a35427b19d369aaf2850 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 10 Aug 2023 18:34:23 +0000 Subject: [PATCH 16/23] Fix string conversions Signed-off-by: Michael Carroll --- src/Capsule_TEST.cc | 2 +- src/Cylinder_TEST.cc | 2 +- src/Plane_TEST.cc | 2 +- src/SDF_TEST.cc | 28 ++++++++++++++-------------- 4 files changed, 17 insertions(+), 17 deletions(-) diff --git a/src/Capsule_TEST.cc b/src/Capsule_TEST.cc index b24495966..f2a2993f2 100644 --- a/src/Capsule_TEST.cc +++ b/src/Capsule_TEST.cc @@ -154,7 +154,7 @@ TEST(DOMCapsule, Load) // Add a radius element sdf::ElementPtr radiusDesc(new sdf::Element()); radiusDesc->SetName("radius"); - radiusDesc->AddValue("double", "1.0", "1", "radius"); + radiusDesc->AddValue("double", "1.0", true, "radius"); sdf->AddElementDescription(radiusDesc); sdf::ElementPtr radiusElem = sdf->AddElement("radius"); radiusElem->Set(2.0); diff --git a/src/Cylinder_TEST.cc b/src/Cylinder_TEST.cc index efc7f302b..b1edb35a5 100644 --- a/src/Cylinder_TEST.cc +++ b/src/Cylinder_TEST.cc @@ -150,7 +150,7 @@ TEST(DOMCylinder, Load) // Add a radius element sdf::ElementPtr radiusDesc(new sdf::Element()); radiusDesc->SetName("radius"); - radiusDesc->AddValue("double", "1.0", "1", "radius"); + radiusDesc->AddValue("double", "1.0", true, "radius"); sdf->AddElementDescription(radiusDesc); sdf::ElementPtr radiusElem = sdf->AddElement("radius"); radiusElem->Set(2.0); diff --git a/src/Plane_TEST.cc b/src/Plane_TEST.cc index ea93941a0..81439ffed 100644 --- a/src/Plane_TEST.cc +++ b/src/Plane_TEST.cc @@ -145,7 +145,7 @@ TEST(DOMPlane, Load) // Add a normal element sdf::ElementPtr normalDesc(new sdf::Element()); normalDesc->SetName("normal"); - normalDesc->AddValue("vector3", "0 0 1", "1", "normal"); + normalDesc->AddValue("vector3", "0 0 1", true, "normal"); sdf->AddElementDescription(normalDesc); sdf::ElementPtr normalElem = sdf->AddElement("normal"); normalElem->Set({1, 0, 0}); diff --git a/src/SDF_TEST.cc b/src/SDF_TEST.cc index 43d2e4732..4b351f9b9 100644 --- a/src/SDF_TEST.cc +++ b/src/SDF_TEST.cc @@ -284,7 +284,7 @@ TEST(SDF, SetRoot) sdf::ElementPtr elem; elem.reset(new sdf::Element()); - elem->AddValue("bool", "true", "0", "description"); + elem->AddValue("bool", "true", false, "description"); s.SetRoot(elem); EXPECT_EQ(elem, s.Root()); @@ -306,56 +306,56 @@ TEST(SDF, EmptyValues) elem.reset(new sdf::Element()); EXPECT_FALSE(elem->Get(emptyString)); - elem->AddValue("bool", "true", "0", "description"); + elem->AddValue("bool", "true", false, "description"); EXPECT_TRUE(elem->Get(emptyString)); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), 0); - elem->AddValue("int", "12", "0", "description"); + elem->AddValue("int", "12", false, "description"); EXPECT_EQ(elem->Get(emptyString), 12); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), static_cast(0)); - elem->AddValue("unsigned int", "123", "0", "description"); + elem->AddValue("unsigned int", "123", false, "description"); EXPECT_EQ(elem->Get(emptyString), static_cast(123)); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), '\0'); - elem->AddValue("char", "a", "0", "description"); + elem->AddValue("char", "a", false, "description"); EXPECT_EQ(elem->Get(emptyString), 'a'); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), ""); - elem->AddValue("string", "hello", "0", "description"); + elem->AddValue("string", "hello", false, "description"); EXPECT_EQ(elem->Get(emptyString), "hello"); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), gz::math::Vector2d()); - elem->AddValue("vector2d", "1 2", "0", "description"); + elem->AddValue("vector2d", "1 2", false, "description"); EXPECT_EQ(elem->Get(emptyString), gz::math::Vector2d(1, 2)); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), gz::math::Vector3d()); - elem->AddValue("vector3", "1 2 3", "0", "description"); + elem->AddValue("vector3", "1 2 3", false, "description"); EXPECT_EQ(elem->Get(emptyString), gz::math::Vector3d(1, 2, 3)); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), gz::math::Quaterniond()); - elem->AddValue("quaternion", "1 2 3", "0", "description"); + elem->AddValue("quaternion", "1 2 3", false, "description"); EXPECT_EQ(elem->Get(emptyString), gz::math::Quaterniond(-2.14159, 1.14159, -0.141593)); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), gz::math::Pose3d()); - elem->AddValue("pose", "1.0 2.0 3.0 4.0 5.0 6.0", "0", "description"); + elem->AddValue("pose", "1.0 2.0 3.0 4.0 5.0 6.0", false, "description"); EXPECT_EQ(elem->Get(emptyString).Pos(), gz::math::Pose3d(1, 2, 3, 4, 5, 6).Pos()); EXPECT_EQ(elem->Get(emptyString).Rot().Euler(), @@ -364,23 +364,23 @@ TEST(SDF, EmptyValues) elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), gz::math::Color()); - elem->AddValue("color", ".1 .2 .3 1.0", "0", "description"); + elem->AddValue("color", ".1 .2 .3 1.0", false, "description"); EXPECT_EQ(elem->Get(emptyString), gz::math::Color(.1f, .2f, .3f, 1.0f)); elem.reset(new sdf::Element()); EXPECT_EQ(elem->Get(emptyString), sdf::Time()); - elem->AddValue("time", "1 2", "0", "description"); + elem->AddValue("time", "1 2", false, "description"); EXPECT_EQ(elem->Get(emptyString), sdf::Time(1, 2)); elem.reset(new sdf::Element()); EXPECT_NEAR(elem->Get(emptyString), 0.0, 1e-6); - elem->AddValue("float", "12.34", "0", "description"); + elem->AddValue("float", "12.34", false, "description"); EXPECT_NEAR(elem->Get(emptyString), 12.34, 1e-6); elem.reset(new sdf::Element()); EXPECT_NEAR(elem->Get(emptyString), 0.0, 1e-6); - elem->AddValue("double", "12.34", "0", "description"); + elem->AddValue("double", "12.34", false, "description"); EXPECT_NEAR(elem->Get(emptyString), 12.34, 1e-6); } From 1212060a6e2f5be55eb009c5c9e693a98898911e Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 10 Aug 2023 18:54:55 +0000 Subject: [PATCH 17/23] Fix embedded sdf Signed-off-by: Michael Carroll --- BUILD.bazel | 2 +- include/sdf/config.hh.in | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/BUILD.bazel b/BUILD.bazel index eaca4bd2b..0becaffeb 100644 --- a/BUILD.bazel +++ b/BUILD.bazel @@ -42,7 +42,7 @@ genrule( "sdf/**/*.convert", ]), outs = ["EmbeddedSdf.cc"], - cmd = "$(execpath :embed_sdf) --output-file $@ --sdf-root sdformat/sdf --input-files $(SRCS)", # noqa + cmd = "$(execpath :embed_sdf) --output-file $@ --sdf-root sdformat/sdf/ --input-files $(SRCS)", # noqa tools = [":embed_sdf"], ) diff --git a/include/sdf/config.hh.in b/include/sdf/config.hh.in index cabba6081..6a32cb8bc 100644 --- a/include/sdf/config.hh.in +++ b/include/sdf/config.hh.in @@ -52,7 +52,7 @@ #endif #ifndef SDF_VERSION_PATH -#define SDF_VERSION_PATH "${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/${SDF_PKG_VERSION}" +#define SDF_VERSION_PATH "${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/${PROJECT_VERSION}" #endif #endif // #ifndef SDF_CONFIG_HH_ From d0062f525e784ef8dcb10667999f347575d46dcb Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 10 Aug 2023 19:54:09 +0000 Subject: [PATCH 18/23] Fix converter test Signed-off-by: Michael Carroll --- src/SDF_TEST.cc | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/src/SDF_TEST.cc b/src/SDF_TEST.cc index 4b351f9b9..44bb9f284 100644 --- a/src/SDF_TEST.cc +++ b/src/SDF_TEST.cc @@ -16,7 +16,10 @@ */ #include + #include +#include + #include #include #include @@ -788,17 +791,17 @@ TEST(SDF, WriteURIPath) ASSERT_EQ(std::remove(tempFile.c_str()), 0); ASSERT_EQ(rmdir(tempDir.c_str()), 0); } - ///////////////////////////////////////////////// TEST(SDF, FindFileModelSDFCurrDir) { - std::string currDir; - - // Get current directory path from $PWD env variable - currDir = sdf::filesystem::current_path(); + // Change to a temporary directory before running test + auto prevPath = std::filesystem::current_path(); + std::string tmpDir; + ASSERT_TRUE(sdf::testing::TestTmpPath(tmpDir)); + std::filesystem::current_path(tmpDir); // A file named model.sdf in current directory - auto tempFile = currDir + "/model.sdf"; + auto tempFile = tmpDir + "/model.sdf"; sdf::SDF tempSDF; tempSDF.Write(tempFile); @@ -815,5 +818,6 @@ TEST(SDF, FindFileModelSDFCurrDir) // Cleanup ASSERT_EQ(std::remove(tempFile.c_str()), 0); + std::filesystem::current_path(prevPath); } #endif // _WIN32 From 27c540c6f922841805c00342b891acb9f3cdc26d Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 7 Sep 2023 21:59:29 +0000 Subject: [PATCH 19/23] Lint Signed-off-by: Michael Carroll --- src/SDF.cc | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/SDF.cc b/src/SDF.cc index 9943b679d..7a43d0f9a 100644 --- a/src/SDF.cc +++ b/src/SDF.cc @@ -126,8 +126,9 @@ std::string findFile(const std::string &_filename, bool _searchLocalPath, // Next check the versioned install path. path = sdf::filesystem::append(sdfSharePath(), - "sdformat" + std::string(SDF_MAJOR_VERSION_STR), - sdf::SDF::Version(), filename); + "sdformat" + std::string(SDF_MAJOR_VERSION_STR), + sdf::SDF::Version(), filename); + if (sdf::filesystem::exists(path)) { return path; From 3d4e5908c8dca93e68857afae2cb5b82516bfbd2 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 7 Dec 2023 15:24:02 +0000 Subject: [PATCH 20/23] Update bazel files Signed-off-by: Michael Carroll --- BUILD.bazel | 45 +++++++++++++++++++++++++++++++++++++++++++++ test/BUILD.bazel | 9 ++++----- 2 files changed, 49 insertions(+), 5 deletions(-) diff --git a/BUILD.bazel b/BUILD.bazel index 0becaffeb..0e26e2c84 100644 --- a/BUILD.bazel +++ b/BUILD.bazel @@ -4,6 +4,7 @@ load( "GZ_ROOT", "GZ_VISIBILITY", "add_lint_tests", + "gz_configure_file", "gz_configure_header", "gz_export_header", "gz_include_header", @@ -125,6 +126,16 @@ cc_library( ], ) +cc_library( + name = "sdformat_internal", + srcs = [ + "src/gz.cc", + "src/gz.hh", + ], + visibility = ["//visibility:private"], + deps = [":sdformat"], +) + test_sources = glob( ["src/*_TEST.cc"], exclude = ["src/gz_TEST.cc"], @@ -150,6 +161,40 @@ test_sources = glob( ], ) for src in test_sources] +gz_configure_file( + name = "sdformat.rb", + src = "src/cmd/cmdsdformat.rb.in", + out = "cmdsdformat.rb", + cmakelists = ["CMakeLists.txt"], + defines = [ + "library_location=libgz-sdformat.so", + ], + package = "sdformat", + visibility = [GZ_ROOT + "tools:__pkg__"], +) + +gz_configure_file( + name = "sdformat_yaml", + src = "conf/sdformat.yaml.in", + out = "sdformat.yaml", + cmakelists = ["CMakeLists.txt"], + defines = [ + "gz_library_path=gz/sdformat/cmdsdformat.rb", + ], + package = "sdformat", + visibility = [GZ_ROOT + "tools:__pkg__"], +) + +cc_binary( + name = "libgz-sdformat.so", + srcs = [":sdformat_internal"], + linkshared = True, + visibility = [GZ_ROOT + "tools:__pkg__"], + deps = [ + ":sdformat", + ], +) + exports_files(["sdf"]) add_lint_tests() diff --git a/test/BUILD.bazel b/test/BUILD.bazel index c2d87d12d..bb1baa410 100644 --- a/test/BUILD.bazel +++ b/test/BUILD.bazel @@ -1,8 +1,8 @@ load( "@gz//bazel/skylark:build_defs.bzl", + "GZ_FEATURES", "GZ_ROOT", "GZ_VISIBILITY", - "GZ_FEATURES", "cmake_configure_file", ) @@ -11,7 +11,6 @@ package( features = GZ_FEATURES, ) - licenses(["notice"]) cmake_configure_file( @@ -30,9 +29,9 @@ cc_library( ], includes = ["."], deps = [ - GZ_ROOT + "utils:utils", - GZ_ROOT + "sdformat:sdformat" - ] + GZ_ROOT + "utils:utils", + GZ_ROOT + "sdformat:sdformat", + ], ) integration_test_sources = glob( From 53732ed2c07379fd65337d535b743d95402aaa13 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 7 Dec 2023 15:37:32 +0000 Subject: [PATCH 21/23] Add detail prefix Signed-off-by: Michael Carroll --- src/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 53ad89e44..a772cdd3a 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -64,7 +64,7 @@ if (BUILD_TESTING) if (TARGET UNIT_gz_TEST) target_compile_definitions(UNIT_gz_TEST PRIVATE -DGZ_PATH="${GZ_PROGRAM}" - -DGZ_CONFIG_PATH="${CMAKE_BINARY_DIR}/test/conf" + -DDETAIL_GZ_CONFIG_PATH="${CMAKE_BINARY_DIR}/test/conf" -DGZ_TEST_LIBRARY_PATH="${PROJECT_BINARY_DIR}/src") endif() From 874d4a4ec9936f424c4065eb4af1b3da39c53164 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 7 Dec 2023 16:09:38 +0000 Subject: [PATCH 22/23] Fix test path Signed-off-by: Michael Carroll --- src/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index a772cdd3a..408add0c5 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -64,7 +64,7 @@ if (BUILD_TESTING) if (TARGET UNIT_gz_TEST) target_compile_definitions(UNIT_gz_TEST PRIVATE -DGZ_PATH="${GZ_PROGRAM}" - -DDETAIL_GZ_CONFIG_PATH="${CMAKE_BINARY_DIR}/test/conf" + -DDETAIL_GZ_CONFIG_PATH="${CMAKE_BINARY_DIR}/test/conf/$" -DGZ_TEST_LIBRARY_PATH="${PROJECT_BINARY_DIR}/src") endif() From 5c4e4e6ac127c804e5995c955aae44def097b109 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Mon, 11 Dec 2023 16:48:43 +0000 Subject: [PATCH 23/23] Set homepath on Windows Signed-off-by: Michael Carroll --- src/CMakeLists.txt | 2 +- src/parser_TEST.cc | 6 ++++++ 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index a772cdd3a..408add0c5 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -64,7 +64,7 @@ if (BUILD_TESTING) if (TARGET UNIT_gz_TEST) target_compile_definitions(UNIT_gz_TEST PRIVATE -DGZ_PATH="${GZ_PROGRAM}" - -DDETAIL_GZ_CONFIG_PATH="${CMAKE_BINARY_DIR}/test/conf" + -DDETAIL_GZ_CONFIG_PATH="${CMAKE_BINARY_DIR}/test/conf/$" -DGZ_TEST_LIBRARY_PATH="${PROJECT_BINARY_DIR}/src") endif() diff --git a/src/parser_TEST.cc b/src/parser_TEST.cc index 09e1641b4..f8a614e34 100644 --- a/src/parser_TEST.cc +++ b/src/parser_TEST.cc @@ -947,7 +947,13 @@ int main(int argc, char **argv) // temporarily set HOME std::string homeDir; sdf::testing::TestTmpPath(homeDir); + +#ifdef _WIN32 + gz::utils::setenv("HOMEPATH", homeDir); +#else gz::utils::setenv("HOME", homeDir); +#endif + sdf::Console::Clear(); ::testing::InitGoogleTest(&argc, argv);