Skip to content

Commit 3a9b349

Browse files
committed
USD -> SDF: Parse Physics and generated SDF file
Signed-off-by: ahcorde <ahcorde@gmail.com>
1 parent 48c499b commit 3a9b349

File tree

12 files changed

+618
-2
lines changed

12 files changed

+618
-2
lines changed
+47
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,47 @@
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_USD_PARSER_PARSE_USD_HH
19+
#define SDF_USD_USD_PARSER_PARSE_USD_HH
20+
21+
#include <string>
22+
23+
#include "sdf/sdf_config.h"
24+
#include "sdf/system_util.hh"
25+
#include "sdf/usd/Export.hh"
26+
#include "sdf/usd/UsdError.hh"
27+
28+
namespace sdf
29+
{
30+
// Inline bracke to help doxygen filtering.
31+
inline namespace SDF_VERSION_NAMESPACE {
32+
//
33+
namespace usd
34+
{
35+
/// \brief It parses a USD file and it converted to SDF
36+
/// \param[in] _inputFilename Path of the USD file to parse
37+
/// \param[in] _outputFilename_sdf Path where the SDF file will be located
38+
/// \return UsdErrors, which is a vector of UsdError objects. Each UsdError
39+
/// includes an error code and message. An empty vector indicates no error
40+
/// occurred when parsing to its SDF representation.
41+
UsdErrors IGNITION_SDFORMAT_USD_VISIBLE parseUSDFile(
42+
const std::string &_inputFilename,
43+
const std::string &_outputFilename_sdf);
44+
}
45+
}
46+
}
47+
#endif

usd/src/CMakeLists.txt

+4
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,10 @@ set(sources
1010
sdf_parser/Sensor.cc
1111
sdf_parser/Visual.cc
1212
sdf_parser/World.cc
13+
usd_parser/ParseUSD.cc
14+
usd_parser/Physics.cc
15+
usd_parser/USD.cc
16+
usd_parser/USD2SDF.cc
1317
usd_parser/USDData.cc
1418
usd_parser/USDMaterial.cc
1519
usd_parser/USDStage.cc

usd/src/cmd/usd2sdf.cc

+3-2
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919

2020
#include <ignition/utils/cli/CLI.hpp>
2121

22+
#include "sdf/usd/usd_parser/ParseUSD.hh"
2223
#include "sdf/sdf.hh"
2324

2425
//////////////////////////////////////////////////
@@ -42,9 +43,9 @@ struct Options
4243
std::string outputFilename{"output.sdf"};
4344
};
4445

45-
void runCommand(const Options &/*_opt*/)
46+
void runCommand(const Options &_opt)
4647
{
47-
// TODO(ahcorde): Call here the USD to SDF conversor code
48+
sdf::usd::parseUSDFile(_opt.inputFilename, _opt.outputFilename);
4849
}
4950

5051
void addFlags(CLI::App &_app)

usd/src/usd_parser/ParseUSD.cc

+43
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,43 @@
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+
#include "sdf/usd/usd_parser/ParseUSD.hh"
19+
#include "USD2SDF.hh"
20+
21+
namespace sdf
22+
{
23+
inline namespace SDF_VERSION_NAMESPACE {
24+
namespace usd
25+
{
26+
UsdErrors parseUSDFile(
27+
const std::string &_inputFilename, const std::string &_outputFilename)
28+
{
29+
UsdErrors errors;
30+
USD2SDF usd2sdf;
31+
auto doc = tinyxml2::XMLDocument(true, tinyxml2::COLLAPSE_WHITESPACE);
32+
auto readErrors = usd2sdf.Read(_inputFilename, &doc);
33+
if (!readErrors.empty())
34+
{
35+
errors.insert(errors.end(), readErrors.begin(), readErrors.end());
36+
return errors;
37+
}
38+
doc.SaveFile(_outputFilename.c_str());
39+
return errors;
40+
}
41+
}
42+
}
43+
}

usd/src/usd_parser/Physics.cc

+49
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
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+
#include "Physics.hh"
19+
20+
#pragma push_macro ("__DEPRECATED")
21+
#undef __DEPRECATED
22+
#include <pxr/base/gf/vec3d.h>
23+
#include <pxr/usd/usdPhysics/scene.h>
24+
#pragma pop_macro ("__DEPRECATED")
25+
26+
#include "sdf/Console.hh"
27+
28+
namespace sdf
29+
{
30+
inline namespace SDF_VERSION_NAMESPACE {
31+
namespace usd
32+
{
33+
void ParsePhysicsScene(
34+
const pxr::UsdPrim &_prim,
35+
std::shared_ptr<WorldInterface> &_world,
36+
double _metersPerUnit)
37+
{
38+
auto variant_physics_scene = pxr::UsdPhysicsScene(_prim);
39+
pxr::GfVec3f gravity;
40+
variant_physics_scene.GetGravityDirectionAttr().Get(&gravity);
41+
_world->gravity[0] = gravity[0];
42+
_world->gravity[1] = gravity[1];
43+
_world->gravity[2] = gravity[2];
44+
variant_physics_scene.GetGravityMagnitudeAttr().Get(&_world->magnitude);
45+
_world->magnitude *= _metersPerUnit;
46+
}
47+
}
48+
}
49+
}

