Skip to content

Commit

Permalink
Migrate ign to gz (#105)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <[email protected]>
  • Loading branch information
ahcorde authored Jul 16, 2022
1 parent fd5dec3 commit 01d2105
Show file tree
Hide file tree
Showing 32 changed files with 62 additions and 62 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ jobs:
sudo /tmp/gzdev/gzdev.py repository enable osrf stable
sudo /tmp/gzdev/gzdev.py repository enable osrf nightly
sudo apt-get update
sudo apt-get install -y libsdformat13-dev python3-ignition-math7 python3-sdformat13
sudo apt-get install -y libsdformat13-dev python3-gz-math7 python3-sdformat13
- name: Install test dependencies
run: python3 -m pip install -U tox
- name: Test sdformat_mjcf
Expand Down
2 changes: 1 addition & 1 deletion sdformat_mjcf/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ pip install -U pip
pip install dm-control
```

Install `python3-ignition-math7` and `python3-sdformat13` from the
Install `python3-gz-math7` and `python3-sdformat13` from the
[nightly](https://gazebosim.org/docs/all/release#type-of-releases) repo.

Install the `sdformat-mjcf` package
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
"""Module to convert MJCF geoms to SDFormat Collision/Visual geometries"""

import os
from ignition.math import Vector2d, Vector3d
from gz.math import Vector2d, Vector3d

import sdformat as sdf
import sdformat_mjcf.utils.sdf_utils as su
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from ignition.math import Vector3d
from gz.math import Vector3d
import logging
import math
import sdformat as sdf
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from ignition.math import Angle, Color, Pose3d, Quaterniond, Vector3d
from gz.math import Angle, Color, Pose3d, Quaterniond, Vector3d

import math

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from ignition.math import (Inertiald, MassMatrix3d, Vector3d, Pose3d,
Quaterniond)
from gz.math import (Inertiald, MassMatrix3d, Vector3d, Pose3d,
Quaterniond)

from sdformat_mjcf.mjcf_to_sdformat.converters.geometry import (
mjcf_visual_to_sdf,
Expand Down Expand Up @@ -129,7 +129,7 @@ def get_orientation(geom):
:param mjcf.Element geom: MJCF geom to extract the orientation
:return: The newly created quaterion.
:rtype ignition.math.Quateriond
:rtype gz.math.Quateriond
"""
if geom.fromto is not None:
v1 = Vector3d(geom.fromto[0], geom.fromto[1], geom.fromto[2])
Expand All @@ -148,7 +148,7 @@ def get_position(geom):
:param mjcf.Element geom: MJCF geom to extract the position
:return: The newly created Vector3d.
:rtype ignition.math.Vector3d
:rtype gz.math.Vector3d
"""
if geom.fromto is not None:
v1 = Vector3d(geom.fromto[0], geom.fromto[1], geom.fromto[2])
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from ignition.math import Quaterniond, Vector3d, Pose3d
from gz.math import Quaterniond, Vector3d, Pose3d

import logging

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from ignition.math import Vector3d, MassMatrix3d, Inertiald
from gz.math import Vector3d, MassMatrix3d, Inertiald

from sdformat_mjcf.mjcf_to_sdformat.converters.joint import (mjcf_joint_to_sdf,
add_fixed_joint)
Expand Down Expand Up @@ -189,19 +189,19 @@ def _get_model_from_sensor(sensor):

if export_world_plugins:
plugins = {
"ignition-gazebo-physics-system":
"gz-gazebo-physics-system":
"gz::sim::systems::Physics",
"ignition-gazebo-sensors-system":
"gz-gazebo-sensors-system":
"gz::sim::systems::Sensors",
"ignition-gazebo-user-commands-system":
"gz-gazebo-user-commands-system":
"gz::sim::systems::UserCommands",
"ignition-gazebo-scene-broadcaster-system":
"gz-gazebo-scene-broadcaster-system":
"gz::sim::systems::SceneBroadcaster",
"ignition-gazebo-forcetorque-system":
"gz-gazebo-forcetorque-system":
"gz::sim::systems::ForceTorque",
"ignition-gazebo-altimeter-system":
"gz-gazebo-altimeter-system":
"gz::sim::systems::Altimeter",
"ignition-gazebo-imu-system":
"gz-gazebo-imu-system":
"gz::sim::systems::Imu"
}
for [key, value] in plugins.items():
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
import math

import sdformat as sdf
from ignition.math import Pose3d
from gz.math import Pose3d

from sdformat_mjcf.sdformat_to_mjcf.converters.sensor import add_sensor
from sdformat_mjcf.sdformat_to_mjcf.sdf_kinematics import (
Expand All @@ -40,7 +40,7 @@ def _compute_joint_axis(joint_axis, joint_pose):
joint.
:param sdformat.JointAxis: The input joint axis
:param ignition.math.Pose3d joint_pose: The pose of the joint that contains
:param gz.math.Pose3d joint_pose: The pose of the joint that contains
the joint axis.
:param axis_xyz_resolver: Function to resolve the unit vector a joint axis.
:return: The computed axis unit vector.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ def add_link(body, link, parent_name="world", link_pose=None):
:param mjcf.Element body: The MJCF body to which the body is added.
:param sdformat.Link link: The SDFormat link to be converted.
:param str parent_name: Name of parent link.
:param ignition.math.Pose3d link_pose: Pose of link. This is optional and
:param gz.math.Pose3d link_pose: Pose of link. This is optional and
if set to None, the pose will be resolved from the link.
:return: The newly created MJCF body.
:rtype: mjcf.Element
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

"""Module to convert SDFormat MAterials to MJCF"""

from ignition.math import clamp
from gz.math import clamp

from sdformat import Pbr, PbrWorkflow, Material # noqa: F401
import sdformat as sdf
Expand Down
26 changes: 13 additions & 13 deletions sdformat_mjcf/src/sdformat_mjcf/utils/sdf_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,14 +16,14 @@

import logging
import math
from ignition.math import Color, Pose3d, Quaterniond, Vector3d, Matrix3d
from gz.math import Color, Pose3d, Quaterniond, Vector3d, Matrix3d

NAME_DELIMITER = '_'


def vec3d_to_list(vec):
"""Convert a Vector3d object to a list.
:param ignition.math.Vector3d vec: Vector3d object to be converted
:param gz.math.Vector3d vec: Vector3d object to be converted
:return: List of values of the x, y, and z components of `vec`
respectively.
:rtype: list[float]
Expand All @@ -36,15 +36,15 @@ def list_to_vec3d(list):
:param List of values of the x, y, and z components of `vec`
respectively.
:return: Vector3d object
:rtype: ignition.math.Vector3d
:rtype: gz.math.Vector3d
"""
return Vector3d(list[0], list[1], list[2])


def get_rotation(element):
"""Get the angles from a MJCF element
:param mjcf.Element element: Element to extract the angles
:rtype: ignition.math.Quateriond
:rtype: gz.math.Quateriond
"""
angle_type = "degree"
if element.root.compiler.angle is not None:
Expand Down Expand Up @@ -93,7 +93,7 @@ def get_rotation(element):
def vec2d_to_list(vec):
"""
Convert a Vector2d object to a list.
:param ignition.math.Vector2d vec: Vector2d object to be converted.
:param gz.math.Vector2d vec: Vector2d object to be converted.
:return: List of values of the x, and y components of `vec` respectively.
:rtype: list[float]
"""
Expand All @@ -106,15 +106,15 @@ def euler_list_to_quat(list):
:param List of values of the roll, pitch, and yaw components of `vec`
respectively.
:return: The newly created Quaterniond
:rtype: ignition.math.Quaterniond
:rtype: gz.math.Quaterniond
"""
return Quaterniond(Vector3d(list[0], list[1], list[2]))


def quat_to_list(quat):
"""
Convert a Quaterniond object to a list in the order expected by MJCF.
:param ignition.math.Quaterniond quat: Quaterniond object to be converted.
:param gz.math.Quaterniond quat: Quaterniond object to be converted.
:return: List of values of the quaternion in wxyz order.
:rtype: list[float]
"""
Expand All @@ -124,7 +124,7 @@ def quat_to_list(quat):
def quat_to_euler_list(quat):
"""
Convert a Quaterniond object to a list of Euler angles in degrees.
:param ignition.math.Quaterniond quat: Quaterniond object to be converted.
:param gz.math.Quaterniond quat: Quaterniond object to be converted.
:return: List of values of the euler angles.
:rtype: list[float]
"""
Expand All @@ -143,10 +143,10 @@ def wxyz_list_to_quat(quat):

def rgba_to_color(rgba):
"""
Convert a MJCF rgba color list to a ignition math Color
Convert a MJCF rgba color list to a gz math Color
:param list rgba: List of color (red, green, blue, alpha).
:return: The newly created color
:rtype: ignition.math.color
:rtype: gz.math.color
"""
return Color(rgba[0], rgba[1], rgba[2], rgba[3])

Expand All @@ -156,7 +156,7 @@ def get_pose_from_mjcf(element):
Get the pose from a MJCF element
:param mjcf.Element element: MJCF element to get the pose
:return: The newly created Pose3d
:rtype: ignition.math.Pose3d
:rtype: gz.math.Pose3d
"""
pos = [0, 0, 0]
quat = Quaterniond()
Expand Down Expand Up @@ -275,7 +275,7 @@ def resolve_pose(self, sem_pose, relative_to=None):
:param str relative_to: (Optional) The frame relative to which the pose
is resolved.
:return: The resolved pose.
:rtype: ignition.math.Pose3d
:rtype: gz.math.Pose3d
:raises SDFErrorsException: if an error is encountered when resolving
the pose.
"""
Expand All @@ -290,7 +290,7 @@ def resolve_axis_xyz(self, joint_axis):
:param sdformat.JointAxis joint_axis: The JointAxis object to be
resolved.
:return: The resolved xyz vector.
:rtype: ignition.math.Vector3d
:rtype: gz.math.Vector3d
:raises SDFErrorsException: if an error is encountered when resolving
the vector.
"""
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
from numpy.testing import assert_allclose

import sdformat as sdf
from ignition.math import Vector3d
from gz.math import Vector3d
from dm_control import mjcf

from sdformat_mjcf.mjcf_to_sdformat.converters import geometry as geometry_conv
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

from dm_control import mjcf

from ignition.math import Color, Vector3d
from gz.math import Color, Vector3d

import sdformat as sdf

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
import math
from math import pi

from ignition.math import Color, Vector3d, Pose3d
from gz.math import Color, Vector3d, Pose3d

import sdformat as sdf

Expand Down
2 changes: 1 addition & 1 deletion sdformat_mjcf/tests/mjcf_to_sdformat/test_defaults.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
)

import sdformat as sdf
from ignition.math import Vector3d, Color
from gz.math import Vector3d, Color

from tests.helpers import get_resources_dir

Expand Down
2 changes: 1 addition & 1 deletion sdformat_mjcf/tests/mjcf_to_sdformat/test_force_torque.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
import math
import unittest

from ignition.math import Vector3d
from gz.math import Vector3d

from dm_control import mjcf
from dm_control import mujoco
Expand Down
2 changes: 1 addition & 1 deletion sdformat_mjcf/tests/mjcf_to_sdformat/test_imu.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
import unittest
import math

from ignition.math import Vector3d
from gz.math import Vector3d

from dm_control import mjcf
from dm_control import mujoco
Expand Down
2 changes: 1 addition & 1 deletion sdformat_mjcf/tests/mjcf_to_sdformat/test_joints.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

import unittest

from ignition.math import Pose3d, Vector3d
from gz.math import Pose3d, Vector3d

from dm_control import mjcf
from dm_control import mujoco
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
import os
import unittest

from ignition.math import Color
from gz.math import Color

from dm_control import mjcf
from dm_control import mujoco
Expand Down
16 changes: 8 additions & 8 deletions sdformat_mjcf/tests/mjcf_to_sdformat/test_mjcf_sensor_to_sdf.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
from dm_control import mjcf
from dm_control import mujoco

from ignition.math import Vector3d
from gz.math import Vector3d

from sdformat_mjcf.mjcf_to_sdformat.converters import sensor as sensor_conv
from sdformat_mjcf.mjcf_to_sdformat.converters.world import (
Expand Down Expand Up @@ -87,31 +87,31 @@ def test_sensor_worldbody_to_sdf(self):
self.assertEqual(7, len(world.plugins()))
self.assertEqual("gz::sim::systems::Physics",
world.plugins()[0].name())
self.assertEqual("ignition-gazebo-physics-system",
self.assertEqual("gz-gazebo-physics-system",
world.plugins()[0].filename())
self.assertEqual("gz::sim::systems::Sensors",
world.plugins()[1].name())
self.assertEqual("ignition-gazebo-sensors-system",
self.assertEqual("gz-gazebo-sensors-system",
world.plugins()[1].filename())
self.assertEqual("gz::sim::systems::UserCommands",
world.plugins()[2].name())
self.assertEqual("ignition-gazebo-user-commands-system",
self.assertEqual("gz-gazebo-user-commands-system",
world.plugins()[2].filename())
self.assertEqual("gz::sim::systems::SceneBroadcaster",
world.plugins()[3].name())
self.assertEqual("ignition-gazebo-scene-broadcaster-system",
self.assertEqual("gz-gazebo-scene-broadcaster-system",
world.plugins()[3].filename())
self.assertEqual("gz::sim::systems::ForceTorque",
world.plugins()[4].name())
self.assertEqual("ignition-gazebo-forcetorque-system",
self.assertEqual("gz-gazebo-forcetorque-system",
world.plugins()[4].filename())
self.assertEqual("gz::sim::systems::Altimeter",
world.plugins()[5].name())
self.assertEqual("ignition-gazebo-altimeter-system",
self.assertEqual("gz-gazebo-altimeter-system",
world.plugins()[5].filename())
self.assertEqual("gz::sim::systems::Imu",
world.plugins()[6].name())
self.assertEqual("ignition-gazebo-imu-system",
self.assertEqual("gz-gazebo-imu-system",
world.plugins()[6].filename())

def test_sensor_non_root_body_site(self):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
from math import pi

import sdformat as sdf
from ignition.math import Vector3d
from gz.math import Vector3d

from sdformat_mjcf.mjcf_to_sdformat.mjcf_to_sdformat import (
mjcf_file_to_sdformat)
Expand Down
Loading

0 comments on commit 01d2105

Please sign in to comment.