Skip to content

Commit 63ddc3a

Browse files
committed
add MyPalletizer class.
1 parent c10d963 commit 63ddc3a

File tree

6 files changed

+146
-37
lines changed

6 files changed

+146
-37
lines changed

pymycobot/__init__.py

Lines changed: 11 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -3,14 +3,22 @@
33
from __future__ import absolute_import
44
import datetime
55

6-
from pymycobot.mycobot import MyCobot
76
from pymycobot.generate import MycobotCommandGenerater
7+
from pymycobot.mycobot import MyCobot
8+
from pymycobot.mypalletizer import MyPalletizer
89
from pymycobot.genre import Angle, Coord
910
from pymycobot import utils
1011

11-
__all__ = ["MyCobot", "MycobotCommandGenerater", "Angle", "Coord", "utils"]
12+
__all__ = [
13+
"MyCobot",
14+
"MycobotCommandGenerater",
15+
"Angle",
16+
"Coord",
17+
"utils",
18+
"MyPalletizer",
19+
]
1220

13-
__version__ = "2.5.9"
21+
__version__ = "2.6.0.beta.1"
1422
__author__ = "Zachary zhang"
1523
__email__ = "[email protected]"
1624
__git_url__ = "https://github.com/elephantrobotics/pymycobot"

pymycobot/common.py

Lines changed: 20 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
# coding=utf-8
22

33
from __future__ import division
4+
import time
45
import struct
56

67

@@ -149,7 +150,7 @@ def _process_received(self, data, genre):
149150

150151
# process valid data
151152
res = []
152-
if data_len == 12:
153+
if data_len == 12 or data_len == 8:
153154
for idx in range(0, len(valid_data), 2):
154155
one = valid_data[idx : idx + 2]
155156
res.append(self._decode_int16(one))
@@ -163,3 +164,21 @@ def _process_received(self, data, genre):
163164

164165
def _process_single(self, data):
165166
return data[0] if data else -1
167+
168+
169+
def write(self, command):
170+
self.log.debug("_write: {}".format(command))
171+
172+
self._serial_port.write(command)
173+
self._serial_port.flush()
174+
time.sleep(0.05)
175+
176+
177+
def read(self):
178+
if self._serial_port.inWaiting() > 0:
179+
data = self._serial_port.read(self._serial_port.inWaiting())
180+
self.log.debug("_read: {}".format(data))
181+
else:
182+
self.log.debug("_read: no data can be read")
183+
data = None
184+
return data

pymycobot/generate.py

Lines changed: 13 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,6 @@
44
import logging
55

66
from pymycobot.log import setup_logging
7-
from pymycobot.error import calibration_parameters
87
from pymycobot.common import ProtocolCode, DataProcessor
98

109

@@ -182,7 +181,7 @@ def send_angle(self, id, degree, speed):
182181
degree (float): angle value.
183182
speed (int): 0 ~ 100
184183
"""
185-
calibration_parameters(id=id, degree=degree, speed=speed)
184+
self.calibration_parameters(id=id, degree=degree, speed=speed)
186185
return self._mesg(ProtocolCode.SEND_ANGLE, id, [self._angle2int(degree)], speed)
187186

188187
# @check_parameters(Command.SEND_ANGLES)
@@ -193,9 +192,8 @@ def send_angles(self, degrees, speed):
193192
degrees (list): example [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
194193
speed (int): 0 ~ 100
195194
"""
196-
calibration_parameters(degrees=degrees, speed=speed)
195+
self.calibration_parameters(degrees=degrees, speed=speed)
197196
degrees = [self._angle2int(degree) for degree in degrees]
198-
# data = [degrees, speed]
199197
return self._mesg(ProtocolCode.SEND_ANGLES, degrees, speed)
200198

201199
def get_coords(self):
@@ -214,7 +212,7 @@ def send_coord(self, id, coord, speed):
214212
coord(float): mm
215213
speed(int): 0 ~ 100
216214
"""
217-
calibration_parameters(id=id, speed=speed)
215+
self.calibration_parameters(id=id, speed=speed)
218216
value = self._coord2int(coord) if id <= 3 else self._angle2int(coord)
219217
return self._mesg(ProtocolCode.SEND_COORD, id, [value], speed)
220218

@@ -226,12 +224,12 @@ def send_coords(self, coords, speed, mode):
226224
speed(int);
227225
mode(int): 0 - normal, 1 - angluar, 2 - linear
228226
"""
229-
calibration_parameters(coords=coords, speed=speed)
227+
self.calibration_parameters(coords=coords, speed=speed)
230228
coord_list = []
231229
for idx in range(3):
232230
coord_list.append(self._coord2int(coords[idx]))
233-
for idx in range(3, 6):
234-
coord_list.append(self._angle2int(coords[idx]))
231+
for angle in coords[3:]:
232+
coord_list.append(self._angle2int(angle))
235233
return self._mesg(ProtocolCode.SEND_COORDS, coord_list, speed, mode)
236234

