Skip to content

Commit 2599eb3

Browse files
committed
fix: send_coord error index.
update test.
1 parent b029bbf commit 2599eb3

File tree

5 files changed

+153
-111
lines changed

5 files changed

+153
-111
lines changed

.gitignore

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,10 @@ test_test.py
1212

1313
.DS_Store
1414

15+
.VSCodeCounter
1516
.vscode/.ropeproject/config.py
1617
.vscode/.ropeproject/objectdb
1718

1819
__pycache__/port.cpython-39.pyc
1920
demo/__pycache__/port.cpython-39.pyc
20-
demo/__pycache__/port_setup.cpython-39.pyc
21+
demo/__pycache__/port_setup.cpython-39.pyc

pymycobot/generate.py

Lines changed: 20 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -218,7 +218,9 @@ def send_coord(self, id, coord, speed):
218218
speed(int): 0 ~ 100
219219
"""
220220
check_datas(speed=speed)
221-
return self._mesg(Command.SEND_COORD, id, [self._coord_to_int(coord)], speed)
221+
return self._mesg(
222+
Command.SEND_COORD, id - 1, [self._coord_to_int(coord)], speed
223+
)
222224

223225
def send_coords(self, coords, speed, mode):
224226
"""Send all coordinations.
@@ -319,9 +321,26 @@ def set_encoder(self, joint_id, encoder):
319321
return self._mesg(Command.SET_ENCODER, joint_id, [encoder])
320322

321323
def get_encoder(self, joint_id):
324+
"""Get servo encoder
325+
326+
Args:
327+
joint_id (int): servo number.
328+
329+
Returns:
330+
(int16): servo encoder value.
331+
"""
322332
return self._mesg(Command.GET_ENCODER, joint_id, has_reply=True)
323333

324334
def set_encoders(self, encoders, sp):
335+
"""Set all servo encoder.
336+
337+
Args:
338+
encoders (list): encoder list
339+
sp (int): speed
340+
341+
Returns:
342+
(str): command.
343+
"""
325344
return self._mesg(Command.SET_ENCODERS, encoders, sp)
326345

327346
def get_encoders(self):

tests/rasp_mycobot_test_gui.py

Lines changed: 109 additions & 95 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,11 @@
11
#!/usr/bin/env python3
2+
import socket
23
import tkinter
34
from tkinter import ttk
45
import time
56
import threading
67
import os
8+
import textwrap
79
import serial
810
import serial.tools.list_ports
911

