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 9c81632
Show file tree
Hide file tree
Showing 8 changed files with 158 additions and 20 deletions.
3 changes: 3 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,9 @@ if (BUILD_SDF)
#################################################
# Find ign command line utility:
find_program(IGN_PROGRAM ign)
# Note that CLI files are installed regardless of whether the dependency is
# available during build time
set(IGN_TOOLS_VER 1)

#################################################
# Copied from catkin/cmake/empy.cmake
Expand Down
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
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
34 changes: 34 additions & 0 deletions src/ign_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,14 @@
*/

#include <gtest/gtest.h>
#include <iostream>
#include <stdio.h>
#include <stdlib.h>
#include <string>

#include <ignition/utils/ExtraTestMacros.hh>

#include "sdf/Filesystem.hh"
#include "sdf/parser.hh"
#include "sdf/SDFImpl.hh"
#include "sdf/sdf_config.h"
Expand Down Expand Up @@ -1878,6 +1880,38 @@ TEST(inertial_stats, IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF))
}
}

//////////////////////////////////////////////////
/// \brief Check help message and bash completion script for consistent flags
TEST(HelpVsCompletionFlags, SDF)
{
// Flags in help message
std::string helpOutput = custom_exec_str(IgnCommand() + " 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");

// Equivalent to:
// sh -c "bash -c \". /path/to/sdf.bash_completion.sh; _gz_sdf_flags\""
std::string cmd = "bash -c \". " + scriptPath +
"; _gz_sdf_flags\"";
std::string scriptOutput = custom_exec_str(cmd);

// Tokenize script output
std::istringstream iss(scriptOutput);
std::vector<std::string> flags((std::istream_iterator<std::string>(iss)),
std::istream_iterator<std::string>());

EXPECT_GT(flags.size(), 0u);

// Match each flag in script output with help message
for (const auto &flag : flags)
{
EXPECT_NE(std::string::npos, helpOutput.find(flag)) << helpOutput;
}
}

/////////////////////////////////////////////////
/// Main
int main(int argc, char **argv)
Expand Down

0 comments on commit 9c81632

Please sign in to comment.