237235
def is_in_position(self, data, id=0):
@@ -247,14 +245,14 @@ def is_in_position(self, data, id=0):
247245
-1: error data
248246
"""
249247
if id == 1:
250-
calibration_parameters(coords=data)
248+
self.calibration_parameters(coords=data)
251249
data_list = []
252250
for idx in range(3):
253251
data_list.append(self._coord2int(data[idx]))
254252
for idx in range(3, 6):
255253
data_list.append(self._angle2int(data[idx]))
256254
elif id == 0:
257-
calibration_parameters(degrees=data)
255+
self.calibration_parameters(degrees=data)
258256
data_list = [self._angle2int(i) for i in data]
259257
else:
260258
raise Exception("id is not right, please input 0 or 1")
@@ -353,7 +351,7 @@ def set_speed(self, speed):
353351
Args:
354352
speed (int): 0 - 100
355353
"""
356-
calibration_parameters(speed=speed)
354+
self.calibration_parameters(speed=speed)
357355
return self._mesg(ProtocolCode.SET_SPEED, speed)
358356

359357
"""
@@ -369,11 +367,11 @@ def get_acceleration(self):
369367
"""
370368

371369
def get_joint_min_angle(self, joint_id):
372-
calibration_parameters(id=joint_id)
370+
self.calibration_parameters(id=joint_id)
373371
return self._mesg(ProtocolCode.GET_JOINT_MIN_ANGLE, joint_id, has_reply=True)
374372

375373
def get_joint_max_angle(self, joint_id):
376-
calibration_parameters(id=joint_id)
374+
self.calibration_parameters(id=joint_id)
377375
return self._mesg(ProtocolCode.GET_JOINT_MAX_ANGLE, joint_id, has_reply=True)
378376

379377
# Servo control
@@ -421,7 +419,7 @@ def set_color(self, r=0, g=0, b=0):
421419
b (int): 0 ~ 255
422420
423421
"""
424-
calibration_parameters(rgb=[r, g, b])
422+
self.calibration_parameters(rgb=[r, g, b])
425423
return self._mesg(ProtocolCode.SET_COLOR, r, g, b)
426424

427425
def set_pin_mode(self, pin_no, pin_mode):
@@ -473,7 +471,7 @@ def set_gripper_value(self, value, speed):
473471
value (int): 0 ~ 100
474472
speed (int): 0 ~ 100
475473
"""
476-
calibration_parameters(speed=speed)
474+
self.calibration_parameters(speed=speed)
477475
return self._mesg(ProtocolCode.SET_GRIPPER_VALUE, value, speed)
478476

479477
def set_gripper_ini(self):

pymycobot/mycobot.py

Lines changed: 10 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@
77

88
from pymycobot.log import setup_logging
99
from pymycobot.generate import MycobotCommandGenerater
10-
from pymycobot.common import ProtocolCode
10+
from pymycobot.common import ProtocolCode, write, read
1111
from pymycobot.error import calibration_parameters
1212

1313

@@ -57,25 +57,15 @@ def __init__(self, port, baudrate="115200", timeout=0.1, debug=False):
5757
self.debug = debug
5858
setup_logging(self.debug)
5959
self.log = logging.getLogger(__name__)
60-
import serial
6160

62-
self._serial_port = serial.Serial(port, baudrate, timeout=timeout)
61+
self.calibration_parameters = calibration_parameters
6362

64-
def _write(self, command):
65-
self.log.debug("_write: {}".format(command))
63+
import serial
6664

67-
self._serial_port.write(command)
68-
self._serial_port.flush()
69-
time.sleep(0.05)
65+
self._serial_port = serial.Serial(port, baudrate, timeout=timeout)
7066

