Skip to content

Commit

Permalink
Merge branch 'main' into gz_cmake_project
Browse files Browse the repository at this point in the history
  • Loading branch information
chapulina authored Jun 25, 2022
2 parents 4ea21c5 + aafcc64 commit 8c4b754
Show file tree
Hide file tree
Showing 39 changed files with 489 additions and 153 deletions.
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -64,8 +64,8 @@ if (BUILD_SDF)
endif()

#################################################
# Find ign command line utility:
find_program(GZ_PROGRAM ign)
# Find gz command line utility:
find_program(GZ_PROGRAM gz)

#################################################
# Copied from catkin/cmake/empy.cmake
Expand Down
26 changes: 13 additions & 13 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
1. Add `L16` pixel format to Camera pixel format conversion function
* [Pull request #487](https://github.com/gazebosim/sdformat/pull/487)

1. Added ``--inertial-stats`` option to ``ign sdf``
1. Added ``--inertial-stats`` option to ``gz sdf``
* [Pull request #936](https://github.com/gazebosim/sdformat/pull/936)

1. Added `anti_aliasing` element to camera's SDF
Expand Down Expand Up @@ -925,7 +925,7 @@

### libsdformat 10.2.0 (2021-01-12)

1. Disable ign test on Windows
1. Disable gz test on Windows
+ [Pull request 456](https://github.com/osrf/sdformat/pull/456)

1. Add Heightmap class
Expand Down Expand Up @@ -1026,7 +1026,7 @@
1. Added `<shininess>` to `<material>`
* [Pull request #985](https://github.com/gazebosim/sdformat/pull/985)

1. Backport ``ign sdf --inertial-stats``
1. Backport ``gz sdf --inertial-stats``
* [Pull request #958](https://github.com/gazebosim/sdformat/pull/958)

1. Add L16 pixel format to Camera pixel format conversion function
Expand Down Expand Up @@ -1361,10 +1361,10 @@

### libsdformat 9.0.0 (2019-12-10)

1. Move recursiveSameTypeUniqueNames from ign.cc to parser.cc and make public.
1. Move recursiveSameTypeUniqueNames from gz.cc to parser.cc and make public.
* [BitBucket pull request 606](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/606)

1. Check that joints have valid parent and child names in `ign sdf --check`.
1. Check that joints have valid parent and child names in `gz sdf --check`.
* [BitBucket pull request 609](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/609)

1. Model DOM: error when trying to load nested models, which aren't yet supported.
Expand All @@ -1382,7 +1382,7 @@
1. Relax name checking, so name collisions generate warnings and names are automatically changed.
* [BitBucket pull request 621](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/621)

1. Unversioned library name for ign tool commands.
1. Unversioned library name for gz tool commands.
* [BitBucket pull request 612](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/612)

1. Initial version of SDFormat 1.7 specification.
Expand Down Expand Up @@ -1544,7 +1544,7 @@
1. Use inline namespaces in Utils.cc
* [BitBucket pull request 574](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/574)

1. Convert `ign sdf` file inputs to absolute paths before processing them
1. Convert `gz sdf` file inputs to absolute paths before processing them
* [BitBucket pull request 583](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/583)

1. Add `emissive_map` to material sdf
Expand Down Expand Up @@ -1581,11 +1581,11 @@
1. Move private headers from include/sdf to src folder.
* [BitBucket pull request 553](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/553)

1. Fix ign library path on macOS.
1. Fix gz library path on macOS.
* [BitBucket pull request 542](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/542)
* [BitBucket pull request 564](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/564)

1. Use `ign sdf --check` to check sibling elements of the same type for non-unique names.
1. Use `gz sdf --check` to check sibling elements of the same type for non-unique names.
* [BitBucket pull request 554](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/554)

1. Converter: remove all matching elements specified by `<remove>` tag.
Expand Down Expand Up @@ -1769,7 +1769,7 @@
* [BitBucket pull request 476](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/476)
* [BitBucket pull request 463](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/463)

1. Fix ign library path on macOS.
1. Fix gz library path on macOS.
* [BitBucket pull request 542](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/542)

1. Preserve XML elements that are not part of the SDF specification.
Expand Down Expand Up @@ -1826,7 +1826,7 @@

### libsdformat 6.3.0 (2021-06-21)

1. Move recursiveSameTypeUniqueNames from ign.cc to parser.cc and make public.
1. Move recursiveSameTypeUniqueNames from gz.cc to parser.cc and make public.
* [Pull request 580](https://github.com/osrf/sdformat/pull/580)

1. Parse rpyOffset as radians
Expand All @@ -1841,10 +1841,10 @@
1. Avoid hardcoding /machine:x64 flag on 64-bit on MSVC with CMake >= 3.5.
* [BitBucket pull request 565](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/565)

1. Fix ign library path on macOS.
1. Fix gz library path on macOS.
* [BitBucket pull request 552](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/552)

1. Use `ign sdf --check` to check sibling elements of the same type for non-unique names.
1. Use `gz sdf --check` to check sibling elements of the same type for non-unique names.
* [BitBucket pull request 554](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/554)

1. Converter: remove all matching elements specified by `<remove>` tag.
Expand Down
16 changes: 15 additions & 1 deletion Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,20 @@ but with improved human-readability..
- **sdf/Types.hh**: The `Inertia` class has been deprecated. Please use the
`Inertial` class in the `gz-math` library.

- **sdf/Joint.hh**:
+ ***Deprecation:*** const std::string &ChildLinkName() const
+ ***Replacement:*** const std::string &ChildName() const
+ ***Deprecation:*** const std::string &ParentLinkName() const
+ ***Replacement:*** const std::string &ParentName() const
+ ***Deprecation:*** void SetChildLinkName(const std::string &)
+ ***Replacement:*** void SetChildName(const std::string &)
+ ***Deprecation:*** void SetParentLinkName(const std::string &)
+ ***Replacement:*** void SetParentName(const std::string &)

- **sdf/parser.hh**:
+ ***Deprecation:*** bool checkJointParentChildLinkNames(const sdf::Root \*)
+ ***Replacement:*** bool checkJointParentChildNames(const sdf::Root \*)

## libsdformat 11.x to 12.0

An error is now emitted instead of a warning for a file containing more than
Expand Down Expand Up @@ -619,7 +633,7 @@ ABI was broken for `sdf::Element`, and restored on version 11.2.1.
Uniqueness is forced so that referencing implicit frames is not ambiguous,
e.g. you cannot have a link and joint share an implicit frame name.
Some existing SDFormat models may not comply with this requirement.
The `ign sdf --check` command can be used to identify models that violate
The `gz sdf --check` command can be used to identify models that violate
this requirement.
+ [BitBucket pull request 600](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/600)

Expand Down
8 changes: 4 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -79,8 +79,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 Down Expand Up @@ -184,8 +184,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 prerequisites:
Expand Down
4 changes: 2 additions & 2 deletions conf/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# Used only for internal testing.
set(gz_library_path "${CMAKE_BINARY_DIR}/test/lib/ruby/ignition/cmd${PROJECT_NAME}")
set(gz_library_path "${CMAKE_BINARY_DIR}/test/lib/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.
Expand All @@ -9,7 +9,7 @@ configure_file(
"${CMAKE_BINARY_DIR}/test/conf/${PROJECT_NAME}.yaml" @ONLY)

# Used for the installed version.
set(gz_library_path "${CMAKE_INSTALL_PREFIX}/lib/ruby/ignition/cmd${PROJECT_NAME}")
set(gz_library_path "${CMAKE_INSTALL_PREFIX}/lib/ruby/gz/cmd${PROJECT_NAME}")

# Generate the configuration file that is installed.
# Note that the major version of the library is included in the name.
Expand Down
28 changes: 24 additions & 4 deletions include/sdf/Joint.hh
Original file line number Diff line number Diff line change
Expand Up @@ -113,21 +113,41 @@ namespace sdf
/// \param[in] _jointType The type of joint.
public: void SetType(const JointType _jointType);

/// \brief Get the name of this joint's parent frame.
/// \return The name of the parent frame.
public: const std::string &ParentName() const;

/// \brief Set the name of the parent frame.
/// \param[in] _name Name of the parent frame.
public: void SetParentName(const std::string &_name);

/// \brief Get the name of this joint's child frame.
/// \return The name of the child frame.
public: const std::string &ChildName() const;

/// \brief Set the name of the child frame.
/// \param[in] _name Name of the child frame.
public: void SetChildName(const std::string &_name);

/// \brief Get the name of this joint's parent link.
/// \return The name of the parent link.
public: const std::string &ParentLinkName() const;
/// \deprecated Use ParentName.
public: GZ_DEPRECATED(13) const std::string &ParentLinkName() const;

/// \brief Set the name of the parent link.
/// \param[in] _name Name of the parent link.
public: void SetParentLinkName(const std::string &_name);
/// \deprecated Use SetParentName.
public: GZ_DEPRECATED(13) void SetParentLinkName(const std::string &_name);

/// \brief Get the name of this joint's child link.
/// \return The name of the child link.
public: const std::string &ChildLinkName() const;
/// \deprecated Use ChildName.
public: GZ_DEPRECATED(13) const std::string &ChildLinkName() const;

/// \brief Set the name of the child link.
/// \param[in] _name Name of the child link.
public: void SetChildLinkName(const std::string &_name);
/// \deprecated Use SetChildName.
public: GZ_DEPRECATED(13) void SetChildLinkName(const std::string &_name);

/// \brief Resolve the name of the child link from the
/// FrameAttachedToGraph.
Expand Down
4 changes: 2 additions & 2 deletions include/sdf/Plugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ namespace sdf
/// The name of the plugin should be unique within the scope of its
/// parent.
/// \return Name of the plugin.
public: std::string Name() const;
public: const std::string &Name() const;

/// \brief Set the name of the plugin.
/// The name of the plugin should be unique within the scope of its
Expand All @@ -90,7 +90,7 @@ namespace sdf

/// \brief Get the filename of the shared library.
/// \return Filename of the shared library associated with the plugin.
public: std::string Filename() const;
public: const std::string &Filename() const;

/// \brief Remove the contents of the plugin, this is everything that
/// is a child element of the `<plugin>`.
Expand Down
11 changes: 11 additions & 0 deletions include/sdf/parser.hh
Original file line number Diff line number Diff line change
Expand Up @@ -393,6 +393,17 @@ namespace sdf
/// \return True if all models have joints with valid parent and child
/// link names.
SDFORMAT_VISIBLE
bool checkJointParentChildNames(const sdf::Root *_root);

/// \brief Check that all joints in contained models specify parent
/// and child link names that match the names of sibling links.
/// This checks recursively and should check the files exhaustively
/// rather than terminating early when the first error is found.
/// \param[in] _root SDF Root object to check recursively.
/// \return True if all models have joints with valid parent and child
/// link names.
/// \deprecated Use checkJointParentChildNames.
SDFORMAT_VISIBLE GZ_DEPRECATED(13)
bool checkJointParentChildLinkNames(const sdf::Root *_root);

/// \brief Check that all joints in contained models specify parent
Expand Down
2 changes: 2 additions & 0 deletions python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,7 @@ pybind11_add_module(sdformat SHARED
src/sdf/pyPlane.cc
src/sdf/pyPlugin.cc
src/sdf/pyRoot.cc
src/sdf/pyScene.cc
src/sdf/pySemanticPose.cc
src/sdf/pySensor.cc
src/sdf/pySky.cc
Expand Down Expand Up @@ -126,6 +127,7 @@ if (BUILD_TESTING)
pyPlane_TEST
pyPlugin_TEST
pyRoot_TEST
pyScene_TEST
pySemanticPose_TEST
pySensor_TEST
pySky_TEST
Expand Down
2 changes: 2 additions & 0 deletions python/src/sdf/_ignition_sdformat_pybind11.cc
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@
#include "pyPlane.hh"
#include "pyPlugin.hh"
#include "pyRoot.hh"
#include "pyScene.hh"
#include "pySemanticPose.hh"
#include "pySensor.hh"
#include "pySky.hh"
Expand Down Expand Up @@ -95,6 +96,7 @@ PYBIND11_MODULE(sdformat, m) {
sdf::python::definePlane(m);
sdf::python::definePlugin(m);
sdf::python::defineRoot(m);
sdf::python::defineScene(m);
sdf::python::defineSemanticPose(m);
sdf::python::defineSensor(m);
sdf::python::defineSky(m);
Expand Down
16 changes: 8 additions & 8 deletions python/src/sdf/pyJoint.cc
Original file line number Diff line number Diff line change
Expand Up @@ -45,14 +45,14 @@ void defineJoint(pybind11::object module)
"Get the joint type")
.def("set_type", &sdf::Joint::SetType,
"Set the joint type.")
.def("parent_link_name", &sdf::Joint::ParentLinkName,
"Get the name of this joint's parent link.")
.def("set_parent_link_name", &sdf::Joint::SetParentLinkName,
"Set the name of the parent link.")
.def("child_link_name", &sdf::Joint::ChildLinkName,
"Get the name of this joint's child link.")
.def("set_child_link_name", &sdf::Joint::SetChildLinkName,
"Set the name of the child link")
.def("parent_name", &sdf::Joint::ParentName,
"Get the name of this joint's parent frame.")
.def("set_parent_name", &sdf::Joint::SetParentName,
"Set the name of the parent frame.")
.def("child_name", &sdf::Joint::ChildName,
"Get the name of this joint's child frame.")
.def("set_child_name", &sdf::Joint::SetChildName,
"Set the name of the child frame.")
.def("resolve_child_link",
[](const sdf::Joint &self)
{
Expand Down
71 changes: 71 additions & 0 deletions python/src/sdf/pyScene.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
/*
* 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.
*/

#include "pyScene.hh"

#include <pybind11/pybind11.h>

#include "sdf/Scene.hh"

using namespace pybind11::literals;

namespace sdf
{
// Inline bracket to help doxygen filtering.
inline namespace SDF_VERSION_NAMESPACE {
namespace python
{
/////////////////////////////////////////////////
void defineScene(pybind11::object module)
{
pybind11::class_<sdf::Scene>(module, "Scene")
.def(pybind11::init<>())
.def(pybind11::init<sdf::Scene>())
.def("ambient", &sdf::Scene::Ambient,
"Get the ambient color of the scene")
.def("set_ambient", &sdf::Scene::SetAmbient,
"Set the ambient color of the scene")
.def("background", &sdf::Scene::Background,
"Get the background color of the scene")
.def("set_background", &sdf::Scene::SetBackground,
"Set the background color of the scene")
.def("grid", &sdf::Scene::Grid,
"Get whether grid is enabled")
.def("set_grid", &sdf::Scene::SetGrid,
"Set whether the grid should be enabled")
.def("origin_visual", &sdf::Scene::OriginVisual,
"Get whether origin visual is enabled")
.def("set_origin_visual", &sdf::Scene::SetOriginVisual,
"Set whether the origin visual should be enabled")
.def("shadows", &sdf::Scene::Shadows,
"Get whether shadows are enabled")
.def("set_shadows", &sdf::Scene::SetShadows,
"Set whether shadows should be enabled")
.def("set_sky", &sdf::Scene::SetSky,
"Set sky")
.def("sky", &sdf::Scene::Sky,
pybind11::return_value_policy::reference_internal,
"Get sky")
.def("__copy__", [](const sdf::Scene &self) {
return sdf::Scene(self);
})
.def("__deepcopy__", [](const sdf::Scene &self, pybind11::dict) {
return sdf::Scene(self);
}, "memo"_a);
}
} // namespace python
} // namespace SDF_VERSION_NAMESPACE
} // namespace sdf
Loading

0 comments on commit 8c4b754

Please sign in to comment.