Skip to content

Commit 091da29

Browse files
committed
fix: MycobotCommandGenerater.method return not right.
1 parent bba258f commit 091da29

File tree

4 files changed

+190
-119
lines changed

4 files changed

+190
-119
lines changed

pymycobot/generate.py

Lines changed: 44 additions & 118 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,3 @@
1-
import time
21
import math
32
import logging
43
import sys
@@ -138,10 +137,10 @@ def version(self): # TODO: test method <11-03-21, yourname> #
138137

139138
# Overall status
140139
def power_on(self):
141-
self._mesg(Command.POWER_ON)
140+
return self._mesg(Command.POWER_ON)
142141

143142
def power_off(self):
144-
self._mesg(Command.POWER_OFF)
143+
return self._mesg(Command.POWER_OFF)
145144

146145
def is_power_on(self):
147146
"""Adjust robot arm status
@@ -151,15 +150,13 @@ def is_power_on(self):
151150
0 : power off
152151
-1: error data
153152
"""
154-
return self._process_single(self._mesg(Command.IS_POWER_ON, has_reply=True))
153+
return self._mesg(Command.IS_POWER_ON, has_reply=True)
155154

156155
def release_all_servos(self):
157-
self._mesg(Command.RELEASE_ALL_SERVOS)
156+
return self._mesg(Command.RELEASE_ALL_SERVOS)
158157

159158
def is_controller_connected(self):
160-
return self._process_single(
161-
self._mesg(Command.IS_CONTROLLER_CONNECTED, has_reply=True)
162-
)
159+
return self._mesg(Command.IS_CONTROLLER_CONNECTED, has_reply=True)
163160

164161
"""
165162
def set_free_mode(self, flag): # TODO:no finish
@@ -179,8 +176,7 @@ def get_angles(self):
179176
Return:
180177
data_list (list[angle...]):
181178
"""
182-
angles = self._mesg(Command.GET_ANGLES, has_reply=True)
183-
return [self._int_to_angle(angle) for angle in angles]
179+
return self._mesg(Command.GET_ANGLES, has_reply=True)
184180

185181
def send_angle(self, id, degree, speed):
186182
"""Send one angle
@@ -191,7 +187,9 @@ def send_angle(self, id, degree, speed):
191187
speed (int): 0 ~100
192188
"""
193189
check_datas(joint_id=id, degree=degree, speed=speed)
194-
self._mesg(Command.SEND_ANGLE, id - 1, [self._angle_to_int(degree)], speed)
190+
return self._mesg(
191+
Command.SEND_ANGLE, id - 1, [self._angle_to_int(degree)], speed
192+
)
195193

196194
# @check_parameters(Command.SEND_ANGLES)
197195
def send_angles(self, degrees, speed):
@@ -204,38 +202,6 @@ def send_angles(self, degrees, speed):
204202
check_datas(degrees=degrees, len6=degrees, speed=speed)
205203
degrees = [self._angle_to_int(degree) for degree in degrees]
206204
# data = [degrees, speed]
207-
self._mesg(Command.SEND_ANGLES, degrees, speed)
208-
209-
def sync_send_angles(self, degrees, speed, timeout=7):
210-
t = time.time()
211-
self.send_angles(degrees, speed)
212-
while time.time() - t < timeout:
213-
f = self.is_in_position(degrees, 0)
214-
if f:
215-
break
216-
time.sleep(0.1)
217-
return self
218-
219-
def get_radians(self):
220-
"""Get all angle return a list
221-
222-
Return:
223-
data_list (list[radian...]):
224-
"""
225-
angles = self._mesg(Command.GET_ANGLES, has_reply=True)
226-
return [
227-
round(self._int_to_angle(angle) * (math.pi / 180), 3) for angle in angles
228-
]
229-
230-
def send_radians(self, radians, speed):
231-
"""Send all angles
232-
233-
Args:
234-
radians (list): example [0, 0, 0, 0, 0, 0]
235-
speed (int): 0 ~ 100
236-
"""
237-
check_datas(len6=radians, speed=speed)
238-
degrees = [self._angle_to_int(radian * (180 / math.pi)) for radian in radians]
239205
return self._mesg(Command.SEND_ANGLES, degrees, speed)
240206

