Skip to content

Commit

Permalink
Merge pull request #14705 from EricCousineau-TRI/feature-libsdformat10
Browse files Browse the repository at this point in the history
Upgrade sdformat to 10.3.0
  • Loading branch information
EricCousineau-TRI authored Mar 2, 2021
2 parents f47387b + f13c731 commit 0c6ac30
Show file tree
Hide file tree
Showing 13 changed files with 81 additions and 270 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
4 changes: 3 additions & 1 deletion multibody/parsing/detail_scene_graph.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,9 @@ std::unique_ptr<geometry::Shape> MakeShapeFromSdfGeometry(
file, this method makes a new drake::geometry::GeometryInstance object from
this specification at a pose `X_LG` relatve to its parent link.
This method returns nullptr when the given SDF specification corresponds
to a geometry of type `sdf::GeometryType::EMPTY` (`<empty/>` SDF tag.)
to an uninterpreted geometry type:
- `sdf::GeometryType::EMPTY` (`<empty/>` SDF tag.)
- `sdf::GeometryType::HEIGHTMAP` (`<heightmap/>` SDF tag.)
<!-- TODO(SeanCurtis-TRI): Ultimately, a module for what we parse should be
written outside of this _internal_ namespace. This should go there and
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
1 change: 1 addition & 0 deletions tools/workspace/pkg_config.BUILD.tpl
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ cc_library(
includes = %{includes},
linkopts = %{linkopts},
deps = %{deps},
deprecation = %{extra_deprecation},
)

%{build_epilog}
12 changes: 12 additions & 0 deletions tools/workspace/pkg_config.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -221,6 +221,14 @@ def setup_pkg_config_repository(repository_ctx):
includes += ["include/" + symlink_dest]
hdrs_prologue = "glob([\"include/**\"]) + "

extra_deprecation = getattr(
repository_ctx.attr,
"extra_deprecation",
"",
)
if extra_deprecation == "":
extra_deprecation = None

# Write out the BUILD.bazel file.
substitutions = {
"%{topcomment}": "DO NOT EDIT: generated by pkg_config_repository()",
Expand Down Expand Up @@ -254,6 +262,7 @@ def setup_pkg_config_repository(repository_ctx):
getattr(repository_ctx.attr, "extra_deps", []),
),
"%{build_epilog}": getattr(repository_ctx.attr, "build_epilog", ""),
"%{extra_deprecation}": repr(extra_deprecation),
}
template = getattr(
repository_ctx.attr,
Expand Down Expand Up @@ -295,6 +304,7 @@ pkg_config_repository = repository_rule(
"extra_deps": attr.string_list(),
"build_epilog": attr.string(),
"pkg_config_paths": attr.string_list(),
"extra_deprecation": attr.string(),
},
local = True,
configure = True,
Expand Down Expand Up @@ -345,4 +355,6 @@ Args:
pkg_config_paths: (Optional) Paths to find pkg-config files (.pc). Note
that we ignore the environment variable PKG_CONFIG_PATH
set by the user.
extra_deprecation: (Optional) Add a deprecation message to the library
BUILD target.
"""
Loading

0 comments on commit 0c6ac30

Please sign in to comment.