Skip to content

Commit 5e3605f

Browse files
adlarkinahcorde
andauthored
sdf -> usd converter: add joints (#837)
Signed-off-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com> Co-authored-by: ahcorde <ahcorde@gmail.com>
1 parent ec11f63 commit 5e3605f

File tree

9 files changed

+998
-2
lines changed

9 files changed

+998
-2
lines changed

test/integration/joint_dom.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -176,7 +176,7 @@ TEST(DOMJoint, LoadJointParentWorld)
176176
EXPECT_EQ(1u, model->LinkCount());
177177
EXPECT_NE(nullptr, model->LinkByIndex(0));
178178
EXPECT_EQ(nullptr, model->LinkByIndex(1));
179-
EXPECT_EQ(Pose(0, 0, 0, 0, 0, 0), model->RawPose());
179+
EXPECT_EQ(Pose(1, 0, 0, 0, 0, 0), model->RawPose());
180180
EXPECT_EQ("", model->PoseRelativeTo());
181181

182182
ASSERT_TRUE(model->LinkNameExists("link"));

test/sdf/ball_prismatic_joint.sdf

+28
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,28 @@
1+
<?xml version="1.0" ?>
2+
<sdf version="1.6">
3+
<model name="test">
4+
<link name="link1">
5+
</link>
6+
<link name="link2">
7+
</link>
8+
<link name="link3">
9+
</link>
10+
<link name="link4">
11+
</link>
12+
13+
<joint name="ball_joint" type="ball">
14+
<pose>0 1 0 0 0 0</pose>
15+
<child>link1</child>
16+
<parent>link2</parent>
17+
</joint>
18+
<joint name="prismatic_joint" type="prismatic">
19+
<pose>0 0 0 0 0 1</pose>
20+
<child>link3</child>
21+
<parent>link4</parent>
22+
<axis>
23+
<xyz>0 0 1</xyz>
24+
</axis>
25+
</joint>
26+
27+
</model>
28+
</sdf>

test/sdf/double_pendulum.sdf

+12
Original file line numberDiff line numberDiff line change
@@ -197,6 +197,12 @@
197197
<child>upper_link</child>
198198
<axis>
199199
<xyz>1.0 0 0</xyz>
200+
<dynamics>
201+
<damping>35</damping>
202+
</dynamics>
203+
<limit>
204+
<stiffness>350</stiffness>
205+
</limit>
200206
</axis>
201207
</joint>
202208
<!-- pin joint for lower link, at origin of child link -->
@@ -205,6 +211,12 @@
205211
<child>lower_link</child>
206212
<axis>
207213
<xyz>1.0 0 0</xyz>
214+
<dynamics>
215+
<damping>35</damping>
216+
</dynamics>
217+
<limit>
218+
<stiffness>350</stiffness>
219+
</limit>
208220
</axis>
209221
</joint>
210222
</model>

test/sdf/joint_parent_world.sdf

+1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
<?xml version="1.0" ?>
22
<sdf version="1.6">
33
<model name="joint_parent_world">
4+
<pose>1 0 0 0 0 0</pose>
45
<link name="link">
56
<pose>0 0 1 0 0 0</pose>
67
</link>
+72
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
/*
2+
* Copyright (C) 2022 Open Source Robotics Foundation
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*
16+
*/
17+
18+
#ifndef SDF_USD_SDF_PARSER_JOINT_HH_
19+
#define SDF_USD_SDF_PARSER_JOINT_HH_
20+
21+
#include <unordered_map>
22+
#include <string>
23+
24+
// TODO(ahcorde) this is to remove deprecated "warnings" in usd, these warnings
25+
// are reported using #pragma message so normal diagnostic flags cannot remove
26+
// them. This workaround requires this block to be used whenever usd is
27+
// included.
28+
#pragma push_macro ("__DEPRECATED")
29+
#undef __DEPRECATED
30+
#include <pxr/usd/sdf/path.h>
31+
#include <pxr/usd/usd/stage.h>
32+
#pragma pop_macro ("__DEPRECATED")
33+
34+
#include "sdf/Joint.hh"
35+
#include "sdf/Model.hh"
36+
#include "sdf/config.hh"
37+
#include "sdf/usd/Export.hh"
38+
#include "sdf/usd/UsdError.hh"
39+
40+
namespace sdf
41+
{
42+
// Inline bracke to help doxygen filtering.
43+
inline namespace SDF_VERSION_NAMESPACE {
44+
//
45+
namespace usd
46+
{
47+
/// \brief Parse a SDF joint into a USD stage.
48+
/// \param[in] _joint The SDF joint to parse.
49+
/// \param[in] _stage The stage that should contain the USD representation
50+
/// of _joint. This must be a valid, initialized stage.
51+
/// \param[in] _path The USD path of the parsed joint in _stage, which must
52+
/// be a valid USD path.
53+
/// \param[in] _parentModel The model that is the parent of _joint
54+
/// \param[in] _linkToUsdPath a map of a link's SDF name to the link's USD
55+
/// path. This is used to determine which USD prims should be assigned as
56+
/// the USD joint's relative links.
57+
/// \param[in] _worldPath The USD path of the world prim. This is needed if
58+
/// _joint's parent is the world.
59+
/// \return UsdErrors, which is a vector of UsdError objects. Each UsdError
60+
/// includes an error code and message. An empty vector indicates no errors
61+
/// occurred when parsing _joint to its USD representation.
62+
UsdErrors IGNITION_SDFORMAT_USD_VISIBLE ParseSdfJoint(
63+
const sdf::Joint &_joint,
64+
pxr::UsdStageRefPtr &_stage, const std::string &_path,
65+
const sdf::Model &_parentModel,
66+
const std::unordered_map<std::string, pxr::SdfPath> &_linkToUsdPath,
67+
const pxr::SdfPath &_worldPath);
68+
}
69+
}
70+
}
71+
72+
#endif

usd/src/CMakeLists.txt

+2
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
set(sources
22
UsdError.cc
33
sdf_parser/Geometry.cc
4+
sdf_parser/Joint.cc
45
sdf_parser/Light.cc
56
sdf_parser/Link.cc
67
sdf_parser/Model.cc
@@ -25,6 +26,7 @@ target_link_libraries(${usd_target}
2526
set(gtest_sources
2627
sdf_parser/sdf2usd_TEST.cc
2728
sdf_parser/Geometry_Sdf2Usd_TEST.cc
29+
sdf_parser/Joint_Sdf2Usd_TEST.cc
2830
sdf_parser/Light_Sdf2Usd_TEST.cc
2931
sdf_parser/Link_Sdf2Usd_TEST.cc
3032
# TODO(adlarkin) add a test for SDF -> USD models once model parsing

0 commit comments

Comments
 (0)