241207
def get_coords(self):
@@ -244,16 +210,7 @@ def get_coords(self):
244210
Return:
245211
data_list (list): [x, y, z, rx, ry, rz]
246212
"""
247-
received = self._mesg(Command.GET_COORDS, has_reply=True)
248-
if not received:
249-
return received
250-
251-
res = []
252-
for idx in range(3):
253-
res.append(self._int_to_coord(received[idx]))
254-
for idx in range(3, 6):
255-
res.append(self._int_to_angle(received[idx]))
256-
return res
213+
return self._mesg(Command.GET_COORDS, has_reply=True)
257214

258215
def send_coord(self, id, coord, speed):
259216
"""Send one coord
@@ -282,28 +239,19 @@ def send_coords(self, coords, speed, mode):
282239
coord_list.append(self._coord_to_int(coords[idx]))
283240
for idx in range(3, 6):
284241
coord_list.append(self._angle_to_int(coords[idx]))
285-
self._mesg(Command.SEND_COORDS, coord_list, speed, mode)
286-
287-
def sync_send_coords(self, coords, speed, mode, timeout=7):
288-
t = time.time()
289-
self.send_coords(coords, speed, mode)
290-
while time.time() - t < timeout:
291-
if self.is_in_position(coords, 1):
292-
break
293-
time.sleep(0.1)
294-
return self
242+
return self._mesg(Command.SEND_COORDS, coord_list, speed, mode)
295243

296244
def pause(self):
297-
self._mesg(Command.PAUSE)
245+
return self._mesg(Command.PAUSE)
298246

299247
def is_paused(self):
300-
return self._process_single(self._mesg(Command.IS_PAUSED, has_reply=True))
248+
return self._mesg(Command.IS_PAUSED, has_reply=True)
301249

302250
def resume(self):
303-
self._mesg(Command.RESUME)
251+
return self._mesg(Command.RESUME)
304252

305253
def stop(self):
306-
self._mesg(Command.STOP)
254+
return self._mesg(Command.STOP)
307255

308256
def is_in_position(self, data, id):
309257
"""
@@ -328,8 +276,7 @@ def is_in_position(self, data, id):
328276
else:
329277
raise Exception("id is not right, please input 0 or 1")
330278

331-
received = self._mesg(Command.IS_IN_POSITION, data_list, id, has_reply=True)
332-
return self._process_single(received)
279+
return self._mesg(Command.IS_IN_POSITION, data_list, id, has_reply=True)
333280

334281
def is_moving(self):
335282
"""
@@ -339,7 +286,7 @@ def is_moving(self):
339286
1 : is moving
340287
-1: error data
341288
"""
342-
return self._process_single(self._mesg(Command.IS_MOVING, has_reply=True))
289+
return self._mesg(Command.IS_MOVING, has_reply=True)
343290

344291
# JOG mode and operation
345292
def jog_angle(self, joint_id, direction, speed):
@@ -350,7 +297,7 @@ def jog_angle(self, joint_id, direction, speed):
350297
direction: int [0, 1]
351298
speed: int (0 - 100)
352299
"""
353-
self._mesg(Command.JOG_ANGLE, joint_id, direction, speed)
300+
return self._mesg(Command.JOG_ANGLE, joint_id, direction, speed)
354301

355302
def jog_coord(self, coord_id, direction, speed):
356303
"""Coord control
@@ -360,10 +307,10 @@ def jog_coord(self, coord_id, direction, speed):
360307
direction: int [0, 1]
361308
speed: int (0 - 100)
362309
"""
363-
self._mesg(Command.JOG_COORD, coord_id, direction, speed)
310+
return self._mesg(Command.JOG_COORD, coord_id, direction, speed)
364311

365312
def jog_stop(self):
366-
self._mesg(Command.JOG_STOP)
313+
return self._mesg(Command.JOG_STOP)
367314

368315
def set_encoder(self, joint_id, encoder):
369316
"""Set joint encoder value.
@@ -372,17 +319,17 @@ def set_encoder(self, joint_id, encoder):
372319
joint_id: Joint id 1 - 7
373320
encoder: The value of the set encoder.
374321
"""
375-
self._mesg(Command.SET_ENCODER, joint_id - 1, [encoder])
322+
return self._mesg(Command.SET_ENCODER, joint_id - 1, [encoder])
376323

