Skip to content

Commit ac6f83c

Browse files
committed
release v3.1.8
1 parent 3f2d527 commit ac6f83c

File tree

5 files changed

+229
-6
lines changed

5 files changed

+229
-6
lines changed

CHANGELOG.md

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,14 @@
11
# ChangeLog for pymycobot
22

3+
## v3.1.8 (2023-09-04)
4+
5+
- release v3.1.8
6+
- Add myAGV interface.
7+
- Increase interface robustness.
8+
39
## v3.1.7 (2023-8-8)
410

5-
- release v3.1.6
11+
- release v3.1.7
612
- Fix myArm interface error
713

814
## v3.1.6 (2023-6-19)

demo/drag_trial_teaching_myArm.py

Lines changed: 217 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,217 @@
1+
import time
2+
import os
3+
import sys
4+
import termios
5+
import tty
6+
import threading
7+
import json
8+
import serial
9+
import serial.tools.list_ports
10+
11+
from pymycobot import MyArm
12+
13+
14+
port: str
15+
mc: MyArm
16+
sp: int = 80
17+
18+
19+
def setup():
20+
print("")
21+
global port, mc
22+
plist = list(serial.tools.list_ports.comports())
23+
idx = 1
24+
for port in plist:
25+
print("{} : {}".format(idx, port))
26+
idx += 1
27+
28+
_in = input("\nPlease input 1 - {} to choice:".format(idx - 1))
29+
port = str(plist[int(_in) - 1]).split(" - ")[0].strip()
30+
print(port)
31+
print("")
32+
33+
baud = 115200
34+
# _baud = input("Please input baud(default:1000000):")
35+
# try:
36+
# baud = int(_baud)
37+
# except Exception:
38+
# pass
39+
# print(baud)
40+
print("")
41+
42+
DEBUG = False
43+
f = input("Wether DEBUG mode[Y/n](default:n):")
44+
if f in ["y", "Y", "yes", "Yes"]:
45+
DEBUG = True
46+
# mc = MyCobot(port, debug=True)
47+
mc = MyArm(port, baud, debug=DEBUG)
48+
49+
50+
class Raw(object):
51+
"""Set raw input mode for device"""
52+
53+
def __init__(self, stream):
54+
self.stream = stream
55+
self.fd = self.stream.fileno()
56+
57+
def __enter__(self):
58+
self.original_stty = termios.tcgetattr(self.stream)
59+
tty.setcbreak(self.stream)
60+
61+
def __exit__(self, type, value, traceback):
62+
termios.tcsetattr(self.stream, termios.TCSANOW, self.original_stty)
63+
64+
65+
class Helper(object):
66+
def __init__(self) -> None:
67+
self.w, self.h = os.get_terminal_size()
68+
69+
def echo(self, msg):
70+
print("\r{}".format(" " * self.w), end="")
71+
print("\r{}".format(msg), end="")
72+
73+
74+
class TeachingTest(Helper):
75+
def __init__(self, mycobot) -> None:
76+
super().__init__()
77+
self.mc = mycobot
78+
self.recording = False
79+
self.playing = False
80+
self.record_list = []
81+
self.record_t = None
82+
self.play_t = None
83+
self.path = os.path.dirname(os.path.abspath(__file__)) + "/record.txt"
84+
85+
def record(self):
86+
self.record_list = []
87+
self.recording = True
88+
#self.mc.set_fresh_mode(0)
89+
def _record():
90+
91+
92+
while self.recording:
93+
start_t = time.time()
94+
angles = self.mc.get_encoders()
95+
speeds = self.mc.get_servo_speeds()
96+
gripper_value = self.mc.get_gripper_value()
97+
interval_time = time.time() - start_t
98+
#print(angles)
99+
if angles:
100+
self.record_list.append([angles, speeds, gripper_value, interval_time])
101+
# time.sleep(0.1)
102+
print("\r {}".format(time.time() - start_t), end="")
103+
104+
self.echo("Start recording.")
105+
self.record_t = threading.Thread(target=_record, daemon=True)
106+
self.record_t.start()
107+
108+
def stop_record(self):
109+
if self.recording:
110+
self.recording = False
111+
self.record_t.join()
112+
self.echo("Stop record")
113+
114+
def play(self):
115+
self.echo("Start play")
116+
i = 0
117+
for angles in self.record_list:
118+
#print(angles)
119+
self.mc.set_encoders_drag(angles[0],angles[1])
120+
self.mc.set_gripper_value(angles[2], 80)
121+
if i == 0:
122+
time.sleep(3)
123+
time.sleep(angles[-1])
124+
self.echo("Finish play")
125+
126+
def loop_play(self):
127+
self.playing = True
128+
129+
def _loop():
130+
len_ = len(self.record_list)
131+
i = 0
132+
while self.playing:
133+
idx_ = i % len_
134+
i += 1
135+
self.mc.set_encoders_drag(self.record_list[idx_][0],self.record_list[idx_][1])
136+
self.mc.set_encoder(7, self.record_list[idx_])
137+
if idx_ == 0:
138+
time.sleep(3)
139+
time.sleep(self.record_list[idx_][-1])
140+
141+
self.echo("Start loop play.")
142+
self.play_t = threading.Thread(target=_loop, daemon=True)
143+
self.play_t.start()
144+
145+
def stop_loop_play(self):
146+
if self.playing:
147+
self.playing = False
148+
self.play_t.join()
149+
self.echo("Stop loop play.")
150+
151+
def save_to_local(self):
152+
if not self.record_list:
153+
self.echo("No data should save.")
154+
return
155+
with open(self.path, "w") as f:
156+
json.dump(self.record_list, f, indent=2)
157+
self.echo("save dir: {}\n".format(self.path))
158+
159+
def load_from_local(self):
160+
with open(self.path, "r") as f:
161+
try:
162+
data = json.load(f)
163+
self.record_list = data
164+
self.echo("Load data success.")
165+
except Exception:
166+
self.echo("Error: invalid data.")
167+
168+
def print_menu(self):
169+
print(
170+
"""\
171+
\r q: quit
172+
\r r: start record
173+
\r c: stop record
174+
\r p: play once
175+
\r P: loop play / stop loop play
176+
\r s: save to local
177+
\r l: load from local
178+
\r f: release mycobot
179+
\r----------------------------------
180+
"""
181+
)
182+
183+
def start(self):
184+
self.print_menu()
185+
186+
while not False:
187+
with Raw(sys.stdin):
188+
key = sys.stdin.read(1)
189+
if key == "q":
190+
break
191+
elif key == "r": # recorder
192+
self.record()
193+
elif key == "c": # stop recorder
194+
self.stop_record()
195+
elif key == "p": # play
196+
self.play()
197+
elif key == "P": # loop play
198+
if not self.playing:
199+
self.loop_play()
200+
else:
201+
self.stop_loop_play()
202+
elif key == "s": # save to local
203+
self.save_to_local()
204+
elif key == "l": # load from local
205+
self.load_from_local()
206+
elif key == "f": # free move
207+
self.mc.release_all_servos()
208+
self.echo("Released")
209+
else:
210+
print(key)
211+
continue
212+
213+
214+
if __name__ == "__main__":
215+
setup()
216+
recorder = TeachingTest(mc)
217+
recorder.start()

