Skip to content

Commit

Permalink
Merge branch 'main' into scpeters/world_frame_name_errors
Browse files Browse the repository at this point in the history
  • Loading branch information
scpeters authored Aug 22, 2023
2 parents 69c108a + af88891 commit c652521
Show file tree
Hide file tree
Showing 101 changed files with 3,986 additions and 456 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/macos.yml
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ jobs:
build:

env:
PACKAGE: sdformat13
PACKAGE: sdformat14
runs-on: macos-latest
steps:
- uses: actions/checkout@v3
Expand Down
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,4 @@ build
build_*
*.*.sw?
.vscode
__pycache__
6 changes: 3 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,11 @@ if(COMMAND CMAKE_POLICY)
CMAKE_POLICY(SET CMP0004 NEW)
endif(COMMAND CMAKE_POLICY)

project (sdformat13 VERSION 13.5.0)
project (sdformat14 VERSION 14.0.0)

# The protocol version has nothing to do with the package version.
# It represents the current version of SDFormat implemented by the software
set (SDF_PROTOCOL_VERSION 1.10)
set (SDF_PROTOCOL_VERSION 1.11)

OPTION(SDFORMAT_DISABLE_CONSOLE_LOGFILE "Disable the sdformat console logfile" OFF)

Expand Down Expand Up @@ -162,7 +162,7 @@ if (BUILD_SDF)
add_subdirectory(conf)
add_subdirectory(doc)
if (pybind11_FOUND AND NOT SKIP_PYBIND11)
add_subdirectory(python)
add_subdirectory(python)
endif()
endif(BUILD_SDF)

Expand Down
4 changes: 4 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
@@ -1,3 +1,7 @@
## libsdformat 14.X

### libsdformat 14.0.0 (202X-XX-XX)

## libsdformat 13.X

### libsdformat 13.5.0 (2023-05-18)
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ conda install libsdformat=12.5.0 --channel conda-forge
## Source Installation


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

Expand Down
2 changes: 1 addition & 1 deletion examples/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR)

find_package(sdformat13 REQUIRED)
find_package(sdformat14 REQUIRED)

set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17")

Expand Down
2 changes: 1 addition & 1 deletion include/sdf/ParticleEmitter.hh
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ namespace sdf

/// \enum ParticleEmitterType
/// \brief The set of particle emitter types.
// Developer note: Make sure to update emitterTypeStrs in the source
// Developer note: Make sure to update kEmitterTypeStrs in the source
// file when changing this enum.
enum class ParticleEmitterType
{
Expand Down
2 changes: 1 addition & 1 deletion include/sdf/Plugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -238,7 +238,7 @@ namespace sdf
const std::string &_name, const std::string &_xmlContent);

/// \brief Private data pointer.
public: std::unique_ptr<sdf::PluginPrivate> dataPtr;
private: std::unique_ptr<sdf::PluginPrivate> dataPtr;
};

/// \brief A vector of Plugin.
Expand Down
2 changes: 1 addition & 1 deletion include/sdf/Sensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ namespace sdf