377324
def get_encoder(self, joint_id):
378325
return self._mesg(Command.GET_ENCODER, joint_id - 1, has_reply=True)
379326

380327
def set_encoders(self, encoders, sp):
381-
self._mesg(Command.SET_ENCODERS, encoders, sp)
328+
return self._mesg(Command.SET_ENCODERS, encoders, sp)
382329

383330
# Running status and Settings
384331
def get_speed(self):
385-
return self._process_single(self._mesg(Command.GET_SPEED, has_reply=True))
332+
return self._mesg(Command.GET_SPEED, has_reply=True)
386333

387334
def set_speed(self, speed):
388335
"""Set speed value
@@ -391,8 +338,7 @@ def set_speed(self, speed):
391338
speed (int): 0 - 100
392339
"""
393340
check_datas(speed=speed)
394-
self._mesg(Command.SET_SPEED, speed)
395-
return self
341+
return self._mesg(Command.SET_SPEED, speed)
396342

397343
"""
398344
def get_feed_override(self):
@@ -408,41 +354,35 @@ def get_acceleration(self):
408354

409355
def get_joint_min_angle(self, joint_id):
410356
check_datas(joint_id=joint_id)
411-
angle = self._mesg(Command.GET_JOINT_MIN_ANGLE, joint_id, has_reply=True)
412-
return self._int_to_angle(angle[0]) if angle else 0
357+
return self._mesg(Command.GET_JOINT_MIN_ANGLE, joint_id, has_reply=True)
413358

414359
def get_joint_max_angle(self, joint_id):
415360
check_datas(joint_id=joint_id)
416-
angle = self._mesg(Command.GET_JOINT_MAX_ANGLE, joint_id, has_reply=True)
417-
return self._int_to_angle(angle[0]) if angle else 0
361+
return self._mesg(Command.GET_JOINT_MAX_ANGLE, joint_id, has_reply=True)
418362

419363
# Servo control
420364
def is_servo_enable(self, servo_id):
421-
return self._process_single(self._mesg(Command.IS_SERVO_ENABLE, servo_id - 1))
365+
return self._mesg(Command.IS_SERVO_ENABLE, servo_id - 1)
422366

423367
def is_all_servo_enable(self):
424-
return self._process_single(
425-
self._mesg(Command.IS_ALL_SERVO_ENABLE, has_reply=True)
426-
)
368+
return self._mesg(Command.IS_ALL_SERVO_ENABLE, has_reply=True)
427369

428370
def set_servo_data(self, servo_no, data_id, value):
429-
self._mesg(Command.SET_SERVO_DATA, servo_no - 1, data_id, value)
371+
return self._mesg(Command.SET_SERVO_DATA, servo_no - 1, data_id, value)
430372

431373
def get_servo_data(self, servo_no, data_id):
432-
return self._process_single(
433-
self._mesg(Command.GET_SERVO_DATA, servo_no - 1, data_id, has_reply=True)
434-
)
374+
return self._mesg(Command.GET_SERVO_DATA, servo_no - 1, data_id, has_reply=True)
435375

436376
def set_servo_calibration(self, servo_no):
437-
self._mesg(Command.SET_SERVO_CALIBRATION, servo_no - 1)
377+
return self._mesg(Command.SET_SERVO_CALIBRATION, servo_no - 1)
438378

439379
def release_servo(self, servo_id):
440380
"""Power off designated servo
441381
442382
Args:
443383
servo_id: 1 ~ 6
444384
"""
445-
self._mesg(Command.RELEASE_SERVO, servo_id)
385+
return self._mesg(Command.RELEASE_SERVO, servo_id)
446386

447387
def focus_servo(self, servo_id):
448388
"""Power on designated servo
@@ -451,7 +391,7 @@ def focus_servo(self, servo_id):
451391
servo_id: 1 ~ 6
452392
453393
"""
454-
self._mesg(Command.FOCUS_SERVO, servo_id)
394+
return self._mesg(Command.FOCUS_SERVO, servo_id)
455395

456396
# Atom IO
457397
def set_color(self, r=0, g=0, b=0):
@@ -464,8 +404,7 @@ def set_color(self, r=0, g=0, b=0):
464404
465405
"""
466406
check_datas(rgb=[r, g, b])
467-
self._mesg(Command.SET_COLOR, r, g, b)
468-
return self
407+
return self._mesg(Command.SET_COLOR, r, g, b)
469408

