-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathcoppeliasim.py
276 lines (236 loc) · 11.7 KB
/
coppeliasim.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
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
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
# =============================================================== #
# Coppeliasim Library
# July 2, 2022
# @yudarismawahyudi
# =============================================================== #
# Please add these following files in your project folder:
# 1. sim.py
# 2. simConst.py
# 3. remoteApi.dll (Windows) or remoteApi.so (linux)
import math
import sim
import time
# ==========================================================================
# CoppeliaSim Class
# ==========================================================================
class CoppeliaSim:
clientId = 0
connected = False
def __init__(self):
self.clientID = 0
def connect(self, port):
sim.simxFinish(-1)
self.clientID = sim.simxStart('127.0.0.1', port, True, True, 5000, 5)
CoppeliaSim.clientId = self.clientID
if self.clientID != -1:
sim.simxStartSimulation(self.clientID, sim.simx_opmode_blocking)
print('Connected to remote API server')
else:
print('Failed connecting to remote API server')
return self.clientID
def getObjectHandle(self, objName):
res, handle = sim.simxGetObjectHandle(self.clientID, objName, sim.simx_opmode_blocking)
return handle
def disconnect(self):
sim.simxStopSimulation(self.clientID, sim.simx_opmode_blocking)
def startSimulation(self):
sim.simxStartSimulation(self.clientID, sim.simx_opmode_blocking)
def stopSimulation(self):
sim.simxStopSimulation(self.clientID, sim.simx_opmode_blocking)
# =======================================================================
# Class Coppelia Arm Robot
# =======================================================================
class CoppeliaArmRobot(CoppeliaSim):
def __init__(self, robot_name):
self.clientID = CoppeliaSim.clientId
self.robot_name = robot_name
self.targetName = "./" + robot_name + '/ikTarget'
self.ftSensorName = './' + robot_name + '/force_sensor'
# Retrieve object handle
res, self.robot_handle = sim.simxGetObjectHandle(self.clientID, robot_name, sim.simx_opmode_oneshot_wait)
res, self.target_handle = sim.simxGetObjectHandle(self.clientID, self.targetName, sim.simx_opmode_oneshot_wait)
res, self.ftSensor_handle = sim.simxGetObjectHandle(self.clientID, self.ftSensorName, sim.simx_opmode_oneshot_wait)
# Start position data streaming
self.script = '/' + robot_name
sim.simxCallScriptFunction(self.clientID, self.script,
sim.sim_scripttype_childscript,
'remoteApi_getPosition',
[], [], [], '',
sim.simx_opmode_streaming)
# Start joint position data streaming
sim.simxCallScriptFunction(self.clientID, self.script,
sim.sim_scripttype_childscript,
'remoteApi_getJointPosition',
[], [], [], '',
sim.simx_opmode_streaming)
# Moving status data streaming
sim.simxGetInt32Signal(self.clientID, 'moving_status', sim.simx_opmode_streaming)
sim.simxGetStringSignal(self.clientID, 'moving_signal', sim.simx_opmode_streaming)
# Print robot handle data
print("\n>>> Arm robot initialization: ", robot_name)
print("Robot handle = ", self.robot_handle)
print("\n")
def readObjectHandle(self):
print('Robot handle = %d' % self.robot_handle)
print('Target handle = %d' % self.target_handle)
def getObjectPosition(self, obj_name):
res, handle = sim.simxGetObjectHandle(self.clientID, obj_name, sim.simx_opmode_oneshot_wait)
res, pos = sim.simxGetObjectPosition(self.clientID, handle, self.robot_handle, sim.simx_opmode_oneshot_wait)
res, ori = sim.simxGetObjectOrientation(self.clientID, handle, self.robot_handle, sim.simx_opmode_oneshot_wait)
ret = [0, 0, 0, 0, 0, 0]
for i in range(3):
ret[i] = pos[i] * 1000
ret[i + 3] = ori[i] * 180 / 3.14
return ret
# Get current robot position
def readPosition(self):
self.posData = [0,0,0,0,0,0]
ret = sim.simxCallScriptFunction(self.clientID, self.script,
sim.sim_scripttype_childscript,
'remoteApi_getPosition',
[], [], [], '',
sim.simx_opmode_buffer)
if ret[0] == sim.simx_return_ok:
self.posData = ret[2]
for i in range(3):
self.posData[i] = self.posData[i] * 1000
self.posData[i + 3] = self.posData[i + 3] * 180 / 3.14
return self.posData
# ===================================================================
# Get current joint position
def readJointPosition(self):
self.jointPos = [0,0,0,0,0,0]
ret = sim.simxCallScriptFunction(self.clientID, self.script,
sim.sim_scripttype_childscript,
'remoteApi_getJointPosition',
[], [], [], '',
sim.simx_opmode_buffer)
if ret[0] == sim.simx_return_ok:
self.jointPos = ret[2]
for i in range(6):
self.jointPos[i] = self.jointPos[i] * 180 / math.pi
else:
print("ERROR: Read joint position failed!")
return self.jointPos
# ===================================================================
# Standard set robot position
def setPosition(self, pos):
cmdPos = [0, 0, 0, 0, 0, 0]
for i in range(3):
cmdPos[i] = pos[i] / 1000
cmdPos[i + 3] = pos[i + 3] * 3.141592 / 180
ret = sim.simxCallScriptFunction(self.clientID, self.script,
sim.sim_scripttype_childscript,
'remoteApi_movePosition',
[], cmdPos, [], '',
sim.simx_opmode_blocking)
# ===================================================================
# Set robot positon with wait signal
def setPosition2(self, pos, wait=True):
self.setPosition(pos)
if wait:
while True:
time.sleep(0.1)
if self.isMoving() == 'NOT_MOVING':
break
# ===================================================================
# Set Joint Position
def setJointPosition(self, pos, wait):
cmdPos = [0, 0, 0, 0, 0, 0]
for i in range(6):
cmdPos[i] = pos[i] * math.pi / 180
ret = sim.simxCallScriptFunction(self.clientID, self.script,
sim.sim_scripttype_childscript,
'remoteApi_moveJointPosition',
[], cmdPos, [], '',
sim.simx_opmode_blocking)
if wait:
while True:
if self.isMoving() == 'NOT_MOVING':
break
# ===================================================================
# Check whether the robot is moving
def isMoving(self):
ret, s = sim.simxGetStringSignal(self.clientID, 'moving_signal', sim.simx_opmode_buffer)
s = s.decode('ascii')
return s
# Set Robot Speed: 0 - 100
def setSpeed(self, lin_vel, ang_vel):
command = [0,0]
command[0] = lin_vel / 1000
command[1] = ang_vel * math.pi / 180
ret = sim.simxCallScriptFunction(self.clientID, self.script,
sim.sim_scripttype_childscript,
'remoteApi_setSpeed',
[], command, [], '',
sim.simx_opmode_blocking)
# ===================================================================
# Catch Gripper
def gripperCatch(self):
command = [0,0]
command[0] = 0
ret = sim.simxCallScriptFunction(self.clientID, self.script,
sim.sim_scripttype_childscript,
'remoteApi_setGripper',
command, [], [], '',
sim.simx_opmode_blocking)
# Release Gripper
def gripperRelease(self):
command = [0,0]
command[0] = 1
ret = sim.simxCallScriptFunction(self.clientID, self.script,
sim.sim_scripttype_childscript,
'remoteApi_setGripper',
command, [], [], '',
sim.simx_opmode_blocking)
# Suction ON
def suctionON(self):
ret = sim.simxCallScriptFunction(self.clientID, self.script,
sim.sim_scripttype_childscript,
'remoteApi_suctionOn',
[], [], [], '',
sim.simx_opmode_blocking)
# Suction OFF
def suctionOFF(self):
ret = sim.simxCallScriptFunction(self.clientID, self.script,
sim.sim_scripttype_childscript,
'remoteApi_suctionOff',
[], [], [], '',
sim.simx_opmode_blocking)
# =======================================================================
# Class Coppelia Sensors
# =======================================================================
class CoppeliaSensor(CoppeliaSim):
def __init__(self, sensorName, sensorType):
self.sensorHandle = 0
self.clientId = CoppeliaSim.clientId
res, self.sensorHandle = sim.simxGetObjectHandle(self.clientId, sensorName, sim.simx_opmode_oneshot_wait)
if self.sensorHandle != 0:
if sensorType == "Vision":
ret, resolution, image = sim.simxGetVisionSensorImage(self.clientId, self.sensorHandle, 0, sim.simx_opmode_streaming)
#elif sensorType == "Proximity":
# ret = sim.simxReadProximitySensor(self.clientId, self.sensorHandle,sim.simx_opmode_streaming)
# ========================================================
def getImage(self):
ret, resolution, image = sim.simxGetVisionSensorImage(self.clientId, self.sensorHandle, 0, sim.simx_opmode_buffer)
return ret, resolution, image
def getProximityStatus(self):
res, dist, point, obj, n = sim.simxReadProximitySensor(self.clientId, self.sensorHandle,sim.simx_opmode_blocking)
return res, dist
# Conveyor:
class Conveyor(CoppeliaSim):
def __init__(self, ObjName):
self.conveyorHandle = 0
self.script = '/UR10'
res, self.conveyorHandle = sim.simxGetObjectHandle(self.clientId, ObjName, sim.simx_opmode_oneshot_wait)
print("Conveyor Handle = ", self.conveyorHandle)
def setSpeed(self, speed):
# Set Conveyor Sped
_speed = [speed]
_handle = [self.conveyorHandle]
ret = sim.simxCallScriptFunction(self.clientId, self.script,
sim.sim_scripttype_childscript,
'remoteApi_setConveyorSpeed',
_handle, _speed, [], '',
sim.simx_opmode_blocking)
print("Set conveyor speed = ", speed)