/// \enum SensorType
/// \brief The set of sensor types.
// Developer note: Make sure to update sensorTypeStrs in the source file
// Developer note: Make sure to update kSensorTypeStrs in the source file
// when changing this enum.
enum class SensorType
{
Expand Down
17 changes: 16 additions & 1 deletion include/sdf/Types.hh
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include <utility>
#include <vector>

#include <gz/utils/NeverDestroyed.hh>
#include <sdf/sdf_config.h>
#include "sdf/system_util.hh"
#include "sdf/Error.hh"
Expand All @@ -35,7 +36,21 @@ namespace sdf
inline namespace SDF_VERSION_NAMESPACE {
//

const std::string kSdfScopeDelimiter = "::";
namespace internal
{
/// \brief Initializes the scope delimiter as a function-local static
/// variable so it can be used to initialize kSdfScopeDelimiter.
/// \note This should not be used directly in user code. It will likely be
/// removed in libsdformat 15 with kSdfScopeDelimiter.
SDFORMAT_VISIBLE const std::string &SdfScopeDelimiter();
} // namespace internal

constexpr std::string_view kScopeDelimiter{"::"};

// Deprecated because it violates the Google Style Guide as it is not
// trivially destructible. Please use sdf::kScopeDelimiter instead.
GZ_DEPRECATED(14)
inline const std::string &kSdfScopeDelimiter = internal::SdfScopeDelimiter();

/// \brief The source path replacement if it was parsed from a string,
/// instead of a file.
Expand Down
2 changes: 1 addition & 1 deletion python/test/gz_test_deps/sdformat.py
Original file line number Diff line number Diff line change
@@ -1 +1 @@
from sdformat13 import *
from sdformat14 import *
2 changes: 1 addition & 1 deletion python/test/pyModel_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -255,7 +255,7 @@ def test_add_modify_frame(self):

def test_uri(self):
model = Model()
uri = "https:#fuel.ignitionrobotics.org/1.0/openrobotics/models/my-model"
uri = "https:#fuel.gazebosim.org/1.0/openrobotics/models/my-model"

model.set_uri(uri)
self.assertEqual(uri, model.uri())
Expand Down
4 changes: 2 additions & 2 deletions sdf/1.10/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -73,8 +73,8 @@ foreach(FIL ${sdfs})

add_custom_command(
OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/${FIL_WE}.xsd"
COMMAND ${RUBY} ${CMAKE_SOURCE_DIR}/tools/xmlschema.rb
ARGS -s ${CMAKE_CURRENT_SOURCE_DIR} -i ${ABS_FIL} -o ${CMAKE_CURRENT_BINARY_DIR}
COMMAND ${Python3_EXECUTABLE} ${CMAKE_SOURCE_DIR}/tools/xmlschema.py
ARGS --sdf-dir ${CMAKE_CURRENT_SOURCE_DIR} --input-file ${ABS_FIL} --output-dir ${CMAKE_CURRENT_BINARY_DIR}
DEPENDS ${ABS_FIL}
COMMENT "Running xml schema compiler on ${FIL}"
VERBATIM)
Expand Down
2 changes: 2 additions & 0 deletions sdf/1.11/1_10.convert
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
<convert name="sdf">
</convert> <!-- End SDF -->
88 changes: 88 additions & 0 deletions sdf/1.11/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
set (sdfs
actor.sdf
air_pressure.sdf
air_speed.sdf
altimeter.sdf
atmosphere.sdf
audio_source.sdf
audio_sink.sdf
battery.sdf
box_shape.sdf
camera.sdf
capsule_shape.sdf
collision.sdf
contact.sdf
cylinder_shape.sdf
ellipsoid_shape.sdf
frame.sdf
forcetorque.sdf
geometry.sdf
gps.sdf
gripper.sdf
gui.sdf
heightmap_shape.sdf
image_shape.sdf
imu.sdf
inertial.sdf
joint.sdf
lidar.sdf
light.sdf
light_state.sdf
link.sdf
link_state.sdf
logical_camera.sdf
magnetometer.sdf
material.sdf
mesh_shape.sdf
model.sdf
model_state.sdf
navsat.sdf
noise.sdf
particle_emitter.sdf
physics.sdf
plane_shape.sdf
plugin.sdf
polyline_shape.sdf
population.sdf
pose.sdf
projector.sdf
ray.sdf
rfidtag.sdf
rfid.sdf
road.sdf
root.sdf
scene.sdf
sensor.sdf
spherical_coordinates.sdf
sphere_shape.sdf
sonar.sdf
state.sdf
surface.sdf
transceiver.sdf
visual.sdf
world.sdf
)

set (SDF_SCHEMA)

foreach(FIL ${sdfs})
get_filename_component(ABS_FIL ${FIL} ABSOLUTE)
get_filename_component(FIL_WE ${FIL} NAME_WE)

list(APPEND SDF_SCHEMA "${CMAKE_CURRENT_BINARY_DIR}/${FIL_WE}.xsd")

add_custom_command(
OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/${FIL_WE}.xsd"
COMMAND ${Python3_EXECUTABLE} ${CMAKE_SOURCE_DIR}/tools/xmlschema.py
ARGS --sdf-dir ${CMAKE_CURRENT_SOURCE_DIR} --input-file ${ABS_FIL} --output-dir ${CMAKE_CURRENT_BINARY_DIR}
DEPENDS ${ABS_FIL}
COMMENT "Running xml schema compiler on ${FIL}"
VERBATIM)
endforeach()

add_custom_target(schema1_11 ALL DEPENDS ${SDF_SCHEMA})

set_source_files_properties(${SDF_SCHEMA} PROPERTIES GENERATED TRUE)

install(FILES 1_10.convert ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/1.11)
install(FILES ${SDF_SCHEMA} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/1.11)
86 changes: 86 additions & 0 deletions sdf/1.11/actor.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
<!-- Actor -->
<element name="actor" required="*">
<description>A special kind of model which can have a scripted motion. This includes both global waypoint type animations and skeleton animations.</description>

<attribute name="name" type="string" default="__default__" required="1">
<description>A unique name for the actor.</description>
</attribute>

<include filename="pose.sdf" required="0"/>

<element name="skin" required="0">
<description>Skin file which defines a visual and the underlying skeleton which moves it.</description>

<element name="filename" type="string" default="__default__" required="1">
<description>Path to skin file, accepted formats: COLLADA, BVH.</description>
</element>

<element name="scale" type="double" default="1.0" required="0">
<description>Scale the skin's size.</description>
</element>
</element> <!-- End Skin -->

<element name="animation" required="*">
<description>Animation file defines an animation for the skeleton in the skin. The skeleton must be compatible with the skin skeleton.</description>

<attribute name="name" type="string" default="__default__" required="1">
<description>Unique name for animation.</description>
</attribute>

<element name="filename" type="string" default="__default__" required="1">
<description>Path to animation file. Accepted formats: COLLADA, BVH.</description>
</element>
<element name="scale" type="double" default="1.0" required="0">
<description>Scale for the animation skeleton.</description>
</element>
<element name="interpolate_x" type="bool" default="false" required="0">
<description>Set to true so the animation is interpolated on X.</description>
</element>
</element> <!-- End Animation -->

<element name="script" required="1">
<description>Adds scripted trajectories to the actor.</description>

<element name="loop" type="bool" default="true" required="0">
<description>Set this to true for the script to be repeated in a loop. For a fluid continuous motion, make sure the last waypoint matches the first one.</description>
</element>

<element name="delay_start" type="double" default="0.0" required="0">
<description>This is the time to wait before starting the script. If running in a loop, this time will be waited before starting each cycle.</description>
</element>

<element name="auto_start" type="bool" default="true" required="0">
<description>Set to true if the animation should start as soon as the simulation starts playing. It is useful to set this to false if the animation should only start playing only when triggered by a plugin, for example.</description>
</element>

<element name="trajectory" required="*">
<description>The trajectory contains a series of keyframes to be followed.</description>
<attribute name="id" type="int" default="0" required="1">
<description>Unique id for a trajectory.</description>
</attribute>

<attribute name="type" type="string" default="__default__" required="1">
<description>If it matches the type of an animation, they will be played at the same time.</description>
</attribute>

<attribute name="tension" type="double" default="0.0" required="0" min="0.0" max="1.0">
<description>The tension of the trajectory spline. The default value of zero equates to a Catmull-Rom spline, which may also cause the animation to overshoot keyframes. A value of one will cause the animation to stick to the keyframes.</description>
</attribute>

<element name="waypoint" required="*">
<description>Each point in the trajectory.</description>
<element name="time" type="double" default="0.0" required="1">
<description>The time in seconds, counted from the beginning of the script, when the pose should be reached.</description>
</element>
<element name="pose" type="pose" default="0 0 0 0 0 0" required="1">
<description>The pose which should be reached at the given time.</description>
</element> <!-- End Pose -->
</element> <!-- End Waypoint -->
</element> <!-- End Trajectory -->
</element> <!-- End Script -->

<include filename="link.sdf" required="+"/>
<include filename="joint.sdf" required="*"/>
<include filename="plugin.sdf" required="*"/>

</element> <!-- End Actor -->
15 changes: 15 additions & 0 deletions sdf/1.11/air_pressure.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
<element name="air_pressure" required="0">
<description>These elements are specific to an air pressure sensor.</description>

<element name="reference_altitude" type="double" default="0.0" required="0">
<description>The initial altitude in meters. This value can be used by a sensor implementation to augment the altitude of the sensor. For example, if you are using simulation instead of creating a 1000 m mountain model on which to place your sensor, you could instead set this value to 1000 and place your model on a ground plane with a Z height of zero.</description>
</element>

<element name="pressure" required="0">
<description>
Noise parameters for the pressure data.
</description>
<include filename="noise.sdf" required="0"/>
</element>

</element>
11 changes: 11 additions & 0 deletions sdf/1.11/air_speed.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<element name="air_speed" required="0">
<description>These elements are specific to an air speed sensor. This sensor determines speed based on the differential between static and dynamic pressure.</description>

<element name="pressure" required="0">
<description>
Noise parameters for the pressure data.
</description>
<include filename="noise.sdf" required="0"/>
</element>

</element>
18 changes: 18 additions & 0 deletions sdf/1.11/altimeter.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<element name="altimeter" required="0">
<description>These elements are specific to an altimeter sensor.</description>

<element name="vertical_position" required="0">
<description>
Noise parameters for vertical position
</description>
<include filename="noise.sdf" required="0"/>
</element>

<element name="vertical_velocity" required="0">
<description>
Noise parameters for vertical velocity
</description>
<include filename="noise.sdf" required="0"/>
</element>

</element>
21 changes: 21 additions & 0 deletions sdf/1.11/atmosphere.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
<!-- Atmosphere -->
<element name="atmosphere" required="1">
<description>The atmosphere tag specifies the type and properties of the atmosphere model.</description>

<attribute name="type" type="string" default="adiabatic" required="1">
<description>The type of the atmosphere engine. Current options are adiabatic. Defaults to adiabatic if left unspecified.</description>
</attribute>

<element name="temperature" type="double" default="288.15" required="0">
<description>Temperature at sea level in kelvins.</description>
</element>

<element name="pressure" type="double" default="101325" required="0">
<description>Pressure at sea level in pascals.</description>
</element>

<element name="temperature_gradient" type="double" default="-0.0065" required="0">
<description>Temperature gradient with respect to increasing altitude at sea level in units of K/m.</description>
</element>

</element> <!-- Atmosphere -->
4 changes: 4 additions & 0 deletions sdf/1.11/audio_sink.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
<!-- Audio Sink -->
<element name="audio_sink" required="*">
<description>An audio sink.</description>
</element>
Loading

0 comments on commit c652521

Please sign in to comment.