Skip to content

Commit

Permalink
Upgrade sdformat to 10.3.0
Browse files Browse the repository at this point in the history
Deprecate `@tinyxml` external
Ignore new `/sdf//heightmap` elements
models: Fix now-invalid usages of `/sdf//pose`

Co-Authored-By: Addisu Z. Taddese <addisu@openrobotics.org>
  • Loading branch information
EricCousineau-TRI and azeey committed Mar 2, 2021
1 parent f806808 commit 49c381b
Show file tree
Hide file tree
Showing 8 changed files with 62 additions and 28 deletions.
4 changes: 2 additions & 2 deletions examples/manipulation_station/models/cupboard.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@
<joint name="left_door_hinge" type="revolute">
<child>left_door</child>
<parent>cupboard_body</parent>
<pose>-0.008 -0.1395 0 0 0 </pose>
<pose>-0.008 -0.1395 0 0 0 0</pose>
<axis>
<xyz> 0 0 1 </xyz>
<limit>
Expand Down Expand Up @@ -174,7 +174,7 @@
<joint name="right_door_hinge" type="revolute">
<child>right_door</child>
<parent>cupboard_body</parent>
<pose>-0.008 0.1395 0 0 0 </pose>
<pose>-0.008 0.1395 0 0 0 0</pose>
<axis>
<xyz> 0 0 1 </xyz>
<limit>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<!-- This sdf file is based on schunk_wsg_50.sdf -->
<?xml version="1.0"?>
<!-- This sdf file is based on schunk_wsg_50.sdf -->
<sdf version="1.7">
<model name="Schunk_Gripper">
<link name="body">
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<!-- This sdf file is based on schunk_wsg_50.sdf -->
<?xml version="1.0"?>
<!-- This sdf file is based on schunk_wsg_50.sdf -->
<sdf version="1.7">
<model name="Schunk_Gripper">
<link name="body">
Expand Down
14 changes: 11 additions & 3 deletions multibody/parsing/detail_scene_graph.cc
Original file line number Diff line number Diff line change
Expand Up @@ -166,6 +166,9 @@ std::unique_ptr<geometry::Shape> MakeShapeFromSdfGeometry(
return make_unique<geometry::Mesh>(file_name, scale);
}
}
case sdf::GeometryType::HEIGHTMAP: {
return std::unique_ptr<geometry::Shape>(nullptr);
}
}

