z1_sdk/examples_py/example_lowcmd.py

28 lines
813 B
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
np.set_printoptions(precision=3, suppress=True)
2023-02-02 18:25:14 +08:00
arm = unitree_arm_interface.ArmInterface(hasGripper=True)
armModel = arm._ctrlComp.armModel
2023-01-30 20:28:13 +08:00
arm.setFsmLowcmd()
duration = 1000
lastPos = arm.lowstate.getQ()
targetPos = np.array([0.0, 1.5, -1.0, -0.54, 0.0, 0.0]) #forward
for i in range(0, duration):
arm.q = lastPos*(1-i/duration) + targetPos*(i/duration)# set position
arm.qd = (targetPos-lastPos)/(duration*0.002) # set velocity
2023-02-02 18:25:14 +08:00
arm.tau = armModel.inverseDynamics(arm.q, arm.qd, np.zeros(6), np.zeros(6)) # set torque
2023-01-30 20:28:13 +08:00
arm.gripperQ = -1*(i/duration)
arm.sendRecv()# udp connection
2023-02-02 18:25:14 +08:00
# print(arm.lowstate.getQ())
time.sleep(arm._ctrlComp.dt)
2023-01-30 20:28:13 +08:00
arm.loopOn()
arm.backToStart()
arm.loopOff()