Skip to content

Commit

Permalink
Merge pull request #1369 from gazebosim/scpeters/merge_14_to_main
Browse files Browse the repository at this point in the history
Merge sdf14 to main
  • Loading branch information
scpeters authored Feb 27, 2024
2 parents 3c8c907 + 72482b1 commit ca74234
Show file tree
Hide file tree
Showing 42 changed files with 1,340 additions and 326 deletions.
9 changes: 7 additions & 2 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
@@ -1,14 +1,19 @@
name: Ubuntu

on: [push, pull_request]
on:
pull_request:
push:
branches:
- 'sdf[0-9]?'
- 'main'

jobs:
jammy-ci:
runs-on: ubuntu-latest
name: Ubuntu Jammy CI
steps:
- name: Checkout
uses: actions/checkout@v3
uses: actions/checkout@v4
- name: Compile and test
id: ci
uses: gazebo-tooling/action-gz-ci@jammy
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/macos.yml
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ jobs:
working-directory: build
run: |
export PYTHONPATH=$PYTHONPATH:$(brew --prefix)/lib/python
cmake .. -DCMAKE_INSTALL_PREFIX=$(brew --prefix)/Cellar/${PACKAGE}/HEAD -DPython3_EXECUTABLE=$(brew --prefix)/bin/python3
cmake .. -DCMAKE_INSTALL_PREFIX=$(brew --prefix)/Cellar/${PACKAGE}/HEAD -DPython3_EXECUTABLE=$(brew --prefix python3)/bin/python3
- run: make
working-directory: build
- run: make test
Expand Down
1 change: 0 additions & 1 deletion .github/workflows/triage.yml
Original file line number Diff line number Diff line change
Expand Up @@ -14,4 +14,3 @@ jobs:
with:
project-url: https://github.com/orgs/gazebosim/projects/7
github-token: ${{ secrets.TRIAGE_TOKEN }}

200 changes: 200 additions & 0 deletions BUILD.bazel
Original file line number Diff line number Diff line change
@@ -0,0 +1,200 @@
load(
"@gz//bazel/skylark:build_defs.bzl",
"GZ_FEATURES",
"GZ_ROOT",
"GZ_VISIBILITY",
"add_lint_tests",
"gz_configure_file",
"gz_configure_header",
"gz_export_header",
"gz_include_header",
"gz_py_binary",
)

package(
default_visibility = GZ_VISIBILITY,
features = GZ_FEATURES,
)

licenses(["notice"])

exports_files(["LICENSE"])

gz_configure_header(
name = "config",
src = "include/sdf/config.hh.in",
cmakelists = ["CMakeLists.txt"],
defines = {
"CMAKE_INSTALL_FULL_DATAROOTDIR": "unused",
},
package = "sdformat",
)

gz_py_binary(
name = "embed_sdf",
srcs = ["sdf/embedSdf.py"],
main = "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,
defines = [
'SDF_SHARE_PATH=\\".\\"',
'SDF_VERSION_PATH=\\"sdformat\\"',
],
includes = [
"include",
"src",
],
deps = [
":urdf",
GZ_ROOT + "math",
GZ_ROOT + "utils",
"@tinyxml2",
],
)

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"],
)

[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]

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()
45 changes: 45 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -529,6 +529,30 @@

## libsdformat 12.X

### libsdformat 12.7.2 (2023-09-01)

