unitree_mujoco/simulate_python/unitree_mujoco.py

84 lines
2.2 KiB
Python
Raw Normal View History

2024-04-29 15:02:43 +08:00
import time
import mujoco
import mujoco.viewer
from threading import Thread
import threading
from unitree_sdk2py.core.channel import ChannelFactoryInitialize
2024-04-29 15:02:43 +08:00
from unitree_sdk2py_bridge import UnitreeSdk2Bridge, ElasticBand
import config
locker = threading.Lock()
mj_model = mujoco.MjModel.from_xml_path(config.ROBOT_SCENE)
mj_data = mujoco.MjData(mj_model)
if config.ENABLE_ELASTIC_BAND:
elastic_band = ElasticBand()
if config.ROBOT == "h1" or config.ROBOT == "g1":
2024-09-03 21:08:21 +08:00
band_attached_link = mj_model.body("torso_link").id
2024-04-29 15:02:43 +08:00
else:
2024-09-03 21:08:21 +08:00
band_attached_link = mj_model.body("base_link").id
2024-04-29 15:02:43 +08:00
viewer = mujoco.viewer.launch_passive(
2024-09-03 21:08:21 +08:00
mj_model, mj_data, key_callback=elastic_band.MujuocoKeyCallback
)
2024-04-29 15:02:43 +08:00
else:
viewer = mujoco.viewer.launch_passive(mj_model, mj_data)
mj_model.opt.timestep = config.SIMULATE_DT
num_motor_ = mj_model.nu
dim_motor_sensor_ = 3 * num_motor_
time.sleep(0.2)
def SimulationThread():
global mj_data, mj_model
2024-09-03 21:08:21 +08:00
ChannelFactoryInitialize(config.DOMAIN_ID, config.INTERFACE)
unitree = UnitreeSdk2Bridge(mj_model, mj_data)
if config.USE_JOYSTICK:
2024-09-03 21:08:21 +08:00
unitree.SetupJoystick(device_id=0, js_type=config.JOYSTICK_TYPE)
if config.PRINT_SCENE_INFORMATION:
unitree.PrintSceneInformation()
2024-09-03 21:08:21 +08:00
2024-04-29 15:02:43 +08:00
while viewer.is_running():
step_start = time.perf_counter()
locker.acquire()
if config.ENABLE_ELASTIC_BAND:
if elastic_band.enable:
mj_data.xfrc_applied[band_attached_link, :3] = elastic_band.Advance(
2024-09-03 21:08:21 +08:00
mj_data.qpos[:3], mj_data.qvel[:3]
)
2024-04-29 15:02:43 +08:00
mujoco.mj_step(mj_model, mj_data)
locker.release()
2024-09-03 21:08:21 +08:00
time_until_next_step = mj_model.opt.timestep - (
time.perf_counter() - step_start
)
2024-04-29 15:02:43 +08:00
if time_until_next_step > 0:
time.sleep(time_until_next_step)
def PhysicsViewerThread():
while viewer.is_running():
locker.acquire()
viewer.sync()
locker.release()
time.sleep(config.VIEWER_DT)
if __name__ == "__main__":
viewer_thread = Thread(target=PhysicsViewerThread)
sim_thread = Thread(target=SimulationThread)
viewer_thread.start()
sim_thread.start()