Skip to content

Commit

Permalink
Merge branch 'sdf12' into formalize_inertial_spec_doc
Browse files Browse the repository at this point in the history
  • Loading branch information
scpeters authored May 3, 2022
2 parents fc0ba0a + 12e7782 commit 4f9487f
Show file tree
Hide file tree
Showing 6 changed files with 105 additions and 16 deletions.
12 changes: 12 additions & 0 deletions include/sdf/Plugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,18 @@ namespace sdf
/// \return A reference to this plugin
public: Plugin &operator=(Plugin &&_plugin) noexcept;

/// \brief Plugin equality operator.
/// \param[in] _plugin Plugin to compare against.
/// \return True if this plugin matches the provided plugin. The name,
/// filename, and contents must all match to return true.
public: bool operator==(const Plugin &_plugin) const;

/// \brief Plugin inequality operator.
/// \param[in] _plugin Plugin to compare against.
/// \return True if this plugin does not match the provided plugin.
/// The name, filename, or contents must be different to return false.
public: bool operator!=(const Plugin &_plugin) const;

/// \brief Output stream operator for a Plugin.
/// \param[in] _out The output stream
/// \param[in] _plugin Plugin to output
Expand Down
13 changes: 13 additions & 0 deletions src/Plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -259,3 +259,16 @@ Plugin &Plugin::operator=(Plugin &&_plugin) noexcept
this->dataPtr = std::move(_plugin.dataPtr);
return *this;
}

/////////////////////////////////////////////////
bool Plugin::operator==(const Plugin &_plugin) const
{
// Simplest thing to do is compare the string form of each plugin
return _plugin.ToElement()->ToString("") == this->ToElement()->ToString("");
}

/////////////////////////////////////////////////
bool Plugin::operator!=(const Plugin &_plugin) const
{
return !(*this == _plugin);
}
31 changes: 31 additions & 0 deletions src/Plugin_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -385,3 +385,34 @@ TEST(DOMPlugin, InsertStringContent)
EXPECT_EQ("name", plugin5.Name());
EXPECT_TRUE(plugin5.Contents().empty());
}

