Skip to content

Commit

Permalink
remove unused imports
Browse files Browse the repository at this point in the history
  • Loading branch information
mees committed Mar 25, 2022
1 parent f4aae48 commit c7377a6
Show file tree
Hide file tree
Showing 16 changed files with 53 additions and 71 deletions.
2 changes: 1 addition & 1 deletion .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ default_language_version:
python: python3.8
repos:
- repo: https://github.com/psf/black
rev: stable
rev: 22.1.0
hooks:
- id: black
language_version: python3.8
Expand Down
40 changes: 20 additions & 20 deletions calvin_env/camera/camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,13 +46,13 @@ def process_rgbd(self, obs, nearval, farval):
# Reference: world2pixel
# https://github.com/bulletphysics/bullet3/issues/1952
def project(self, point):
'''
Projects a world point in homogeneous coordinates to pixel coordinates
Args
point: np.array of len 4; indicates the desired point to project
Output
(x, y): tuple (u, v); pixel coordinates of the projected point
'''
"""
Projects a world point in homogeneous coordinates to pixel coordinates
Args
point: np.array of len 4; indicates the desired point to project
Output
(x, y): tuple (u, v); pixel coordinates of the projected point
"""

# reshape to get homogeneus transform
persp_m = np.array(self.projectionMatrix).reshape((4, 4)).T
Expand All @@ -67,16 +67,16 @@ def project(self, point):
return (x, y)

def deproject(self, point, depth_img, homogeneous=False):
'''
Deprojects a pixel point to 3D coordinates
Args
point: tuple (u, v); pixel coordinates of point to deproject
depth_img: np.array; depth image used as reference to generate 3D coordinates
homogeneous: bool; if true it returns the 3D point in homogeneous coordinates,
else returns the world coordinates (x, y, z) position
Output
(x, y): np.array; world coordinates of the deprojected point
'''
"""
Deprojects a pixel point to 3D coordinates
Args
point: tuple (u, v); pixel coordinates of point to deproject
depth_img: np.array; depth image used as reference to generate 3D coordinates
homogeneous: bool; if true it returns the 3D point in homogeneous coordinates,
else returns the world coordinates (x, y, z) position
Output
(x, y): np.array; world coordinates of the deprojected point
"""
T_world_cam = np.linalg.inv(np.array(self.viewMatrix).reshape((4, 4)).T)