DRAKE_UNREACHABLE();
Expand Down Expand Up @@ -200,6 +203,7 @@ std::unique_ptr<GeometryInstance> MakeGeometryInstanceFromSdfVisual(
// other geometry types whenever X_LC != X_LG.
switch (sdf_geometry.Type()) {
case sdf::GeometryType::EMPTY: // Also includes custom geometries.
case sdf::GeometryType::HEIGHTMAP:
case sdf::GeometryType::BOX:
case sdf::GeometryType::CYLINDER:
case sdf::GeometryType::MESH:
Expand Down Expand Up @@ -227,9 +231,12 @@ std::unique_ptr<GeometryInstance> MakeGeometryInstanceFromSdfVisual(
}
}

auto instance = make_unique<GeometryInstance>(
X_LC, MakeShapeFromSdfGeometry(sdf_geometry, resolve_filename),
sdf_visual.Name());
auto shape = MakeShapeFromSdfGeometry(sdf_geometry, resolve_filename);
if (shape == nullptr) {
return nullptr;
}
auto instance =
make_unique<GeometryInstance>(X_LC, move(shape), sdf_visual.Name());
instance->set_illustration_properties(
MakeVisualPropertiesFromSdfVisual(sdf_visual, resolve_filename));
return instance;
Expand Down Expand Up @@ -345,6 +352,7 @@ RigidTransformd MakeGeometryPoseFromSdfCollision(
const sdf::Geometry& sdf_geometry = *sdf_collision.Geom();
switch (sdf_geometry.Type()) {
case sdf::GeometryType::EMPTY:
case sdf::GeometryType::HEIGHTMAP:
case sdf::GeometryType::BOX:
case sdf::GeometryType::CYLINDER:
case sdf::GeometryType::MESH:
Expand Down
36 changes: 33 additions & 3 deletions multibody/parsing/test/detail_scene_graph_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -343,6 +343,17 @@ GTEST_TEST(SceneGraphParserDetail, MakeConvexFromSdfGeometry) {
EXPECT_EQ(convex->scale(), 3);
}

// Verify that MakeShapeFromSdfGeometry does nothing with a heightmap.
GTEST_TEST(SceneGraphParserDetail, MakeHeightmapFromSdfGeometry) {
unique_ptr<sdf::Geometry> sdf_geometry = MakeSdfGeometryFromString(
"<heightmap>"
" <uri>/path/to/some/heightmap.png</uri>"
"</heightmap>");
unique_ptr<Shape> shape = MakeShapeFromSdfGeometry(
*sdf_geometry, NoopResolveFilename);
EXPECT_EQ(shape, nullptr);
}

// Verify MakeGeometryInstanceFromSdfVisual can make a GeometryInstance from an
// sdf::Visual.
// Since we test MakeShapeFromSdfGeometry separately, there is no need to unit
Expand Down Expand Up @@ -430,7 +441,7 @@ GTEST_TEST(SceneGraphParserDetail, VisualGeometryNameRequirements) {

// These whitespace characters are *not* considered to be whitespace by SDF.
std::vector<std::pair<char, std::string>> ignored_whitespace{
{'\n', "\\n"}, {'\v', "\\v"}, {'\r', "\\r"}, {'\f', "\\f"}};
{'\v', "\\v"}, {'\f', "\\f"}};
for (const auto& pair : ignored_whitespace) {
// Case: Whitespace-only name.
EXPECT_TRUE(valid_parse(fmt::format(visual_tag, pair.first)))
Expand Down Expand Up @@ -549,6 +560,25 @@ GTEST_TEST(SceneGraphParserDetail, MakeEmptyGeometryInstanceFromSdfVisual) {
EXPECT_EQ(geometry_instance, nullptr);
}


// Verify that MakeGeometryInstanceFromSdfVisual does nothing with a heightmap.
GTEST_TEST(SceneGraphParserDetail, MakeHeightmapGeometryInstanceFromSdfVisual) {
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
"<visual name='some_link_visual'>"
" <pose>1.0 2.0 3.0 3.14 6.28 1.57</pose>"
" <geometry>"
" <heightmap>"
" <uri>/path/to/some/heightmap.png</uri>"
" </heightmap>"
" </geometry>"
"</visual>");
unique_ptr<GeometryInstance> geometry_instance =
MakeGeometryInstanceFromSdfVisual(
*sdf_visual, NoopResolveFilename,
ToRigidTransform(sdf_visual->RawPose()));
EXPECT_EQ(geometry_instance, nullptr);
}

// Reports if the indicated typed geometry property matches expectations.
// The expectation is given by an optional `expected_value`. If nullopt, we
// expect the property to be absent. If provided, we expect the property to
Expand Down Expand Up @@ -779,7 +809,7 @@ GTEST_TEST(SceneGraphParserDetail, ParseVisualMaterial) {
// TODO(SeanCurtis-TRI): The following tests capture current behavior for
// sdformat. The behavior isn't necessarily desirable and an issue has been
// filed.
// https://bitbucket.org/osrf/sdformat/issues/193/using-element-get-has-surprising-defaults
// https://github.com/osrf/sdformat/issues/193
// When this issue gets resolved, modify these tests accordingly.

// sdformat maps the diffuse values into a `Color` using the following rules:
Expand Down Expand Up @@ -824,7 +854,7 @@ GTEST_TEST(SceneGraphParserDetail, ParseVisualMaterial) {
"</visual>");
IllustrationProperties material =
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename);
Vector4<double> expected_diffuse{0, 1, 0, 1};
Vector4<double> expected_diffuse{0, 1, 1, 1};
EXPECT_TRUE(expect_phong(material, true, expected_diffuse, {}, {}, {}, {}));
}

Expand Down
15 changes: 11 additions & 4 deletions tools/workspace/sdformat/package.BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ cc_library(
includes = ["src/urdf"],
linkstatic = 1,
visibility = ["//visibility:private"],
deps = ["@tinyxml"],
deps = ["@tinyxml2"],
)

# Generates sdf_config.h based on the version numbers in CMake code.
Expand Down Expand Up @@ -99,6 +99,7 @@ SDFORMAT_MOST_PUBLIC_HDRS = [
"include/sdf/Frame.hh",
"include/sdf/Geometry.hh",
"include/sdf/Gui.hh",
"include/sdf/Heightmap.hh",
"include/sdf/Imu.hh",
"include/sdf/Joint.hh",
"include/sdf/JointAxis.hh",
Expand All @@ -119,6 +120,7 @@ SDFORMAT_MOST_PUBLIC_HDRS = [
"include/sdf/Scene.hh",
"include/sdf/SemanticPose.hh",
"include/sdf/Sensor.hh",
"include/sdf/Sky.hh",
"include/sdf/Sphere.hh",
"include/sdf/Surface.hh",
"include/sdf/Types.hh",
Expand Down Expand Up @@ -169,7 +171,6 @@ SDFORMAT_ALL_PUBLIC_HDRS = SDFORMAT_MOST_PUBLIC_HDRS + [
cc_library(
name = "sdformat",
srcs = [
"include/sdf/parser_urdf.hh",
"src/Actor.cc",
"src/AirPressure.cc",
"src/Altimeter.cc",
Expand All @@ -192,6 +193,7 @@ cc_library(
"src/FrameSemantics.hh",
"src/Geometry.cc",
"src/Gui.cc",
"src/Heightmap.cc",
"src/Imu.cc",
"src/Joint.cc",
"src/JointAxis.cc",
Expand All @@ -213,18 +215,23 @@ cc_library(
"src/SDFExtension.hh",
"src/SDFImplPrivate.hh",
"src/Scene.cc",
# "src/ScopedGraph.hh",
"src/SemanticPose.cc",
"src/Sensor.cc",
"src/Sky.cc",
"src/Sphere.cc",
"src/Surface.cc",
"src/Types.cc",
"src/Utils.cc",
"src/Utils.hh",
"src/Visual.cc",
"src/World.cc",
"src/XmlUtils.cc",
"src/XmlUtils.hh",
"src/parser.cc",
"src/parser_private.hh",
"src/parser_urdf.cc",
"src/parser_urdf.hh",
":src/EmbeddedSdf.cc",
],
hdrs = SDFORMAT_ALL_PUBLIC_HDRS,
Expand All @@ -233,13 +240,13 @@ cc_library(
# runtime. This was likely caused by different translation units being
# compiled with different visibility settings."
copts = ["-w"],
defines = ["SDFORMAT_STATIC_DEFINE"],
defines = ["SDFORMAT_STATIC_DEFINE", "SDFORMAT_DISABLE_CONSOLE_LOGFILE"],
includes = ["include"],
linkstatic = 1,
deps = [
":urdfdom",
"@ignition_math",
"@tinyxml",
"@tinyxml2",
],
)

Expand Down
16 changes: 2 additions & 14 deletions tools/workspace/sdformat/repository.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -8,20 +8,8 @@ def sdformat_repository(
github_archive(
name = name,
repository = "osrf/sdformat",
commit = "sdformat9_9.3.0",
sha256 = "6886cd905c74698000bf4e4bb378efe292411fab939d80d3263dfad430e50204", # noqa
commit = "sdformat10_10.3.0",
sha256 = "ef52bddc49e962faf8d6df80f6c685de47a749e335ec552fd03fa355eb03d2a7", # noqa
build_file = "@drake//tools/workspace/sdformat:package.BUILD.bazel",
patches = [
# TODO(jwnimmer-tri) This patch is cherry-picked from upstream; we
# should remove it once we reach a new enough version, probably for
# sdformat10 or so.
"@drake//tools/workspace/sdformat:3bbd303.patch",
# Disable logging to $HOME/.sdformat/sdformat.log
# TODO(jwnimmer-tri) Once osrf/sdformat#338 is released, we can
# remove this patch and set SDFORMAT_DISABLE_CONSOLE_LOGFILE=1
# instead, probably for sdformat10 or so.
"@drake//tools/workspace/sdformat:no-console-file.patch",
],
patch_args = ["-p1"],
mirrors = mirrors,
)
1 change: 1 addition & 0 deletions tools/workspace/tinyxml/repository.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -16,5 +16,6 @@ def tinyxml_repository(
licenses = licenses,
modname = modname,
pkg_config_paths = pkg_config_paths,
build_file_deprecation = "DRAKE DEPRECATED: The @tinyxml external is being removed from Drake on or after 2021-06-01. Downstream projects should add it to their own WORKSPACE if needed.", # noqa
**kwargs
)

0 comments on commit 49c381b

Please sign in to comment.