/////////////////////////////////////////////////
TEST(DOMPlugin, EqualityOperators)
{
sdf::Plugin plugin("my-filename", "my-name",
"<render_engine>ogre2</render_engine>");
sdf::Plugin plugin2(plugin);
sdf::Plugin plugin3;

EXPECT_EQ(plugin, plugin2);
EXPECT_NE(plugin, plugin3);
EXPECT_NE(plugin2, plugin3);

// Test contents
plugin2.ClearContents();
EXPECT_NE(plugin, plugin2);
plugin.ClearContents();
EXPECT_EQ(plugin, plugin2);

// test name
plugin2.SetName("new-name");
EXPECT_NE(plugin, plugin2);
plugin.SetName("new-name");
EXPECT_EQ(plugin, plugin2);

// test filename
plugin2.SetFilename("new-filename");
EXPECT_NE(plugin, plugin2);
plugin.SetFilename("new-filename");
EXPECT_EQ(plugin, plugin2);
}
20 changes: 15 additions & 5 deletions test/usd/upAxisZ.usda
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,9 @@ def Xform "box" (
double3 xformOp:translate = (0, 0, 0)
uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:rotateXYZ"]

def Cube "geometry"
def Cube "geometry" (
kind = "model"
)
{
float3[] extent = [(-0.5, -0.5, -0.5), (0.5, 0.5, 0.5)]
rel material:binding = </Looks/Material_1>
Expand Down Expand Up @@ -159,7 +161,9 @@ def Xform "cylinder"
double3 xformOp:translate = (0, 0, 0)
uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:rotateXYZ"]

def Cylinder "geometry"
def Cylinder "geometry" (
kind = "model"
)
{
float3[] extent = [(-0.5, -0.5, -0.5), (0.5, 0.5, 0.5)]
double height = 1
Expand Down Expand Up @@ -202,7 +206,9 @@ def Xform "sphere"
double3 xformOp:translate = (0, 0, 0)
uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:rotateXYZ"]

def Sphere "geometry"
def Sphere "geometry" (
kind = "model"
)
{
float3[] extent = [(-0.5, -0.5, -0.5), (0.5, 0.5, 0.5)]
rel material:binding = </Looks/Material_3>
Expand Down Expand Up @@ -243,7 +249,9 @@ def Xform "capsule"
double3 xformOp:translate = (0, 0, 0)
uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:rotateZYX"]

def Capsule "geometry"
def Capsule "geometry" (
kind = "model"
)
{
float3[] extent = [(-0.2, -0.2, -0.5), (0.2, 0.2, 0.5)]
double height = 0.6
Expand Down Expand Up @@ -286,7 +294,9 @@ def Xform "ellipsoid"
double3 xformOp:translate = (0, 0, 0)
uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:rotateXYZ"]

def Sphere "geometry"
def Sphere "geometry" (
kind = "model"
)
{
float3[] extent = [(-0.5, -0.5, -0.5), (0.5, 0.5, 0.5)]
rel material:binding = </Looks/Material_5>
Expand Down
40 changes: 30 additions & 10 deletions usd/src/usd_parser/USDLinks.cc
Original file line number Diff line number Diff line change
Expand Up @@ -233,7 +233,7 @@ int ParseMeshSubGeom(const pxr::UsdPrim &_prim,

ignition::common::SubMesh subMeshSubset;
subMeshSubset.SetPrimitiveType(ignition::common::SubMesh::TRISTRIPS);
subMeshSubset.SetName("subgeommesh");
subMeshSubset.SetName("subgeommesh_" + std::to_string(numSubMeshes));

if (it != _usdData.Materials().end())
{
Expand Down Expand Up @@ -288,12 +288,18 @@ int ParseMeshSubGeom(const pxr::UsdPrim &_prim,
_meshGeom.SetUri(directoryMesh + ".dae");

geomSubset.SetMeshShape(_meshGeom);
visSubset.SetName("mesh_subset");
visSubset.SetName("mesh_subset_" + std::to_string(numSubMeshes));
visSubset.SetGeom(geomSubset);

ignition::math::Pose3d pose;
ignition::math::Vector3d scale(1, 1, 1);
GetTransform(child, _usdData, pose, scale, _link->Name());
std::string linkName = pxr::TfStringify(_prim.GetPath());
auto found = linkName.find(_link->Name());
if (found != std::string::npos)
{
linkName = linkName.substr(0, found + _link->Name().size());
}
GetTransform(child, _usdData, pose, scale, linkName);
_scale *= scale;
visSubset.SetRawPose(pose);
_link->AddVisual(visSubset);
Expand Down Expand Up @@ -386,15 +392,21 @@ UsdErrors ParseMesh(

ignition::math::Pose3d pose;
ignition::math::Vector3d scale(1, 1, 1);
std::string linkName = _link->Name();
std::string linkName = pxr::TfStringify(_prim.GetPath());
auto found = linkName.find(_link->Name());
if (found != std::string::npos)
{
linkName = linkName.substr(0, found + _link->Name().size());
}

size_t nSlash = std::count(linkName.begin(), linkName.end(), '/');
if (nSlash == 1)
{
GetTransform(_prim, _usdData, pose, scale, "/");
}
else
{
GetTransform(_prim, _usdData, pose, scale, _link->Name());
GetTransform(_prim, _usdData, pose, scale, linkName);
}

_pose = pose;
Expand Down Expand Up @@ -522,7 +534,7 @@ void ParseCylinder(
_geom.SetType(sdf::GeometryType::CYLINDER);

c.SetRadius(radius * _metersPerUnit * _scale.X());
c.SetLength(height * _metersPerUnit * _scale.Y());
c.SetLength(height * _metersPerUnit * _scale.Z());

_geom.SetCylinderShape(c);
}
Expand Down Expand Up @@ -632,9 +644,9 @@ UsdErrors ParseUSDLinks(
pxr::UsdModelAPI(parent).GetKind(&kindOfSchema);
}

if (_prim.HasAPI<pxr::UsdPhysicsRigidBodyAPI>()
|| pxr::KindRegistry::IsA(kindOfSchema, pxr::KindTokens->model)
|| !collisionEnabled)
if ((_prim.HasAPI<pxr::UsdPhysicsRigidBodyAPI>()
|| pxr::KindRegistry::IsA(kindOfSchema, pxr::KindTokens->model))
&& (!collisionEnabled || _prim.HasAPI<pxr::UsdPhysicsMassAPI>()))
{
double metersPerUnit = data.second->MetersPerUnit();

Expand Down Expand Up @@ -696,7 +708,15 @@ UsdErrors ParseUSDLinks(

ignition::math::Pose3d poseCol;
ignition::math::Vector3d scaleCol(1, 1, 1);
GetTransform(_prim, _usdData, poseCol, scaleCol, _link->Name());
std::string linkName = pxr::TfStringify(_prim.GetPath());
auto found = linkName.find(_link->Name());
if (found != std::string::npos)
{
linkName = linkName.substr(0, found + _link->Name().size());
}
GetTransform(_prim, _usdData, poseCol, scaleCol, linkName);

scaleCol *= _scale;

double metersPerUnit = data.second->MetersPerUnit();

Expand Down
5 changes: 4 additions & 1 deletion usd/src/usd_parser/USDWorld.cc
Original file line number Diff line number Diff line change
Expand Up @@ -351,7 +351,8 @@ namespace usd
}

std::optional<sdf::Link> optionalLink;
if (auto linkInserted = modelPtr->LinkByName(linkName))
if (auto linkInserted =
modelPtr->LinkByName(ignition::common::basename(linkName)))
{
optionalLink = *linkInserted;
auto scale = linkScaleMap.find(linkName);
Expand All @@ -362,6 +363,8 @@ namespace usd
}
sdf::usd::ParseUSDLinks(
prim, linkName, optionalLink, usdData, scale->second);
*linkInserted = optionalLink.value();
linkScaleMap[linkName] = scale->second;
}
else
{
Expand Down

0 comments on commit 4f9487f

Please sign in to comment.