Skip to content

Commit

Permalink
Added feedback
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde committed Sep 17, 2024
1 parent 4944fee commit 99d990c
Show file tree
Hide file tree
Showing 12 changed files with 21 additions and 21 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/pr-collection-labeler.yml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,6 @@ jobs:
steps:
- name: Add collection labels
if: github.event.action == 'opened'
uses: ignition-tooling/pr-collection-labeler@v1
uses: gazebo-tooling/pr-collection-labeler@v1
with:
github-token: ${{ secrets.GITHUB_TOKEN }}
8 changes: 4 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,13 +8,13 @@ project(gz_usd0 VERSION 0.0.1)
if("$ENV{GZ_VERSION}" STREQUAL "harmonic")
find_package(gz-cmake3 REQUIRED)
#--------------------------------------
# Find ignition-common
# Find gz-common
gz_find_package(gz-common5 REQUIRED COMPONENTS graphics)
set(GZ_COMMON_VER ${gz-common5_VERSION_MAJOR})
set(GZ_COMMON_LIB gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER})
set(GZ_COMMON_GRAPHICS_LIB gz-common${GZ_COMMON_VER}::graphics)
#--------------------------------------
# Find ignition-utils
# Find gz-utils
gz_find_package(gz-utils2 REQUIRED COMPONENTS cli)
set(GZ_UTILS_VER ${gz-utils2_VERSION_MAJOR})
set(GZ_UTILS_LIB gz-utils${GZ_UTILS_VER}::gz-utils${GZ_UTILS_VER})
Expand All @@ -24,13 +24,13 @@ if("$ENV{GZ_VERSION}" STREQUAL "harmonic")
else()
find_package(gz-cmake4 REQUIRED)
#--------------------------------------
# Find ignition-common
# Find gz-common
gz_find_package(gz-common6 REQUIRED COMPONENTS graphics)
set(GZ_COMMON_VER ${gz-common6_VERSION_MAJOR})
set(GZ_COMMON_LIB gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER})
set(GZ_COMMON_GRAPHICS_LIB gz-common${GZ_COMMON_VER}::graphics)
#--------------------------------------
# Find ignition-utils
# Find gz-utils
gz_find_package(gz-utils3 REQUIRED COMPONENTS cli)
set(GZ_UTILS_VER ${gz-utils3_VERSION_MAJOR})
set(GZ_UTILS_LIB gz-utils${GZ_UTILS_VER}::gz-utils${GZ_UTILS_VER})
Expand Down
8 changes: 4 additions & 4 deletions src/Conversions.hh
Original file line number Diff line number Diff line change
Expand Up @@ -34,16 +34,16 @@ namespace gz
//
namespace usd
{
/// \brief Specialized conversion from an Ignition Common Material
/// \brief Specialized conversion from an Gazebo Common Material
/// to a SDF material
/// \param[in] _in Ignition Common Material.
/// \param[in] _in Gazebo Common Material.
/// \return SDF material.
sdf::Material GZ_USD_VISIBLE convert(const gz::common::Material *_in);

/// \brief Specialized conversion from an SDF material to a Ignition Common
/// \brief Specialized conversion from an SDF material to a Gazebo Common
/// material.
/// \param[in] _in SDF material.
/// \param[out] _out The Ignition Common Material.
/// \param[out] _out The Gazebo Common Material.
void GZ_USD_VISIBLE
convert(const sdf::Material &_in, gz::common::Material &_out);
}
Expand Down
6 changes: 3 additions & 3 deletions src/cmd/sdf2usd.cc
Original file line number Diff line number Diff line change
Expand Up @@ -178,11 +178,11 @@ std::string FindResources(const std::string &_uri)
const std::string type = gz::common::lowercase(tokens[3]);
const std::string modelName = gz::common::lowercase(tokens[4]);
path = gz::common::joinPaths(
home, ".ignition", "fuel", server, owner, type, modelName);
home, ".gz", "fuel", server, owner, type, modelName);
}
else
{
path = gz::common::joinPaths(home, ".ignition", "fuel");
path = gz::common::joinPaths(home, ".gz", "fuel");
}

auto fileName = gz::common::basename(uri.Path().Str());
Expand Down Expand Up @@ -211,7 +211,7 @@ std::string FindResourceUri(const gz::common::URI &_uri)