usd/src/usd_parser/Physics.hh

+49
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
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 USD_PARSER_PHYSYCS_HH
19+
#define USD_PARSER_PHYSYCS_HH
20+
21+
#include "usd_model/WorldInterface.hh"
22+
23+
#pragma push_macro ("__DEPRECATED")
24+
#undef __DEPRECATED
25+
#include <pxr/usd/usd/primRange.h>
26+
#pragma pop_macro ("__DEPRECATED")
27+
28+
#include <sdf/sdf_config.h>
29+
30+
namespace sdf
31+
{
32+
// Inline bracke to help doxygen filtering.
33+
inline namespace SDF_VERSION_NAMESPACE {
34+
//
35+
namespace usd
36+
{
37+
/// \brief It parses the physics attributes of the USD file
38+
/// \param[in] _prim Prim to extract the physics attributes
39+
/// \param[out] _world World interface where the data is placed
40+
/// \param[in] _metersPerUnit meter per unit in the USD
41+
void ParsePhysicsScene(
42+
const pxr::UsdPrim &_prim,
43+
std::shared_ptr<WorldInterface> &_world,
44+
double _metersPerUnit);
45+
}
46+
}
47+
}
48+
49+
#endif

usd/src/usd_parser/USD.cc

+71
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,71 @@
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+
#include "USD.hh"
18+
19+
#include "sdf/usd/usd_parser/USDData.hh"
20+
#include "sdf/usd/usd_parser/USDStage.hh"
21+
#include "Physics.hh"
22+
23+
#pragma push_macro ("__DEPRECATED")
24+
#undef __DEPRECATED
25+
#include <pxr/usd/usdPhysics/scene.h>
26+
#pragma pop_macro ("__DEPRECATED")
27+
28+
#include <string>
29+
30+
namespace sdf
31+
{
32+
inline namespace SDF_VERSION_NAMESPACE {
33+
namespace usd
34+
{
35+
UsdErrors parseUSDWorld(
36+
const std::string &_inputFilename,
37+
std::shared_ptr<WorldInterface> &_world)
38+
{
39+
UsdErrors errors;
40+
USDData usdData(_inputFilename);
41+
usdData.Init();
42+
usdData.ParseMaterials();
43+
44+
auto referencee = pxr::UsdStage::Open(_inputFilename);
45+
if (!referencee)
46+
{
47+
errors.emplace_back(UsdError(
48+
UsdErrorCode::INVALID_USD_FILE,
49+
"Unable to open [" + _inputFilename + "]"));
50+
return errors;
51+
}
52+
auto range = pxr::UsdPrimRange::Stage(referencee);
53+
54+
_world->_worldName = referencee->GetDefaultPrim().GetName().GetText();
55+
56+
for (auto const &prim : range)
57+
{
58+
if (prim.IsA<pxr::UsdPhysicsScene>())
59+
{
60+
std::pair<std::string, std::shared_ptr<USDStage>> data =
61+
usdData.FindStage(prim.GetPath().GetName());
62+
63+
ParsePhysicsScene(prim, _world, data.second->MetersPerUnit());
64+
continue;
65+
}
66+
}
67+
return errors;
68+
}
69+
}
70+
}
71+
}

usd/src/usd_parser/USD.hh

+47
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,47 @@
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 USD_PARSER_USD_HH
19+
#define USD_PARSER_USD_HH
20+
21+
#include <string>
22+
23+
#include "sdf/sdf_config.h"
24+
#include "sdf/usd/UsdError.hh"
25+
26+
#include "usd_model/WorldInterface.hh"
27+
28+
namespace sdf
29+
{
30+
// Inline bracke to help doxygen filtering.
31+
inline namespace SDF_VERSION_NAMESPACE {
32+
//
33+
namespace usd
34+
{
35+
/// \brief it parses the USD file
36+
/// \param[in] _inputFilename Path where the USD is located
37+
/// \param[out] _world World interface where all USD data is placed
38+
/// \return UsdErrors, which is a vector of UsdError objects. Each UsdError
39+
/// includes an error code and message. An empty vector indicates no error
40+
/// occurred when parsing to its SDF representation.
41+
UsdErrors parseUSDWorld(
42+
const std::string &_inputFilename,
43+
std::shared_ptr<WorldInterface> &_world);
44+
}
45+
}
46+
}
47+
#endif

0 commit comments

Comments
 (0)