|
|
|
@ -15,9 +15,6 @@ sys.path.append(parent_dir) |
|
|
|
from televuer import TeleVuerWrapper |
|
|
|
from teleop.robot_control.robot_arm import G1_29_ArmController, G1_23_ArmController, H1_2_ArmController, H1_ArmController |
|
|
|
from teleop.robot_control.robot_arm_ik import G1_29_ArmIK, G1_23_ArmIK, H1_2_ArmIK, H1_ArmIK |
|
|
|
from teleop.robot_control.robot_hand_unitree import Dex3_1_Controller, Dex1_1_Gripper_Controller |
|
|
|
from teleop.robot_control.robot_hand_inspire import Inspire_Controller_DFX, Inspire_Controller_FTP |
|
|
|
from teleop.robot_control.robot_hand_brainco import Brainco_Controller |
|
|
|
from teleimager.image_client import ImageClient |
|
|
|
from teleop.utils.episode_writer import EpisodeWriter |
|
|
|
from teleop.utils.ipc import IPC_Server |
|
|
|
@ -154,6 +151,7 @@ if __name__ == '__main__': |
|
|
|
|
|
|
|
# end-effector |
|
|
|
if args.ee == "dex3": |
|
|
|
from teleop.robot_control.robot_hand_unitree import Dex3_1_Controller |
|
|
|
left_hand_pos_array = Array('d', 75, lock = True) # [input] |
|
|
|
right_hand_pos_array = Array('d', 75, lock = True) # [input] |
|
|
|
dual_hand_data_lock = Lock() |
|
|
|
@ -162,6 +160,7 @@ if __name__ == '__main__': |
|
|
|
hand_ctrl = Dex3_1_Controller(left_hand_pos_array, right_hand_pos_array, dual_hand_data_lock, |
|
|
|
dual_hand_state_array, dual_hand_action_array, simulation_mode=args.sim) |
|
|
|
elif args.ee == "dex1": |
|
|
|
from teleop.robot_control.robot_hand_unitree import Dex1_1_Gripper_Controller |
|
|
|
left_gripper_value = Value('d', 0.0, lock=True) # [input] |
|
|
|
right_gripper_value = Value('d', 0.0, lock=True) # [input] |
|
|
|
dual_gripper_data_lock = Lock() |
|
|
|
@ -170,6 +169,7 @@ if __name__ == '__main__': |
|
|
|
gripper_ctrl = Dex1_1_Gripper_Controller(left_gripper_value, right_gripper_value, dual_gripper_data_lock, |
|
|
|
dual_gripper_state_array, dual_gripper_action_array, simulation_mode=args.sim) |
|
|
|
elif args.ee == "inspire_dfx": |
|
|
|
from teleop.robot_control.robot_hand_inspire import Inspire_Controller_DFX |
|
|
|
left_hand_pos_array = Array('d', 75, lock = True) # [input] |
|
|
|
right_hand_pos_array = Array('d', 75, lock = True) # [input] |
|
|
|
dual_hand_data_lock = Lock() |
|
|
|
@ -177,6 +177,7 @@ if __name__ == '__main__': |
|
|
|
dual_hand_action_array = Array('d', 12, lock = False) # [output] current left, right hand action(12) data. |
|
|
|
hand_ctrl = Inspire_Controller_DFX(left_hand_pos_array, right_hand_pos_array, dual_hand_data_lock, dual_hand_state_array, dual_hand_action_array, simulation_mode=args.sim) |
|
|
|
elif args.ee == "inspire_ftp": |
|
|
|
from teleop.robot_control.robot_hand_inspire import Inspire_Controller_FTP |
|
|
|
left_hand_pos_array = Array('d', 75, lock = True) # [input] |
|
|
|
right_hand_pos_array = Array('d', 75, lock = True) # [input] |
|
|
|
dual_hand_data_lock = Lock() |
|
|
|
@ -184,6 +185,7 @@ if __name__ == '__main__': |
|
|
|
dual_hand_action_array = Array('d', 12, lock = False) # [output] current left, right hand action(12) data. |
|
|
|
hand_ctrl = Inspire_Controller_FTP(left_hand_pos_array, right_hand_pos_array, dual_hand_data_lock, dual_hand_state_array, dual_hand_action_array, simulation_mode=args.sim) |
|
|
|
elif args.ee == "brainco": |
|
|
|
from teleop.robot_control.robot_hand_brainco import Brainco_Controller |
|
|
|
left_hand_pos_array = Array('d', 75, lock = True) # [input] |
|
|
|
right_hand_pos_array = Array('d', 75, lock = True) # [input] |
|
|
|
dual_hand_data_lock = Lock() |
|
|
|
@ -463,6 +465,9 @@ if __name__ == '__main__': |
|
|
|
|
|
|
|
except KeyboardInterrupt: |
|
|
|
logger_mp.info("KeyboardInterrupt, exiting program...") |
|
|
|
except Exception: |
|
|
|
import traceback |
|
|
|
logger_mp.error(traceback.format_exc()) |
|
|
|
finally: |
|
|
|
try: |
|
|
|
arm_ctrl.ctrl_dual_arm_go_home() |
|
|
|
@ -490,8 +495,9 @@ if __name__ == '__main__': |
|
|
|
|
|
|
|
try: |
|
|
|
if not args.motion: |
|
|
|
status, result = motion_switcher.Exit_Debug_Mode() |
|
|
|
logger_mp.info(f"Exit debug mode: {'Success' if status == 3104 else 'Failed'}") |
|
|
|
pass |
|
|
|
# status, result = motion_switcher.Exit_Debug_Mode() |
|
|
|
# logger_mp.info(f"Exit debug mode: {'Success' if status == 3104 else 'Failed'}") |
|
|
|
except Exception as e: |
|
|
|
logger_mp.error(f"Failed to exit debug mode: {e}") |
|
|
|
|
|
|
|
|