import time import math import sys import csv import datetime import crtk import dvrk import numpy import argparse import surrol from surrol.robots.ecm import Ecm import pybullet as p import numpy as np from surrol.utils.pybullet_utils import * from surrol.tasks.ecm_env import EcmEnv, goal_distance import torch import torch.nn as nn import numpy as np import os import cv2 import dvrk import PyKDL from PIL import Image import matplotlib.pyplot as plt import yaml import math from scipy.spatial.transform import Rotation as R # def cVc_to_dq(robot, sim_robot, cVc: np.ndarray) -> np.ndarray: # """ # convert the camera velocity in its own frame (cVc) into the joint velocity q_dot # """ # cVc = cVc.reshape((3, 1)) # # restrict the step size, need tune # if np.abs(cVc).max() > 0.01: # cVc = cVc / np.abs(cVc).max() * 0.01 # # Forward kinematics # q = robot.measured_jp() # bRe = sim_robot.robot.fkine(q).R # use rtb instead of PyBullet, no tool_tip_offset # orn_cam = robot.measured_cp().M # wRc = np.array(p.getMatrixFromQuaternion(orn_cam)).reshape((3, 3)) # # Rotation # R1, R2 = self._wRc0, wRc # x = R1[0, 0] * R2[1, 0] - R1[1, 0] * R2[0, 0] + R1[0, 1] * R2[1, 1] - R1[1, 1] * R2[0, 1] # y = R1[0, 0] * R2[1, 1] - R1[1, 0] * R2[0, 1] - R1[0, 1] * R2[1, 0] + R1[1, 1] * R2[0, 0] # dz = np.arctan(x / y) # k1, k2 = 25.0, 0.1 # self._wz = k1 * dz * np.exp(-k2 * np.linalg.norm(self._homo_delta)) # # print(' -> x: {:.4f}, y: {:.4f}, dz: {:.4f}, wz: {:.4f}'.format(x, y, dz, self._wz)) # # Pseudo Solution # d = self._tip_offset # Jd = np.matmul(self._eRc, # np.array([[0, 0, d, 0], # [0, -d, 0, 0], # [1, 0, 0, 0]])) # Je = np.matmul(self._eRc, # np.array([[0, 1, 0, 0], # [0, 0, 1, 0], # [0, 0, 0, 1]])) # eVe4 = np.dot(np.linalg.pinv(Jd), cVc) \ # + np.dot(np.dot((np.eye(4) - np.dot(np.linalg.pinv(Jd), Jd)), np.linalg.pinv(Je)), # np.array([[0], [0], [self._wz]])) # eVe = np.zeros((6, 1)) # eVe[2: 6] = eVe4[0: 4] # Q = np.zeros((6, 6)) # Q[0: 3, 0: 3] = - bRe # Q[3: 6, 3: 6] = - bRe # bVe = np.dot(Q, eVe) # # Compute the Jacobian matrix # bJe = self.get_jacobian_spatial() # dq = np.dot(np.linalg.pinv(bJe), bVe) # # print(" -> cVc: {}, q: {}, dq: {}".format(list(np.round(cVc.flatten(), 4)), q, list(dq.flatten()))) # return dq.flatten() def reset_camera(yaw=50.0, pitch=-35.0, dist=5.0, target=(0.0, 0.0, 0.0)): p.resetDebugVisualizerCamera( cameraDistance=dist, cameraYaw=yaw, cameraPitch=pitch, cameraTargetPosition=target) def get_camera(): return CameraInfo(*p.getDebugVisualizerCamera()) def render_image(width, height, view_matrix, proj_matrix, shadow=1): (_, _, px, _, mask) = p.getCameraImage(width=width, height=height, viewMatrix=view_matrix, projectionMatrix=proj_matrix, shadow=shadow, lightDirection=(10, 0, 10), renderer=p.ER_BULLET_HARDWARE_OPENGL) rgb_array = np.array(px, dtype=np.uint8) rgb_array = np.reshape(rgb_array, (height, width, 4)) rgb_array = rgb_array[:, :, :3] return rgb_array, mask class Sim_ECM(EcmEnv): ACTION_SIZE = 3 # (dx, dy, dz) or cVc or droll (1) ACTION_MODE = 'cVc' DISTANCE_THRESHOLD = 0.005 POSE_ECM = ((0.15, 0.0, 0.7524), (0, 20 / 180 * np.pi, 0)) QPOS_ECM = (0, 0.6, 0.04, 0) WORKSPACE_LIMITS = ((0.45, 0.55), (-0.05, 0.05), (0.60, 0.70)) SCALING = 1. p = p.connect(p.GUI) def __init__(self, render_mode: str = None, cid = -1): # workspace self.workspace_limits = np.asarray(self.WORKSPACE_LIMITS) self.workspace_limits *= self.SCALING # camera self.use_camera = False # has_object self.has_object = False self.obj_id = None # super(Sim_ECM, self).__init__(render_mode, cid) # change duration self._duration = 0.1 # distance_threshold self.distance_threshold = self.DISTANCE_THRESHOLD * self.SCALING # render related setting self._view_matrix = p.computeViewMatrixFromYawPitchRoll( cameraTargetPosition=(0.27 * self.SCALING, -0.20 * self.SCALING, 0.55 * self.SCALING), distance=1.80 * self.SCALING, yaw=150, pitch=-30, roll=0, upAxisIndex=2 ) def reset_env(self): assert self.ACTION_MODE in ('cVc', 'dmove', 'droll') # camera reset_camera(yaw=150.0, pitch=-30.0, dist=1.50 * self.SCALING, target=(0.27 * self.SCALING, -0.20 * self.SCALING, 0.55 * self.SCALING)) # robot self.ecm = Ecm(self.POSE_ECM[0], p.getQuaternionFromEuler(self.POSE_ECM[1]), scaling=self.SCALING) def run(name): # create dVRK robot robot = dvrk.ecm('ECM') # # file to save data # now = datetime.datetime.now() # now_string = now.strftime("%Y-%m-%d-%H-%M") # csv_file_name = name + '-gc-' + now_string + '.csv' # print("Values will be saved in: ", csv_file_name) # # compute joint limits d2r = math.pi / 180.0 # degrees to radians lower_limits = [-80.0 * d2r, -40.0 * d2r, 0.005] upper_limits = [ 80.0 * d2r, 60.0 * d2r, 0.230] sim_ecm = Sim_ECM('human') sim_ecm.reset_env() current_dvrk_jp = robot.measured_jp() print('current dvrk jp: ',current_dvrk_jp) current_dvrk_pose = robot.measured_cp() state = current_dvrk_pose.M position = current_dvrk_pose.p ECM_rotate = np.array([[state[0,0], state[0,1], state[0,2]], [state[1,0], state[1,1], state[1,2]], [state[2,0], state[2,1], state[2,2]]]) ECM_position = np.array([position[0], position[1], position[2]]) print(ECM_position) ECM_quat = R.from_matrix(ECM_rotate).as_quat() print(ECM_quat) # transform_M[:3, :3] = orn # transform_M[:3, 3] = np.array(pos) sim_ecm.ecm.reset_joint(np.array(current_dvrk_jp)) print('current sim ecm jp: ', sim_ecm.ecm.get_current_joint_position()) print('current sim ecm position: ', sim_ecm._get_robot_state()) print('converted') while True: p.stepSimulation() # # set sampling for data # # increments = [40.0 * d2r, 40.0 * d2r, 0.10] # less samples # increments = [20.0 * d2r, 20.0 * d2r, 0.05] # more samples # directions = [1.0, 1.0, 1.0] # # start position # positions = [lower_limits[0], # lower_limits[1], # lower_limits[2]] # all_reached = False # robot.home() # while not all_reached: # next_dimension_increment = True # for index in range(3): # if next_dimension_increment: # future = positions[index] + directions[index] * increments[index] # if (future > upper_limits[index]): # directions[index] = -1.0 # if index == 2: # all_reached = True # elif (future < lower_limits[index]): # directions[index] = 1.0 # else: # positions[index] = future # next_dimension_increment = False # robot.move_jp(numpy.array([positions[0], # positions[1], # positions[2], # 0.0])).wait() # time.sleep(1.0) if __name__ == '__main__': # extract ros arguments (e.g. __ns:= for namespace) # parse arguments parser = argparse.ArgumentParser() parser.add_argument('-a', '--arm', type=str, required=True, choices=['ECM', 'PSM1', 'PSM2', 'PSM3'], help = 'arm name corresponding to ROS topics without namespace. Use __ns:= to specify the namespace') parser.add_argument('-i', '--interval', type=float, default=0.01, help = 'expected interval in seconds between messages sent by the device') run('ECM')