Skip to content

Commit 85ce7f6

Browse files
committed
review feedback
Signed-off-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
1 parent 5f5919b commit 85ce7f6

File tree

5 files changed

+27
-21
lines changed

5 files changed

+27
-21
lines changed

usd/src/usd_parser/USDJoints.cc

+18-14
Original file line numberDiff line numberDiff line change
@@ -203,13 +203,7 @@ namespace sdf
203203
jointAxis.SetMaxVelocity(vel);
204204
}
205205

206-
if (_prim.IsA<pxr::UsdPhysicsFixedJoint>())
207-
{
208-
_joint.SetType(sdf::JointType::FIXED);
209-
210-
return errors;
211-
}
212-
else if (_prim.IsA<pxr::UsdPhysicsPrismaticJoint>())
206+
if (_prim.IsA<pxr::UsdPhysicsPrismaticJoint>())
213207
{
214208
auto variant_physics_prismatic_joint =
215209
pxr::UsdPhysicsPrismaticJoint(_prim);
@@ -220,9 +214,9 @@ namespace sdf
220214
if (!errorsAxis.empty())
221215
{
222216
errors.emplace_back(UsdError(
223-
sdf::usd::UsdErrorCode::SDF_TO_USD_PARSING_ERROR,
224-
std::string("Errors encountered when setting xyz of prismatic") +
225-
"_joint axis: [" + std::string(_prim.GetName()) + "]"));
217+
sdf::usd::UsdErrorCode::USD_TO_SDF_PARSING_ERROR,
218+
"Errors encountered when setting xyz of prismatic "
219+
"joint axis: [" + std::string(_prim.GetName()) + "]"));
226220
for (const auto & error : errorsAxis)
227221
errors.emplace_back(error);
228222
return errors;
@@ -250,9 +244,9 @@ namespace sdf
250244
if (!errorsAxis.empty())
251245
{
252246
errors.emplace_back(UsdError(
253-
sdf::usd::UsdErrorCode::SDF_TO_USD_PARSING_ERROR,
254-
std::string("Errors encountered when setting xyz of revolute") +
255-
"_joint axis: [" + std::string(_prim.GetName()) + "]"));
247+
sdf::usd::UsdErrorCode::USD_TO_SDF_PARSING_ERROR,
248+
"Errors encountered when setting xyz of revolute "
249+
"joint axis: [" + std::string(_prim.GetName()) + "]"));
256250
for (const auto & error : errorsAxis)
257251
errors.emplace_back(error);
258252
return errors;
@@ -268,10 +262,20 @@ namespace sdf
268262

269263
return errors;
270264
}
271-
else if (_prim.IsA<pxr::UsdPhysicsJoint>())
265+
else if (_prim.IsA<pxr::UsdPhysicsFixedJoint>() ||
266+
_prim.IsA<pxr::UsdPhysicsJoint>())
272267
{
273268
_joint.SetType(sdf::JointType::FIXED);
274269
}
270+
else
271+
{
272+
errors.emplace_back(UsdError(
273+
sdf::usd::UsdErrorCode::USD_TO_SDF_PARSING_ERROR,
274+
"Unable to create a SDF joint from USD prim [" +
275+
std::string(_prim.GetName()) +
276+
"] because the prim is not a USD joint."));
277+
}
278+
275279
return errors;
276280
}
277281
}

usd/src/usd_parser/USDJoints.hh

-1
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,6 @@ namespace sdf
4141
/// a joint
4242
///
4343
/// \param[in] _prim The USD prim that holds the USD joint
44-
/// \param[in] _path The path to _prim
4544
/// \param[in] _usdData Object that holds data about the USD stage
4645
/// \param[out] _joint SDF joint to return
4746
/// \return UsdErrors, which is a list of UsdError objects. An empty list

usd/src/usd_parser/USDJoints_TEST.cc

+4
Original file line numberDiff line numberDiff line change
@@ -59,13 +59,15 @@ TEST(USDJointTest, JointTest)
5959
upperJoint, usdData, joint1);
6060

6161
EXPECT_EQ(0u, errors.size());
62+
EXPECT_EQ(sdf::JointType::REVOLUTE, joint1.Type());
6263
EXPECT_EQ("upper_joint", joint1.Name());
6364
EXPECT_EQ("upper_link", joint1.ChildLinkName());
6465
EXPECT_EQ("base", joint1.ParentLinkName());
6566
EXPECT_EQ(ignition::math::Pose3d(0, 0, 0.021, -1.5708, 0, 0),
6667
joint1.RawPose());
6768

6869
auto axis = joint1.Axis(0);
70+
ASSERT_NE(nullptr, axis);
6971
EXPECT_EQ(ignition::math::Vector3d(1, 0, 0), axis->Xyz());
7072

7173
const auto lowerJoint = stage->GetPrimAtPath(pxr::SdfPath(
@@ -77,11 +79,13 @@ TEST(USDJointTest, JointTest)
7779
lowerJoint, usdData, joint2);
7880

7981
EXPECT_EQ(0u, errors.size());
82+
EXPECT_EQ(sdf::JointType::REVOLUTE, joint2.Type());
8083
EXPECT_EQ("lower_joint", joint2.Name());
8184
EXPECT_EQ("lower_link", joint2.ChildLinkName());
8285
EXPECT_EQ("upper_link", joint2.ParentLinkName());
8386
EXPECT_EQ(ignition::math::Pose3d(0.0025, -0, 0.01, -0.4292, 0, 0),
8487
joint2.RawPose());
8588
axis = joint2.Axis(0);
89+
ASSERT_NE(nullptr, axis);
8690
EXPECT_EQ(ignition::math::Vector3d(1, 0, 0), axis->Xyz());
8791
}

usd/src/usd_parser/USDLinks_TEST.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -70,11 +70,11 @@ TEST(USDLinksTest, LinksNameMassAndDiagonalMoments)
7070
ASSERT_NE(nullptr, visual);
7171
auto geom = visual->Geom();
7272
ASSERT_NE(nullptr, geom);
73+
EXPECT_EQ(_type, geom->Type());
7374
auto collision = _link.CollisionByIndex(0);
7475
ASSERT_NE(nullptr, collision);
7576
auto geomCol = collision->Geom();
7677
ASSERT_NE(nullptr, geomCol);
77-
EXPECT_EQ(_type, geom->Type());
7878
}
7979
};
8080

usd/src/usd_parser/USDWorld.cc

+4-5
Original file line numberDiff line numberDiff line change
@@ -203,16 +203,15 @@ namespace usd
203203

204204
if (prim.IsA<pxr::UsdPhysicsJoint>())
205205
{
206-
sdf::Joint joint;
207-
modelPtr = _world.ModelByName(currentModelName);
208206
if (!modelPtr)
209207
{
210208
errors.push_back(UsdError(UsdErrorCode::USD_TO_SDF_PARSING_ERROR,
211-
"Unable to find a sdf::Model named [" + currentModelName +
212-
"] in world named [" + _world.Name() +
213-
"], but a sdf::Model with this name should exist."));
209+
"Unable to parse joint corresponding to USD prim [" +
210+
std::string(prim.GetName()) +
211+
"] because the corresponding sdf::Model object wasn't found."));
214212
return errors;
215213
}
214+
sdf::Joint joint;
216215
auto errorsJoint = ParseJoints(prim, usdData, joint);
217216
if (!errorsJoint.empty())
218217
{

0 commit comments

Comments
 (0)