@@ -123,11 +125,11 @@ def run(self):
123125
# Connect method
124126
# ============================================================
125127
def connect_mycobot(self):
126-
port = self.port_list.get()
128+
self.prot = port = self.port_list.get()
127129
if not port:
128130
self.write_log_to_Text("请选择串口")
129131
return
130-
baud = self.baud_list.get()
132+
self.baud = baud = self.baud_list.get()
131133
if not baud:
132134
self.write_log_to_Text("请选择波特率")
133135
return
@@ -291,101 +293,113 @@ def _aging_test(self):
291293
Aging test thread target.
292294
By using in `start_aging_test()` and `stop_aging_test()`.
293295
"""
296+
# if socket.gethostname() != "pi":
297+
# self.write_log_to_Text("老化测试支持 Raspberry OS.")
298+
# return
299+
300+
aging_test_content_py = textwrap.dedent(
301+
"""\
302+
#!/usr/bin/python3
303+
304+
from pymycobot.mycobot import MyCobot
305+
from pymycobot import PI_PORT, PI_BAUD
306+
import time
307+
308+
309+
mycobot = MyCobot('%s', %s)
310+
311+
def aging_test():
312+
# fast
313+
mycobot.wait(5).send_angles([0, 0, 0, 0, 0, 0], 95)
314+
mycobot.wait(3).send_angles([170, 0, 0, 0, 0, 0], 95)
315+
mycobot.wait(3).send_angles([-170, 0, 0, 0, 0, 0], 95)
316+
mycobot.wait(3).send_angles([0, 0, 0, 0, 0, 0], 95)
317+
mycobot.wait(3).send_angles([0, 90, 0, 0, 0, 0], 95)
318+
mycobot.wait(3).send_angles([0, -90, 0, 0, 0, 0], 95)
319+
mycobot.wait(3).send_angles([0, 0, 0, 0, 0, 0], 95)
320+
mycobot.wait(3).send_angles([0, 0, 140, 0, 0, 0], 95)
321+
mycobot.wait(3).send_angles([0, 0, -140, 0, 0, 0], 95)
322+
mycobot.wait(3).send_angles([0, 0, 0, 0, 0, 0], 95)
323+
mycobot.wait(3).send_angles([0, 0, 0, 130, 0, 0], 95)
324+
mycobot.wait(3).send_angles([0, 0, 0, -110, 0, 0], 95)
325+
mycobot.wait(3).send_angles([0, 0, 0, 0, 0, 0], 95)
326+
mycobot.wait(3).send_angles([0, 0, 0, 0, 165, 0], 95)
327+
mycobot.wait(3).send_angles([0, 0, 0, 0, -165, 0], 95)
328+
mycobot.wait(3).send_angles([0, 0, 0, 0, 0, 0], 95)
329+
mycobot.wait(3).send_angles([0, 0, 0, 0, 0, 180], 95)
330+
mycobot.wait(3).send_angles([0, 0, 0, 0, 0, -180], 95)
331+
332+
# middle
333+
mycobot.wait(3).send_angles([0, 0, 0, 0, 0, 0], 55)
334+
mycobot.wait(5).send_angles([170, 0, 0, 0, 0, 0], 55)
335+
mycobot.wait(6.5).send_angles([-170, 0, 0, 0, 0, 0], 55)
336+
mycobot.wait(5).send_angles([0, 0, 0, 0, 0, 0], 55)
337+
mycobot.wait(5).send_angles([0, 90, 0, 0, 0, 0], 55)
338+
mycobot.wait(5).send_angles([0, -90, 0, 0, 0, 0], 55)
339+
mycobot.wait(5).send_angles([0, 0, 0, 0, 0, 0], 55)
340+
mycobot.wait(5).send_angles([0, 0, 140, 0, 0, 0], 55)
341+
mycobot.wait(5).send_angles([0, 0, -140, 0, 0, 0], 55)
342+
mycobot.wait(5).send_angles([0, 0, 0, 0, 0, 0], 55)
343+
mycobot.wait(5).send_angles([0, 0, 0, 130, 0, 0], 55)
344+
mycobot.wait(5).send_angles([0, 0, 0, -110, 0, 0], 55)
345+
mycobot.wait(5).send_angles([0, 0, 0, 0, 0, 0], 55)
346+
mycobot.wait(5).send_angles([0, 0, 0, 0, 165, 0], 55)
347+
mycobot.wait(5).send_angles([0, 0, 0, 0, -165, 0], 55)
348+
mycobot.wait(5).send_angles([0, 0, 0, 0, 0, 0], 55)
349+
mycobot.wait(5).send_angles([0, 0, 0, 0, 0, 180], 55)
350+
mycobot.wait(5).send_angles([0, 0, 0, 0, 0, -180], 55)
351+
352+
# slow
353+
mycobot.wait(5).send_angles([0, 0, 0, 0, 0, 0], 15)
354+
mycobot.wait(7).send_angles([170, 0, 0, 0, 0, 0], 15)
355+
mycobot.wait(7).send_angles([-170, 0, 0, 0, 0, 0], 15)
356+
mycobot.wait(11).send_angles([0, 0, 0, 0, 0, 0], 15)
357+
mycobot.wait(7).send_angles([0, 90, 0, 0, 0, 0], 15)
358+
mycobot.wait(7).send_angles([0, -90, 0, 0, 0, 0], 15)
359+
mycobot.wait(0).send_angles([0, 0, 0, 0, 0, 0], 15)
360+
mycobot.wait(7).send_angles([0, 0, 140, 0, 0, 0], 15)
361+
mycobot.wait(7).send_angles([0, 0, -140, 0, 0, 0], 15)
362+
mycobot.wait(11).send_angles([0, 0, 0, 0, 0, 0], 15)
363+
mycobot.wait(7).send_angles([0, 0, 0, 130, 0, 0], 15)
364+
mycobot.wait(7).send_angles([0, 0, 0, -110, 0, 0], 15)
365+
mycobot.wait(11).send_angles([0, 0, 0, 0, 0, 0], 15)
366+
mycobot.wait(7).send_angles([0, 0, 0, 0, 165, 0], 15)
367+
mycobot.wait(7).send_angles([0, 0, 0, 0, -165, 0], 15)
368+
mycobot.wait(11).send_angles([0, 0, 0, 0, 0, 0], 15)
369+
mycobot.wait(7).send_angles([0, 0, 0, 0, 0, 180], 15)
370+
mycobot.wait(7).send_angles([0, 0, 0, 0, 0, -180], 15)
371+
372+
373+
if __name__ == '__main__':
374+
while True:
375+
aging_test()
376+
"""
377+
% (self.prot, self.baud)
378+
)
294379

295-
aging_test_content_py = """\
296-
#!/usr/bin/python3
297-
298-
from pymycobot.mycobot import MyCobot
299-
from pymycobot import PI_PORT, PI_BAUD
300-
import time
301-
302-
303-
mycobot = MyCobot(PI_PORT, PI_BAUD)
304-
305-
def aging_test():
306-
mycobot.send_angles([0, 0, 0, 0, 0, 0], 90)
307-
time.sleep(2.5)
308-
309-
mycobot.send_angles([170, 0, 0, 0, 0, 0], 90)
310-
time.sleep(2)
311-
312-
mycobot.send_angles([-170, 0, 0, 0, 0, 0], 90)
313-
time.sleep(3.5)
314-
315-
mycobot.send_angles([0, 0, 0, 0, 0, 0], 90)
316-
time.sleep(2)
317-
318-
mycobot.send_angles([0, 90, 0, 0, 0, 0], 90)
319-
time.sleep(2)
320-
321-
mycobot.send_angles([0, -90, 0, 0, 0, 0], 90)
322-
time.sleep(3.5)
323-
324-
mycobot.send_angles([0, 0, 0, 0, 0, 0], 90)
325-
time.sleep(2.5)
326-
327-
mycobot.send_angles([0, 0, 140, 0, 0, 0], 90)
328-
time.sleep(2)
329-
330-
mycobot.send_angles([0, 0, -140, 0, 0, 0], 90)
331-
time.sleep(3.5)
332-
333-
mycobot.send_angles([0, 0, 0, 0, 0, 0], 90)
334-
time.sleep(2)
335-
336-
mycobot.send_angles([0, 0, 0, 130, 0, 0], 90)
337-
time.sleep(2)
338-
339-
mycobot.send_angles([0, 0, 0, -110, 0, 0], 90)
340-
time.sleep(3.5)
341-
342-
mycobot.send_angles([0, 0, 0, 0, 0, 0], 90)
343-
time.sleep(2.5)
344-
345-
mycobot.send_angles([0, 0, 0, 0, 165, 0], 90)
346-
time.sleep(2)
347-
348-
mycobot.send_angles([0, 0, 0, 0, -165, 0], 90)
349-
time.sleep(3.5)
350-
351-
mycobot.send_angles([0, 0, 0, 0, 0, 0], 90)
352-
time.sleep(2.5)
353-
354-
mycobot.send_angles([0, 0, 0, 0, 0, 180], 90)
355-
time.sleep(2)
356-
357-
mycobot.send_angles([0, 0, 0, 0, 0, -180], 90)
358-
time.sleep(3.5)
359-
360-
361-
if __name__ == '__main__':
362-
#i=10
363-
while 1:
364-
aging_test()
365-
# i-=1
366-
367-
"""
368-
369-
aging_test_content_sh = """\
370-
#!/bin/bash
371-
/usr/bin/python3 /home/pi/Desktop/aging_test.py
372-
373-
"""
374-
375-
aging_test_content_service = """\
376-
[Unit]
377-
Description=aging-test
378-
379-
[Service]
380-
Type=forking
381-
Restart=on-failure
382-
RestartSec=2
383-
ExecStart=/home/pi/aging_test.sh
384-
385-
[Install]
386-
WantedBy=multi-user.target
380+
aging_test_content_sh = textwrap.dedent(
381+
"""\
382+
#!/bin/bash
383+
/usr/bin/python3 /home/pi/Desktop/aging_test.py
384+
"""
385+
)
387386