1. Fixed 1.9/light.sdf
* [Pull request #1281](https://github.com/gazebosim/sdformat/pull/1281)

1. URDF->SDF handle links with no inertia or small mass
* [Pull request #1238](https://github.com/gazebosim/sdformat/pull/1238)

1. Fix Element::Set method return value
* [Pull request #1256](https://github.com/gazebosim/sdformat/pull/1256)

1. Add missing values in Surace ToElement method
* [Pull request #1263](https://github.com/gazebosim/sdformat/pull/1263)

1. Rename COPYING to LICENSE
* [Pull request #1252](https://github.com/gazebosim/sdformat/pull/1252)

1. Infrastructure
* [Pull request #1245](https://github.com/gazebosim/sdformat/pull/1245)
* [Pull request #1271](https://github.com/gazebosim/sdformat/pull/1271)

1. Allow relative paths in URDF
* [Pull request #1213](https://github.com/gazebosim/sdformat/pull/1213)

### libsdformat 12.7.1 (2023-02-28)

1. Fix camera info topic default value
Expand Down Expand Up @@ -1606,6 +1630,27 @@

## libsdformat 9.X

### libsdformat 9.10.1 (2024-01-05)

1. URDF->SDF handle links with no inertia or small mass
* [Pull request #1238](https://github.com/gazebosim/sdformat/pull/1238)

1. Fix Element::Set method return value
* [Pull request #1256](https://github.com/gazebosim/sdformat/pull/1256)

1. Allowing relative paths in URDF
* [Pull request #1213](https://github.com/gazebosim/sdformat/pull/1213)

1. Use `File.exist?` for Ruby 3.2 compatibility
* [Pull request #1216](https://github.com/gazebosim/sdformat/pull/1216)

1. Infrastructure
* [Pull request #1217](https://github.com/gazebosim/sdformat/pull/1217)
* [Pull request #1225](https://github.com/gazebosim/sdformat/pull/1225)
* [Pull request #1271](https://github.com/gazebosim/sdformat/pull/1271)
* [Pull request #1345](https://github.com/gazebosim/sdformat/pull/1345)
* [Pull request #1252](https://github.com/gazebosim/sdformat/pull/1252)

### libsdformat 9.10.0 (2022-11-30)

1. Ign to gz header migration.
Expand Down
8 changes: 4 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,16 +10,16 @@ Note: The branch name in the codecov URL & library version should be updated whe
-->
Build | Status
-- | --
Test coverage | [![codecov](https://codecov.io/gh/gazebosim/sdformat/branch/main/graph/badge.svg)](https://codecov.io/gh/gazebosim/sdformat/branch/main)
Ubuntu Focal | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=sdformat-ci-main-focal-amd64)](https://build.osrfoundation.org/job/sdformat-ci-main-focal-amd64)
Test coverage | [![codecov](https://codecov.io/gh/gazebosim/sdformat/tree/main/graph/badge.svg)](https://codecov.io/gh/gazebosim/sdformat/tree/main)
Ubuntu Jammy | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=sdformat-ci-main-jammy-amd64)](https://build.osrfoundation.org/job/sdformat-ci-main-jammy-amd64)
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=sdformat-ci-main-homebrew-amd64)](https://build.osrfoundation.org/job/sdformat-ci-main-homebrew-amd64)
Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=sdformat-ci-main-windows7-amd64)](https://build.osrfoundation.org/job/sdformat-ci-main-windows7-amd64)
Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=sdformat-main-win)](https://build.osrfoundation.org/job/sdformat-main-win)


SDFormat is an XML file format that describes environments, objects, and robots
in a manner suitable for robotic applications. SDFormat is capable of representing
and describing different physic engines, lighting properties, terrain, static
or dynamic objects, and articulated robots with various sensors, and acutators.
or dynamic objects, and articulated robots with various sensors, and actuators.
The format of SDFormat is also described by XML, which facilitates updates and
allows conversion from previous versions.

Expand Down
8 changes: 6 additions & 2 deletions conf/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,12 +1,16 @@
# Used only for internal testing.
set(gz_library_path "${CMAKE_BINARY_DIR}/test/lib/ruby/gz/cmd${PROJECT_NAME}")
set(gz_library_path "${CMAKE_BINARY_DIR}/test/lib/$<CONFIG>/ruby/gz/cmd${PROJECT_NAME}")

# Generate a configuration file for internal testing.
# Note that the major version of the library is included in the name.
# Ex: sdformat0.yaml
configure_file(
"${PROJECT_NAME_NO_VERSION_LOWER}.yaml.in"
"${CMAKE_BINARY_DIR}/test/conf/${PROJECT_NAME}.yaml" @ONLY)
"${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}.yaml.configured" @ONLY)

file(GENERATE
OUTPUT "${CMAKE_BINARY_DIR}/test/conf/$<CONFIG>/${PROJECT_NAME}.yaml"
INPUT "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}.yaml.configured")

# Used for the installed version.
set(gz_library_path "${CMAKE_INSTALL_PREFIX}/lib/ruby/gz/cmd${PROJECT_NAME}")
Expand Down
2 changes: 1 addition & 1 deletion doc/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ if (DOXYGEN_FOUND)
${CMAKE_BINARY_DIR}/doxygen/html/search
COMMAND make -C ${CMAKE_BINARY_DIR}/doxygen/latex
COMMAND mv ${CMAKE_BINARY_DIR}/doxygen/latex/refman.pdf
${CMAKE_BINARY_DIR}/doxygen/latex/sdf-${SDF_VERSION_FULL}.pdf
${CMAKE_BINARY_DIR}/doxygen/latex/sdf-${PROJECT_VERSION_FULL}.pdf

COMMENT "Generating API documentation with Doxygen" VERBATIM)
endif()
27 changes: 26 additions & 1 deletion include/sdf/Collision.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#define SDF_COLLISION_HH_

#include <memory>
#include <optional>
#include <string>
#include <gz/math/Pose3.hh>
#include <gz/math/Vector3.hh>
Expand Down Expand Up @@ -78,6 +79,11 @@ namespace sdf
/// \param[in] _name Name of the collision.
public: void SetName(const std::string &_name);

/// \brief Get the default density of a collision if its density is not
/// specified.
/// \return Default density.
public: static double DensityDefault();

/// \brief Get the density of the collision.
/// \return Density of the collision.
public: double Density() const;
Expand Down Expand Up @@ -145,13 +151,32 @@ namespace sdf
/// \brief Calculate and return the MassMatrix for the collision
/// \param[out] _errors A vector of Errors objects. Each errors contains an
/// Error code and a message. An empty errors vector indicates no errors
/// \param[in] _config Custom parser configuration
/// \param[out] _inertial An inertial object which will be set with the
/// calculated inertial values
/// \param[in] _config Custom parser configuration
public: void CalculateInertial(sdf::Errors &_errors,
gz::math::Inertiald &_inertial,
const ParserConfig &_config);

/// \brief Calculate and return the MassMatrix for the collision
/// \param[out] _errors A vector of Errors objects. Each errors contains an
/// Error code and a message. An empty errors vector indicates no errors
/// \param[out] _inertial An inertial object which will be set with the
/// calculated inertial values
/// \param[in] _config Custom parser configuration
/// \param[in] _density An optional density value to override the default
/// collision density. This value is used instead of DefaultDensity()
// if this collision's density has not been explicitly set.
/// \param[in] _autoInertiaParams An ElementPtr to the auto_inertia_params
/// element to be used if the auto_inertia_params have not been set in this
/// collision.
public: void CalculateInertial(
sdf::Errors &_errors,
gz::math::Inertiald &_inertial,
const ParserConfig &_config,
const std::optional<double> &_density,
sdf::ElementPtr _autoInertiaParams);

/// \brief Get a pointer to the SDF element that was used during
/// load.
/// \return SDF element pointer. The value will be nullptr if Load has
Expand Down
Loading

0 comments on commit ca74234

Please sign in to comment.