Skip to content

Commit

Permalink
Merge branch 'sdf12' into ahcorde/usd_to_sdf_initial_commit
Browse files Browse the repository at this point in the history
  • Loading branch information
ahcorde authored Mar 8, 2022
2 parents 0f34f61 + ed04483 commit 654ae66
Show file tree
Hide file tree
Showing 3 changed files with 114 additions and 7 deletions.
62 changes: 62 additions & 0 deletions test/sdf/ellipsoid.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
<?xml version="1.0" ?>
<sdf version="1.8">
<world name="ellipsoid_world">
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>10 10</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>10 10</size>
</plane>
</geometry>
</visual>
</link>
</model>

<model name="ellipsoid">
<pose>0 3.0 0.5 0 0 0</pose>
<link name="ellipsoid_link">
<inertial>
<inertia>
<ixx>0.068</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.058</iyy>
<iyz>0</iyz>
<izz>0.026</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="ellipsoid_collision">
<geometry>
<ellipsoid>
<radii>0.2 0.3 0.5</radii>
</ellipsoid>
</geometry>
</collision>
<visual name="ellipsoid_visual">
<geometry>
<ellipsoid>
<radii>0.2 0.3 0.5</radii>
</ellipsoid>
</geometry>
<material>
<ambient>1 0 1 1</ambient>
<diffuse>1 0 1 1</diffuse>
<specular>1 0 1 1</specular>
</material>
</visual>
</link>
</model>
</world>
</sdf>
13 changes: 6 additions & 7 deletions usd/src/sdf_parser/Geometry.cc
Original file line number Diff line number Diff line change
Expand Up @@ -550,18 +550,17 @@ namespace usd
return errors;
}

const float maxRadii = sdfEllipsoid->Radii().Max();
usdEllipsoid.CreateRadiusAttr().Set(maxRadii);
usdEllipsoid.CreateRadiusAttr().Set(1.0);
pxr::UsdGeomXformCommonAPI xform(usdEllipsoid);
xform.SetScale(pxr::GfVec3f{
static_cast<float>(sdfEllipsoid->Radii().X() / maxRadii),
static_cast<float>(sdfEllipsoid->Radii().Y() / maxRadii),
static_cast<float>(sdfEllipsoid->Radii().Z() / maxRadii),
static_cast<float>(sdfEllipsoid->Radii().X()),
static_cast<float>(sdfEllipsoid->Radii().Y()),
static_cast<float>(sdfEllipsoid->Radii().Z()),
});
// extents is the bounds before any transformation
pxr::VtArray<pxr::GfVec3f> extentBounds;
extentBounds.push_back(pxr::GfVec3f{-maxRadii});
extentBounds.push_back(pxr::GfVec3f{maxRadii});
extentBounds.push_back(pxr::GfVec3f{-1.0f});
extentBounds.push_back(pxr::GfVec3f{1.0f});
usdEllipsoid.CreateExtentAttr().Set(extentBounds);

return errors;
Expand Down
46 changes: 46 additions & 0 deletions usd/src/sdf_parser/Geometry_Sdf2Usd_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,52 @@ class UsdStageFixture : public::testing::Test
public: pxr::UsdStageRefPtr stage;
};

/////////////////////////////////////////////////
TEST_F(UsdStageFixture, Ellipsoid)
{
const auto testFile = sdf::testing::TestFile("sdf", "ellipsoid.sdf");

sdf::Root root;
ASSERT_TRUE(sdf::testing::LoadSdfFile(testFile, root));
ASSERT_EQ(1u, root.WorldCount());
const auto world = root.WorldByIndex(0u);

const auto worldPath = std::string("/" + world->Name());
const auto usdErrors = sdf::usd::ParseSdfWorld(*world, stage, worldPath);
EXPECT_TRUE(usdErrors.empty());

const auto usdSphere = pxr::UsdGeomSphere::Define(
this->stage,
pxr::SdfPath("/ellipsoid_world/ellipsoid/ellipsoid_link/"
"ellipsoid_visual/geometry"));
ASSERT_TRUE(usdSphere);
bool resetXformStack;
const auto xformOps = usdSphere.GetOrderedXformOps(&resetXformStack);
ASSERT_EQ(xformOps.size(), 1u);
EXPECT_FALSE(resetXformStack);
const auto scaleOp = xformOps[0];
EXPECT_EQ(scaleOp.GetOpType(), pxr::UsdGeomXformOp::TypeScale);
pxr::GfVec3f scaleValue;
scaleOp.Get(&scaleValue);
EXPECT_FLOAT_EQ(scaleValue[0], 0.2);
EXPECT_FLOAT_EQ(scaleValue[1], 0.3);
EXPECT_FLOAT_EQ(scaleValue[2], 0.5);

double radius;
EXPECT_TRUE(usdSphere.GetRadiusAttr().Get(&radius));
EXPECT_DOUBLE_EQ(radius, 1);

pxr::VtArray<pxr::GfVec3f> extent;
usdSphere.GetExtentAttr().Get(&extent);
ASSERT_EQ(extent.size(), 2u);
EXPECT_FLOAT_EQ(extent[0][0], -1.0f);
EXPECT_FLOAT_EQ(extent[0][1], -1.0f);
EXPECT_FLOAT_EQ(extent[0][2], -1.0f);
EXPECT_FLOAT_EQ(extent[1][0], 1.0f);
EXPECT_FLOAT_EQ(extent[1][1], 1.0f);
EXPECT_FLOAT_EQ(extent[1][2], 1.0f);
}

/////////////////////////////////////////////////
TEST_F(UsdStageFixture, Geometry)
{
Expand Down

0 comments on commit 654ae66

Please sign in to comment.