Skip to content

Commit

Permalink
9 ➡ 12
Browse files Browse the repository at this point in the history
Signed-off-by: Jenn Nguyen <[email protected]>
  • Loading branch information
jennuine committed Jul 21, 2022
2 parents 3dd02cc + e9e9546 commit 26e5ca3
Show file tree
Hide file tree
Showing 8 changed files with 307 additions and 20 deletions.
41 changes: 27 additions & 14 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,21 @@
# sdformat

[![GitHub open issues](https://img.shields.io/github/issues-raw/gazebosim/sdformat.svg)](https://github.com/gazebosim/sdformat/issues)
[![GitHub open pull requests](https://img.shields.io/github/issues-pr-raw/gazebosim/sdformat.svg)](https://github.com/gazebosim/sdformat/pulls)
[![Discourse topics](https://img.shields.io/discourse/https/community.gazebosim.org/topics.svg)](https://community.gazebosim.org)
[![Hex.pm](https://img.shields.io/hexpm/l/plug.svg)](https://www.apache.org/licenses/LICENSE-2.0)

<!--
Note: The branch name in the codecov URL & library version should be updated when forward porting
-->
Build | Status
-- | --
Test coverage | [![codecov](https://codecov.io/gh/gazebosim/sdformat/branch/sdf12/graph/badge.svg)](https://codecov.io/gh/gazebosim/sdformat/branch/sdf12)
Ubuntu Focal | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=sdformat-ci-sdformat12-focal-amd64)](https://build.osrfoundation.org/job/sdformat-ci-sdformat12-focal-amd64)
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=sdformat-ci-sdformat12-homebrew-amd64)](https://build.osrfoundation.org/job/sdformat-ci-sdformat12-homebrew-amd64)
Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=sdformat-ci-sdformat12-windows7-amd64)](https://build.osrfoundation.org/job/sdformat-ci-sdformat12-windows7-amd64)


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
Expand All @@ -13,7 +29,7 @@ See the [SDFormat Website](http://sdformat.org/) for a more comprehensive
description of the specification, proposals for modifications, developer
information, etc.
This website is published using some information from the
[`sdf_tutorials`](https://github.com/osrf/sdf_tutorials) repository.
[`sdf_tutorials`](https://github.com/gazebosim/sdf_tutorials) repository.

<!--
TODO(eric.cousineau): Move installation instructions to sdf_tutorials, and link
Expand All @@ -29,10 +45,7 @@ TODO(eric.cousineau): Move terminology section to sdf_tutorials?
* `libsdformat` - The C++ parsing code contained within this repository,
which can be used to read SDFormat files and return a C++ interface.

## Test coverage

<!-- Note: The branch name in the codecov URL should be updated when forward porting -->
[![codecov](https://codecov.io/gh/ignitionrobotics/sdformat/branch/sdf12/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/sdformat/branch/sdf12)
[http://sdformat.org/](http://sdformat.org/)

# Installation

Expand Down Expand Up @@ -79,8 +92,8 @@ Miniconda suffices.

Create if necessary, and activate a Conda environment:
```
conda create -n ign-ws
conda activate ign-ws
conda create -n gz-ws
conda activate gz-ws
```

Install `sdformat`:
Expand All @@ -95,14 +108,14 @@ conda search libsdformat --channel conda-forge

and install a specific minor version with
```
conda install libsdformat=9.3.0 --channel conda-forge
conda install libsdformat=12.5.0 --channel conda-forge
```

## Source Installation


**Note:** the `main` branch is under development for `libsdformat12` and is
currently unstable. A release branch (`sdf11`, `sdf10`, `sdf9`, etc.) is
**Note:** the `main` branch is under development for `libsdformat13` and is
currently unstable. A release branch (`sdf12`, `sdf11`, `sdf10`, `sdf9`, etc.) is
recommended for most users.

## UNIX
Expand Down Expand Up @@ -143,7 +156,7 @@ make uninstall

Clone the repository
```sh
git clone https://github.com/ignitionrobotics/sdformat -b sdf<#>
git clone https://github.com/gazebosim/sdformat -b sdf<#>
```
Be sure to replace `<#>` with a number value, such as 1 or 2, depending on
which version you need.
Expand Down Expand Up @@ -184,16 +197,16 @@ Miniconda suffices.

Create if necessary, and activate a Conda environment:
```
conda create -n ign-ws
conda activate ign-ws
conda create -n gz-ws
conda activate gz-ws
```

Install prerequisites:
```
conda install urdfdom --channel conda-forge
```

Install Ignition dependencies:
Install Gazebo dependencies:

You can view lists of dependencies:
```
Expand Down
152 changes: 152 additions & 0 deletions cmake/SearchForStuff.cmake
Original file line number Diff line number Diff line change
@@ -0,0 +1,152 @@
include (FindPkgConfig)

# Detect the architecture
include (${project_cmake_dir}/TargetArch.cmake)
target_architecture(ARCH)
message(STATUS "Building for arch: ${ARCH}")

if (USE_EXTERNAL_TINYXML)
#################################################
# Find tinyxml. Only debian distributions package tinyxml with a pkg-config
# Use pkg_check_modules and fallback to manual detection (needed, at least, for MacOS)
pkg_check_modules(tinyxml tinyxml)
if (NOT tinyxml_FOUND)
find_path (tinyxml_INCLUDE_DIRS tinyxml.h ${tinyxml_INCLUDE_DIRS} ENV CPATH)
find_library(tinyxml_LIBRARIES NAMES tinyxml)
set (tinyxml_FAIL False)
if (NOT tinyxml_INCLUDE_DIRS)
message (STATUS "Looking for tinyxml headers - not found")
set (tinyxml_FAIL True)
endif()
if (NOT tinyxml_LIBRARIES)
message (STATUS "Looking for tinyxml library - not found")
set (tinyxml_FAIL True)
endif()
endif()

if (tinyxml_FAIL)
message (STATUS "Looking for tinyxml.h - not found")
BUILD_ERROR("Missing: tinyxml")
endif()
else()
# Needed in WIN32 since in UNIX the flag is added in the code installed
add_definitions(-DTIXML_USE_STL)
include_directories (${PROJECT_SOURCE_DIR}/src/win/tinyxml)
set (tinyxml_LIBRARIES "tinyxml")
set (tinyxml_LIBRARY_DIRS "")
endif()

################################################
# Find urdfdom parser. Logic:
#
# 1. if USE_INTERNAL_URDF is unset, try to use system installation, fallback to internal copy
# 2. if USE_INTERNAL_URDF is set to True, use the internal copy
# 3. if USE_INTERNAL_URDF is set to False, force to search system installation, fail on error

if (NOT PKG_CONFIG_FOUND)
if (NOT DEFINED USE_INTERNAL_URDF)
BUILD_WARNING("Couldn't find pkg-config for urdfdom, using internal copy")
set(USE_INTERNAL_URDF true)
elseif(NOT USE_INTERNAL_URDF)
BUILD_ERROR("Couldn't find pkg-config for urdfdom")
endif()
endif()

if (NOT DEFINED USE_INTERNAL_URDF OR NOT USE_INTERNAL_URDF)
# check for urdfdom with pkg-config
pkg_check_modules(URDF urdfdom>=1.0)

if (NOT URDF_FOUND)
find_package(urdfdom)
if (urdfdom_FOUND)
set(URDF_INCLUDE_DIRS ${urdfdom_INCLUDE_DIRS})
# ${urdfdom_LIBRARIES} already contains absolute library filenames
set(URDF_LIBRARY_DIRS "")
set(URDF_LIBRARIES ${urdfdom_LIBRARIES})
elseif (NOT DEFINED USE_INTERNAL_URDF)
message(STATUS "Couldn't find urdfdom >= 1.0, using internal copy")
set(USE_INTERNAL_URDF true)
else()
BUILD_ERROR("Couldn't find the urdfdom >= 1.0 system installation")
endif()
else()
# what am I doing here? pkg-config and cmake
set(URDF_INCLUDE_DIRS ${URDF_INCLUDEDIR})
set(URDF_LIBRARY_DIRS ${URDF_LIBDIR})
endif()
endif()

#################################################
# Find ign command line utility:
find_package(ignition-tools)
if (IGNITION-TOOLS_BINARY_DIRS)
message(STATUS "Looking for ignition-tools-config.cmake - found")
else()
BUILD_WARNING ("ignition-tools not found, for command line utilities and for \
generating aggregated SDFormat descriptions for sdformat.org, please install \
ignition-tools.")
endif()
if (ignition-tools_FOUND)
set (HAVE_IGN_TOOLS TRUE)
endif()
# Note that CLI files are installed regardless of whether the dependency is
# available during build time
set (IGN_TOOLS_VER 1)

################################################
# Find the Python interpreter for running the
# check_test_ran.py script
find_package(PythonInterp 3 QUIET)

################################################
# Find psutil python package for memory tests
find_python_module(psutil)
if(NOT PY_PSUTIL)
BUILD_WARNING("Python psutil package not found. Memory leak tests will be skipped")
endif()

################################################
# Find Valgrind for checking memory leaks in the
# tests
find_program(VALGRIND_PROGRAM NAMES valgrind PATH ${VALGRIND_ROOT}/bin)
option(SDFORMAT_RUN_VALGRIND_TESTS "Run sdformat tests with Valgrind" FALSE)
mark_as_advanced(SDFORMAT_RUN_VALGRIND_TESTS)
if (SDFORMAT_RUN_VALGRIND_TESTS AND NOT VALGRIND_PROGRAM)
BUILD_WARNING("valgrind not found. Memory check tests will be skipped.")
endif()

################################################
# Find ruby executable to produce xml schemas
find_program(RUBY ruby)
if (NOT RUBY)
BUILD_ERROR ("Ruby version 1.9 is needed to build xml schemas")
else()
message(STATUS "Found ruby executable: ${RUBY}")
endif()

#################################################
# Macro to check for visibility capability in compiler
# Original idea from: https://gitorious.org/ferric-cmake-stuff/
macro (check_gcc_visibility)
include (CheckCXXCompilerFlag)
check_cxx_compiler_flag(-fvisibility=hidden GCC_SUPPORTS_VISIBILITY)
endmacro()

########################################
# Find ignition cmake2
# Only for using the testing macros and creating the codecheck target, not
# really being use to configure the whole project
find_package(ignition-cmake2 REQUIRED)
set(IGN_CMAKE_VER ${ignition-cmake2_VERSION_MAJOR})

########################################
# Find ignition math
# Set a variable for generating ProjectConfig.cmake
find_package(ignition-math6 QUIET)
if (NOT ignition-math6_FOUND)
message(STATUS "Looking for ignition-math6-config.cmake - not found")
BUILD_ERROR ("Missing: Ignition math (libignition-math6-dev)")
else()
set(IGN_MATH_VER ${ignition-math6_VERSION_MAJOR})
message(STATUS "Looking for ignition-math${IGN_MATH_VER}-config.cmake - found")
endif()
10 changes: 10 additions & 0 deletions include/sdf/Link.hh
Original file line number Diff line number Diff line change
Expand Up @@ -263,6 +263,16 @@ namespace sdf
/// \sa const ignition::math::Inertiald &Inertial() const
public: bool SetInertial(const ignition::math::Inertiald &_inertial);

/// \brief Resolve the Inertial to a specified frame.
/// If there are any errors resolving the Inertial, the output will not
/// be modified.
/// \param[out] _inertial The resolved Inertial.
/// \param[in] _resolveTo The Inertial will be resolved with respect to this
/// frame. If unset or empty, the default resolve-to frame will be used.
/// \return Errors in resolving pose.
public: Errors ResolveInertial(ignition::math::Inertiald &_inertial,
const std::string &_resolveTo = "") const;

/// \brief Get the pose of the link. This is the pose of the link
/// as specified in SDF (<link> <pose> ... </pose></link>).
/// \return The pose of the link.
Expand Down
15 changes: 15 additions & 0 deletions src/Link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -421,6 +421,21 @@ bool Link::SetInertial(const ignition::math::Inertiald &_inertial)
return _inertial.MassMatrix().IsValid();
}

/////////////////////////////////////////////////
Errors Link::ResolveInertial(
ignition::math::Inertiald &_inertial,
const std::string &_resolveTo) const
{
ignition::math::Pose3d linkPose;
auto errors = this->SemanticPose().Resolve(linkPose, _resolveTo);
if (errors.empty())
{
_inertial = this->dataPtr->inertial;
_inertial.SetPose(linkPose * _inertial.Pose());
}
return errors;
}

/////////////////////////////////////////////////
const ignition::math::Pose3d &Link::RawPose() const
{
Expand Down
13 changes: 13 additions & 0 deletions src/cmd/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -42,3 +42,16 @@ file(GENERATE

# Install the ruby command line library in an unversioned location.
install(FILES ${cmd_script_generated} DESTINATION lib/ruby/ignition)

#===============================================================================
# Bash completion

# Tack version onto and install the bash completion script
configure_file(
"sdf.bash_completion.sh"
"${CMAKE_CURRENT_BINARY_DIR}/sdf${PROJECT_VERSION_MAJOR}.bash_completion.sh" @ONLY)
install(
FILES
${CMAKE_CURRENT_BINARY_DIR}/sdf${PROJECT_VERSION_MAJOR}.bash_completion.sh
DESTINATION
${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_DATAROOTDIR}/gz/gz${IGN_TOOLS_VER}.completion.d)
54 changes: 54 additions & 0 deletions src/cmd/sdf.bash_completion.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
#!/usr/bin/env bash
#
# Copyright (C) 2022 Open Source Robotics Foundation
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#

# bash tab-completion

# This is a per-library function definition, used in conjunction with the
# top-level entry point in ign-tools.

GZ_SDF_COMPLETION_LIST="
-k --check
-d --describe
-p --print
--inertial-stats
-h --help
--force-version
--versions
"

function _gz_sdf
{
if [[ ${COMP_WORDS[COMP_CWORD]} == -* ]]; then
# Specify options (-*) word list for this subcommand
COMPREPLY=($(compgen -W "$GZ_SDF_COMPLETION_LIST" \
-- "${COMP_WORDS[COMP_CWORD]}" ))
return
else
# Just use bash default auto-complete, because we never have two
# subcommands in the same line. If that is ever needed, change here to
# detect subsequent subcommands
COMPREPLY=($(compgen -o default -- "${COMP_WORDS[COMP_CWORD]}"))
return
fi
}

function _gz_sdf_flags
{
for word in $GZ_SDF_COMPLETION_LIST; do
echo "$word"
done
}
8 changes: 2 additions & 6 deletions src/ign.cc
Original file line number Diff line number Diff line change
Expand Up @@ -314,13 +314,9 @@ extern "C" SDFORMAT_VISIBLE int cmdInertialStats(

for (uint64_t i = 0; i < model->LinkCount(); i++)
{
ignition::math::Pose3d linkPoseRelativeToModel;
errors = model->LinkByIndex(i)->SemanticPose().
Resolve(linkPoseRelativeToModel, "__model__");
ignition::math::Inertiald currentLinkInertial;
model->LinkByIndex(i)->ResolveInertial(currentLinkInertial, "__model__");

auto currentLinkInertial = model->LinkByIndex(i)->Inertial();
currentLinkInertial.SetPose(linkPoseRelativeToModel *
currentLinkInertial.Pose());
totalInertial += currentLinkInertial;
}

Expand Down
Loading

0 comments on commit 26e5ca3

Please sign in to comment.