pymycobot/__init__.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@
4848
from pymycobot.mybuddyemoticon import MyBuddyEmoticon
4949
__all__.append("MyBuddyEmoticon")
5050

51-
__version__ = "3.1.8b4"
51+
__version__ = "3.1.8"
5252
__author__ = "Elephantrobotics"
5353
__email__ = "[email protected]"
5454
__git_url__ = "https://github.com/elephantrobotics/pymycobot"

pymycobot/elephantrobot.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -211,7 +211,7 @@ def get_digital_out(self, pin_number):
211211
print(command)
212212
self.send_command(command)
213213

214-
def get_joint_current(self, joint_number: int):
214+
def get_joint_current(self, joint_number):
215215
command = "get_joint_current(" + str(joint_number) + ")\n"
216216
print(command)
217217
self.send_command(command)
@@ -255,7 +255,7 @@ def get_variable(self, var_name):
255255
return self.send_command(command)
256256

257257
def jog_relative(self, joint_id, angle, speed):
258-
command = 'SendJogIncrement("' + str(var_name) + '")\n'
258+
command = 'SendJogIncrement("{}","{}","{}")\n'.format(joint_id, angle, speed)
259259
return self.send_command(command)
260260

261261

pymycobot/robot_limit.json

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,8 +43,8 @@
4343
},
4444
"MyArm":{
4545
"id":[1,2,3,4,5,6,7],
46-
"angles_min":[-160, -80, -165, -100, -165, -110, -165],
47-
"angles_max":[160, 80, 165, 80, 165, 110, 165],
46+
"angles_min":[-160, -70, -170, -113, -170, -115, -180],
47+
"angles_max":[160, 115, 170, 75, 170, 115, 180],
4848
"coords_min":[-310, -310, -140, -180, -180, -180],
4949
"coords_max":[310, 310, 480, 180, 180, 180]
5050
},

0 commit comments

Comments
 (0)