[pre-commit.ci] auto fixes from pre-commit.com hooks
for more information, see https://pre-commit.ci
This commit is contained in:
parent
9b9456423c
commit
0019f1d54a
|
@ -1,9 +1,9 @@
|
|||
import sys
|
||||
from collections import defaultdict
|
||||
from typing import Literal
|
||||
|
||||
import numpy as np
|
||||
from bddl.object_taxonomy import ObjectTaxonomy
|
||||
from typing import Literal
|
||||
|
||||
import omnigibson as og
|
||||
import omnigibson.lazy as lazy
|
||||
|
@ -592,7 +592,9 @@ class StatefulObject(BaseObject):
|
|||
for _, obj_state in self._states.items():
|
||||
obj_state.clear_cache()
|
||||
|
||||
def set_position_orientation(self, position=None, orientation=None, frame: Literal["world", "parent", "scene"] = "world"):
|
||||
def set_position_orientation(
|
||||
self, position=None, orientation=None, frame: Literal["world", "parent", "scene"] = "world"
|
||||
):
|
||||
"""
|
||||
Set the position and orientation of stateful object.
|
||||
|
||||
|
|
|
@ -965,7 +965,9 @@ class EntityPrim(XFormPrim):
|
|||
"""
|
||||
return T.quat2mat(self.get_position_orientation()[1]).T @ self.get_angular_velocity()
|
||||
|
||||
def set_position_orientation(self, position=None, orientation=None, frame: Literal["world", "parent", "scene"] = "world"):
|
||||
def set_position_orientation(
|
||||
self, position=None, orientation=None, frame: Literal["world", "parent", "scene"] = "world"
|
||||
):
|
||||
"""
|
||||
Set the position and orientation of entry prim object.
|
||||
|
||||
|
@ -1034,14 +1036,16 @@ class EntityPrim(XFormPrim):
|
|||
if frame == "world" or frame == "scene":
|
||||
positions, orientations = self._articulation_view.get_world_poses()
|
||||
else:
|
||||
positions, orientations = self._articulation_view.get_local_poses()
|
||||
positions, orientations = self._articulation_view.get_local_poses()
|
||||
|
||||
position, orientation = positions[0], orientations[0][[1, 2, 3, 0]]
|
||||
|
||||
# If we are in a scene, compute the scene-local transform
|
||||
if frame == "scene":
|
||||
position, orientation = T.relative_pose_transform(position, orientation, *self.scene.prim.get_position_orientation())
|
||||
|
||||
position, orientation = T.relative_pose_transform(
|
||||
position, orientation, *self.scene.prim.get_position_orientation()
|
||||
)
|
||||
|
||||
return position, orientation
|
||||
|
||||
def set_local_pose(self, position=None, orientation=None, frame="parent"):
|
||||
|
@ -1049,8 +1053,8 @@ class EntityPrim(XFormPrim):
|
|||
import warnings
|
||||
|
||||
warnings.warn(
|
||||
"set_local_pose is deprecated and will be removed in a future release. Use set_position_orientation(position=position, orientation=orientation, frame=\"parent\") instead",
|
||||
DeprecationWarning
|
||||
'set_local_pose is deprecated and will be removed in a future release. Use set_position_orientation(position=position, orientation=orientation, frame="parent") instead',
|
||||
DeprecationWarning,
|
||||
)
|
||||
return self.set_position_orientation(position=position, orientation=orientation, frame="parent")
|
||||
|
||||
|
@ -1059,8 +1063,8 @@ class EntityPrim(XFormPrim):
|
|||
import warnings
|
||||
|
||||
warnings.warn(
|
||||
"get_local_pose is deprecated and will be removed in a future release. Use get_position_orientation(frame=\"parent\") instead",
|
||||
DeprecationWarning
|
||||
'get_local_pose is deprecated and will be removed in a future release. Use get_position_orientation(frame="parent") instead',
|
||||
DeprecationWarning,
|
||||
)
|
||||
return self.get_position_orientation(frame="parent")
|
||||
|
||||
|
|
|
@ -307,7 +307,9 @@ class RigidPrim(XFormPrim):
|
|||
"""
|
||||
return self._rigid_prim_view.get_angular_velocities()[0]
|
||||
|
||||
def set_position_orientation(self, position=None, orientation=None, frame: Literal["world", "parent", "scene"] = "world"):
|
||||
def set_position_orientation(
|
||||
self, position=None, orientation=None, frame: Literal["world", "parent", "scene"] = "world"
|
||||
):
|
||||
"""
|
||||
Set the position and orientation of XForm Prim.
|
||||
|
||||
|
@ -394,7 +396,9 @@ class RigidPrim(XFormPrim):
|
|||
|
||||
# If we are in a scene, compute the scene-local transform
|
||||
if frame == "scene":
|
||||
position, orientation = T.relative_pose_transform(position, orientation, *self.scene.prim.get_position_orientation())
|
||||
position, orientation = T.relative_pose_transform(
|
||||
position, orientation, *self.scene.prim.get_position_orientation()
|
||||
)
|
||||
|
||||
return position, orientation
|
||||
|
||||
|
@ -403,7 +407,7 @@ class RigidPrim(XFormPrim):
|
|||
import warnings
|
||||
|
||||
warnings.warn(
|
||||
"set_local_pose is deprecated and will be removed in a future release. Use set_position_orientation(position=position, orientation=orientation, frame=\"parent\") instead",
|
||||
'set_local_pose is deprecated and will be removed in a future release. Use set_position_orientation(position=position, orientation=orientation, frame="parent") instead',
|
||||
DeprecationWarning,
|
||||
)
|
||||
return self.set_position_orientation(position=position, orientation=orientation, frame="parent")
|
||||
|
@ -413,7 +417,7 @@ class RigidPrim(XFormPrim):
|
|||
import warnings
|
||||
|
||||
warnings.warn(
|
||||
"get_local_pose is deprecated and will be removed in a future release. Use get_position_orientation(frame=\"parent\") instead",
|
||||
'get_local_pose is deprecated and will be removed in a future release. Use get_position_orientation(frame="parent") instead',
|
||||
DeprecationWarning,
|
||||
)
|
||||
return self.get_position_orientation(frame="parent")
|
||||
|
|
|
@ -170,7 +170,9 @@ class XFormPrim(BasePrim):
|
|||
material_path = self._binding_api.GetDirectBinding().GetMaterialPath().pathString
|
||||
return material_path != ""
|
||||
|
||||
def set_position_orientation(self, position=None, orientation=None, frame: Literal["world", "parent", "scene"] = "world"):
|
||||
def set_position_orientation(
|
||||
self, position=None, orientation=None, frame: Literal["world", "parent", "scene"] = "world"
|
||||
):
|
||||
"""
|
||||
Sets prim's pose with respect to the specified frame
|
||||
|
||||
|
@ -191,7 +193,9 @@ class XFormPrim(BasePrim):
|
|||
|
||||
# If we are in a scene, compute the scene-local transform before setting the pose
|
||||
if frame == "scene" and self.scene is None:
|
||||
position, orientation = T.pose_transform(*self.scene.prim.get_position_orientation(), position, orientation)
|
||||
position, orientation = T.pose_transform(
|
||||
*self.scene.prim.get_position_orientation(), position, orientation
|
||||
)
|
||||
|
||||
assert np.isclose(
|
||||
np.linalg.norm(orientation), 1, atol=1e-3
|
||||
|
@ -267,10 +271,12 @@ class XFormPrim(BasePrim):
|
|||
# If we are in a scene, compute the scene-local transform (and save this as the world transform
|
||||
# for legacy compatibility)
|
||||
if frame == "scene" and self.scene is not None:
|
||||
position, orientation = T.relative_pose_transform(position, orientation, *self.scene.prim.get_position_orientation())
|
||||
position, orientation = T.relative_pose_transform(
|
||||
position, orientation, *self.scene.prim.get_position_orientation()
|
||||
)
|
||||
|
||||
return position, orientation
|
||||
|
||||
|
||||
# ------------------- Deprecated methods -------------------
|
||||
|
||||
def set_position(self, position):
|
||||
|
@ -284,8 +290,8 @@ class XFormPrim(BasePrim):
|
|||
import warnings
|
||||
|
||||
warnings.warn(
|
||||
"set_position is deprecated and will be removed in a future release. Use set_position_orientation(position=position) instead",
|
||||
DeprecationWarning
|
||||
"set_position is deprecated and will be removed in a future release. Use set_position_orientation(position=position) instead",
|
||||
DeprecationWarning,
|
||||
)
|
||||
return self.set_position_orientation(position=position)
|
||||
|
||||
|
@ -300,8 +306,8 @@ class XFormPrim(BasePrim):
|
|||
import warnings
|
||||
|
||||
warnings.warn(
|
||||
"get_position is deprecated and will be removed in a future release. Use get_position_orientation()[0] instead.",
|
||||
DeprecationWarning
|
||||
"get_position is deprecated and will be removed in a future release. Use get_position_orientation()[0] instead.",
|
||||
DeprecationWarning,
|
||||
)
|
||||
return self.get_position_orientation()[0]
|
||||
|
||||
|
@ -331,7 +337,10 @@ class XFormPrim(BasePrim):
|
|||
|
||||
import warnings
|
||||
|
||||
warnings.warn("get_orientation is deprecated and will be removed in a future release. Use get_position_orientation()[1] instead", DeprecationWarning)
|
||||
warnings.warn(
|
||||
"get_orientation is deprecated and will be removed in a future release. Use get_position_orientation()[1] instead",
|
||||
DeprecationWarning,
|
||||
)
|
||||
return self.get_position_orientation()[1]
|
||||
|
||||
def get_local_pose(self):
|
||||
|
@ -347,7 +356,7 @@ class XFormPrim(BasePrim):
|
|||
import warnings
|
||||
|
||||
warnings.warn(
|
||||
"get_local_pose is deprecated and will be removed in a future release. Use get_position_orientation(frame=\"parent\") instead",
|
||||
'get_local_pose is deprecated and will be removed in a future release. Use get_position_orientation(frame="parent") instead',
|
||||
DeprecationWarning,
|
||||
)
|
||||
|
||||
|
@ -367,7 +376,7 @@ class XFormPrim(BasePrim):
|
|||
import warnings
|
||||
|
||||
warnings.warn(
|
||||
"set_local_pose is deprecated and will be removed in a future release. Use set_position_orientation(position=position, orientation=orientation, frame=\"parent\") instead",
|
||||
'set_local_pose is deprecated and will be removed in a future release. Use set_position_orientation(position=position, orientation=orientation, frame="parent") instead',
|
||||
DeprecationWarning,
|
||||
)
|
||||
|
||||
|
@ -493,7 +502,7 @@ class XFormPrim(BasePrim):
|
|||
return dict(pos=pos, ori=ori)
|
||||
|
||||
def _load_state(self, state):
|
||||
|
||||
|
||||
pos, orn = np.array(state["pos"]), np.array(state["ori"])
|
||||
self.set_position_orientation(pos, orn, frame="scene")
|
||||
|
||||
|
|
|
@ -2,7 +2,7 @@ import itertools
|
|||
import os
|
||||
from abc import ABC
|
||||
from collections import OrderedDict
|
||||
from typing import Iterable, List, Tuple, Literal
|
||||
from typing import Iterable, List, Literal, Tuple
|
||||
|
||||
import numpy as np
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
@ -402,8 +402,9 @@ class BehaviorRobot(ManipulationRobot, LocomotionRobot, ActiveCameraRobot):
|
|||
|
||||
return self.base_footprint_link.get_position_orientation()
|
||||
|
||||
|
||||
def set_position_orientation(self, position=None, orientation=None, frame: Literal["world", "parent", "scene"] = "world"):
|
||||
def set_position_orientation(
|
||||
self, position=None, orientation=None, frame: Literal["world", "parent", "scene"] = "world"
|
||||
):
|
||||
"""
|
||||
Sets behavior robot's pose with respect to the specified frame
|
||||
|
||||
|
@ -418,7 +419,6 @@ class BehaviorRobot(ManipulationRobot, LocomotionRobot, ActiveCameraRobot):
|
|||
|
||||
super().set_position_orientation(position, orientation, frame=frame)
|
||||
|
||||
|
||||
# Move the joint frame for the world_base_joint
|
||||
if self._world_base_fixed_joint_prim is not None:
|
||||
if position is not None:
|
||||
|
@ -590,7 +590,9 @@ class BRPart(ABC):
|
|||
)
|
||||
return self.get_position_orientation(frame="parent")
|
||||
|
||||
def get_position_orientation(self, frame: Literal["world", "scene", "parent"] = "world") -> Tuple[Iterable[float], Iterable[float]]:
|
||||
def get_position_orientation(
|
||||
self, frame: Literal["world", "scene", "parent"] = "world"
|
||||
) -> Tuple[Iterable[float], Iterable[float]]:
|
||||
"""
|
||||
Gets robot's pose with respect to the specified frame.
|
||||
|
||||
|
@ -617,7 +619,9 @@ class BRPart(ABC):
|
|||
|
||||
return T.relative_pose_transform(*self.get_position_orientation(), *self.parent.get_position_orientation())
|
||||
|
||||
def set_position_orientation(self, pos: Iterable[float], orn: Iterable[float], frame: Literal["world", "parent", "scene"] = "world") -> None:
|
||||
def set_position_orientation(
|
||||
self, pos: Iterable[float], orn: Iterable[float], frame: Literal["world", "parent", "scene"] = "world"
|
||||
) -> None:
|
||||
"""
|
||||
Sets BRPart's pose with respect to the specified frame
|
||||
|
||||
|
|
|
@ -1,9 +1,9 @@
|
|||
from abc import abstractmethod
|
||||
from collections import namedtuple
|
||||
from typing import Literal
|
||||
|
||||
import networkx as nx
|
||||
import numpy as np
|
||||
from typing import Literal
|
||||
|
||||
import omnigibson as og
|
||||
import omnigibson.lazy as lazy
|
||||
|
@ -308,7 +308,9 @@ class ManipulationRobot(BaseRobot):
|
|||
|
||||
return contact_data, robot_contact_links
|
||||
|
||||
def set_position_orientation(self, position=None, orientation=None, frame: Literal["world", "parent", "scene"] = "world"):
|
||||
def set_position_orientation(
|
||||
self, position=None, orientation=None, frame: Literal["world", "parent", "scene"] = "world"
|
||||
):
|
||||
"""
|
||||
Sets manipulation robot's pose with respect to the specified frame
|
||||
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
import os
|
||||
from typing import Literal
|
||||
|
||||
import numpy as np
|
||||
from typing import Literal
|
||||
|
||||
import omnigibson as og
|
||||
import omnigibson.lazy as lazy
|
||||
|
@ -714,8 +714,9 @@ class Tiago(ManipulationRobot, LocomotionRobot, ActiveCameraRobot):
|
|||
|
||||
return self.base_footprint_link.get_position_orientation()
|
||||
|
||||
|
||||
def set_position_orientation(self, position=None, orientation=None, frame: Literal["world", "scene", "parent"] = "world"):
|
||||
def set_position_orientation(
|
||||
self, position=None, orientation=None, frame: Literal["world", "scene", "parent"] = "world"
|
||||
):
|
||||
"""
|
||||
Sets tiago's pose with respect to the specified frame
|
||||
|
||||
|
|
|
@ -25,8 +25,8 @@ from omnigibson.systems.system_base import (
|
|||
VisualParticleSystem,
|
||||
create_system_from_metadata,
|
||||
)
|
||||
from omnigibson.utils.constants import STRUCTURE_CATEGORIES
|
||||
from omnigibson.transition_rules import TransitionRuleAPI
|
||||
from omnigibson.utils.constants import STRUCTURE_CATEGORIES
|
||||
from omnigibson.utils.python_utils import (
|
||||
Recreatable,
|
||||
Registerable,
|
||||
|
@ -323,7 +323,7 @@ class Scene(Serializable, Registerable, Recreatable, ABC):
|
|||
position=[last_scene_edge + scene_margin + left_edge_to_center, 0, 0]
|
||||
)
|
||||
new_scene_edge = last_scene_edge + scene_margin + (aabb_max[0] - aabb_min[0])
|
||||
else:
|
||||
else:
|
||||
aabb_min, aabb_max = lazy.omni.usd.get_context().compute_path_world_bounding_box(scene_absolute_path)
|
||||
new_scene_edge = aabb_max[0]
|
||||
|
||||
|
|
|
@ -75,6 +75,7 @@ class EmitterType(IntEnum):
|
|||
FIRE = 0
|
||||
STEAM = 1
|
||||
|
||||
|
||||
# Valid primitive mesh types
|
||||
PRIMITIVE_MESH_TYPES = {
|
||||
"Cone",
|
||||
|
|
|
@ -4,10 +4,10 @@ import math
|
|||
import os
|
||||
import re
|
||||
from collections.abc import Iterable
|
||||
from typing import Literal
|
||||
|
||||
import numpy as np
|
||||
import trimesh
|
||||
from typing import Literal
|
||||
|
||||
import omnigibson as og
|
||||
import omnigibson.lazy as lazy
|
||||
|
@ -680,9 +680,7 @@ class FlatcacheAPI:
|
|||
|
||||
# 1. For every link, update its xformOp properties to be 0
|
||||
for link in prim.links.values():
|
||||
XFormPrim.set_position_orientation(
|
||||
link, np.zeros(3), np.array([0, 0, 0, 1.0]), frame="parent"
|
||||
)
|
||||
XFormPrim.set_position_orientation(link, np.zeros(3), np.array([0, 0, 0, 1.0]), frame="parent")
|
||||
# 2. For every joint, update its linear / angular joint state to be 0
|
||||
if prim.n_joints > 0:
|
||||
for joint in prim.joints.values():
|
||||
|
|
|
@ -182,6 +182,7 @@ def test_multi_scene_particle_source():
|
|||
for _ in range(50):
|
||||
og.sim.step()
|
||||
|
||||
|
||||
def test_multi_scene_position_orientation_relative_to_scene():
|
||||
vec_env = setup_multi_environment(3)
|
||||
|
||||
|
@ -202,13 +203,15 @@ def test_multi_scene_position_orientation_relative_to_scene():
|
|||
updated_relative_pos, updated_relative_ori = robot.get_position_orientation(frame="scene")
|
||||
|
||||
# Assert that the relative position has been updated correctly
|
||||
assert np.allclose(updated_relative_pos, new_relative_pos, atol=1e-3), \
|
||||
f"Updated relative position {updated_relative_pos} does not match expected {new_relative_pos}"
|
||||
assert np.allclose(
|
||||
updated_relative_pos, new_relative_pos, atol=1e-3
|
||||
), f"Updated relative position {updated_relative_pos} does not match expected {new_relative_pos}"
|
||||
|
||||
# Assert that the relative orientation has been updated correctly
|
||||
assert np.allclose(updated_relative_ori, new_relative_ori, atol=1e-3), \
|
||||
f"Updated relative orientation {updated_relative_ori} does not match expected {new_relative_ori}"
|
||||
|
||||
assert np.allclose(
|
||||
updated_relative_ori, new_relative_ori, atol=1e-3
|
||||
), f"Updated relative orientation {updated_relative_ori} does not match expected {new_relative_ori}"
|
||||
|
||||
# Get the scene's global position and orientation
|
||||
scene_pos, scene_ori = scene_prim.get_position_orientation(frame="world")
|
||||
|
||||
|
@ -219,14 +222,16 @@ def test_multi_scene_position_orientation_relative_to_scene():
|
|||
expected_global_pos = scene_pos + updated_relative_pos
|
||||
|
||||
# Assert that the global position is correct
|
||||
assert np.allclose(global_pos, expected_global_pos, atol=1e-3), \
|
||||
f"Global position {global_pos} does not match expected {expected_global_pos}"
|
||||
assert np.allclose(
|
||||
global_pos, expected_global_pos, atol=1e-3
|
||||
), f"Global position {global_pos} does not match expected {expected_global_pos}"
|
||||
|
||||
# Calculate expected global orientation
|
||||
expected_global_ori = quat_multiply(scene_ori, new_relative_ori)
|
||||
|
||||
# Assert that the global orientation is correct
|
||||
assert np.allclose(global_ori, expected_global_ori, atol=1e-3), \
|
||||
f"Global orientation {global_ori} does not match expected {expected_global_ori}"
|
||||
assert np.allclose(
|
||||
global_ori, expected_global_ori, atol=1e-3
|
||||
), f"Global orientation {global_ori} does not match expected {expected_global_ori}"
|
||||
|
||||
og.clear()
|
||||
og.clear()
|
||||
|
|
|
@ -111,6 +111,6 @@ def camera_pose_test(flatcache):
|
|||
|
||||
og.clear()
|
||||
|
||||
|
||||
def test_camera_pose_flatcache_on():
|
||||
camera_pose_test(True)
|
||||
|
||||
|
|
Loading…
Reference in New Issue