1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222
| import gym import numpy as np from gym import error, spaces
import diffusion_policy.env.gym_envs from diffusion_policy.env.gym_envs.utils import ctrl_set_action, mocap_set_action import cv2 import mujoco_py from diffusion_policy.env.gym_envs import rotations
from scipy.spatial.transform import Rotation as R
import forcedimension_core.containers as containers import forcedimension_core.dhd as dhd import forcedimension_core.drd as drd
import ctypes
dhd.open()
pos = np.zeros(3) matrix = np.zeros((3, 3)) gripper_pointer = ctypes.pointer(ctypes.c_double(0.0)) linear_velocity = np.zeros(3) angular_velocity = np.zeros(3) euler = np.zeros(3)
devicePosition = np.zeros(3) deviceRotation = np.zeros((3, 3)) deviceLinearVelocity = np.zeros(3) deviceAngularVelocity = np.zeros(3)
flagHoldPosition = True flagHoldPositionReady = True holdPosition = np.zeros(3) holdRotation = np.zeros((3, 3)) last_display_time = dhd.os_independent.getTime()
if drd.open() < 0: print("无法打开设备: " + drd.error()) dhd.os_independent.sleep(2) if not drd.isInitialized() and drd.autoInit() < 0: print("无法初始化设备: " + drd.error()) dhd.os_independent.sleep(2) if drd.start() < 0: print("无法启动设备: " + drd.error()) dhd.os_independent.sleep(2) if drd.moveToPos(pos, block=True) < 0: print("无法移动到位置: " + drd.error()) dhd.os_independent.sleep(2) if drd.moveToRot(euler, block=True) < 0: print("无法移动到旋转矩阵: " + drd.error()) dhd.os_independent.sleep(2) if drd.stop(True) < 0: print("无法停止设备: " + drd.error()) dhd.os_independent.sleep(2)
last_action = np.array([1.17, 0.75, 0.70, -np.pi, 0., -np.pi/2, 0.]) action_list = []
def quaternion2euler(quaternion): r = R.from_quat(quaternion) euler = r.as_euler('xyz', degrees=True) return euler
def euler2quaternion(euler): r = R.from_euler('xyz', euler, degrees=True) quaternion = r.as_quat() return quaternion
test_env = gym.make('PutInDrawer-v0') test_env.reset()
i=0
while True: dhd.getPositionAndOrientationFrame(pos, matrix) dhd.getGripperAngleDeg(gripper_pointer) gripper = gripper_pointer.contents.value dhd.getLinearVelocity(linear_velocity) dhd.getAngularVelocityDeg(angular_velocity)
devicePosition = pos deviceRotation = matrix deviceLinearVelocity = linear_velocity deviceAngularVelocity = angular_velocity deviceForce = np.zeros(3) deviceTorque = np.zeros(3) deviceGripperForce = 0.0
Kp = 2000.0 Kv = 10.0 Kr = 5.0 Kw = 0.05
if flagHoldPosition: if flagHoldPositionReady: force = -Kp * (devicePosition - holdPosition) - Kv * deviceLinearVelocity deltaRotation = np.transpose(deviceRotation) @ holdRotation axis, angle = np.zeros(3), 0.0 angle = np.arccos((np.trace(deltaRotation) - 1) / 2) if angle > 1e-6: axis = np.array([deltaRotation[2, 1] - deltaRotation[1, 2], deltaRotation[0, 2] - deltaRotation[2, 0], deltaRotation[1, 0] - deltaRotation[0, 1]]) / (2 * np.sin(angle)) torque = deviceRotation @ ((Kr * angle) * axis) - Kw * deviceAngularVelocity
deviceForce = deviceForce + force deviceTorque = deviceTorque + torque else: holdPosition = devicePosition holdRotation = deviceRotation flagHoldPositionReady = True
MaxTorque = 0.3 if np.linalg.norm(deviceTorque) > MaxTorque: deviceTorque = MaxTorque * deviceTorque / np.linalg.norm(deviceTorque)
if dhd.setForceAndTorqueAndGripperForce(np.zeros(3), np.zeros(3), 0.0) < 0: print("无法设置力和力矩: " + dhd.error()) dhd.os_independent.sleep(2) break
if dhd.os_independent.kbHit(): keyboard = dhd.os_independent.kbGet() if keyboard == ' ': continue if keyboard == 'q': break
device_time = dhd.os_independent.getTime() if device_time - last_display_time > 0.1: last_display_time = device_time print("Pos (%.3f %.3f %.3f) m | Gripper %.3f deg | Rot (%.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f) | Force (%.3f %.3f %.3f) N | Freq %.2f kHz \r" % (pos[0], pos[1], pos[2], gripper, matrix[0, 0], matrix[0, 1], matrix[0, 2], matrix[1, 0], matrix[1, 1], matrix[1, 2], matrix[2, 0], matrix[2, 1], matrix[2, 2], deviceForce[0], deviceForce[1], deviceForce[2], dhd.getComFreq()), end="\r", flush=True)
action_pos = pos action_matrix = matrix action_gripper = gripper
action_pos[0] = pos[0]*7 action_pos[1] = pos[1]*6 action_pos[2] = pos[2]*4
action_matrix *= 0.05 matrix_rotation_x_180 = np.array([[1, 0, 0], [0, -1, 0], [0, 0, -1]]) matrix_rotation_z_n90 = np.array([[0, 1, 0], [-1, 0, 0], [0, 0, 1]]) action_matrix = np.dot(action_matrix, matrix_rotation_x_180) action_matrix = np.dot(action_matrix, matrix_rotation_z_n90)
action_quat = rotations.mat2quat(action_matrix) action_gripper = abs((action_gripper - 30.0) / 30.0)
action = np.concatenate([action_pos, action_quat, [action_gripper]]) test_env.step(action)
test_env.render(mode="human")
action_list.append(action)
action_list = np.array(action_list)
if drd.close() < 0: print("无法关闭设备: " + drd.error()) dhd.os_independent.sleep(2) print("\n设备已关闭")
|