-
Notifications
You must be signed in to change notification settings - Fork 6
/
dvrk_data_collect.py
executable file
·184 lines (151 loc) · 7.09 KB
/
dvrk_data_collect.py
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
#!/usr/bin/env python2
# derived from dvrk_bag_replay
import crtk
import os
import sys
import csv
import time
import signal
import numpy as np
import rospy
import rosbag
import numpy
import PyKDL
import argparse
import subprocess
# simplified arm class to replay motion, better performance than
# dvrk.psm since we're only subscribing to topics we need
class arm_custom:
# simplified jaw class to close gripper
class __Jaw:
def __init__(self, ros_namespace, expected_interval, operating_state_instance):
self.__crtk_utils = crtk.utils(self, ros_namespace, expected_interval, operating_state_instance)
self.__crtk_utils.add_move_jp()
def __init__(self, device_namespace, expected_interval):
# ROS initialization
if not rospy.get_node_uri():
rospy.init_node('simplified_arm_class', anonymous = True, log_level = rospy.WARN)
# populate this class with all the ROS topics we need
self.crtk_utils = crtk.utils(self, device_namespace, expected_interval)
self.crtk_utils.add_operating_state()
self.crtk_utils.add_servo_jp()
self.crtk_utils.add_move_jp()
self.jaw = self.__Jaw(device_namespace + '/jaw', expected_interval, operating_state_instance = self)
# helper function to kill the rosbag process
def terminate_process_and_children(p):
ps_command = subprocess.Popen("ps -o pid --ppid %d --noheaders" % p.pid, shell=True, stdout=subprocess.PIPE)
ps_output = ps_command.stdout.read()
retcode = ps_command.wait()
assert retcode == 0, "ps command returned %d" % retcode
for pid_str in ps_output.split(b'\n')[:-1]:
os.kill(int(pid_str), signal.SIGINT)
p.terminate()
if sys.version_info.major < 3:
input = raw_input
# ---------------------------------------------
# ros setup
# ---------------------------------------------
# ros init node
rospy.init_node('dvrk_data_collection', anonymous=True)
# strip ros arguments
argv = rospy.myargv(argv=sys.argv)
# ---------------------------------------------
# parse arguments
# ---------------------------------------------
parser = argparse.ArgumentParser()
parser.add_argument('-a', '--arm', type=str, required=True,
choices=['ECM', 'MTML', 'MTMR', 'PSM1', 'PSM2', 'PSM3'],
help='arm name corresponding to ROS topics without namespace.')
parser.add_argument('-f', '--csv', type=argparse.FileType('r'), required=True,
help='csv file containing the trajectory to replay.')
parser.add_argument('-s', '--setup', type=str, required=True,
choices=['PSM', 'PSM-SUJ'],
help='description of your dvrk setup, necessary for collect shell script selection.')
parser.add_argument('-c', '--config', type=str, required=False, default='1',
help='index of your current configuration, if you changed SUJ position, please use another index. e.g., \"-c 1\" for configuration 1 and \"-c 2\" for for configuration 1')
args = parser.parse_args(argv[1:]) # skip argv[0], script name
# ---------------------------------------------
# prepare rosbag script
# ---------------------------------------------
# create data folder
if not os.path.exists(os.path.join(os.getcwd(), 'data')):
os.mkdir(os.path.join(os.getcwd(), 'data'))
# create configuration sub_folder
folder_name = os.path.join(os.getcwd(), 'data')
sub_folder_name = os.path.join(os.getcwd(), os.path.join('data', (args.config)))
if not os.path.exists(sub_folder_name):
os.mkdir(sub_folder_name)
# determine script based on setup
PSM_id = args.arm.strip('PSM')
if args.setup == 'PSM':
command = "rosbag record -O {0}_{1}.bag /{1}/tool_type /{1}/measured_cp /{1}/measured_js /{1}/jaw/measured_js /{1}/spatial/jacobian".format(os.path.join(sub_folder_name,
os.path.basename(args.csv.name).split('.csv')[0]),
'PSM'+str(PSM_id))
# sanity check command
sanity_cmd = "rosbag info {0}_{1}.bag".format(os.path.join(sub_folder_name, os.path.basename(args.csv.name).split('.csv')[0]), 'PSM'+str(PSM_id))
elif args.setup == 'PSM-SUJ':
command = "rosbag record -O {0}_{1}_SUJ.bag /{1}/measured_cp /{1}/measured_js /{1}/jaw/measured_js /{1}/spatial/jacobian /SUJ/{1}/measured_cp /SUJ/{1}/measured_js".format(os.path.join(sub_folder_name, os.path.basename(args.csv.name).split('.csv')[0]), 'PSM'+str(PSM_id))
# sanity check command
sanity_cmd = "rosbag info {0}_{1}_SUJ.bag".format(os.path.join(sub_folder_name, os.path.basename(args.csv.name).split('.csv')[0]), 'PSM'+str(PSM_id))
else:
sys.exit('-- Unsupported setup')
# ---------------------------------------------
# read commanded joint position
# ---------------------------------------------
poses = []
with open(args.csv.name) as csvfile:
for pose in csv.reader(csvfile, delimiter=','):
poses.append(np.array(pose).astype(float))
csvfile.close()
# ---------------------------------------------
# prepare psm
# ---------------------------------------------
print('-- This script will replay a trajectory defined in %s on arm %s' % (args.csv.name, args.arm))
# create arm
arm = arm_custom(device_namespace=args.arm, expected_interval=0.001)
# make sure the arm is powered
print('-- Enabling arm')
if not arm.enable(10):
sys.exit('-- Failed to enable within 10 seconds')
print('-- Homing arm')
if not arm.home(10):
sys.exit('-- Failed to home within 10 seconds')
input('---> Make sure the arm is ready to move using joint positions\n You need to have a tool/instrument in place and properly engaged\n Press "Enter" when the arm is ready')
# close gripper
input('---> Press \"Enter\" to close the instrument\'s jaws')
jaw_jp = np.array([-20.0 * np.pi / 180.0])
arm.jaw.move_jp(jaw_jp).wait()
# go to initial position and wait
input('---> Press \"Enter\" to move to start position')
jp = poses[0]
arm.move_jp(jp).wait()
# ---------------------------------------------
# start playing trajectory and data collection
# ---------------------------------------------
# play trajectory
input('---> Press \"Enter\" to replay the recorded trajectory and collect data')
# run shell script
rosbag_process = subprocess.Popen(command.split(' '))
time.sleep(2)
# main play process
counter = 0
total = len(poses)
start_time = time.time()
for pose in poses:
start_t = time.time()
arm.servo_jp(pose)
counter = counter + 1
# report progress
sys.stdout.write('\r-- Progress %02.1f%%' % (float(counter) / float(total) * 100.0))
sys.stdout.flush()
end_t = time.time()
delta_t = 0.0018 - (end_t - start_t)
# if process takes time larger than console rate, don't sleep
if delta_t > 0:
time.sleep(delta_t)
# stop bagging
terminate_process_and_children(rosbag_process)
print('\n--> Time to replay trajectory: %f seconds' % (time.time() - start_time))
print('--> Done!')
# check if required topics are collected correctly
os.system(sanity_cmd)