Skip to content

Commit

Permalink
Switch to formatting via ruff
Browse files Browse the repository at this point in the history
  • Loading branch information
cgokmen committed Dec 27, 2024
1 parent 757cdd9 commit dbdd9d0
Show file tree
Hide file tree
Showing 27 changed files with 20 additions and 45 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -338,7 +338,6 @@ def __init__(
quat_relative_axis_angle = T.quat2axisangle(quat_relative)
self._arm_targets[arm] = (pos_relative, quat_relative_axis_angle)
else:

arm_target = cb.to_torch(control_dict["joint_position"])[arm_ctrl.dof_idx]
self._arm_targets[arm] = arm_target

Expand Down
1 change: 0 additions & 1 deletion omnigibson/envs/data_wrapper.py
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,6 @@ def save_data(self):
self.flush_current_traj()

if self.hdf5_file is not None:

log.info(
f"\nSaved:\n"
f"{self.traj_count} trajectories / {self.step_count} total steps\n"
Expand Down
1 change: 0 additions & 1 deletion omnigibson/object_states/filled.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@


class Filled(RelativeObjectState, BooleanStateMixin):

def _get_value(self, system):
# Sanity check to make sure system is valid
assert self.obj.scene.is_physical_particle_system(
Expand Down
1 change: 0 additions & 1 deletion omnigibson/object_states/joint_state.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@


class Joint(AbsoluteObjectState):

def _get_value(self):
return self.obj.get_joint_positions() if self.obj.n_joints > 0 else th.tensor([])

Expand Down
1 change: 0 additions & 1 deletion omnigibson/object_states/next_to.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@


class NextTo(KinematicsMixin, RelativeObjectState, BooleanStateMixin):

@classmethod
def get_dependencies(cls):
deps = super().get_dependencies()
Expand Down
1 change: 0 additions & 1 deletion omnigibson/object_states/on_top.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@


class OnTop(KinematicsMixin, RelativeObjectState, BooleanStateMixin):

@classmethod
def get_dependencies(cls):
deps = super().get_dependencies()
Expand Down
1 change: 0 additions & 1 deletion omnigibson/object_states/overlaid.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@


class Overlaid(KinematicsMixin, RelativeObjectState, BooleanStateMixin):

@classmethod
def get_dependencies(cls):
deps = super().get_dependencies()
Expand Down
1 change: 0 additions & 1 deletion omnigibson/object_states/particle_modifier.py
Original file line number Diff line number Diff line change
Expand Up @@ -224,7 +224,6 @@ def condition(obj) --> bool
"""

def __init__(self, obj, conditions, method=ParticleModifyMethod.ADJACENCY, projection_mesh_params=None):

# Store internal variables
self.method = method
self.projection_source_sphere = None
Expand Down
1 change: 0 additions & 1 deletion omnigibson/object_states/pose.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@


class Pose(AbsoluteObjectState):

def _get_value(self):
pos, orn = self.obj.get_position_orientation()
return pos, orn
Expand Down
1 change: 0 additions & 1 deletion omnigibson/object_states/temperature.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@


class Temperature(TensorizedValueState):

def __init__(self, obj):
# Run super first
super(Temperature, self).__init__(obj)
Expand Down
1 change: 0 additions & 1 deletion omnigibson/object_states/toggle.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@


class ToggledOn(AbsoluteObjectState, BooleanStateMixin, LinkBasedStateMixin, UpdateStateMixin, GlobalUpdateStateMixin):

# List of set of prim paths defining robot finger links belonging to any manipulation robots per scene
_robot_finger_paths = None

Expand Down
1 change: 0 additions & 1 deletion omnigibson/object_states/touching.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@


class Touching(KinematicsMixin, RelativeObjectState, BooleanStateMixin):

@staticmethod
def _check_contact(obj_a, obj_b):
return len(set(obj_a.links.values()) & obj_b.states[ContactBodies].get_value()) > 0
Expand Down
3 changes: 0 additions & 3 deletions omnigibson/prims/geom_prim.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@ def __init__(
name,
load_config=None,
):

# Run super method
super().__init__(
relative_prim_path=relative_prim_path,
Expand Down Expand Up @@ -193,7 +192,6 @@ def extent(self):


class CollisionGeomPrim(GeomPrim):

def __init__(
self,
relative_prim_path,
Expand Down Expand Up @@ -436,7 +434,6 @@ class VisualGeomPrim(GeomPrim):


class CollisionVisualGeomPrim(CollisionGeomPrim, VisualGeomPrim):

def _post_load(self):
# run super first
super()._post_load()
Expand Down
5 changes: 3 additions & 2 deletions omnigibson/robots/behavior_robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -468,8 +468,9 @@ def teleop_data_to_action(self, teleop_action) -> th.Tensor:
# Process local transform adjustments
hand_data = 0
if teleop_action.is_valid[part_name]:
des_world_part_pos, des_world_part_orn = teleop_action[part_name][:3], T.euler2quat(
teleop_action[part_name][3:6]
des_world_part_pos, des_world_part_orn = (
teleop_action[part_name][:3],
T.euler2quat(teleop_action[part_name][3:6]),
)
if part_name in self.arm_names:
# compute gripper action
Expand Down
1 change: 0 additions & 1 deletion omnigibson/tasks/behavior_task.py
Original file line number Diff line number Diff line change
Expand Up @@ -392,7 +392,6 @@ def _get_obs(self, env):
for (obj, obj_exist), obj_rpy, obj_rpy_cos, obj_rpy_sin in zip(
objs_exist.items(), objs_rpy, objs_rpy_cos, objs_rpy_sin
):

# TODO: May need to update checking here to USDObject? Or even baseobject?
# TODO: How to handle systems as part of obs?
if obj_exist:
Expand Down
5 changes: 3 additions & 2 deletions omnigibson/utils/asset_conversion_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -735,8 +735,9 @@ def _process_meta_link(stage, obj_model, meta_link_type, meta_link_infos):
xform_prim = lazy.omni.isaac.core.prims.xform_prim.XFormPrim(prim_path=prim_path)

# Get the mesh/light pose in the parent link frame
mesh_in_parent_link_pos, mesh_in_parent_link_orn = th.tensor(mesh_info["position"]), th.tensor(
mesh_info["orientation"]
mesh_in_parent_link_pos, mesh_in_parent_link_orn = (
th.tensor(mesh_info["position"]),
th.tensor(mesh_info["orientation"]),
)

# Get the mesh/light pose in the meta link frame
Expand Down
1 change: 0 additions & 1 deletion omnigibson/utils/backend_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@ def add_compute_function(name, np_function, th_function):


class _ComputeBackend:

# Dictionary mapping custom externally-defined function name to function
_custom_fcns = None

Expand Down
1 change: 0 additions & 1 deletion omnigibson/utils/motion_planning_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,6 @@ def plan_base_motion(
from ompl import geometric as ompl_geo

class CustomMotionValidator(ob.MotionValidator):

def __init__(self, si, space):
super(CustomMotionValidator, self).__init__(si)
self.si = si
Expand Down
1 change: 0 additions & 1 deletion omnigibson/utils/python_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@


class classproperty:

def __init__(self, fget):
self.fget = fget

Expand Down
1 change: 0 additions & 1 deletion omnigibson/utils/sim_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,6 @@ def get_contacts(inp_prims):

# Only run the following (expensive) code if we are actively using filtering criteria
if should_check_collisions or should_filter_collisions:

# First filter out unnecessary collisions
if should_filter_collisions:
# First filter pass, remove the intersection of the main contacts and the contacts from the exclusion set minus
Expand Down
5 changes: 3 additions & 2 deletions omnigibson/utils/teleop_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -88,8 +88,9 @@ def get_action(self, robot_obs: TeleopObservation) -> th.Tensor:
# optionally update control marker
if self.show_control_marker:
for arm_name in self.control_markers:
delta_pos, delta_orn = self.teleop_action[arm_name][:3], T.euler2quat(
th.tensor(self.teleop_action[arm_name][3:6])
delta_pos, delta_orn = (
self.teleop_action[arm_name][:3],
T.euler2quat(th.tensor(self.teleop_action[arm_name][3:6])),
)
rel_target_pos = robot_obs[arm_name][:3] + delta_pos
rel_target_orn = T.quat_multiply(delta_orn, robot_obs[arm_name][3:7])
Expand Down
1 change: 0 additions & 1 deletion omnigibson/utils/transform_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -575,7 +575,6 @@ def euler2quat(euler: torch.Tensor) -> torch.Tensor:

@torch.compile
def quat2euler(q):

single_dim = q.dim() == 1

if single_dim:
Expand Down
13 changes: 6 additions & 7 deletions omnigibson/utils/transform_utils_np.py
Original file line number Diff line number Diff line change
Expand Up @@ -82,12 +82,12 @@ def unit_vector(data, axis=None, out=None):
>>> v0 = numpy.random.rand(5, 4, 3)
>>> v1 = unit_vector(v0, axis=-1)
>>> v2 = v0 / numpy.expand_dims(numpy.sqrt(numpy.sum(v0*v0, axis=2)), 2)
>>> v2 = v0 / numpy.expand_dims(numpy.sqrt(numpy.sum(v0 * v0, axis=2)), 2)
>>> numpy.allclose(v1, v2)
True
>>> v1 = unit_vector(v0, axis=1)
>>> v2 = v0 / numpy.expand_dims(numpy.sqrt(numpy.sum(v0*v0, axis=1)), 1)
>>> v2 = v0 / numpy.expand_dims(numpy.sqrt(numpy.sum(v0 * v0, axis=1)), 1)
>>> numpy.allclose(v1, v2)
True
Expand Down Expand Up @@ -840,11 +840,11 @@ def rotation_matrix(angle, direction, point=None):
Returns matrix to rotate about axis defined by point and direction.
E.g.:
>>> angle = (random.random() - 0.5) * (2*math.pi)
>>> angle = (random.random() - 0.5) * (2 * math.pi)
>>> direc = numpy.random.random(3) - 0.5
>>> point = numpy.random.random(3) - 0.5
>>> R0 = rotation_matrix(angle, direc, point)
>>> R1 = rotation_matrix(angle-2*math.pi, direc, point)
>>> R1 = rotation_matrix(angle - 2 * math.pi, direc, point)
>>> is_same_transform(R0, R1)
True
Expand All @@ -854,11 +854,10 @@ def rotation_matrix(angle, direction, point=None):
True
>>> I = numpy.identity(4, numpy.float32)
>>> numpy.allclose(I, rotation_matrix(math.pi*2, direc))
>>> numpy.allclose(I, rotation_matrix(math.pi * 2, direc))
True
>>> numpy.allclose(2., numpy.trace(rotation_matrix(math.pi/2,
... direc, point)))
>>> numpy.allclose(2.0, numpy.trace(rotation_matrix(math.pi / 2, direc, point)))
True
Args:
Expand Down
3 changes: 0 additions & 3 deletions omnigibson/utils/ui_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -550,7 +550,6 @@ def _sub_keyboard_event(self, event, *args, **kwargs):
event.type == lazy.carb.input.KeyboardEventType.KEY_PRESS
or event.type == lazy.carb.input.KeyboardEventType.KEY_REPEAT
):

if event.type == lazy.carb.input.KeyboardEventType.KEY_PRESS and event.input in self.input_to_function:
self.input_to_function[event.input]()

Expand Down Expand Up @@ -763,7 +762,6 @@ def keyboard_event_handler(self, event, *args, **kwargs):
event.type == lazy.carb.input.KeyboardEventType.KEY_PRESS
or event.type == lazy.carb.input.KeyboardEventType.KEY_REPEAT
):

# Handle special cases
if (
event.input in {lazy.carb.input.KeyboardInput.KEY_1, lazy.carb.input.KeyboardInput.KEY_2}
Expand Down Expand Up @@ -883,7 +881,6 @@ def get_teleop_action(self):

# Possibly set the persistent gripper action
if len(self.binary_grippers) > 0 and self.keypress_mapping[lazy.carb.input.KeyboardInput.T]["val"] is not None:

for i, binary_gripper in enumerate(self.binary_grippers):
# Possibly update the stored value if the toggle gripper key has been pressed and
# it's the active gripper being controlled
Expand Down
10 changes: 5 additions & 5 deletions omnigibson/utils/urdfpy_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -3323,20 +3323,20 @@ def animate(self, cfg_trajectory=None, loop_time=3.0, use_collision=False):
You can run this without specifying a ``cfg_trajectory`` to view
the full articulation of the URDF
>>> robot = URDF.load('ur5.urdf')
>>> robot = URDF.load("ur5.urdf")
>>> robot.animate()
.. image:: /_static/ur5.gif
>>> ct = {'shoulder_pan_joint': [0.0, 2 * np.pi]}
>>> ct = {"shoulder_pan_joint": [0.0, 2 * np.pi]}
>>> robot.animate(cfg_trajectory=ct)
.. image:: /_static/ur5_shoulder.gif
>>> ct = {
... 'shoulder_pan_joint' : [-np.pi / 4, np.pi / 4],
... 'shoulder_lift_joint' : [0.0, -np.pi / 2.0],
... 'elbow_joint' : [0.0, np.pi / 2.0]
... "shoulder_pan_joint": [-np.pi / 4, np.pi / 4],
... "shoulder_lift_joint": [0.0, -np.pi / 2.0],
... "elbow_joint": [0.0, np.pi / 2.0],
... }
>>> robot.animate(cfg_trajectory=ct)
Expand Down
2 changes: 0 additions & 2 deletions tests/test_robot_states_flatcache.py
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,6 @@ def test_robot_load_drive():

# Iterate over all robots and test their motion
for robot_name, robot_cls in REGISTERED_ROBOTS.items():

if robot_name in ["FrankaMounted", "Stretch"]:
# TODO: skipping FrankaMounted and Stretch for now because CI doesn't have the required assets
continue
Expand Down Expand Up @@ -214,7 +213,6 @@ def test_robot_load_drive():


def test_grasping_mode():

if og.sim is None:
# Set global flags
gm.ENABLE_FLATCACHE = True
Expand Down
1 change: 0 additions & 1 deletion tests/test_scene_graph.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@


def test_scene_graph():

if og.sim is None:
# Set global flags
gm.ENABLE_OBJECT_STATES = True
Expand Down

0 comments on commit dbdd9d0

Please sign in to comment.