71-
def _read(self):
72-
if self._serial_port.inWaiting() > 0:
73-
data = self._serial_port.read(self._serial_port.inWaiting())
74-
self.log.debug("_read: {}".format(data))
75-
else:
76-
self.log.debug("_read: no data can be read")
77-
data = None
78-
return data
67+
_write = write
68+
_read = read
7969

8070
def _mesg(self, genre, *args, **kwargs):
8171
"""
@@ -124,7 +114,10 @@ def _mesg(self, genre, *args, **kwargs):
124114
return r
125115
else:
126116
return res
127-
elif genre in [ProtocolCode.GET_JOINT_MIN_ANGLE, ProtocolCode.GET_JOINT_MAX_ANGLE]:
117+
elif genre in [
118+
ProtocolCode.GET_JOINT_MIN_ANGLE,
119+
ProtocolCode.GET_JOINT_MAX_ANGLE,
120+
]:
128121
return self._int2angle(res[0]) if res else 0
129122
else:
130123
return res

pymycobot/mypalletizer.py

Lines changed: 92 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,92 @@
1+
# coding=utf-8
2+
3+
import logging
4+
5+
from .log import setup_logging
6+
from .generate import MycobotCommandGenerater
7+
from .common import ProtocolCode, read, write
8+
9+
10+
def calibration_parameters(**kwargs):
11+
pass
12+
13+
14+
class MyPalletizer(MycobotCommandGenerater):
15+
def __init__(self, port, baudrate="115200", timeout=0.1, debug=False):
16+
"""
17+
Args:
18+
port : port string
19+
baudrate : baud rate string, default '115200'
20+
timeout : default 0.1
21+
debug : whether show debug info
22+
"""
23+
super(MyPalletizer, self).__init__(debug)
24+
self.debug = debug
25+
setup_logging(self.debug)
26+
self.log = logging.getLogger(__name__)
27+
28+
self.calibration_parameters = calibration_parameters
29+
30+
import serial
31+
32+
self._serial_port = serial.Serial(port, baudrate, timeout=timeout)
33+
34+
_write = write
35+
_read = read
36+
37+
def _mesg(self, genre, *args, **kwargs):
38+
"""
39+
40+
Args:
41+
genre: command type (Command)
42+
*args: other data.
43+
It is converted to octal by default.
44+
If the data needs to be encapsulated into hexadecimal,
45+
the array is used to include them. (Data cannot be nested)
46+
**kwargs: support `has_reply`
47+
has_reply: Whether there is a return value to accept.
48+
"""
49+
real_command, has_reply = super(MyPalletizer, self)._mesg(
50+
genre, *args, **kwargs
51+
)
52+
self._write(self._flatten(real_command))
53+
54+
if has_reply:
55+
data = self._read()
56+
res = self._process_received(data, genre)
57+
if genre in [
58+
ProtocolCode.IS_POWER_ON,
59+
ProtocolCode.IS_CONTROLLER_CONNECTED,
60+
ProtocolCode.IS_PAUSED,
61+
ProtocolCode.IS_IN_POSITION,
62+
ProtocolCode.IS_MOVING,
63+
ProtocolCode.IS_SERVO_ENABLE,
64+
ProtocolCode.IS_ALL_SERVO_ENABLE,
65+
ProtocolCode.GET_SERVO_DATA,
66+
ProtocolCode.GET_DIGITAL_INPUT,
67+
ProtocolCode.GET_GRIPPER_VALUE,
68+
ProtocolCode.IS_GRIPPER_MOVING,
69+
ProtocolCode.GET_SPEED,
70+
ProtocolCode.GET_ENCODER,
71+
ProtocolCode.GET_BASIC_INPUT,
72+
]:
73+
return self._process_single(res)
74+
elif genre in [ProtocolCode.GET_ANGLES]:
75+
return [self._int2angle(angle) for angle in res]
76+
elif genre in [ProtocolCode.GET_COORDS]:
77+
if res:
78+
r = []
79+
for idx in range(3):
80+
r.append(self._int2coord(res[idx]))
81+
r.append(self._int2angle(res[3]))
82+
return r
83+
else:
84+
return res
85+
elif genre in [
86+
ProtocolCode.GET_JOINT_MIN_ANGLE,
87+
ProtocolCode.GET_JOINT_MAX_ANGLE,
88+
]:
89+
return self._int2angle(res[0]) if res else 0
90+
else:
91+
return res
92+
return None

tests/test_generator.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,3 @@
1-
from ensurepip import version
21
import os
32
import sys
43
import pytest

0 commit comments

Comments
 (0)