388-
"""
387+
aging_test_content_service = textwrap.dedent(
388+
"""\
389+
[Unit]
390+
Description=aging-test
391+
392+
[Service]
393+
Type=forking
394+
User=pi
395+
Restart=on-failure
396+
RestartSec=2
397+
ExecStart=/home/pi/aging_test.sh
398+
399+
[Install]
400+
WantedBy=multi-user.target
401+
"""
402+
)
389403

390404
os.system(
391405
'echo "' + aging_test_content_py + '" >> /home/pi/Desktop/aging_test.py'

tests/test_api.py

Lines changed: 22 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,13 @@
1-
import time
21
import os
32
import sys
4-
import serial
5-
import serial.tools.list_ports
3+
import time
64
import pytest
75

86
# Add relevant ranger module to PATH... there surely is a better way to do this...
97
sys.path.insert(0, os.path.join(os.path.dirname(__file__), ".."))
108

119
from pymycobot import MyCobot, Angle, Coord
10+
from pymycobot import utils
1211

1312
# from pymycobot.genre import Angle, Coord
1413

@@ -21,14 +20,19 @@
2120
def setup():
2221
print("")
2322
global port, mc
24-
plist = list(serial.tools.list_ports.comports())
25-
idx = 1
26-
for port in plist:
27-
print("{} : {}".format(idx, port))
28-
idx += 1
29-
30-
_in = input("\nPlease input 1 - {} to choice:".format(idx - 1))
31-
port = str(plist[int(_in) - 1]).split(" - ")[0].strip()
23+
24+
detected = utils.detect_port_of_basic()
25+
if not detected:
26+
plist = utils.get_port_list()
27+
idx = 1
28+
for port in plist:
29+
print("{} : {}".format(idx, port))
30+
idx += 1
31+
32+
_in = input("\nPlease input 1 - {} to choice:".format(idx - 1))
33+
port = plist[int(_in) - 1]
34+
else:
35+
port = detected
3236
print(port)
3337
print("")
3438

@@ -42,7 +46,6 @@ def setup():
4246
f = input("Wether DEBUG mode[Y/n] (default: no):")
4347
if f in ["y", "Y", "yes", "Yes"]:
4448
DEBUG = True
45-
# mc = MyCobot(port, debug=True)
4649
mc = MyCobot(port, baud, debug=DEBUG)
4750
print("")
4851

@@ -287,6 +290,13 @@ def pump_off():
287290
time.sleep(3)
288291

289292

293+
def test_encoder(setup):
294+
print(mc.get_encoders())
295+
time.sleep(1)
296+
for i in range(1, 7):
297+
print(i, mc.get_encoder(i))
298+
299+
290300
def test_error_data(setup):
291301
print("==========================================================")
292302
print("Start data check test...\n")

tests/test_utils.py

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,5 @@
1-
import time
21
import os
32
import sys
4-
import pytest
53

64
# Add relevant ranger module to PATH... there surely is a better way to do this...
75
sys.path.insert(0, os.path.join(os.path.dirname(__file__), ".."))

0 commit comments

Comments
 (0)