| 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 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 |
| 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): |
| |
| self.workspace_limits = np.asarray(self.WORKSPACE_LIMITS) |
| self.workspace_limits *= self.SCALING |
|
|
| |
| self.use_camera = False |
|
|
| |
| self.has_object = False |
| self.obj_id = None |
|
|
| |
|
|
| |
| self._duration = 0.1 |
|
|
| |
| self.distance_threshold = self.DISTANCE_THRESHOLD * self.SCALING |
|
|
| |
| 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') |
| |
| |
| 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)) |
|
|
| |
| self.ecm = Ecm(self.POSE_ECM[0], p.getQuaternionFromEuler(self.POSE_ECM[1]), |
| scaling=self.SCALING) |
| |
| def run(name): |
| |
| robot = dvrk.ecm('ECM') |
| |
| |
| |
| |
| |
| |
|
|
| |
| d2r = math.pi / 180.0 |
| 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) |
| |
| |
| 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() |
| |
| |
| |
| |
|
|
| |
| |
| |
| |
|
|
| |
|
|
| |
|
|
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
|
|
| |
| |
| |
| |
| |
|
|
|
|
| if __name__ == '__main__': |
| |
|
|
| |
| 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') |