470409
def set_pin_mode(self, pin_no, pin_mode):
471410
"""Set the state mode of the specified pin in atom.
@@ -474,7 +413,7 @@ def set_pin_mode(self, pin_no, pin_mode):
474413
pin_no (int):
475414
pin_mode (int): 0 - input, 1 - output, 2 - input_pullup
476415
"""
477-
self._mesg(Command.SET_PIN_MODE, pin_no, pin_mode)
416+
return self._mesg(Command.SET_PIN_MODE, pin_no, pin_mode)
478417

479418
def set_digital_output(self, pin_no, pin_signal):
480419
"""
@@ -483,25 +422,21 @@ def set_digital_output(self, pin_no, pin_signal):
483422
pin_no (int):
484423
pin_signal (int): 0 / 1
485424
"""
486-
self._mesg(Command.SET_DIGITAL_OUTPUT, pin_no, pin_signal)
425+
return self._mesg(Command.SET_DIGITAL_OUTPUT, pin_no, pin_signal)
487426

488427
def get_digital_input(self, pin_no):
489-
return self._process_single(
490-
self._mesg(Command.GET_DIGITAL_INPUT, pin_no, has_reply=True)
491-
)
428+
return self._mesg(Command.GET_DIGITAL_INPUT, pin_no, has_reply=True)
492429

493430
"""
494431
def set_pwm_mode(self, pin_no, channel):
495432
self._mesg(Command.SET_PWM_MODE, pin_no, channel)
496433
"""
497434

498435
def set_pwm_output(self, channel, frequency, pin_val):
499-
self._mesg(Command.SET_PWM_OUTPUT, channel, [frequency], pin_val)
436+
return self._mesg(Command.SET_PWM_OUTPUT, channel, [frequency], pin_val)
500437

501438
def get_gripper_value(self):
502-
return self._process_single(
503-
self._mesg(Command.GET_GRIPPER_VALUE, has_reply=True)
504-
)
439+
return self._mesg(Command.GET_GRIPPER_VALUE, has_reply=True)
505440

506441
def set_gripper_state(self, flag, speed):
507442
"""Set gripper switch
@@ -510,8 +445,7 @@ def set_gripper_state(self, flag, speed):
510445
flag (int): 0 - open, 1 - close
511446
speed (int): 0 ~ 100
512447
"""
513-
self._mesg(Command.SET_GRIPPER_STATE, flag, speed)
514-
return self
448+
return self._mesg(Command.SET_GRIPPER_STATE, flag, speed)
515449

516450
def set_gripper_value(self, value, speed):
517451
"""Set gripper value
@@ -521,14 +455,14 @@ def set_gripper_value(self, value, speed):
521455
speed (int): 0 ~ 100
522456
"""
523457
check_datas(speed=speed)
524-
self._mesg(Command.SET_GRIPPER_VALUE, [value], speed)
458+
return self._mesg(Command.SET_GRIPPER_VALUE, [value], speed)
525459

526460
def set_gripper_ini(self):
527461
"""Set the current position to zero
528462
529463
Current position value is `2048`.
530464
"""
531-
self._mesg(Command.SET_GRIPPER_INI)
465+
return self._mesg(Command.SET_GRIPPER_INI)
532466

533467
def is_gripper_moving(self):
534468
"""Judge whether the gripper is moving or not
@@ -538,9 +472,7 @@ def is_gripper_moving(self):
538472
1 : is moving
539473
-1: error data
540474
"""
541-
return self._process_single(
542-
self._mesg(Command.IS_GRIPPER_MOVING, has_reply=True)
543-
)
475+
return self._mesg(Command.IS_GRIPPER_MOVING, has_reply=True)
544476

545477
# Basic
546478
def set_basic_output(self, pin_no, pin_signal):
@@ -549,10 +481,4 @@ def set_basic_output(self, pin_no, pin_signal):
549481
Args:
550482
pin_signal: 0 / 1
551483
"""
552-
self._mesg(Command.SET_BASIC_OUTPUT, pin_no, pin_signal)
553-
return self
554-
555-
# Other
556-
def wait(self, t):
557-
time.sleep(t)
558-
return self
484+
return self._mesg(Command.SET_BASIC_OUTPUT, pin_no, pin_signal)

0 commit comments

Comments
 (0)