robocad-py 0.0.2.3__tar.gz → 1.0.2.3__tar.gz
This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
- robocad-py-1.0.2.3/LICENSE +27 -0
- robocad-py-1.0.2.3/PKG-INFO +43 -0
- robocad-py-1.0.2.3/robocad/common.py +20 -0
- robocad-py-1.0.2.3/robocad/internal/logger.py +18 -0
- {robocad-py-0.0.2.3/robocad/pycad → robocad-py-1.0.2.3/robocad/internal/studica}/COM.py +8 -8
- {robocad-py-0.0.2.3/robocad/pycad → robocad-py-1.0.2.3/robocad/internal/studica}/SPI.py +8 -8
- {robocad-py-0.0.2.3/robocad/robocadSim → robocad-py-1.0.2.3/robocad/internal/studica}/connection.py +49 -61
- robocad-py-1.0.2.3/robocad/internal/studica/connection_base.py +17 -0
- robocad-py-1.0.2.3/robocad/internal/studica/connection_real.py +55 -0
- robocad-py-1.0.2.3/robocad/internal/studica/connection_sim.py +106 -0
- {robocad-py-0.0.2.3/robocad/pycad → robocad-py-1.0.2.3/robocad/internal/studica}/shared.py +9 -0
- {robocad-py-0.0.2.3 → robocad-py-1.0.2.3}/robocad/shufflecad/connections.py +74 -86
- robocad-py-1.0.2.3/robocad/shufflecad/shufflecad.py +40 -0
- robocad-py-0.0.2.3/robocad/shufflecad/shared.py → robocad-py-1.0.2.3/robocad/shufflecad/shufflecad_holder.py +7 -25
- robocad-py-1.0.2.3/robocad/studica.py +158 -0
- robocad-py-1.0.2.3/robocad_py.egg-info/PKG-INFO +43 -0
- robocad-py-1.0.2.3/robocad_py.egg-info/SOURCES.txt +26 -0
- {robocad-py-0.0.2.3 → robocad-py-1.0.2.3}/setup.py +2 -2
- robocad-py-0.0.2.3/LICENSE +0 -21
- robocad-py-0.0.2.3/PKG-INFO +0 -42
- robocad-py-0.0.2.3/robocad/robocad.py +0 -380
- robocad-py-0.0.2.3/robocad/robocadSim/connection_helper_vmx_titan.py +0 -34
- robocad-py-0.0.2.3/robocad/shufflecad/logger.py +0 -22
- robocad-py-0.0.2.3/robocad/shufflecad/shufflecad.py +0 -32
- robocad-py-0.0.2.3/robocad/vex.py +0 -117
- robocad-py-0.0.2.3/robocad_py.egg-info/PKG-INFO +0 -42
- robocad-py-0.0.2.3/robocad_py.egg-info/SOURCES.txt +0 -24
- {robocad-py-0.0.2.3 → robocad-py-1.0.2.3}/CHANGELOG.md +0 -0
- {robocad-py-0.0.2.3 → robocad-py-1.0.2.3}/MANIFEST.in +0 -0
- {robocad-py-0.0.2.3 → robocad-py-1.0.2.3}/robocad/__init__.py +0 -0
- {robocad-py-0.0.2.3/robocad/pycad → robocad-py-1.0.2.3/robocad/internal}/__init__.py +0 -0
- {robocad-py-0.0.2.3/robocad/robocadSim → robocad-py-1.0.2.3/robocad/internal/studica}/__init__.py +0 -0
- {robocad-py-0.0.2.3 → robocad-py-1.0.2.3}/robocad/shufflecad/__init__.py +0 -0
- {robocad-py-0.0.2.3 → robocad-py-1.0.2.3}/robocad_py.egg-info/dependency_links.txt +0 -0
- {robocad-py-0.0.2.3 → robocad-py-1.0.2.3}/robocad_py.egg-info/requires.txt +0 -0
- {robocad-py-0.0.2.3 → robocad-py-1.0.2.3}/robocad_py.egg-info/top_level.txt +0 -0
- {robocad-py-0.0.2.3 → robocad-py-1.0.2.3}/setup.cfg +0 -0
|
@@ -0,0 +1,27 @@
|
|
|
1
|
+
Freeware licence Terms
|
|
2
|
+
|
|
3
|
+
Copyright (c) 2024 Airat Abdrakov
|
|
4
|
+
|
|
5
|
+
THIS SOFTWARE IS COPYRIGHTED, AND THE OWNER OF THE COPYRIGHT CLAIMS ALL EXCLUSIVE RIGHTS TO SUCH SOFTWARE, EXCEPT AS licenced TO USERS HEREUNDER AND SUBJECT TO STRICT COMPLIANCE WITH THE TERMS OF THIS FREEWARE LICENSE.
|
|
6
|
+
|
|
7
|
+
Even though a licence fee is not paid for use of such Freeware, it does not mean that there are no conditions for using such Freeware. As a condition for granting you a licence to use Freeware programmes that are available through this repository, you agree to all of the following terms and conditions. You are deemed to have read, understood and accepted all such terms and conditions upon executing a download of any Freeware program.
|
|
8
|
+
|
|
9
|
+
If you fail to abide by any of the terms and conditions set forth herein, your licence to use such Freeware shall be immediately and automatically revoked, without any notice or other action by the Copyright Owner.
|
|
10
|
+
|
|
11
|
+
TERMS AND CONDITIONS
|
|
12
|
+
Background
|
|
13
|
+
|
|
14
|
+
1. You are granted a non-exclusive licence to use the Downloaded Software subject to your compliance with all of the terms and conditions of this Freeware License.
|
|
15
|
+
2. You may only use the software on a single computer that you own, lease or control. You may make one backup copy of the software for your own use to replace the primary copy in the event of hard-drive failure or other unavailability of the primary copy. The backup copy shall retain all copyright notices.
|
|
16
|
+
3. You are only granted a licence for the machine-readable (object code portion of the software) and the code provided in the repository. You will not modify, enhance, reverse engineer or otherwise alter the software from its current [Province].
|
|
17
|
+
4. You may not use the software for multiple users or on a local area network without written consent from the Licensor.
|
|
18
|
+
5. You may not distribute, copy, publish, assign, sell, bargain, convey, transfer, pledge, lease or grant any further rights to use the software.
|
|
19
|
+
6. You will not have any proprietary rights in and to the software. You acknowledge and agree that the Licensor retains all copyrights and other proprietary rights in and to the software.
|
|
20
|
+
7. Your licence to use the software shall be revocable by the Licensor upon written notice to you. This licence shall automatically terminate upon your violation of the terms hereof or upon your use of the software beyond the scope of the licence provided herein.
|
|
21
|
+
8. Use within the scope of this licence is free of charge and no royalty or licencing fees shall be payable by you. Use beyond the scope of this licence shall constitute copyright infringement.
|
|
22
|
+
9. This licence shall be effective and bind you upon your downloading of the software.
|
|
23
|
+
10. You accept the software on an “AS IS” and with all faults basis. No representations and warranties are made to you regarding any aspect of the software.
|
|
24
|
+
11. THE LICENSOR HEREBY DISCLAIMS ANY AND ALL WARRANTIES, EXPRESS OR IMPLIED, RELATIVE TO THE SOFTWARE, INCLUDING BUT NOT LIMITED TO ANY WARRANTY OF FITNESS FOR A PARTICULAR PURPOSE OR MERCHANTABILITY. LICENSOR SHALL NOT BE LIABLE OR RESPONSIBLE FOR ANY DAMAGES, INJURIES OR LIABILITIES CAUSED DIRECTLY OR INDIRECTLY FROM THE USE OF THE SOFTWARE, INCLUDING BUT NOT LIMITED TO INCIDENTAL, CONSEQUENTIAL OR SPECIAL DAMAGES.
|
|
25
|
+
12. This Freeware licence shall be interpreted under the laws of Russian Federation. You agree that all controversies pertaining to the software and/or this Freeware Agreement shall be brought in the courts of Russian Federation. You hereby submit to the jurisdictions of such court. However, courts located in Russian Federation shall have jurisdiction over copyright claims brought by the Licensor, and you hereby submit to the jurisdiction of the court located in the Russian Federation.
|
|
26
|
+
13. Licensor’s failure to enforce any rights hereunder or its copyright in the software shall not be construed as amending this agreement or waiving any of Licensor’s rights hereunder or under any provision of
|
|
27
|
+
Russian Federation law.
|
|
@@ -0,0 +1,43 @@
|
|
|
1
|
+
Metadata-Version: 2.1
|
|
2
|
+
Name: robocad-py
|
|
3
|
+
Version: 1.0.2.3
|
|
4
|
+
Summary: python lib for real and virtual robots
|
|
5
|
+
Home-page: https://github.com/Soft-V/robocad-py
|
|
6
|
+
Author: Airat Abdrakov
|
|
7
|
+
Author-email: softvery@yandex.ru
|
|
8
|
+
License: MIT
|
|
9
|
+
Keywords: simulator,robotics,robot,3d,raspberry,control
|
|
10
|
+
Classifier: Development Status :: 5 - Production/Stable
|
|
11
|
+
Classifier: Intended Audience :: Education
|
|
12
|
+
Classifier: Operating System :: Microsoft :: Windows :: Windows 10
|
|
13
|
+
Classifier: License :: OSI Approved :: MIT License
|
|
14
|
+
Classifier: Programming Language :: Python :: 3
|
|
15
|
+
License-File: LICENSE
|
|
16
|
+
|
|
17
|
+
Python library for real and virtual robots
|
|
18
|
+
|
|
19
|
+
# Change Log
|
|
20
|
+
|
|
21
|
+
## 0.0.0.1
|
|
22
|
+
- First Release
|
|
23
|
+
|
|
24
|
+
## 0.0.0.2
|
|
25
|
+
- Real camera exception checker added
|
|
26
|
+
|
|
27
|
+
## 0.0.0.5
|
|
28
|
+
- Hope this works
|
|
29
|
+
|
|
30
|
+
## 0.0.0.6
|
|
31
|
+
- Servo motors should work now
|
|
32
|
+
|
|
33
|
+
## 0.0.0.7
|
|
34
|
+
- Thread joins added
|
|
35
|
+
|
|
36
|
+
## 0.0.0.8
|
|
37
|
+
- Thread joins fixed :)
|
|
38
|
+
|
|
39
|
+
## 0.0.0.9
|
|
40
|
+
- Thread joins fixed 2 :)
|
|
41
|
+
|
|
42
|
+
## 0.0.1.1
|
|
43
|
+
- Library fully changed according to the new requirements
|
|
@@ -0,0 +1,20 @@
|
|
|
1
|
+
class Common:
|
|
2
|
+
# logger object
|
|
3
|
+
logger = None
|
|
4
|
+
# control the type of the shufflecad work
|
|
5
|
+
on_real_robot: bool = True
|
|
6
|
+
|
|
7
|
+
power: float = 0.0
|
|
8
|
+
|
|
9
|
+
# some things
|
|
10
|
+
spi_time_dev: float = 0
|
|
11
|
+
rx_spi_time_dev: float = 0
|
|
12
|
+
tx_spi_time_dev: float = 0
|
|
13
|
+
spi_count_dev: float = 0
|
|
14
|
+
com_time_dev: float = 0
|
|
15
|
+
rx_com_time_dev: float = 0
|
|
16
|
+
tx_com_time_dev: float = 0
|
|
17
|
+
com_count_dev: float = 0
|
|
18
|
+
temperature: float = 0
|
|
19
|
+
memory_load: float = 0
|
|
20
|
+
cpu_load: float = 0
|
|
@@ -0,0 +1,18 @@
|
|
|
1
|
+
import logging
|
|
2
|
+
from datetime import datetime
|
|
3
|
+
from robocad.common import Common
|
|
4
|
+
|
|
5
|
+
|
|
6
|
+
class Logger:
|
|
7
|
+
FORMAT = '[%(levelname)s]\t(%(threadName)-10s)\t%(message)s'
|
|
8
|
+
|
|
9
|
+
def __init__(self):
|
|
10
|
+
log_path = '/home/pi/robocad/logs/cad_main.log' if Common.on_real_robot else './cad_main.log'
|
|
11
|
+
logging.basicConfig(level=logging.INFO,
|
|
12
|
+
format=self.FORMAT,
|
|
13
|
+
filename=log_path,
|
|
14
|
+
filemode='w+')
|
|
15
|
+
self.main_logger = logging.getLogger()
|
|
16
|
+
|
|
17
|
+
def write_main_log(self, s: str):
|
|
18
|
+
self.main_logger.info(datetime.now().strftime("%H:%M:%S") + " " + s)
|
|
@@ -3,7 +3,7 @@ import sys
|
|
|
3
3
|
import time
|
|
4
4
|
from threading import Thread
|
|
5
5
|
|
|
6
|
-
from robocad.
|
|
6
|
+
from robocad.common import Common
|
|
7
7
|
from .shared import TitanStatic
|
|
8
8
|
from .shared import LibHolder
|
|
9
9
|
from funcad.funcad import Funcad
|
|
@@ -31,29 +31,29 @@ class TitanCOM:
|
|
|
31
31
|
while not cls.stop_th:
|
|
32
32
|
tx_time: float = time.time() * 1000
|
|
33
33
|
tx_data = cls.set_up_tx_data()
|
|
34
|
-
|
|
34
|
+
Common.tx_com_time_dev = round(time.time() * 1000 - tx_time, 2)
|
|
35
35
|
|
|
36
36
|
rx_data: bytearray = LibHolder.rw_usb(tx_data)
|
|
37
37
|
|
|
38
38
|
rx_time: float = time.time() * 1000
|
|
39
39
|
cls.set_up_rx_data(rx_data)
|
|
40
|
-
|
|
40
|
+
Common.rx_com_time_dev = round(time.time() * 1000 - rx_time, 2)
|
|
41
41
|
|
|
42
42
|
comm_counter += 1
|
|
43
43
|
if time.time() - send_count_time > 1:
|
|
44
44
|
send_count_time = time.time()
|
|
45
|
-
|
|
45
|
+
Common.com_count_dev = comm_counter
|
|
46
46
|
comm_counter = 0
|
|
47
47
|
|
|
48
48
|
time.sleep(0.001)
|
|
49
|
-
|
|
49
|
+
Common.com_time_dev = round(time.time() * 10000) - start_time
|
|
50
50
|
start_time = round(time.time() * 10000)
|
|
51
51
|
except Exception as e:
|
|
52
52
|
LibHolder.stop_usb()
|
|
53
53
|
exc_type, exc_obj, exc_tb = sys.exc_info()
|
|
54
54
|
file_name = os.path.split(exc_tb.tb_frame.f_code.co_filename)[1]
|
|
55
|
-
|
|
56
|
-
|
|
55
|
+
Common.logger.write_main_log(" ".join(map(str, [exc_type, file_name, exc_tb.tb_lineno])))
|
|
56
|
+
Common.logger.write_main_log(str(e))
|
|
57
57
|
|
|
58
58
|
@staticmethod
|
|
59
59
|
def set_up_rx_data(data: bytearray) -> None:
|
|
@@ -76,7 +76,7 @@ class TitanCOM:
|
|
|
76
76
|
TitanStatic.limit_h_3 = Funcad.access_bit(data[10], 2)
|
|
77
77
|
|
|
78
78
|
else:
|
|
79
|
-
|
|
79
|
+
Common.logger.write_main_log("received wrong data " + " ".join(map(str, data)))
|
|
80
80
|
|
|
81
81
|
@staticmethod
|
|
82
82
|
def set_up_tx_data() -> bytearray:
|
|
@@ -3,7 +3,7 @@ import sys
|
|
|
3
3
|
import time
|
|
4
4
|
from threading import Thread
|
|
5
5
|
|
|
6
|
-
from robocad.
|
|
6
|
+
from robocad.common import Common
|
|
7
7
|
from .shared import VMXStatic
|
|
8
8
|
from .shared import LibHolder
|
|
9
9
|
from funcad.funcad import Funcad
|
|
@@ -33,29 +33,29 @@ class VMXSPI:
|
|
|
33
33
|
while not cls.stop_th:
|
|
34
34
|
tx_time: float = time.time() * 1000
|
|
35
35
|
tx_list = cls.set_up_tx_data()
|
|
36
|
-
|
|
36
|
+
Common.tx_spi_time_dev = round(time.time() * 1000 - tx_time, 2)
|
|
37
37
|
|
|
38
38
|
rx_list: bytearray = LibHolder.rw_spi(tx_list)
|
|
39
39
|
|
|
40
40
|
rx_time: float = time.time() * 1000
|
|
41
41
|
cls.set_up_rx_data(rx_list)
|
|
42
|
-
|
|
42
|
+
Common.rx_spi_time_dev = round(time.time() * 1000 - rx_time, 2)
|
|
43
43
|
|
|
44
44
|
comm_counter += 1
|
|
45
45
|
if time.time() - send_count_time > 1:
|
|
46
46
|
send_count_time = time.time()
|
|
47
|
-
|
|
47
|
+
Common.spi_count_dev = comm_counter
|
|
48
48
|
comm_counter = 0
|
|
49
49
|
|
|
50
50
|
time.sleep(0.002)
|
|
51
|
-
|
|
51
|
+
Common.spi_time_dev = round(time.time() * 1000 - start_time, 2)
|
|
52
52
|
start_time = time.time() * 1000
|
|
53
53
|
except (Exception, EOFError) as e:
|
|
54
54
|
LibHolder.stop_spi()
|
|
55
55
|
exc_type, exc_obj, exc_tb = sys.exc_info()
|
|
56
56
|
file_name = os.path.split(exc_tb.tb_frame.f_code.co_filename)[1]
|
|
57
|
-
|
|
58
|
-
|
|
57
|
+
Common.logger.write_main_log(" ".join(map(str, [exc_type, file_name, exc_tb.tb_lineno])))
|
|
58
|
+
Common.logger.write_main_log(str(e))
|
|
59
59
|
|
|
60
60
|
@classmethod
|
|
61
61
|
def set_up_rx_data(cls, data: bytearray) -> None:
|
|
@@ -67,7 +67,7 @@ class VMXSPI:
|
|
|
67
67
|
VMXStatic.ultrasound_2 = us2_ui / 100
|
|
68
68
|
|
|
69
69
|
power: float = ((data[8] & 0xff) << 8 | (data[7] & 0xff)) / 100
|
|
70
|
-
|
|
70
|
+
Common.power = power
|
|
71
71
|
|
|
72
72
|
# calc yaw unlim
|
|
73
73
|
new_yaw = (yaw_ui / 100) * (1 if Funcad.access_bit(data[9], 1) else -1)
|
{robocad-py-0.0.2.3/robocad/robocadSim → robocad-py-1.0.2.3/robocad/internal/studica}/connection.py
RENAMED
|
@@ -2,18 +2,17 @@ import socket
|
|
|
2
2
|
import threading
|
|
3
3
|
import time
|
|
4
4
|
import warnings
|
|
5
|
+
import struct
|
|
5
6
|
|
|
6
|
-
from robocad.
|
|
7
|
+
from robocad.common import Common
|
|
7
8
|
|
|
8
9
|
|
|
9
10
|
class ListenPort:
|
|
10
|
-
def __init__(self, port: int
|
|
11
|
+
def __init__(self, port: int):
|
|
11
12
|
self.__port = port
|
|
12
|
-
self.__is_camera = is_camera
|
|
13
13
|
|
|
14
14
|
# other
|
|
15
15
|
self.__stop_thread = False
|
|
16
|
-
self.out_string = ''
|
|
17
16
|
self.out_bytes = b''
|
|
18
17
|
|
|
19
18
|
self.__sct = None
|
|
@@ -26,38 +25,32 @@ class ListenPort:
|
|
|
26
25
|
def listening(self):
|
|
27
26
|
self.__sct = socket.socket(socket.AF_INET, socket.SOCK_STREAM, socket.IPPROTO_TCP)
|
|
28
27
|
self.__sct.connect(('127.0.0.1', self.__port))
|
|
29
|
-
|
|
28
|
+
Common.logger.write_main_log("connected: " + str(self.__port))
|
|
30
29
|
while not self.__stop_thread:
|
|
31
30
|
try:
|
|
32
|
-
|
|
33
|
-
|
|
34
|
-
|
|
35
|
-
|
|
36
|
-
|
|
37
|
-
|
|
38
|
-
|
|
39
|
-
|
|
40
|
-
|
|
41
|
-
|
|
42
|
-
|
|
43
|
-
data_size = self.__sct.recv(4)
|
|
44
|
-
if len(data_size) < 4:
|
|
45
|
-
continue
|
|
46
|
-
length = (data_size[3] & 0xff) << 24 | (data_size[2] & 0xff) << 16 | \
|
|
47
|
-
(data_size[1] & 0xff) << 8 | (data_size[0] & 0xff)
|
|
48
|
-
self.out_bytes = self.__sct.recv(length)
|
|
49
|
-
self.out_string = self.out_bytes.decode('utf-16-le')
|
|
31
|
+
dt = "Wait for data".encode('utf-16-le')
|
|
32
|
+
dt_ln = struct.pack('<I', len(dt))
|
|
33
|
+
self.__sct.sendall(dt_ln)
|
|
34
|
+
self.__sct.sendall(dt)
|
|
35
|
+
|
|
36
|
+
data_size = self.__sct.recv(4)
|
|
37
|
+
if len(data_size) < 4:
|
|
38
|
+
continue
|
|
39
|
+
length = (data_size[3] & 0xff) << 24 | (data_size[2] & 0xff) << 16 | \
|
|
40
|
+
(data_size[1] & 0xff) << 8 | (data_size[0] & 0xff)
|
|
41
|
+
self.out_bytes = self.__sct.recv(length)
|
|
50
42
|
# задержка для слабых компов
|
|
51
43
|
time.sleep(0.004)
|
|
52
|
-
except (ConnectionAbortedError, BrokenPipeError):
|
|
44
|
+
except (ConnectionAbortedError, BrokenPipeError, OSError):
|
|
53
45
|
# возникает при отключении сокета
|
|
54
46
|
break
|
|
55
|
-
|
|
56
|
-
|
|
57
|
-
|
|
47
|
+
Common.logger.write_main_log("disconnected: " + str(self.__port))
|
|
48
|
+
try:
|
|
49
|
+
self.__sct.shutdown(socket.SHUT_RDWR)
|
|
50
|
+
self.__sct.close()
|
|
51
|
+
except (OSError, Exception): pass # idc
|
|
58
52
|
|
|
59
53
|
def reset_out(self):
|
|
60
|
-
self.out_string = ''
|
|
61
54
|
self.out_bytes = b''
|
|
62
55
|
|
|
63
56
|
def stop_listening(self):
|
|
@@ -67,19 +60,19 @@ class ListenPort:
|
|
|
67
60
|
try:
|
|
68
61
|
self.__sct.shutdown(socket.SHUT_RDWR)
|
|
69
62
|
except (OSError, Exception):
|
|
70
|
-
|
|
63
|
+
Common.logger.write_main_log("Something went wrong while shutting down socket on port " +
|
|
71
64
|
str(self.__port))
|
|
72
65
|
if self.__thread is not None:
|
|
73
66
|
st_time = time.time()
|
|
74
67
|
# если поток все еще живой, ждем 1 секунды и закрываем сокет
|
|
75
68
|
while self.__thread.is_alive():
|
|
76
69
|
if time.time() - st_time > 1:
|
|
77
|
-
|
|
70
|
+
Common.logger.write_main_log("Something went wrong. Rude disconnection on port " +
|
|
78
71
|
str(self.__port))
|
|
79
72
|
try:
|
|
80
73
|
self.__sct.close()
|
|
81
74
|
except (OSError, Exception):
|
|
82
|
-
|
|
75
|
+
Common.logger.write_main_log("Something went wrong while closing socket on port " +
|
|
83
76
|
str(self.__port))
|
|
84
77
|
st_time = time.time()
|
|
85
78
|
|
|
@@ -90,7 +83,7 @@ class TalkPort:
|
|
|
90
83
|
|
|
91
84
|
# other
|
|
92
85
|
self.__stop_thread = False
|
|
93
|
-
self.
|
|
86
|
+
self.out_bytes = b''
|
|
94
87
|
|
|
95
88
|
self.__sct = None
|
|
96
89
|
self.__thread = None
|
|
@@ -102,22 +95,27 @@ class TalkPort:
|
|
|
102
95
|
def talking(self):
|
|
103
96
|
self.__sct = socket.socket(socket.AF_INET, socket.SOCK_STREAM, socket.IPPROTO_TCP)
|
|
104
97
|
self.__sct.connect(('127.0.0.1', self.__port))
|
|
105
|
-
|
|
98
|
+
Common.logger.write_main_log("connected: " + str(self.__port))
|
|
106
99
|
while not self.__stop_thread:
|
|
107
100
|
try:
|
|
108
|
-
|
|
109
|
-
|
|
101
|
+
dt_ln = struct.pack('<I', len(self.out_bytes))
|
|
102
|
+
self.__sct.sendall(dt_ln)
|
|
103
|
+
self.__sct.sendall(self.out_bytes)
|
|
104
|
+
_ = self.__sct.recv(4) # ответ сервера
|
|
105
|
+
_ = self.__sct.recv(4) # ответ сервера
|
|
110
106
|
# задержка для слабых компов
|
|
111
107
|
time.sleep(0.004)
|
|
112
|
-
except (ConnectionAbortedError, BrokenPipeError):
|
|
108
|
+
except (ConnectionAbortedError, BrokenPipeError, OSError):
|
|
113
109
|
# возникает при отключении сокета
|
|
114
110
|
break
|
|
115
|
-
|
|
116
|
-
|
|
117
|
-
|
|
111
|
+
Common.logger.write_main_log("disconnected: " + str(self.__port))
|
|
112
|
+
try:
|
|
113
|
+
self.__sct.shutdown(socket.SHUT_RDWR)
|
|
114
|
+
self.__sct.close()
|
|
115
|
+
except (OSError, Exception): pass # idc
|
|
118
116
|
|
|
119
117
|
def reset_out(self):
|
|
120
|
-
self.
|
|
118
|
+
self.out_bytes = b''
|
|
121
119
|
|
|
122
120
|
def stop_talking(self):
|
|
123
121
|
self.__stop_thread = True
|
|
@@ -126,42 +124,32 @@ class TalkPort:
|
|
|
126
124
|
try:
|
|
127
125
|
self.__sct.shutdown(socket.SHUT_RDWR)
|
|
128
126
|
except (OSError, Exception):
|
|
129
|
-
|
|
127
|
+
Common.logger.write_main_log("Something went wrong while shutting down socket on port " +
|
|
130
128
|
str(self.__port))
|
|
131
129
|
if self.__thread is not None:
|
|
132
130
|
st_time = time.time()
|
|
133
131
|
# если поток все еще живой, ждем 1 секунды и закрываем сокет
|
|
134
132
|
while self.__thread.is_alive():
|
|
135
133
|
if time.time() - st_time > 1:
|
|
136
|
-
|
|
134
|
+
Common.logger.write_main_log("Something went wrong. Rude disconnection on port " +
|
|
137
135
|
str(self.__port))
|
|
138
136
|
try:
|
|
139
137
|
self.__sct.close()
|
|
140
138
|
except (OSError, Exception):
|
|
141
|
-
|
|
139
|
+
Common.logger.write_main_log("Something went wrong while closing socket on port " +
|
|
142
140
|
str(self.__port))
|
|
143
141
|
st_time = time.time()
|
|
144
142
|
|
|
145
143
|
|
|
146
144
|
class ParseChannels:
|
|
147
145
|
@staticmethod
|
|
148
|
-
def
|
|
149
|
-
|
|
150
|
-
return
|
|
151
|
-
|
|
152
|
-
|
|
153
|
-
|
|
146
|
+
def join_studica_channel(lst: tuple) -> bytes:
|
|
147
|
+
if len(lst) < 14:
|
|
148
|
+
return b''
|
|
149
|
+
return struct.pack('14f', *lst)
|
|
150
|
+
|
|
154
151
|
@staticmethod
|
|
155
|
-
def
|
|
156
|
-
|
|
157
|
-
return tuple(map(bool, map(int, txt.split(';'))))
|
|
158
|
-
except (Exception, ValueError):
|
|
152
|
+
def parse_studica_channel(data: bytes) -> tuple:
|
|
153
|
+
if len(data) < 52:
|
|
159
154
|
return tuple()
|
|
160
|
-
|
|
161
|
-
@staticmethod
|
|
162
|
-
def join_float_channel(lst: tuple):
|
|
163
|
-
return ';'.join(map(str, lst))
|
|
164
|
-
|
|
165
|
-
@staticmethod
|
|
166
|
-
def join_bool_channel(lst: tuple):
|
|
167
|
-
return ';'.join(map(str, map(int, lst)))
|
|
155
|
+
return struct.unpack('<4i2f4Hf16B', data)
|
|
@@ -0,0 +1,17 @@
|
|
|
1
|
+
from abc import ABC, abstractmethod
|
|
2
|
+
|
|
3
|
+
import cv2
|
|
4
|
+
|
|
5
|
+
|
|
6
|
+
class ConnectionBase(ABC):
|
|
7
|
+
@abstractmethod
|
|
8
|
+
def start(self) -> None:
|
|
9
|
+
pass
|
|
10
|
+
|
|
11
|
+
@abstractmethod
|
|
12
|
+
def stop(self) -> None:
|
|
13
|
+
pass
|
|
14
|
+
|
|
15
|
+
@abstractmethod
|
|
16
|
+
def get_camera(self) -> cv2.typing.MatLike:
|
|
17
|
+
pass
|
|
@@ -0,0 +1,55 @@
|
|
|
1
|
+
import subprocess
|
|
2
|
+
from threading import Thread
|
|
3
|
+
import time
|
|
4
|
+
import cv2
|
|
5
|
+
|
|
6
|
+
from robocad.common import Common
|
|
7
|
+
from .connection_base import ConnectionBase
|
|
8
|
+
|
|
9
|
+
from .SPI import VMXSPI
|
|
10
|
+
from .COM import TitanCOM
|
|
11
|
+
|
|
12
|
+
|
|
13
|
+
class ConnectionReal(ConnectionBase):
|
|
14
|
+
def start(self) -> None:
|
|
15
|
+
try:
|
|
16
|
+
self.__camera_instance = cv2.VideoCapture(0)
|
|
17
|
+
except Exception as e:
|
|
18
|
+
Common.logger.write_main_log("Exception while creating camera instance: ")
|
|
19
|
+
Common.logger.write_main_log(str(e))
|
|
20
|
+
|
|
21
|
+
VMXSPI.start_spi()
|
|
22
|
+
TitanCOM.start_com()
|
|
23
|
+
subprocess.run(['sudo', '/home/pi/pi-blaster/pi-blaster'])
|
|
24
|
+
self.__stop_robot_info_thread = False
|
|
25
|
+
self.__robot_info_thread: Thread = Thread(target=self.__update_rpi_cringe)
|
|
26
|
+
self.__robot_info_thread.daemon = True
|
|
27
|
+
self.__robot_info_thread.start()
|
|
28
|
+
|
|
29
|
+
def stop(self) -> None:
|
|
30
|
+
self.__stop_robot_info_thread = True
|
|
31
|
+
self.__robot_info_thread.join()
|
|
32
|
+
TitanCOM.stop_th = True
|
|
33
|
+
TitanCOM.th.join()
|
|
34
|
+
VMXSPI.stop_th = True
|
|
35
|
+
VMXSPI.th.join()
|
|
36
|
+
|
|
37
|
+
def get_camera(self) -> cv2.typing.MatLike:
|
|
38
|
+
try:
|
|
39
|
+
ret, frame = self.__camera_instance.read()
|
|
40
|
+
if ret:
|
|
41
|
+
return frame
|
|
42
|
+
except Exception:
|
|
43
|
+
# there could be an error if there is no camera instance
|
|
44
|
+
pass
|
|
45
|
+
return None
|
|
46
|
+
|
|
47
|
+
def __update_rpi_cringe(self):
|
|
48
|
+
from gpiozero import CPUTemperature # type: ignore
|
|
49
|
+
import psutil # type: ignore
|
|
50
|
+
cpu_temp: CPUTemperature = CPUTemperature()
|
|
51
|
+
while not self.__stop_robot_info_thread:
|
|
52
|
+
Common.temperature = cpu_temp.temperature
|
|
53
|
+
Common.memory_load = psutil.virtual_memory().percent
|
|
54
|
+
Common.cpu_load = psutil.cpu_percent(interval=0.5)
|
|
55
|
+
time.sleep(0.5)
|
|
@@ -0,0 +1,106 @@
|
|
|
1
|
+
from threading import Thread
|
|
2
|
+
import time
|
|
3
|
+
|
|
4
|
+
import cv2
|
|
5
|
+
import numpy as np
|
|
6
|
+
|
|
7
|
+
from .connection import TalkPort, ListenPort, ParseChannels
|
|
8
|
+
from .shared import TitanStatic, VMXStatic
|
|
9
|
+
from .connection_base import ConnectionBase
|
|
10
|
+
|
|
11
|
+
|
|
12
|
+
class ConnectionSim(ConnectionBase):
|
|
13
|
+
__port_set_data: int = 65431
|
|
14
|
+
__port_get_data: int = 65432
|
|
15
|
+
__port_camera: int = 65438
|
|
16
|
+
|
|
17
|
+
__talk_channel: TalkPort = None
|
|
18
|
+
__listen_channel: ListenPort = None
|
|
19
|
+
__camera_channel: ListenPort = None
|
|
20
|
+
__update_thread: Thread = None
|
|
21
|
+
__stop_update_thread: bool = False
|
|
22
|
+
|
|
23
|
+
def start(self) -> None:
|
|
24
|
+
if (self.__talk_channel is None):
|
|
25
|
+
self.__talk_channel = TalkPort(self.__port_set_data)
|
|
26
|
+
self.__talk_channel.start_talking()
|
|
27
|
+
if (self.__listen_channel is None):
|
|
28
|
+
self.__listen_channel = ListenPort(self.__port_get_data)
|
|
29
|
+
self.__listen_channel.start_listening()
|
|
30
|
+
if (self.__camera_channel is None):
|
|
31
|
+
self.__camera_channel = ListenPort(self.__port_camera)
|
|
32
|
+
self.__camera_channel.start_listening()
|
|
33
|
+
|
|
34
|
+
self.__stop_update_thread = False
|
|
35
|
+
self.__update_thread = Thread(target=self.__update)
|
|
36
|
+
self.__update_thread.daemon = True
|
|
37
|
+
self.__update_thread.start()
|
|
38
|
+
|
|
39
|
+
def stop(self) -> None:
|
|
40
|
+
self.__stop_update_thread = True
|
|
41
|
+
self.__update_thread.join()
|
|
42
|
+
self.__talk_channel.stop_talking()
|
|
43
|
+
self.__listen_channel.stop_listening()
|
|
44
|
+
self.__camera_channel.stop_listening()
|
|
45
|
+
|
|
46
|
+
def get_camera(self) -> cv2.typing.MatLike:
|
|
47
|
+
camera_data = self.__camera_channel.out_bytes
|
|
48
|
+
if len(camera_data) == 921600:
|
|
49
|
+
nparr = np.frombuffer(camera_data, np.uint8)
|
|
50
|
+
if nparr.size > 0:
|
|
51
|
+
img_rgb = nparr.reshape(480, 640, 3)
|
|
52
|
+
img_bgr = cv2.cvtColor(img_rgb, cv2.COLOR_RGB2BGR)
|
|
53
|
+
return img_bgr
|
|
54
|
+
return None
|
|
55
|
+
|
|
56
|
+
def __set_data(self, values: tuple) -> None:
|
|
57
|
+
self.__talk_channel.out_bytes = ParseChannels.join_studica_channel(values)
|
|
58
|
+
|
|
59
|
+
def __get_data(self) -> tuple:
|
|
60
|
+
return ParseChannels.parse_studica_channel(self.__listen_channel.out_bytes)
|
|
61
|
+
|
|
62
|
+
def __update(self):
|
|
63
|
+
while not self.__stop_update_thread:
|
|
64
|
+
# set data
|
|
65
|
+
values = [TitanStatic.speed_motor_0,
|
|
66
|
+
TitanStatic.speed_motor_1,
|
|
67
|
+
TitanStatic.speed_motor_2,
|
|
68
|
+
TitanStatic.speed_motor_3]
|
|
69
|
+
values.extend(VMXStatic.hcdio_values)
|
|
70
|
+
self.__set_data(tuple(values))
|
|
71
|
+
|
|
72
|
+
# get data
|
|
73
|
+
values = self.__get_data()
|
|
74
|
+
if len(values) > 0:
|
|
75
|
+
TitanStatic.enc_motor_0 = values[0]
|
|
76
|
+
TitanStatic.enc_motor_1 = values[1]
|
|
77
|
+
TitanStatic.enc_motor_2 = values[2]
|
|
78
|
+
TitanStatic.enc_motor_3 = values[3]
|
|
79
|
+
VMXStatic.ultrasound_1 = values[4]
|
|
80
|
+
VMXStatic.ultrasound_2 = values[5]
|
|
81
|
+
VMXStatic.analog_1 = values[6]
|
|
82
|
+
VMXStatic.analog_2 = values[7]
|
|
83
|
+
VMXStatic.analog_3 = values[8]
|
|
84
|
+
VMXStatic.analog_4 = values[9]
|
|
85
|
+
VMXStatic.yaw = values[10]
|
|
86
|
+
|
|
87
|
+
TitanStatic.limit_h_0 = values[11] == 1
|
|
88
|
+
TitanStatic.limit_l_0 = values[12] == 1
|
|
89
|
+
TitanStatic.limit_h_1 = values[13] == 1
|
|
90
|
+
TitanStatic.limit_l_1 = values[14] == 1
|
|
91
|
+
TitanStatic.limit_h_2 = values[15] == 1
|
|
92
|
+
TitanStatic.limit_l_2 = values[16] == 1
|
|
93
|
+
TitanStatic.limit_h_3 = values[17] == 1
|
|
94
|
+
TitanStatic.limit_l_3 = values[18] == 1
|
|
95
|
+
|
|
96
|
+
VMXStatic.flex_0 = values[19] == 1
|
|
97
|
+
VMXStatic.flex_1 = values[20] == 1
|
|
98
|
+
VMXStatic.flex_2 = values[21] == 1
|
|
99
|
+
VMXStatic.flex_3 = values[22] == 1
|
|
100
|
+
VMXStatic.flex_4 = values[23] == 1
|
|
101
|
+
VMXStatic.flex_5 = values[24] == 1
|
|
102
|
+
VMXStatic.flex_6 = values[25] == 1
|
|
103
|
+
VMXStatic.flex_7 = values[26] == 1
|
|
104
|
+
|
|
105
|
+
# задержка для слабых компов
|
|
106
|
+
time.sleep(0.004)
|
|
@@ -1,5 +1,6 @@
|
|
|
1
1
|
import sys
|
|
2
2
|
import ctypes
|
|
3
|
+
from robocad.common import Common
|
|
3
4
|
|
|
4
5
|
|
|
5
6
|
class LibHolder:
|
|
@@ -100,27 +101,35 @@ class VMXStatic:
|
|
|
100
101
|
flex_6: bool = False
|
|
101
102
|
flex_7: bool = False
|
|
102
103
|
|
|
104
|
+
hcdio_values: list = [0.0] * 10
|
|
105
|
+
|
|
103
106
|
@classmethod
|
|
104
107
|
def set_servo_angle(cls, angle: float, pin: int):
|
|
105
108
|
dut: float = 0.000666 * angle + 0.05
|
|
109
|
+
cls.hcdio_values[pin] = dut
|
|
106
110
|
VMXStatic.echo_to_file(str(cls.HCDIO_CONST_ARRAY[pin]) + "=" + str(dut))
|
|
107
111
|
|
|
108
112
|
@classmethod
|
|
109
113
|
def set_led_state(cls, state: bool, pin: int):
|
|
110
114
|
dut: float = 0.2 if state else 0.0
|
|
115
|
+
cls.hcdio_values[pin] = dut
|
|
111
116
|
VMXStatic.echo_to_file(str(cls.HCDIO_CONST_ARRAY[pin]) + "=" + str(dut))
|
|
112
117
|
|
|
113
118
|
@classmethod
|
|
114
119
|
def set_servo_pwm(cls, pwm: float, pin: int):
|
|
115
120
|
dut: float = pwm
|
|
121
|
+
cls.hcdio_values[pin] = dut
|
|
116
122
|
VMXStatic.echo_to_file(str(cls.HCDIO_CONST_ARRAY[pin]) + "=" + str(dut))
|
|
117
123
|
|
|
118
124
|
@classmethod
|
|
119
125
|
def disable_servo(cls, pin: int):
|
|
126
|
+
cls.hcdio_values[pin] = 0.0
|
|
120
127
|
VMXStatic.echo_to_file(str(cls.HCDIO_CONST_ARRAY[pin]) + "=" + "0.0")
|
|
121
128
|
|
|
122
129
|
@staticmethod
|
|
123
130
|
def echo_to_file(st: str):
|
|
131
|
+
if not Common.on_real_robot:
|
|
132
|
+
return None
|
|
124
133
|
original_stdout = sys.stdout
|
|
125
134
|
with open('/dev/pi-blaster', 'w') as f:
|
|
126
135
|
sys.stdout = f # Change the standard output to the file we created.
|