z1_sdk/examples_py/example_highcmd.py

46 lines
1.2 KiB
Python
Raw Normal View History

2023-01-30 20:28:13 +08:00
import sys
sys.path.append("../lib")
import unitree_arm_interface
import time
import numpy as np
2024-09-25 10:21:03 +08:00
np.set_printoptions(precision=3, suppress=True)
2023-01-30 20:28:13 +08:00
2023-02-09 10:32:09 +08:00
print("Press ctrl+\ to quit process.")
2023-02-02 18:25:14 +08:00
arm = unitree_arm_interface.ArmInterface(hasGripper=True)
2023-01-30 20:28:13 +08:00
armState = unitree_arm_interface.ArmFSMState
arm.loopOn()
# 1. highcmd_basic : armCtrlInJointCtrl
arm.labelRun("forward")
arm.startTrack(armState.JOINTCTRL)
2023-07-06 16:09:07 +08:00
jnt_speed = 1.0
2023-01-30 20:28:13 +08:00
for i in range(0, 1000):
2024-09-25 10:21:03 +08:00
# dp = directions * speed; include 7 joints
arm.jointCtrlCmd([0,0,0,-1,0,0,-1], jnt_speed)
2023-02-02 18:25:14 +08:00
time.sleep(arm._ctrlComp.dt)
2023-01-30 20:28:13 +08:00
# 2. highcmd_basic : armCtrlByFSM
arm.labelRun("forward")
2023-07-06 16:09:07 +08:00
gripper_pos = 0.0
jnt_speed = 2.0
2024-09-25 10:21:03 +08:00
arm.MoveJ([0.5,0.1,0.1,0.5,-0.2,0.5], gripper_pos, jnt_speed)
2023-07-06 16:09:07 +08:00
gripper_pos = -1.0
cartesian_speed = 0.5
2024-09-25 10:21:03 +08:00
arm.MoveL([0,0,0,0.45,-0.2,0.2], gripper_pos, cartesian_speed)
2023-07-06 16:09:07 +08:00
gripper_pos = 0.0
2024-09-25 10:21:03 +08:00
arm.MoveC([0,0,0,0.45,0,0.4], [0,0,0,0.45,0.2,0.2], gripper_pos, cartesian_speed)
2023-01-30 20:28:13 +08:00
# 3. highcmd_basic : armCtrlInCartesian
arm.labelRun("forward")
arm.startTrack(armState.CARTESIAN)
2023-07-06 16:09:07 +08:00
angular_vel = 0.3
linear_vel = 0.3
2023-01-30 20:28:13 +08:00
for i in range(0, 1000):
2024-09-25 10:21:03 +08:00
arm.cartesianCtrlCmd([0,0,0,0,0,-1,-1], angular_vel, linear_vel)
2023-02-02 18:25:14 +08:00
time.sleep(arm._ctrlComp.dt)
2023-01-30 20:28:13 +08:00
arm.backToStart()
arm.loopOff()