Skip to content

Commit

Permalink
test to load the traces from thomas W.
Browse files Browse the repository at this point in the history
Unfortunately, 6DoF and not 5Dof

Also did a small snippet in example/ to create a video from hdf5
  • Loading branch information
perezjln committed May 20, 2024
1 parent 8e29cbb commit a9a18d9
Show file tree
Hide file tree
Showing 3 changed files with 75 additions and 0 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ __pycache__/

# C extensions
*.so
*.hdf5

# Distribution / packaging
.Python
Expand Down
28 changes: 28 additions & 0 deletions examples/trace_hdf5_img.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@

import h5py, tqdm
import matplotlib.pyplot as plt
import matplotlib.cm as cm
import matplotlib.animation as animation


# Specify the path to your HDF5 file
file_path = 'data/episode_46.hdf5'

# Open the HDF5 file
with h5py.File(file_path, 'r') as file:

# Access the datasets or attributes in the file
# For example, to access a dataset named 'data':
group_obs_img = file['observations/images/front']

img = [] # some array of images
frames = [] # for storing the generated images

# Write each image to the video
fig = plt.figure()
for i in tqdm.tqdm(range(group_obs_img.shape[0]), desc='Writing video'):
frames.append([plt.imshow(group_obs_img[i],animated=True)])

ani = animation.ArtistAnimation(fig, frames, interval=50, blit=True,
repeat_delay=1000)
ani.save('movie.mp4')
46 changes: 46 additions & 0 deletions examples/trace_hdf5_mujoco.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
import h5py
import time

import mujoco
import mujoco.viewer
import numpy as np

from gym_lowcostrobot.simulated_robot import SimulatedRobot

def do_replay_hdf5():

# Specify the path to your HDF5 file
file_path = 'data/episode_46.hdf5'
with h5py.File(file_path, 'r') as file:

m = mujoco.MjModel.from_xml_path("assets/scene_one_cube.xml")
data = mujoco.MjData(m)
robot = SimulatedRobot(m, data)

group_action = file['action']
group_qpos = file['observations/qpos']

with mujoco.viewer.launch_passive(m, data) as viewer:

# Run the simulation
step = 0
while viewer.is_running():
step_start = time.time()

# Step the simulation forward
robot.set_target_pos(group_action[step][0:5])
mujoco.mj_step(m, data)

viewer.sync()

# Rudimentary time keeping, will drift relative to wall clock.
time_until_next_step = m.opt.timestep - (time.time() - step_start)
if time_until_next_step > 0:
time.sleep(time_until_next_step)

step += 1
step = step % len(group_qpos)


if __name__ == "__main__":
do_replay_hdf5()

0 comments on commit a9a18d9

Please sign in to comment.