void runCommand(const Options &_opt)
{
// Configure SDF to fetch assets from ignition fuel.
// Configure SDF to fetch assets from Gazebo fuel.
sdf::setFindCallback(std::bind(&FindResources, std::placeholders::_1));
gz::common::addFindFileURICallback(
std::bind(&FindResourceUri, std::placeholders::_1));
Expand Down
2 changes: 1 addition & 1 deletion src/sdf_parser/Geometry.cc
Original file line number Diff line number Diff line change
Expand Up @@ -398,7 +398,7 @@ namespace usd

// TODO(adlarkin) update this call in sdf13 to avoid casting the index to
// an int:
// https://github.com/ignitionrobotics/ign-common/pull/319
// https://github.com/gazebosim/gz-common/pull/319
int materialIndex = subMesh->GetMaterialIndex().value();
if (materialIndex != -1)
{
Expand Down
2 changes: 1 addition & 1 deletion src/sdf_parser/Joint.cc
Original file line number Diff line number Diff line change
Expand Up @@ -357,7 +357,7 @@ namespace usd
// range, SDF does not have limits for a ball joint. So, there's
// nothing to do after creating a UsdPhysicsSphericalJoint, since this
// joint by default has no limits (i.e., allows for circular motion)
// related issue https://github.com/ignitionrobotics/sdformat/issues/860
// related issue https://github.com/gazebosim/sdformat/issues/860
pxr::UsdPhysicsSphericalJoint::Define(_stage, pxr::SdfPath(_path));
break;
case sdf::JointType::FIXED:
Expand Down
2 changes: 1 addition & 1 deletion src/sdf_parser/Sensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ namespace usd
else
{
// The default value in USD is 50, but something more
// similar to ignition Gazebo is 40.
// similar to Gazebo is 40.
usdCamera.CreateFocalLengthAttr().Set(
static_cast<float>(40.0f));
}
Expand Down
2 changes: 1 addition & 1 deletion src/usd_parser/USDLinks.cc
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ void GetInertial(

// TODO(ahcorde) Figure out how to use PrincipalMoments and
// PrincipalAxesOffset: see
// https://github.com/ignitionrobotics/sdformat/pull/902#discussion_r840905534
// https://github.com/gazebosim/sdformat/pull/902#discussion_r840905534
massMatrix.SetDiagonalMoments(
math::Vector3d(
diagonalInertia[0],
Expand Down
2 changes: 1 addition & 1 deletion src/usd_parser/USDSensors.cc
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ namespace gz
camera.SetName(_prim.GetPath().GetName());
camera.SetHorizontalFov(20.955);
camera.SetLensFocalLength(focalLength);
// Camera is Y up axis, rotate the camera to match with Ignition
// Camera is Y up axis, rotate the camera to match with Gazebo
math::Pose3d poseCamera(0, 0, 0, GZ_PI_2, 0, -GZ_PI_2);
sensor.SetRawPose(pose * poseCamera.Inverse());
camera.SetNearClip(clippingRange[0]);
Expand Down
2 changes: 1 addition & 1 deletion src/usd_parser/USDTransforms.cc
Original file line number Diff line number Diff line change
Expand Up @@ -256,7 +256,7 @@ UDSTransforms ParseUSDTransform(const pxr::UsdPrim &_prim)

// TODO(ahcorde) This part should be reviewed, revisit how rotateXYZ
// and rotateZYX are handle.
// Related issue https://github.com/ignitionrobotics/sdformat/issues/926
// Related issue https://github.com/gazebosim/sdformat/issues/926
// if (op == kXFormOpRotateZYX)
// {
// std::swap(angleX, angleZ);
Expand Down
4 changes: 2 additions & 2 deletions src/usd_parser/USDWorld.cc
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@ namespace usd
// This conversion might only work with Issac Sim USDs
// TODO(adlarkin) find a better way to get root model prims/parent prims
// of lights attached to the stage: see
// https://github.com/ignitionrobotics/sdformat/issues/927
// https://github.com/gazebosim/sdformat/issues/927
if (primPathTokens.size() >= 2)
{
bool shortName = false;
Expand Down Expand Up @@ -411,7 +411,7 @@ namespace usd

if (_useGazeboPlugins)
{
// Add some plugins to run the Ignition Gazebo simulation
// Add some plugins to run the Gazebo simulation
sdf::Plugin physicsPlugin;
physicsPlugin.SetName("gz::sim::systems::Physics");
physicsPlugin.SetFilename("gz-sim-physics-system");
Expand Down
2 changes: 1 addition & 1 deletion test/test_config.h.in
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#define GZ_CONFIG_PATH "@CMAKE_BINARY_DIR@/test/conf"
#define GZ_PATH "@GZ_PATH@"
#define GZ_TEST_LIBRARY_PATH "${PROJECT_BINARY_DIR}/src:"\
"@IGNITION-MSGS_LIBRARY_DIRS@:"
"@GZ-MSGS_LIBRARY_DIRS@:"
#define PROJECT_SOURCE_PATH "${PROJECT_SOURCE_DIR}"
#define PROJECT_BINARY_DIR "${CMAKE_BINARY_DIR}"
#define GZ_USD_TMP_DIR "tmp-gz-usd/"
Expand Down

0 comments on commit 99d990c

Please sign in to comment.