u, v = point
Expand All @@ -85,7 +85,7 @@ def deproject(self, point, depth_img, homogeneous=False):
x = (u - self.width // 2) * z / foc
y = -(v - self.height // 2) * z / foc
z = -z
world_pos = (T_world_cam @ np.array([x, y, z, 1]))
if(not homogeneous):
world_pos = T_world_cam @ np.array([x, y, z, 1])
if not homogeneous:
world_pos = world_pos[:3]
return world_pos
return world_pos
1 change: 0 additions & 1 deletion calvin_env/camera/tactile_sensor.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
import os

import numpy as np
import pybullet as p

from calvin_env.camera.camera import Camera
import tacto
Expand Down
2 changes: 1 addition & 1 deletion calvin_env/datarenderer.py
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ def set_static_cams_from_gui(cfg, load_dir, max_frames):
fov = cam.fov
while True:
file_path = load_dir / f"{frame:012d}.pickle"
state_ob, done, info = env.reset_from_storage(file_path)
_, _, _ = env.reset_from_storage(file_path)
env.p.stepSimulation()
frame_rgbs, frame_depths = env.get_camera_obs()
rgb_static = frame_rgbs[cam_index]
Expand Down
2 changes: 1 addition & 1 deletion calvin_env/envs/play_lmp_wrapper.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
import os
from typing import Any, Dict, Tuple, Union

from calvin_agent.datasets.utils.episode_utils import process_actions, process_depth, process_rgb, process_state
from calvin_agent.datasets.utils.episode_utils import process_depth, process_rgb, process_state
import gym
import numpy as np
import torch
Expand Down
10 changes: 6 additions & 4 deletions calvin_env/envs/play_table_env.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
from copy import deepcopy
import logging
from math import pi
import os
Expand All @@ -19,13 +18,15 @@
import pybullet_utils.bullet_client as bc

import calvin_env
from calvin_env.utils.utils import FpsController, get_git_commit_hash, timeit
from calvin_env.utils.utils import FpsController, get_git_commit_hash

# A logger for this file
log = logging.getLogger(__name__)
from rich.traceback import install

install(show_locals=True)


class PlayTableSimEnv(gym.Env):
def __init__(
self,
Expand Down Expand Up @@ -262,7 +263,7 @@ def reset_from_storage(self, filename):
return data["state_obs"], data["done"], data["info"]

def serialize(self):
data = {"time": time.time_ns() / (10 ** 9), "robot": self.robot.serialize(), "scene": self.scene.serialize()}
data = {"time": time.time_ns() / (10**9), "robot": self.robot.serialize(), "scene": self.scene.serialize()}
return data


Expand Down Expand Up @@ -294,9 +295,10 @@ def run_env(cfg):

env.reset()
while True:
env.step(np.array((0.,0, 0,0,0, 1)))
env.step(np.array((0.0, 0, 0, 0, 0, 1)))
# env.render()
time.sleep(0.01)


if __name__ == "__main__":
run_env()
2 changes: 0 additions & 2 deletions calvin_env/envs/tasks.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,6 @@
from omegaconf import ListConfig
from scipy.spatial.transform import Rotation as R

from calvin_env.utils.utils import timeit


class Tasks:
def __init__(self, tasks):
Expand Down
3 changes: 1 addition & 2 deletions calvin_env/robot/IKfast.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
from ikfast_franka_panda import get_dof, get_fk, get_free_dof, get_ik
from ikfast_franka_panda import get_ik
import numpy as np
import pybullet as p
from scipy.spatial.transform import Rotation as R


Expand Down
5 changes: 0 additions & 5 deletions calvin_env/robot/robot.py
Original file line number Diff line number Diff line change
@@ -1,14 +1,9 @@
import logging
import math
import os

import cv2
import numpy as np
import pybullet as p
import quaternion

from calvin_env.robot.mixed_ik import MixedIK
from calvin_env.utils.utils import timeit

# A logger for this file
log = logging.getLogger(__name__)
Expand Down
2 changes: 1 addition & 1 deletion calvin_env/scene/objects/button.py
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ def _is_pressed(self):
return self.get_state() < self.trigger_threshold

def get_state(self):
""" return button joint state """
"""return button joint state"""
return float(self.p.getJointState(self.uid, self.joint_index, physicsClientId=self.cid)[0])

def get_info(self):
Expand Down
1 change: 0 additions & 1 deletion calvin_env/scene/objects/movable_object.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
import logging

import numpy as np
from omegaconf import ListConfig
from omegaconf.errors import ConfigKeyError

from calvin_env.scene.objects.base_object import BaseObject
Expand Down
2 changes: 1 addition & 1 deletion calvin_env/scene/objects/switch.py
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ def is_pressed(self):
return self.get_state() < self.trigger_threshold

def get_state(self):
""" return button joint state """
"""return button joint state"""
return float(self.p.getJointState(self.uid, self.joint_index, physicsClientId=self.cid)[0])

def get_info(self):
Expand Down
6 changes: 0 additions & 6 deletions calvin_env/scripts/check_tasks.py
Original file line number Diff line number Diff line change
@@ -1,16 +1,10 @@
from copy import deepcopy
import glob
import os
from pathlib import Path
import time

import cv2
import hydra
import numpy as np
import pybullet as p

from calvin_env.envs.tasks import Tasks

"""
This script loads a rendered episode and replays it using the recorded actions.
Optionally, gaussian noise can be added to the actions.
Expand Down
43 changes: 20 additions & 23 deletions calvin_env/scripts/record_video_icra.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,4 @@
from copy import deepcopy
import glob
import os
from pathlib import Path
import time

Expand All @@ -10,7 +8,6 @@
import numpy as np
import pybullet as p

from calvin_env.envs.tasks import Tasks
from calvin_env.utils import utils

"""
Expand Down Expand Up @@ -81,34 +78,34 @@ def run_env(cfg):
cv2.imshow("im", im)
cv2.waitKey(1)
video.write(im[:, :, ::-1])
# video_gripper.write(depth2rgb(obs["depth_obs"][1], minval=0.1, maxval=0.5)[:, :, ::-1])
# video_static.write(depth2rgb(obs["depth_obs"][0], minval=3.5, maxval=5)[:, :, ::-1])
video_gripper.write(depth2rgb(obs["depth_obs"][1], minval=0.1, maxval=0.5)[:, :, ::-1])
video_static.write(depth2rgb(obs["depth_obs"][0], minval=3.5, maxval=5)[:, :, ::-1])
# action = data["rel_actions"]
# action = np.split(data["actions"], [3, 6])
# action = noise(action)
action = np.split(data["actions"], [3, 6])
action = noise(action)

# rel_actions.append(create_relative_action(data["actions"], data["robot_obs"][:6]))
rel_actions.append(utils.to_relative_action(data["actions"], data["robot_obs"][:6]))
# action = utils.to_relative_action(data["actions"], data["robot_obs"], max_pos=0.04, max_orn=0.1)
# tcp_pos, tcp_orn = p.getLinkState(env.robot.robot_uid, env.robot.tcp_link_id, physicsClientId=env.cid)[:2]
# tcp_orn = p.getEulerFromQuaternion(tcp_orn)
# action2 = create_relative_action(data["actions"], np.concatenate([tcp_pos, tcp_orn]))
# o, _, _, info = env.step(action)
# print(info["scene_info"]["lights"]["led"]["logical_state"])
# if (i - s) % 32 != 0:
# print(tasks.get_task_info(prev_info, info))
# else:
# prev_info = deepcopy(info)
# time.sleep(0.01)
# video.release()
# action2 = utils.to_relative_action(data["actions"], np.concatenate([tcp_pos, tcp_orn]))
o, _, _, info = env.step(action)
print(info["scene_info"]["lights"]["led"]["logical_state"])
if (i - s) % 32 != 0:
print(tasks.get_task_info(prev_info, info))
else:
prev_info = deepcopy(info)
time.sleep(0.01)
video.release()
video_static.release()
video_gripper.release()
print(time.time() - t1)
# rel_actions = np.array(rel_actions)
# for j in range(rel_actions.shape[1]):
# plt.figure(j)
# plt.hist(rel_actions[:, j], bins=10)
# plt.plot()
# plt.show()
rel_actions = np.array(rel_actions)
for j in range(rel_actions.shape[1]):
plt.figure(j)
plt.hist(rel_actions[:, j], bins=10)
plt.plot()
plt.show()


if __name__ == "__main__":
Expand Down
2 changes: 1 addition & 1 deletion calvin_env/utils/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ def timed(*args, **kw):

class FpsController:
def __init__(self, freq):
self.loop_time = (1.0 / freq) * 10 ** 9
self.loop_time = (1.0 / freq) * 10**9
self.prev_time = time.time_ns()

def step(self):
Expand Down
1 change: 0 additions & 1 deletion requirements.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,4 +13,3 @@ pandas
pybullet
scipy
rich

0 comments on commit c7377a6

Please sign in to comment.