diff --git a/CHANGELOG.md b/CHANGELOG.md index 5aa7a8d..2f30d0c 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,11 @@ # ChangeLog for pymycobot +## v2.9.7 (2022-11-14) + +- release v2.9.7 +- Add MechArm class: Separate mecharm from mycobot +- Fix known bug + ## v2.9.6 (2022-9-13) - release v2.9.6 diff --git a/docs/README.md b/docs/README.md index 6ea573d..cd457dc 100644 --- a/docs/README.md +++ b/docs/README.md @@ -10,7 +10,7 @@ We support Python2, Python3.5 or later. - [pymycobot](#pymycobot) -- [MyCobot / Mypalletizer](#mycobot--mypalletizer) +- [MyCobot / Mypalletizer / MechArm](#mycobot--mypalletizer--mecharm) - [Overall status](#overall-status) - [power_on](#power_on) - [power_off](#power_off) @@ -229,7 +229,7 @@ We support Python2, Python3.5 or later. -# MyCobot / Mypalletizer +# MyCobot / Mypalletizer / MechArm **Import to your project**: @@ -239,6 +239,15 @@ from pymycobot import MyCobot # for mypalletizer # from pymycobot import MyPalletizer + +# for MechArm +# from pymycobot import MechArm + +mc = MyCobot("com10",115200) +# mc = MyPalletizer("com10",115200) +# mc = MechArm("com10",115200) + +print(mc.get_angles()) ``` > Note: If no parameter is given, there is no parameter; if no return value is given, there is no return value @@ -381,7 +390,7 @@ Set command refresh mode - **Parameters**: - - `radians`: a list of radian value(`List[float]`), length 6. + - `radians`: a list of radian value(`List[float]`). - `speed`: (`int`) 0 ~ 100 - **Example** @@ -434,7 +443,7 @@ Set command refresh mode - **Parameters** - - `coords`: a list of coords value(`List[float]`), length 6. + - `coords`: a list of coords value(`List[float]`). - `speed`: (`int`) 0 ~ 100 - `mode`: (`int`): `0` - angular, `1` - linear @@ -457,7 +466,7 @@ Set command refresh mode - **Parameters** - - `degrees`: a list of degree value(`List[float]`), length 6. + - `degrees`: a list of degree value(`List[float]`). - `speed`: (`int`) 0 ~ 100 - `timeout`: default 7s. @@ -482,7 +491,7 @@ Set command refresh mode - **Parameters** - - `data`: A data list, angles or coords, length 6. + - `data`: A data list, angles or coords. - `flag`: Tag the data type, `0` - angles, `1` - coords. - **Returns** @@ -593,7 +602,7 @@ Set command refresh mode - **Description**: Set the six joints of the manipulator to execute synchronously to the specified position. - **Parameters**: - - `encoders`: A encoder list, length 6. + - `encoders`: A encoder list. - `sp`: speed 0 - 100 ### get_encoders diff --git a/pymycobot/Interface.py b/pymycobot/Interface.py index 4dd25b1..3ab817e 100644 --- a/pymycobot/Interface.py +++ b/pymycobot/Interface.py @@ -742,7 +742,7 @@ def set_gripper_value(self, id, value, speed): value (int): 0 ~ 100 speed (int): 0 - 100 """ - return self._mesg(ProtocolCode.SET_GRIPPER_VALUE, id, value) + return self._mesg(ProtocolCode.SET_GRIPPER_VALUE, id, value, speed) def set_gripper_calibration(self, id): """Set the current position to zero, set current position value is `2048`. diff --git a/pymycobot/__init__.py b/pymycobot/__init__.py index 6fb1a98..2ff67eb 100644 --- a/pymycobot/__init__.py +++ b/pymycobot/__init__.py @@ -2,11 +2,13 @@ from __future__ import absolute_import import datetime +import sys from pymycobot.generate import MyCobotCommandGenerator from pymycobot.Interface import MyBuddyCommandGenerator from pymycobot.mycobot import MyCobot from pymycobot.mybuddy import MyBuddy +from pymycobot.mecharm import MechArm from pymycobot.mypalletizer import MyPalletizer from pymycobot.mycobotsocket import MyCobotSocket from pymycobot.genre import Angle, Coord @@ -14,8 +16,8 @@ from pymycobot.mybuddysocket import MyBuddySocket from pymycobot.mira import Mira from pymycobot.mybuddybluetooth import MyBuddyBlueTooth -from pymycobot.mybuddyemoticon import MyBuddyEmoticon from pymycobot.mypalletizersocket import MyPalletizerSocket + __all__ = [ "MyCobot", @@ -30,11 +32,16 @@ "MyBuddySocket", "MyBuddyBlueTooth", "Mira", - "MyBuddyEmoticon", - "MyPalletizerSocket" + "MyPalletizerSocket", + "MechArm" ] -__version__ = "2.9.7b3" + +if sys.platform == "linux": + from pymycobot.mybuddyemoticon import MyBuddyEmoticon + __all__.append("MyBuddyEmoticon") + +__version__ = "2.9.7" __author__ = "Elephantrobotics" __email__ = "weiquan.xu@elephantrobotics.com" __git_url__ = "https://github.com/elephantrobotics/pymycobot" diff --git a/pymycobot/common.py b/pymycobot/common.py index d275c6a..eb594f1 100644 --- a/pymycobot/common.py +++ b/pymycobot/common.py @@ -383,7 +383,6 @@ def read(self, genre): wait_time = 1 while True and time.time() - t < wait_time: data = self._serial_port.read() - # print("1:",data) k += 1 if data_len == 1 and data == b"\xfa": datas += data diff --git a/pymycobot/mecharm.py b/pymycobot/mecharm.py new file mode 100644 index 0000000..a484fa5 --- /dev/null +++ b/pymycobot/mecharm.py @@ -0,0 +1,6 @@ +# coding=utf-8 +from pymycobot import MyCobot + +class MechArm(MyCobot): + def __init__(self, port, baudrate="115200", timeout=0.1, debug=False): + super().__init__(port, baudrate, timeout, debug) \ No newline at end of file diff --git a/pymycobot/mira.py b/pymycobot/mira.py index 3951eb4..27eec87 100644 --- a/pymycobot/mira.py +++ b/pymycobot/mira.py @@ -1,7 +1,5 @@ # coding: utf-8 -from ctypes.wintypes import SIZE import time -from tkinter import E from pymycobot.common import ProtocolCode import math