107 Commits

Author SHA1 Message Date
fb31ab0d73 Add LED animations to runtime 2024-04-24 14:42:47 -05:00
302d275c64 Update config 2024-04-24 14:42:47 -05:00
43392fa3ca Freeze math3d version 2024-04-24 14:42:47 -05:00
660fe29236 Update camera image parser 2024-04-24 14:42:47 -05:00
275cbd027e Added open gripper to init routine 2024-04-24 14:42:07 -05:00
f4e43f33d2 Created functions for routines 2024-04-24 14:40:38 -05:00
ae97ed1a14 Made pickup and dropoff routines for tray and holder. Adjusted home position 2024-04-23 18:56:11 -05:00
237319db14 Fixed drop off routine to not hit walls 2024-04-22 21:56:07 -05:00
a698c4a753 Add more routines 2024-04-18 20:33:55 -05:00
939474378a Add open and close gripper functions 2024-04-12 22:05:34 -05:00
145f51d08c Update IPs for LED system 2024-04-12 20:28:34 -05:00
4973fc79be Merge branch 'main' of https://git.myitr.org/Jukebox/jukebox-software 2024-04-12 20:28:33 -05:00
ff2269193b small dimensions fixes 2024-04-12 20:28:31 -05:00
5edd7f4592 Remove extraneous pass 2024-03-27 20:41:07 -05:00
4dd6f7649a Implement cable_search 2024-03-27 20:40:20 -05:00
dc1e568a96 Add basic cable_map implementation 2024-03-27 20:33:21 -05:00
1ec6d92cfa Deploy docker containers 2024-03-27 19:50:01 -05:00
e21ded46f1 Update juekbox-web 2024-03-27 19:47:17 -05:00
672507f498 Add jukebox web 2024-03-27 19:46:45 -05:00
64bb50f055 Add setup-alpine-vm.sh 2024-03-28 00:44:57 +00:00
5016b4e99f Update compose.yml 2024-03-28 00:44:35 +00:00
efbda23c38 Fix docker runtime support 2024-03-27 18:53:50 -05:00
19ce328596 Correctly parse results from get_specs 2024-03-27 17:49:02 -05:00
ad216f21fa Implement cable_details call 2024-03-26 18:42:01 -05:00
6d6c2030a9 Merge branch 'main' of https://git.myitr.org/Jukebox/jukebox-software 2024-03-26 15:24:20 -05:00
9893222335 Pick-up routine 2024-03-26 15:24:18 -05:00
82a52dea5a Add cables to meilisearch db 2024-03-26 15:09:26 -05:00
77fdc43fce Add missing robot pass-ins 2024-03-24 15:35:46 -05:00
3de59f5985 Convert ur5_control to class based (untested) 2024-03-24 15:31:58 -05:00
6887fa943b Merge branch 'main' of https://git.myitr.org/Jukebox/jukebox-software 2024-03-24 13:50:17 -05:00
2ec7906ee4 Basic move restrictions and flip routine 2024-03-23 15:47:10 -05:00
069d2175d9 Convert led code to class based for multithreading 2024-03-23 15:33:51 -05:00
9b1b92e21d Re-add https:// format, needed for most devices 2024-03-21 19:48:46 -05:00
ee0f8f4250 Remove cairosvg VERSION patch 2024-03-21 19:41:46 -05:00
9c9435570b Remove cairosvg as it doesn't have pip-only lib. Use png instead. 2024-03-21 19:39:43 -05:00
1bf10f7349 Update label generator to include belden logo, use QR code, URL matching 2024-03-21 18:57:59 -05:00
3c8d6c7ad3 Remove debug print 2024-03-20 16:31:29 -05:00
cbe7225fc9 Fix bug with part name in query_search 2024-03-20 16:27:43 -05:00
44efc4006e Correct flip rz orientation 2024-03-19 17:48:32 -05:00
218303e92b Try different moves 2024-03-17 22:01:34 -05:00
e5d3f87b5c Go to home position first 2024-03-17 20:49:39 -05:00
2ab1d0dbb3 Add flip around mode to fit edge slots 2024-03-17 20:48:26 -05:00
1338c3f440 Added tool z rotation for angled gripper 2024-03-17 20:07:25 -05:00
83b077b4df Make limb lengths and offsets global 2024-03-17 19:59:17 -05:00
f16242f5be Re-merge calculate_theta into get_joints_from_xyz_rel 2024-03-17 19:53:49 -05:00
2f28a01b7c Add basic kinematics for gripper angle 2024-03-17 19:50:04 -05:00
fb85a56d47 Use movejs to go to all cable positions 2024-03-17 16:21:57 -05:00
bec0c63763 Fix ur5_control bugs, fully working IK!! Thanks Nadeem 2024-03-17 16:13:53 -05:00
4ae30b82a0 Cleaned up notebook 2024-03-17 15:43:06 -05:00
4bc3e30116 Fixed edge cases when calculating base angle 2024-03-17 01:01:39 -05:00
6053d1b4ec Update Dockerfile with runtime dependencies, copy only necessary files 2024-03-15 21:02:59 -05:00
f43f9cda2f Catch RuntimeError when GS not installed 2024-03-15 20:41:01 -05:00
992040e812 Add basic label generator app, add return values to parsing 2024-03-15 20:31:37 -05:00
5502a5069d All real samples ordered have working spec lookup 2024-03-14 22:09:12 -05:00
fc2af34450 Add Alphawire datasheet fallback 2024-03-14 22:06:13 -05:00
39723ec442 Update Alphawire table parsing 2024-03-14 21:35:28 -05:00
25ceb6c133 Merge branch 'main' of https://git.myitr.org/Jukebox/jukebox-software 2024-03-14 01:49:19 -05:00
56451d3e5c Inverse kinematic update to account for base rotation 2024-03-14 01:49:15 -05:00
53638f72e1 Merge branch 'dthomas_meilisearch' 2024-03-12 16:15:13 -05:00
5ef8795eb4 Merge branch 'main' into dthomas_meilisearch
# Conflicts:
#	.gitignore
#	read_datasheet.py
2024-03-12 16:13:41 -05:00
a63faba2aa Add checks to updating filterable attributes to avoid hitting weird edge cases 2024-03-12 16:08:47 -05:00
dd0ac46662 Improve search & parsing algorithm, easier to source venv files 2024-03-11 23:52:26 -05:00
1a07501d53 Edited test site and added ping 2024-03-09 20:13:43 -06:00
0b97079cfd Created Notes, Edited websocket_test.html 2024-03-08 21:35:21 -06:00
a6d557d1c6 Changes to install files for Ubuntu and added *.png to .gitignore 2024-03-08 20:31:22 -06:00
5a11acfa42 Add basic LED animations 2024-03-08 19:45:45 -06:00
0f2c19e811 Merge remote-tracking branch 'origin/dthomas_meilisearch' into dthomas_meilisearch 2024-03-08 19:13:03 -06:00
b18355fc14 nuke database.py 2024-03-08 19:12:41 -06:00
6921d5c4b4 Added ipywidgets requirement 2024-03-06 11:00:24 -06:00
b861a61f07 Merge branch 'main' of https://git.myitr.org/Jukebox/jukebox-software 2024-03-05 16:30:26 -06:00
925ceb4b5a Commented jupytr notebook 2024-03-05 16:30:19 -06:00
dd2559130d Commented jupytr notebook 2024-03-05 16:27:48 -06:00
1fa7654da5 removed temp file 2024-03-05 16:21:07 -06:00
051cc1d003 Merge branch 'main' of https://git.myitr.org/Jukebox/jukebox-software 2024-03-05 16:20:11 -06:00
e1af00e1db Inverse kinematics complete 2024-03-05 16:20:05 -06:00
aadb6ba24d add search functions to JukeboxSearch 2024-03-01 21:24:37 -06:00
4561b1c1a3 fix error when index does not exist 2024-03-01 20:37:22 -06:00
6edd0b4ef0 fix map datatype 2024-03-01 20:37:02 -06:00
2c242aac29 Merge branch 'main' into dthomas_meilisearch 2024-03-01 19:26:57 -06:00
af6ffe451d Fix get_specs 2024-03-01 19:26:47 -06:00
b585f8cdb7 Merge branch 'main' into dthomas_meilisearch 2024-03-01 19:25:30 -06:00
50bf835d13 Update parsing and stuff 2024-03-01 19:25:01 -06:00
f12d8a8062 add print statement 2024-03-01 19:24:47 -06:00
fc9ff4c8b2 split lists if they contain more than 2 commas 2024-03-01 19:13:28 -06:00
e903150fd4 Add functions for connecting to Meilisearch and adding documents 2024-02-20 10:33:01 -06:00
d0ea696274 reorganize gitignore and add comments 2024-02-20 10:15:56 -06:00
eea8c9f5fa Merge branch 'main' into dthomas_meilisearch 2024-02-20 10:04:33 -06:00
fe5de4e54c Adjust datasheet parsing for meilisearch, add dockerfile 2024-02-17 23:08:21 -06:00
68b95bfe17 add a module for using meilisearch 2024-02-17 22:46:11 -06:00
e3e9b855f9 add compose file with meilisearch image 2024-02-17 22:45:30 -06:00
523915feb0 add partnum to parsing 2024-02-17 20:31:43 -06:00
b5b2a936c1 Switch to binary dependency 2024-02-17 20:25:51 -06:00
afd144bd32 FIx requirements.txt 2024-02-17 20:22:54 -06:00
eb221a5206 Create main runner app, with async multithreading 2024-02-17 20:21:42 -06:00
db7c8c4577 Add video abstraction class 2024-02-17 20:06:37 -06:00
21b1bf7992 Added system exit 2024-02-16 20:36:43 -06:00
d376dba67c Add keyboard control scripts, add websocket server 2024-02-08 12:35:30 -06:00
95631dbdbe Add LED array mapping, load base config for tabletop rings, and image/video player mode 2024-01-25 20:06:10 -06:00
9aef296763 More logging 2024-01-18 16:45:37 -06:00
2b287492de Make firefox start faster, verbose start 2024-01-18 16:41:57 -06:00
d2a4d93590 Working network test 2024-01-18 16:35:02 -06:00
58605dbe85 test server/client setup 2024-01-18 16:00:12 -06:00
7bf3276ce9 Add basic windows control system. Needs VM functional to continue 2024-01-17 20:14:20 -06:00
818688452b Add local loading page 2024-01-17 16:46:20 -06:00
01526524d4 Create main runner app, with async multithreading 2024-01-17 16:06:15 -06:00
33671683ea test rendering json in HTML table format 2024-01-17 09:23:06 -06:00
fad885c610 Add UR5 control test, datasheet JSON output 2024-01-16 17:27:55 -06:00
40 changed files with 4006 additions and 756 deletions

17
.gitignore vendored
View File

@ -1,9 +1,22 @@
# python
venv
__pycache__
# cable data folder(s)
cables
cables-sample.zip
# meilisearch (mainly where I've put the data volume for the container)
meili_data
# IDE things
.vscode
output.log
.idea
# videos
*.webm
output.mp4
# log files
output.log
cables-sample.zip
# images
map*.png
# Built app
build
# Generated label images
labels

3
.gitmodules vendored Normal file
View File

@ -0,0 +1,3 @@
[submodule "jukebox-web"]
path = jukebox-web
url = https://git.myitr.org/Jukebox/jukebox-web

13
Dockerfile Normal file
View File

@ -0,0 +1,13 @@
FROM python:3.11-slim
# Get runtime dependencies
# glx for OpenCV, ghostscript for datasheet PDF rendering, zbar for barcode scanning, git for cloning repos
RUN apt-get update && apt-get install -y libgl1-mesa-glx ghostscript libzbar0 git && apt-get clean && rm -rf /var/lib/apt/lists
COPY requirements.txt ./
#COPY config-server.yml config.yml
RUN pip3 install -r requirements.txt
COPY *.py *.yml *.sh *.txt *.html static templates ./
CMD ["sh", "-c", "python3 run.py"]
EXPOSE 5000
EXPOSE 8000
EXPOSE 9000

BIN
GothamCond-Medium.otf Normal file

Binary file not shown.

View File

@ -40,13 +40,16 @@ class DriveImg():
self.onLine = False
fprint("Offline")
def close(self):
self.trans.close()
def read_img(self):
resposta = 'Falha'
try:
if not self.onLine:
#print(f'tentando Conectar camera {self.ip}...')
gravaLog(ip=self.ip,msg=f'Trying to connect...')
sleep(2)
#sleep(2)
try:
self.trans = socket.socket(socket.AF_INET,socket.SOCK_STREAM)
self.trans.connect((self.ip,self.PORT))
@ -63,13 +66,13 @@ class DriveImg():
if valida.find("TC IMAGE")<0:
self.onLine = False
self.trans.close()
sleep(2)
#sleep(2)
gravaLog(ip=self.ip,tipo="Falha",msg=f'Unable to find TC IMAGE bookmark')
return "Error"
except Exception as ex:
self.onLine = False
self.trans.close()
sleep(2)
#sleep(2)
gravaLog(ip=self.ip,tipo="Falha",msg=f'Error - {str(ex)}')
return "Error"
if ret:
@ -113,7 +116,7 @@ class DriveImg():
#print(f'erro {str(ex)}')
self.onLine = False
self.trans.close()
sleep(2)
#sleep(2)
return resposta
class DriveData():
@ -139,7 +142,7 @@ class DriveData():
if not self.onLine:
#print(f'tentando Conectar...\n')
gravaLog(ip=self.ip,msg=f'tentando Conectar...',file="log_data.txt")
sleep(2)
#sleep(2)
try:
self.trans = socket.socket(socket.AF_INET,socket.SOCK_STREAM)
self.trans.connect((self.ip,self.PORT))
@ -154,7 +157,7 @@ class DriveData():
except Exception as ex:
self.onLine = False
gravaLog(ip=self.ip,tipo="Falha Generica",msg=f'erro {str(ex)}',file="log_data.txt")
sleep(2)
#sleep(2)
return resposta

BIN
belden-logo-superhires.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 448 KiB

41
belden-logo.svg Normal file
View File

@ -0,0 +1,41 @@
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 25.2.1, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 446.6 151.4" style="enable-background:new 0 0 446.6 151.4;" xml:space="preserve">
<style type="text/css">
.st0{fill:#004990;}
</style>
<g>
<g>
<path class="st0" d="M21.2,32.1h-1.4v87.2H55c20.3,0,32-9.1,32-24.9c0-12.3-5.6-19.7-15.8-22.1c5.1-3.6,7.8-9.1,7.8-16.9
c0-15.5-8.9-23.3-26.5-23.3H21.2z M44.7,51.6c7.4,0,11.4,1.1,11.4,6.8c0,4.8-3.1,6.8-10.5,6.8c0,0-0.6,0-1.1,0
c0-2.1,0-11.5,0-13.6C44.5,51.6,44.7,51.6,44.7,51.6z M45.4,84.4l1.8,0c4.6,0,10.3-0.1,13,2.6c1.2,1.2,1.8,2.9,1.8,5.2
c0,2-0.6,3.5-1.7,4.7c-3,3-9.2,2.9-13.8,2.9c0,0-1.4,0-2.1,0c0-2.1,0-13.3,0-15.4C44.9,84.4,45.4,84.4,45.4,84.4z"/>
<g>
<path class="st0" d="M139.8,32.1H90.4v87.2h50.8V98c0,0-23.7,0-26.1,0c0-2,0-9.8,0-11.8c2.4,0,24.8,0,24.8,0V64.8
c0,0-22.3,0-24.8,0c0-2,0-9.4,0-11.4c2.5,0,26.1,0,26.1,0V32.1H139.8z"/>
</g>
<g>
<path class="st0" d="M169.3,32.1H146v87.2h51V98c0,0-23.9,0-26.3,0c0-2.6,0-65.9,0-65.9H169.3z"/>
</g>
<g>
<path class="st0" d="M332.4,32.1H283v87.2h50.8V98c0,0-23.7,0-26.1,0c0-2,0-9.8,0-11.8c2.4,0,24.8,0,24.8,0V64.8
c0,0-22.3,0-24.8,0c0-2,0-9.4,0-11.4c2.5,0,26.1,0,26.1,0V32.1H332.4z"/>
</g>
<g>
<path class="st0" d="M424.6,32.1h-23.3c0,0,0,43,0,49.3c-4-5.1-38.4-49.3-38.4-49.3h-24v87.2h24.7c0,0,0-43.1,0-49.5
c4,5.1,38.4,49.5,38.4,49.5h24V32.1H424.6z"/>
</g>
<g>
<g>
<path class="st0" d="M233.8,32.1h-32.5v87.2h32.5c24.4,0,44.3-19.6,44.3-43.6C278.1,51.7,258.2,32.1,233.8,32.1z M226,53.5
c13.6,0.3,22,8.7,22,22.2c0,13.6-8.2,21.9-22,22.2V53.5z M231.5,101.3c12.5-3,20.7-10.7,20.8-25.7c-0.2-15-8.3-22.7-20.8-25.7
c14,2.1,25,9.5,25,25.6v0.1C256.5,91.8,245.5,99.2,231.5,101.3z M260.2,75.6c-0.2-18-10-29.8-24.9-33.3
c16.7,2.5,29.6,14,29.6,33.3c0,0,0,0,0,0.1h0c0,19.3-13,30.7-29.7,33.2C250.1,105.3,260,93.6,260.2,75.6z M240.3,115.7
c16.7-4.7,28.3-19.2,28.5-39.9v-0.3c-0.2-20.7-11.9-35.1-28.5-39.8c19,3.9,33.5,17.7,33.6,39.7v0.4
C273.9,97.9,259.4,111.8,240.3,115.7z"/>
</g>
</g>
</g>
</g>
</svg>

After

Width:  |  Height:  |  Size: 2.2 KiB

13
compose-search-only.yml Normal file
View File

@ -0,0 +1,13 @@
services:
meilisearch:
image: "getmeili/meilisearch:v1.6.2"
ports:
- "7700:7700"
environment:
MEILI_MASTER_KEY: fluffybunnyrabbit
MEILI_NO_ANALYTICS: true
volumes:
- "meili_data:/meili_data"
volumes:
meili_data:

30
compose.yml Normal file
View File

@ -0,0 +1,30 @@
services:
meilisearch:
image: "getmeili/meilisearch:v1.6.2"
ports:
- "7700:7700"
environment:
MEILI_MASTER_KEY: fluffybunnyrabbit
MEILI_NO_ANALYTICS: true
volumes:
- "meili_data:/meili_data"
jukebox-software:
build: .
init: true
ports:
- "5000:5000"
- "8000:8000"
- "9000:9000"
environment:
- PYTHONUNBUFFERED=1
depends_on:
- meilisearch
jukebox-web:
build: jukebox-web
ports:
- "3000:3000"
volumes:
meili_data:

View File

@ -3,9 +3,21 @@ core:
serverip: 172.26.178.114
clientip: 172.26.176.1
server: Hyper-Vd
loopspeed: 60 # fps
arm:
ip: 192.168.1.145
tool:
offset_x: 0
offset_y: 0
offset_z: 0.14
limbs:
limb_base: 0.11
limb1: 0.425
limb2: 0.39225
limb3: 0.1
limb_wrist: 0.0997
#cable_map:
cameras:
@ -15,55 +27,55 @@ cameras:
led:
fps: 90
timeout: 0
timeout: 1
controllers:
- universe: 9
ip: 192.168.68.131
- universe: 0
ip: 192.168.1.200
ledstart: 0
ledend: 143
mode: rgb
- universe: 3
ip: 192.168.68.131
- universe: 1
ip: 192.168.1.201
ledstart: 144
ledend: 287
mode: rgb
- universe: 2
ip: 192.168.68.131
ip: 192.168.1.202
ledstart: 288
ledend: 431
mode: rgb
- universe: 1
ip: 192.168.68.130
- universe: 3
ip: 192.168.1.203
ledstart: 432
ledend: 575
mode: rgb
- universe: 4
ip: 192.168.68.131
ip: 192.168.1.204
ledstart: 576
ledend: 719
mode: rgb
- universe: 5
ip: 192.168.68.131
ip: 192.168.1.205
ledstart: 720
ledend: 863
mode: rgb
- universe: 6
ip: 192.168.68.131
ip: 192.168.1.206
ledstart: 864
ledend: 1007
mode: rgb
- universe: 7
ip: 192.168.68.131
ip: 192.168.1.207
ledstart: 1008
ledend: 1151
mode: rgb
- universe: 8
ip: 192.168.68.131
ip: 192.168.1.208
ledstart: 1152
ledend: 1295
mode: rgb
- universe: 0
ip: 192.168.68.130
- universe: 9
ip: 192.168.1.209
ledstart: 1296
ledend: 1365
mode: rgbw
@ -159,7 +171,7 @@ led:
size: 24
diameter: 63.5
angle: 0
pos: [-65.936, 114.3]
pos: [-65.991, 114.3]
- type: circle
start: 336
size: 24
@ -420,6 +432,116 @@ led:
size: 70
length: 600
angle: 270 # down
pos: [300, 300]
pos: [375, 300]
global_position_offset: [0,0] # default coordinate spce below as center of arm at 0,0 - adjust if necessary
animation_time: 40
position_map:
- index: 0
pos: [-152.4, 263.965]
- index: 1
pos: [-76.2, 263.965]
- index: 2
pos: [0, 263.965]
- index: 3
pos: [76.2, 263.965]
- index: 4
pos: [152.4, 263.965]
- index: 5
pos: [-190.5, 197.973]
- index: 6
pos: [-114.3, 197.973]
- index: 7
pos: [-38.1, 197.973]
- index: 8
pos: [38.1, 197.973]
- index: 9
pos: [114.3, 197.973]
- index: 10
pos: [190.5, 197.973]
- index: 11
pos: [-228.6, 131.982]
- index: 12
pos: [-152.4, 131.982]
- index: 13
pos: [-76.2, 131.982]
- index: 14
pos: [0, 131.982]
- index: 15
pos: [76.2, 131.982]
- index: 16
pos: [152.4, 131.982]
- index: 17
pos: [228.6, 131.982]
- index: 18
pos: [-266.7, 65.991]
- index: 19
pos: [-190.5, 65.991]
- index: 20
pos: [-114.3, 65.991]
- index: 21
pos: [114.3, 65.991]
- index: 22
pos: [190.5, 65.991]
- index: 23
pos: [266.7, 65.991]
- index: 24
pos: [-304.8, 0]
- index: 25
pos: [-228.6, 0]
- index: 26
pos: [-152.4, 0]
- index: 27
pos: [152.4, 0]
- index: 28
pos: [228.6, 0]
- index: 29
pos: [304.8, 0]
- index: 30
pos: [-266.7, -65.991]
- index: 31
pos: [-190.5, -65.991]
- index: 32
pos: [-114.3, -65.991]
- index: 33
pos: [114.3, -65.991]
- index: 34
pos: [190.5, -65.991]
- index: 35
pos: [266.7, -65.991]
- index: 36
pos: [-228.6, -131.982]
- index: 37
pos: [-152.4, -131.982]
- index: 38
pos: [-76.2, -131.982]
- index: 39
pos: [0, -131.982]
- index: 40
pos: [76.2, -131.982]
- index: 41
pos: [152.4, -131.982]
- index: 42
pos: [228.6, -131.982]
- index: 43
pos: [-190.5, -197.973]
- index: 44
pos: [-114.3, -197.973]
- index: 45
pos: [-38.1, -197.973]
- index: 46
pos: [38.1, -197.973]
- index: 47
pos: [114.3, -197.973]
- index: 48
pos: [190.5, -197.973]
- index: 49
pos: [-152.4, -263.965]
- index: 50
pos: [-76.2, -263.965]
- index: 51
pos: [0, -263.965]
- index: 52
pos: [76.2, -263.965]
- index: 53
pos: [152.4, -263.965]

View File

@ -1,140 +0,0 @@
"""This module contains functionality for interacting with a PostgreSQL database. It will automatically handle error
conditions (i.e. missing columns) without terminating the entire program. Use the :py:class:`DBConnector` class to
handle database interactions, either as a standalone object or in a context manager."""
from __future__ import annotations
import os
import psycopg2
from psycopg2 import DatabaseError, OperationalError
from psycopg2.errors import UndefinedColumn
DB_ADDRESS = os.getenv('DB_ADDRESS', 'localhost')
DB_PORT = os.getenv('DB_PORT', 5432)
DB_USER = os.getenv('DB_USER', 'postgres')
DB_PASSWORD = os.getenv('DB_PASSWORD', '')
DB_NAME = os.getenv('DB_NAME', 'postgres')
DB_TABLE = os.getenv('DB_TABLE', 'cables')
class DBConnector:
"""Context managed database class. Use with statements to automatically open and close the database connection, like
so:
.. code-block:: python
with DBConnector() as db:
db.read()
"""
def _db_start(self):
"""Setup the database connection and cursor."""
try:
self.conn = psycopg2.connect(
f"host={DB_ADDRESS} port={DB_PORT} dbname={DB_NAME} user={DB_USER} password={DB_PASSWORD}")
self.cur = self.conn.cursor()
except OperationalError as e:
raise e
def _db_stop(self):
"""Close the cursor and connection."""
self.cur.close()
self.conn.close()
def __init__(self):
self._db_start()
def __del__(self):
self._db_stop()
def __enter__(self):
self._db_start()
def __exit__(self):
self._db_stop()
def _get_cols(self) -> set[str]:
"""Get the list of columns in the database.
:return: A list of column names."""
query = f"select COLUMN_NAME from information_schema.columns where table_name={DB_TABLE}"
rows = {x["COLUMN_NAME"] for x in self._query(query)}
return rows
def _column_parity(self, columns: list[str] | set[str]) -> set[str]:
"""If the listed columns are not in the database, add them.
:param columns: The columns we expect are in the database.
:return: The list of columns in the database after querying."""
cols = set(columns)
existing = self._get_cols()
needs = cols.difference(existing.intersection(cols))
if len(needs) > 0:
query = f"ALTER TABLE {DB_TABLE} {', '.join([f'ADD COLUMN {c}' for c in needs])}"
self._query(query)
existing = self._get_cols()
return existing
def _query(self, sql) -> list[dict]:
"""Basic function for running queries.
:param sql: SQL query as plaintext.
:return: Results of the query, or an empty list if none."""
result = []
try:
self.cur.execute(sql)
result = self._read_dict()
except DatabaseError as e:
print(f"ERROR {e.pgcode}: {e.pgerror}\n"
f"Caused by query: {sql}")
finally:
return result
def _read_dict(self) -> list[dict]:
"""Read the cursor as a list of dictionaries. psycopg2 defaults to using a list of tuples, so we want to convert
each row into a dictionary before we return it."""
cols = [i.name for i in self.cur.description]
results = []
for row in self.cur:
row_dict = {}
for i in range(0, len(row)):
if row[i]:
row_dict = {**row_dict, cols[i]: row[i]}
results.append(row_dict)
return results
def read(self, **kwargs) -> list[dict]:
"""Read rows from a database that match the specified filters.
:param kwargs: Column constraints; i.e. what value to filter by in what column.
:returns: A list of dictionaries of all matching rows, or an empty list if no match."""
args = []
for kw in kwargs.keys():
args.append(f"{kw} ILIKE {kwargs['kw']}")
query = f"SELECT * FROM {DB_TABLE}"
if len(args) > 0:
query += f" WHERE {' AND '.join(args)}"
return self._query(query)
def write(self, **kwargs) -> dict:
"""Write a row to the database.
:param kwargs: Values to write for each database; specify each column separately!
:returns: The row you just added."""
self._column_parity(set(kwargs.keys()))
values = []
for val in kwargs.keys():
values.append(kwargs[val])
query = f"INSERT INTO {DB_TABLE} ({', '.join(kwargs.keys())}) VALUES ({', '.join(values)})"
self._query(query)
return kwargs
def write_all(self, items: list[dict]) -> list[dict]:
"""Write multiple rows to the database.
:param items: Rows to write, as a list of dictionaries.
:returns: The rows that were added successfully."""
successes = []
for i in items:
res0 = self.write(**i)
if res0:
successes.append(res0)
return successes

View File

@ -5,7 +5,7 @@ import sys
import read_datasheet
from alive_progress import alive_bar
import requests
#import time
import time
import json
import subprocess
from util import fprint
@ -26,30 +26,82 @@ def check_internet(url='https://belden.com', timeout=5):
def query_search(partnum):
"""token_url = "https://www.belden.com/coveo/rest/token?t=" + str(int(time.time()))
def query_search(partnum, source):
fprint("Searching for " + partnum)
if source == "Belden":
token_url = "https://www.belden.com/coveo/rest/token?t=" + str(int(time.time()))
with requests.get(token_url) as r:
out = json.loads(r.content)
token = out["token"]
search_url = "https://www.belden.com/coveo/rest/search"
search_data ='{ "q": "' + str(partnum) + '", "sortCriteria": "relevancy", "numberOfResults": "250", "sortCriteria": "@catalogitemwebdisplaypriority ascending", "searchHub": "products-only-search", "pipeline": "Site Search", "maximumAge": "900000", "tab": "products-search", "locale": "en" }'
# Ridiculous search parameters extracted from website. Do not touch
search_data = r"""{ "q": "{QUERY}", "sortCriteria": "relevancy", "numberOfResults": "250", "sortCriteria": "@catalogitemwebdisplaypriority ascending", "searchHub": "products-only-search", "pipeline": "Site Search", "maximumAge": "900000", "tab": "products-search", "locale": "en", "aq": "(NOT @z95xtemplate==(ADB6CA4F03EF4F47B9AC9CE2BA53FF97,FE5DD82648C6436DB87A7C4210C7413B)) ((@syssource==\"website_001002_catalog_index-rg-nc-prod-sitecore-prod\" @catalogitemprimarycategorypublished==true)) ((@catalogitemregionavailable=Global) (@z95xlanguage==en))", "cq": "((@z95xlanguage==en) (@z95xlatestversion==1) (@source==\"Coveo_web_index - rg-nc-prod-sitecore-prod\")) OR (@source==(\"website_001002_catalog_index-rg-nc-prod-sitecore-prod\",\"website_001002_Category_index-rg-nc-prod-sitecore-prod\"))", "firstResult": "0" }, "categoryFacets": "[{\"field\":\"@catalogitemcategories\",\"path\":[],\"injectionDepth\":1000,\"maximumNumberOfValues\":6,\"delimitingCharacter\":\"|\"}]", "facetOptions": "{}", "groupBy": " [{\"field\":\"@contenttype\",\"maximumNumberOfValues\":6,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[\"Products\"],\"queryOverride\":\"{QUERY}\",\"advancedQueryOverride\":\"(NOT @z95xtemplate==(ADB6CA4F03EF4F47B9AC9CE2BA53FF97,FE5DD82648C6436DB87A7C4210C7413B)) ((((((((@z95xpath=3324AF2D58F64C0FB725521052F679D2 @z95xid<>3324AF2D58F64C0FB725521052F679D2) ((@z95xpath=C292F3A37B3A4E6BAB345DF87ADDE516 @z95xid<>C292F3A37B3A4E6BAB345DF87ADDE516) @z95xtemplate==E4EFEB787BDC4B1A908EFC64D56CB2A4)) OR ((@z95xpath=723501A864754FEEB8AE377E4C710271 @z95xid<>723501A864754FEEB8AE377E4C710271) ((@z95xpath=600114EAB0E5407A84AAA9F0985B6575 @z95xid<>600114EAB0E5407A84AAA9F0985B6575) @z95xtemplate==2BE4FD6B3B2C49EBBD9E1F6C92238B05))) OR (@syssource==\\"website_001002_catalog_index-rg-nc-prod-sitecore-prod\\" @catalogitemprimarycategorypublished==true)) OR ((@z95xpath=3324AF2D58F64C0FB725521052F679D2 @z95xid<>3324AF2D58F64C0FB725521052F679D2) @z95xpath<>C292F3A37B3A4E6BAB345DF87ADDE516)) OR @syssource==\\"website_001002_Category_index-rg-nc-prod-sitecore-prod\\") NOT @z95xtemplate==(ADB6CA4F03EF4F47B9AC9CE2BA53FF97,FE5DD82648C6436DB87A7C4210C7413B))) ((@catalogitemregionavailable=Global) (@z95xlanguage==en) OR (@contenttype=(Blogs,Resources,Other)) (NOT @ez120xcludefromcoveo==1))\",\"constantQueryOverride\":\"((@z95xlanguage==en) (@z95xlatestversion==1) (@source==\\"Coveo_web_index - rg-nc-prod-sitecore-prod\\")) OR (@source==(\\"website_001002_catalog_index-rg-nc-prod-sitecore-prod\\",\\"website_001002_Category_index-rg-nc-prod-sitecore-prod\\"))\"},{\"field\":\"@catalogitembrand\",\"maximumNumberOfValues\":6,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@catalogitemenvironment\",\"maximumNumberOfValues\":6,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@catalogitemregionalavailability\",\"maximumNumberOfValues\":6,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@prez45xtez120xt\",\"maximumNumberOfValues\":5,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@tags\",\"maximumNumberOfValues\":4,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@facetassettype\",\"maximumNumberOfValues\":3,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@facetbrand\",\"maximumNumberOfValues\":3,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@facetmarket\",\"maximumNumberOfValues\":6,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@facetsolution\",\"maximumNumberOfValues\":6,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@facetsearchcontentpagetype\",\"maximumNumberOfValues\":6,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]}]" }"""
search_data = search_data.replace(r"{QUERY}", partnum)
#"aq": "", "cq": "((@z95xlanguage==en) (@z95xlatestversion==1) (@source==\\"Coveo_web_index - rg-nc-prod-sitecore-prod\\")) OR (@source==(\\"website_001002_catalog_index-rg-nc-prod-sitecore-prod\\",\\"website_001002_Category_index-rg-nc-prod-sitecore-prod\\"))", "firstResult": "0", "categoryFacets": "[{\\"field\\":\\"@catalogitemcategories\\",\\"path\\":[],\\"injectionDepth\\":1000,\\"maximumNumberOfValues\\":6,\\"delimitingCharacter\\":\\"|\\"}]", "facetOptions": "{}", "groupBy": "" }'
#fprint(search_data)
fprint(json.loads(search_data))
#fprint(json.loads(search_data))
#search_data = '{ "q": "' + str(partnum) + '" }'
fprint(search_data)
#fprint(search_data)
headers = headers = {
'Authorization': f'Bearer {token}',
'Content-Type': 'application/json'
}
try:
with requests.post(search_url, headers=headers, data=search_data) as r:
fprint(r.text)"""
a = r.text
a = json.loads(a)
idx = -1
name = ""
for partid in range(len(a["results"])-1, -1, -1):
name = a["results"][partid]["title"]
if name != partnum:
if name.find(partnum) >= 0:
idx = partid
#break
elif partnum.find(name) >= 0:
idx = partid
#break
# TODO: Reimplement in python
# Bash script uses some crazy json formatting that I could not figure out
# Despite the fact that I wrote it
# So I'll just leave it, becuase it works.
else:
idx = partid
break
if idx < 0:
fprint("Could not find part in API: " + partnum)
return False
name = a["results"][idx]["title"]
#fprint("Search result found: result " + str(idx) + ", for ID " + name)
#urlname = a["results"][0]["raw"]["catalogitemurlname"]
img = a["results"][idx]["raw"]["catalogitemimageurl"]
img = img[0:img.index("?")]
uri = a["results"][idx]["raw"]["clickableuri"]
dsid = a["results"][idx]["raw"]["catalogitemdatasheetid"]
brand = a["results"][idx]["raw"]["catalogitembrand"]
desc = a["results"][idx]["raw"]["catalogitemlongdesc"]
shortdesc = a["results"][idx]["raw"]["catalogitemshortdesc"]
a = json.dumps(a["results"][idx], indent=2)
#print(a, urlname, img, uri, dsurl)
out = dict()
out["url"] = "https://www.belden.com/products/" + uri
out["datasheet"] = "https://catalog.belden.com/techdata/EN/" + dsid + "_techdata.pdf"
out["brand"] = brand
out["name"] = shortdesc
out["description"] = desc
out["image"] = "https://www.belden.com" + img
out["partnum"] = name
#print(out)
return out
except:
print("Failed to search with API. Falling back to datasheet lookup.")
return False
# Original bash script
# superceded by above
if source == "Belden_shell":
command = ["./query-search.sh", partnum]
result = subprocess.run(command, stdout=subprocess.PIPE, stderr=subprocess.PIPE, text=True)
if result.returncode != 0: # error
@ -58,6 +110,48 @@ def query_search(partnum):
else:
data_out = json.loads(result.stdout)
return data_out
elif source == "Alphawire":
alphaurl = "https://www.alphawire.com//sxa/search/results/?l=en&s={4A774076-6068-460C-9CC6-A2D8E85E407F}&itemid={BF82F58C-EFD9-4D8B-AE3E-097DD12CF7DA}&sig=&autoFireSearch=true&productpartnumber=*" + partnum + "*&v={B22CD56D-AB95-4048-8AA1-5BBDF2F2D17F}&p=10&e=0&o=ProductPartNumber%2CAscending"
r = requests.get(url=alphaurl)
data = r.json()
output = dict()
#print(data["Results"])
try:
if data["Count"] > 0:
#print(data["Results"][0]["Url"])
for result in data["Results"]:
#print(result["Url"])
if result["Url"].split("/")[-1] == partnum.replace("-", "").replace("/", "_"):
#print(partnum)
#print(result["Html"])
try:
imgidx = result["Html"].index("<img src=") + 10
imgidx2 = result["Html"].index("?", imgidx)
output["image"] = result["Html"][imgidx:imgidx2]
if output["image"].index("http") != 0:
output["image"] = ""
print("No cable image found.")
except:
print("No cable image found.")
dsidx = result["Html"].index("<a href=\"/disteAPI/") + 9
dsidx2 = result["Html"].index(partnum, dsidx) + len(partnum)
output["datasheet"] = "https://www.alphawire.com" + result["Html"][dsidx:dsidx2]
output["partnum"] = partnum.replace("/", "_") #.replace("-", "").replace("/", "_")
#
# "test".index()
#print(output)
return output
except:
print("Failed to search with API. Falling back to datasheet lookup.")
return False
print("Failed to search with API. Falling back to datasheet lookup.")
return False
def touch(path):
with open(path, 'a'):
@ -65,14 +159,19 @@ def touch(path):
def get_multi(partnums):
with alive_bar(len(partnums) * 2, dual_line=True, calibrate=30, bar="classic2", spinner="classic") as bar:
def _try_download_datasheet(partnum, output_dir): # Guess datasheet URL
def get_multi(partnums, delay=0.25, dir="cables/", cache=True, bar=None):
#with alive_bar(len(partnums) * 2, dual_line=True, calibrate=30, bar="classic2", spinner="classic", disable=True, file=sys.stdout) as bar:
failed = list()
actualpartnums = list()
def _try_download_datasheet(partnum, output_dir, dstype): # Guess datasheet URL
global bartext
if dstype == "Belden":
sanitized_name = partnum.replace(" ", "")
url = "https://catalog.belden.com/techdata/EN/" + sanitized_name + "_techdata.pdf"
elif dstype == "Alphawire":
# Alphawire Datasheet URLs do not use a sanitized part number (but product pages do)
url = "https://www.alphawire.com/disteAPI/SpecPDF/DownloadProductSpecPdf?productPartNumber=" + partnum
#fprint(url)
try:
with requests.get(url, stream=True) as r:
@ -82,13 +181,14 @@ def get_multi(partnums):
if r.status_code == 404:
return False
os.makedirs(output_dir, exist_ok=True)
bartext = ""
with open(output_dir + "/datasheet.pdf", 'wb') as f:
for chunk in r.iter_content(chunk_size=131072):
for chunk in r.iter_content(chunk_size=65536):
# If you have chunk encoded response uncomment if
# and set chunk_size parameter to None.
#if chunk:
bartext = bartext + "."
bar.text = bartext
# bar.text = bartext
f.write(chunk)
#fprint("")
return output_dir + "/datasheet.pdf"
@ -110,13 +210,14 @@ def get_multi(partnums):
if r.status_code == 404:
return False
os.makedirs(output_dir, exist_ok=True)
bartext = ""
with open(output_dir + "/datasheet.pdf", 'wb') as f:
for chunk in r.iter_content(chunk_size=131072):
for chunk in r.iter_content(chunk_size=65536):
# If you have chunk encoded response uncomment if
# and set chunk_size parameter to None.
#if chunk:
bartext = bartext + "."
bar.text = bartext
# bar.text = bartext
f.write(chunk)
#fprint("")
return output_dir + "/datasheet.pdf"
@ -126,7 +227,7 @@ def get_multi(partnums):
sys.exit()
def _download_image(url, output_dir): # Download datasheet with known URL
def _download_image(url, output_dir): # Download image with known URL
global bartext
#fprint(url)
@ -136,13 +237,14 @@ def get_multi(partnums):
if r.status_code == 404:
return False
os.makedirs(output_dir, exist_ok=True)
bartext = ""
with open(output_dir + "/part-hires." + url.split(".")[-1], 'wb') as f:
for chunk in r.iter_content(chunk_size=131072):
for chunk in r.iter_content(chunk_size=65536):
# If you have chunk encoded response uncomment if
# and set chunk_size parameter to None.
#if chunk:
bartext = bartext + "."
bar.text = bartext
# bar.text = bartext
f.write(chunk)
#fprint("")
return output_dir + "/part-hires." + url.split(".")[-1]
@ -151,97 +253,222 @@ def get_multi(partnums):
os.remove(partnum + "/datasheet.pdf")
sys.exit()
def __use_cached_datasheet(partnum, path, output_dir):
def __use_cached_datasheet(partnum, path, output_dir, dstype):
fprint("Using cached datasheet for " + partnum)
bar.text = "Using cached datasheet for " + partnum
bar(skipped=True)
fprint("Parsing Datasheet contents of " + partnum)
bar.text = "Parsing Datasheet contents of " + partnum + ".pdf..."
read_datasheet.parse(path, output_dir)
bar(skipped=False)
# bar.text = "Using cached datasheet for " + partnum
# bar(skipped=True)
if not os.path.exists(output_dir + "/parsed"):
def __downloaded_datasheet(partnum, path, output_dir):
fprint("Parsing Datasheet contents of " + partnum)
# bar.text = "Parsing Datasheet contents of " + partnum + ".pdf..."
out = read_datasheet.parse(path, output_dir, partnum, dstype)
# bar(skipped=False)
return out
else:
fprint("Datasheet already parsed for " + partnum)
# bar.text = "Datasheet already parsed for " + partnum + ".pdf"
# bar(skipped=True)
def __downloaded_datasheet(partnum, path, output_dir, dstype):
fprint("Downloaded " + path)
bar.text = "Downloaded " + path
bar(skipped=False)
# bar.text = "Downloaded " + path
# bar(skipped=False)
fprint("Parsing Datasheet contents of " + partnum)
bar.text = "Parsing Datasheet contents of " + partnum + ".pdf..."
read_datasheet.parse(path, output_dir)
bar(skipped=False)
# bar.text = "Parsing Datasheet contents of " + partnum + ".pdf..."
out = read_datasheet.parse(path, output_dir, partnum, dstype)
# bar(skipped=False)
return out
for partnum in partnums:
output_dir = "cables/" + partnum
def run_search(partnum):
partnum = partnum.replace("%20", " ") # undo URL encoding
oldpartnum = partnum
if dstype == "Alphawire":
# For alphawire, sanitize the part number for only the final result check, because their API is very wierd
# For the actual search, it must be un-sanitized
partnum = partnum.replace("/","_")
output_dir = dir + partnum
path = output_dir + "/datasheet.pdf"
bartext = "Downloading files for part " + partnum
bar.text = bartext
#
if (not os.path.exists(output_dir + "/found_part_hires")) or not (os.path.exists(path) and os.path.getsize(path) > 1):
# bar.text = bartext
partnum = oldpartnum.replace("_","/")
returnval = [partnum, dstype, False, False]
if (not os.path.exists(output_dir + "/found_part_hires")) or not (os.path.exists(path) and os.path.getsize(path) > 1) or not cache:
# Use query
search_result = query_search(partnum.replace(" ", ""))
search_result = query_search(partnum, dstype)
# Try to use belden.com search
if search_result is not False:
# Download high resolution part image if available and needed
if not os.path.exists(output_dir + "/found_part_hires"):
#oldpartnum = partnum
partnum = search_result["partnum"]
returnval = [partnum, dstype, False, False]
output_dir = dir + partnum
path = output_dir + "/datasheet.pdf"
bartext = "Downloading files for part " + partnum
# bar.text = bartext
if not os.path.exists(output_dir + "/found_part_hires") or not cache:
if _download_image(search_result["image"], output_dir):
fprint("Downloaded hi-res part image for " + partnum)
returnval = [partnum, dstype, True, False]
touch(output_dir + "/found_part_hires")
else:
fprint("Using cached hi-res part image for " + partnum)
# Download datasheet from provided URL if needed
if os.path.exists(path) and os.path.getsize(path) > 1:
__use_cached_datasheet(partnum, path, output_dir)
if os.path.exists(path) and os.path.getsize(path) > 1 and cache:
out = __use_cached_datasheet(partnum, path, output_dir, dstype)
returnval = [partnum, dstype, True, out]
elif _download_datasheet(search_result["datasheet"], output_dir) is not False:
__downloaded_datasheet(partnum, path, output_dir)
out = __downloaded_datasheet(partnum, path, output_dir, dstype)
returnval = [partnum, dstype, True, out]
elif os.path.exists(path) and os.path.getsize(path) > 1:
__use_cached_datasheet(partnum, path, output_dir)
elif os.path.exists(path) and os.path.getsize(path) > 1 and cache:
out = __use_cached_datasheet(partnum, path, output_dir, dstype)
returnval = [partnum, dstype, True, out]
# If search fails, and we don't already have the datasheet, guess datasheet URL and skip the hires image download
elif _try_download_datasheet(partnum, output_dir) is not False:
__downloaded_datasheet(partnum, path, output_dir)
elif _try_download_datasheet(partnum, output_dir, dstype) is not False:
out = __downloaded_datasheet(partnum, path, output_dir, dstype)
returnval = [partnum, dstype, False, out]
# Failed to download with search or guess :(
else:
fprint("Failed to download datasheet for part " + partnum)
bar.text = "Failed to download datasheet for part " + partnum
failed.append(partnum)
bar(skipped=True)
bar(skipped=True)
return False
actualpartnums.append(returnval)
return returnval
# We already have a hi-res image and the datasheet - perfect!
else:
fprint("Using cached hi-res part image for " + partnum)
__use_cached_datasheet(partnum, path, output_dir)
out = __use_cached_datasheet(partnum, path, output_dir, dstype)
returnval = [partnum, dstype, False, out]
actualpartnums.append(returnval)
return True
for fullpartnum in partnums:
if fullpartnum is False:
actualpartnums.append(False)
continue
if fullpartnum[0:2] == "BL": # catalog.belden.com entry
partnum = fullpartnum[2:]
dstype = "Belden"
elif fullpartnum[0:2] == "AW":
partnum = fullpartnum[2:]
dstype = "Alphawire"
else:
dstype = "Belden" # guess
partnum = fullpartnum
if not run_search(partnum):
success = False
if len(partnum.split(" ")) > 1:
for name in partnum.split(" "):
fprint("Retrying with alternate name: " + name)
if(run_search(name)):
success = True
break
time.sleep(delay)
if not success:
namestripped = partnum.strip(" ")
fprint("Retrying with alternate name: " + namestripped)
if(run_search(namestripped)):
success = True
time.sleep(delay)
if not success:
fprint("Failed to download datasheet for part " + partnum)
# bar.text = "Failed to download datasheet for part " + partnum
failed.append((partnum, dstype))
# bar(skipped=True)
# bar(skipped=True)
time.sleep(delay)
if len(failed) > 0:
fprint("Failed to download:")
for partnum in failed:
fprint(partnum)
return False # Go to manual review upload page
fprint(partnum[1] + " " + partnum[0])
return False, actualpartnums # Go to manual review upload page
else:
return True # All cables downloaded; we are good to go
return True, actualpartnums # All cables downloaded; we are good to go
if __name__ == "__main__":
partnums = ["10GXS12", "RST 5L-RKT 5L-949",
"10GXS13",
"10GXW12",
"10GXW13",
"2412",
"2413",
"OSP6AU",
"FI4D024P9",
"FISD012R9",
"FDSD012A9",
"FSSL024NG",
"FISX006W0",
"FISX00103",
"C6D1100007"
# partnums = ["BLFISX012W0", "BL7958A", "BL10GXS12", "BLRST 5L-RKT 5L-949",
# "BL10GXS13",
# "BL10GXW12",
# "BL10GXW13",
# "BL2412",
# "BL2413",
# "BLOSP6AU",
# "BLFI4D024P9",
# "BLFISD012R9",
# "BLFDSD012A9",
# "BLFSSL024NG",
# "BLFISX006W0",
# "BLFISX00103",
# "BLC6D1100007"
# ]
partnums = [
# Actual cables in Jukebox
"BL3092A",
"AW86104CY",
"AW3050",
"AW6714",
"AW1172C",
"AWFIT-221-1/4",
"BLTF-1LF-006-RS5N",
"BLTF-SD9-006-RI5N",
"BLTT-SLG-024-HTNN",
"BLFISX012W0",
"BLFI4X012W0",
"BLSPE101 006Q",
"BLSPE102 006Q",
"BL7922A 010Q",
"BL7958A 008Q",
"BLIOP6U 010Q",
"BL10GXW13 D15Q",
"BL10GXW53 D15Q",
"BL29501F 010Q",
"BL29512 010Q",
"BL3106A 010Q",
"BL9841 060Q",
"BL3105A 010Q",
"BL3092A 010Q",
"BL8760 060Q",
"BL6300UE 008Q",
"BL6300FE 009Q",
"BLRA500P 006Q",
]
get_multi(partnums)
# Some ones I picked, including some invalid ones
a = [
"BL10GXS12",
"BLRST%205L-RKT%205L-949",
"BL10GXS13",
"BL10GXW12",
"BL10GXW13",
"BL2412",
"BL2413",
"BLOSP6AU",
"BLFI4D024P9",
"BLFISD012R9",
"BLFDSD012A9",
"BLFSSL024NG",
"BLFISX006W0", # datasheet only
"BLFISX00103", # invalid
"BLC6D1100007" # invalid
]
#print(query_search("TT-SLG-024-HTNN", "Belden"))
from label_generator import gen_label
gen_label("BLTF-SD9-006-RI5")
gen_label("BLRA500P")
gen_label("AWFIT-221-1_4")
gen_label("BLRST 5L-RKT 5L-949")
get_multi(partnums, 0.25)
#query_search("10GXS13", "Belden")

BIN
gs10030w64.exe Normal file

Binary file not shown.

View File

@ -1 +0,0 @@
<html> <head> <title>RGB Controller Configuration</title> <style> body { background-color: #cccccc; font-family: Arial, Helvetica, Sans-Serif; Color: #000088; } </style> </head> <body> <h1>RGB Controller Configuration</h1><br> <h2>Set IP address</h2> Needs reboot to apply<br> Set to 0.0.0.0 for DHCP <form method="post" enctype="application/x-www-form-urlencoded" action="/postform/"> <input type="text" name="ipa" value="0" size="3">. <input type="text" name="ipb" value="0" size="3">. <input type="text" name="ipc" value="0" size="3">. <input type="text" name="ipd" value="0" size="3"> <input type="submit" value="Set"> </form><br> <h2>Set Hostname</h2> Needs reboot to apply<br> Max 64 characters <form method="post" enctype="application/x-www-form-urlencoded" action="/postform/"> <input type="text" name="hostname" value="RGBController" size="20"> <input type="submit" value="Set"> </form><br> <h2>DMX512 Start Universe</h2> Applies immediately<br> Between (inclusive) 1-65000 <form method="post" enctype="application/x-www-form-urlencoded" action="/postform/"> <input type="text" name="universe" value="1" size="5"> <input type="submit" value="Set"> </form><br> <form method="post" enctype="application/x-www-form-urlencoded" action="/postform/"> <input type="submit" name="reboot" value="Reboot"> </form><br> </body></html>

View File

@ -1,4 +1,5 @@
#!/bin/sh
# change this to #!/bin/bash for windows
if ! [ -d "venv" ]; then
./venv-setup.sh

467
inv_kin_testing.ipynb Normal file

File diff suppressed because one or more lines are too long

1
jukebox-web Submodule

Submodule jukebox-web added at f3d8ec0cc4

106
label_generator.py Executable file
View File

@ -0,0 +1,106 @@
#!/usr/bin/env python3
from get_specs import get_multi
import sys
import uuid
import os
import signal
from PIL import Image
from label_image import generate_code
def input_cable():
print("")
print("Use the full part number. Spaces, special characters are allowed. Do not specify the brand.")
print("")
print("Please enter a part number and press enter:")
inputnum = input("").strip()
if len(inputnum) < 2:
killall_signal(0, 0)
print("Input part number:", inputnum)
print("Searching databases for cables...")
# Search both AW and BL sites
status, output = get_multi(["BL"+inputnum, "AW"+inputnum], delay=0.1, dir="temp/" + str(uuid.uuid4()) + "/", cache=False)
print("")
if len(output) > 1:
for i in output:
print(i[1], i[0])
print("Multiple brands with the same part number! Please type \"b\" for the Belden part number or \"a\" for the Alphawire cable")
inputbrand = input()
if inputbrand == "b":
output = [output[0]]
elif inputbrand == "a":
output = [output[1]]
elif len(output) == 0:
print("No results found for part number", inputnum + ". Please try again with a different part number.")
return
output = output[0]
print("")
if output[2] and output[3]:
print("Cable result found -",output[1], output[0], "with high-quality image and full specs")
elif output[2]:
print("Cable result found -",output[1], output[0], "with high-quality image and no specs")
elif output[3]:
print("Cable result found -",output[1], output[0], "with no/low quality image and full specs")
else:
print("Cable result found -",output[1], output[0], "with no/low quality image and no specs")
print("")
if not output[3]:
print("Unable to decode cable specs. Please try again with a different part number.")
return False
else:
print("")
print("*** Cable details confirmed. Creating label...")
print("")
img = None
imgstr = ""
if output[1] == "Belden":
imgstr = "BL"
elif output[1] == "Alphawire":
imgstr = "AW"
gen_label(imgstr + output[0])
#img = generate_code(imgstr + output[0])
#os.makedirs("labels", exist_ok=True)
#img.save("labels/" + imgstr + output[0] + ".png")
def gen_label(partnum, path="labels"):
img = generate_code(partnum)
os.makedirs(path, exist_ok=True)
img.save(path + "/" + partnum + ".png")
def delete_folder(path):
# Check if the path is a directory
if not os.path.isdir(path):
return
# List all files and directories in the path
for filename in os.listdir(path):
file_path = os.path.join(path, filename)
# If it's a directory, recursively call this function
if os.path.isdir(file_path):
delete_folder(file_path)
else:
# If it's a file, remove it
os.remove(file_path)
# After removing all contents, remove the directory itself
os.rmdir(path)
def killall_signal(a,b):
delete_folder("temp")
os.kill(os.getpid(), 9) # dirty kill of self
if __name__ == "__main__":
signal.signal(signal.SIGINT, killall_signal)
signal.signal(signal.SIGTERM, killall_signal)
print("Welcome to the Jukebox cable utility. This tool will allow you to verify Belden & Alphawire cable part numbers and create labels for samples in the Jukebox.")
print("This tool requires internet access to download cable specifications and verify part numbers.")
#print("Use Ctrl+C to exit.")
while True:
delete_folder("temp")
input_cable()

319
label_image.py Executable file
View File

@ -0,0 +1,319 @@
#!/usr/bin/env python3
from util import fprint
from PIL import Image
from PIL import ImageDraw
from PIL import ImageFont
#import cv2
import numpy as np
from util import find_data_file
import segno
import io
#import cairosvg
#import math
# Copied from http://en.wikipedia.org/wiki/Code_128
# Value Weights 128A 128B 128C
CODE128_CHART = """
0 212222 space space 00
1 222122 ! ! 01
2 222221 " " 02
3 121223 # # 03
4 121322 $ $ 04
5 131222 % % 05
6 122213 & & 06
7 122312 ' ' 07
8 132212 ( ( 08
9 221213 ) ) 09
10 221312 * * 10
11 231212 + + 11
12 112232 , , 12
13 122132 - - 13
14 122231 . . 14
15 113222 / / 15
16 123122 0 0 16
17 123221 1 1 17
18 223211 2 2 18
19 221132 3 3 19
20 221231 4 4 20
21 213212 5 5 21
22 223112 6 6 22
23 312131 7 7 23
24 311222 8 8 24
25 321122 9 9 25
26 321221 : : 26
27 312212 ; ; 27
28 322112 < < 28
29 322211 = = 29
30 212123 > > 30
31 212321 ? ? 31
32 232121 @ @ 32
33 111323 A A 33
34 131123 B B 34
35 131321 C C 35
36 112313 D D 36
37 132113 E E 37
38 132311 F F 38
39 211313 G G 39
40 231113 H H 40
41 231311 I I 41
42 112133 J J 42
43 112331 K K 43
44 132131 L L 44
45 113123 M M 45
46 113321 N N 46
47 133121 O O 47
48 313121 P P 48
49 211331 Q Q 49
50 231131 R R 50
51 213113 S S 51
52 213311 T T 52
53 213131 U U 53
54 311123 V V 54
55 311321 W W 55
56 331121 X X 56
57 312113 Y Y 57
58 312311 Z Z 58
59 332111 [ [ 59
60 314111 \ \ 60
61 221411 ] ] 61
62 431111 ^ ^ 62
63 111224 _ _ 63
64 111422 NUL ` 64
65 121124 SOH a 65
66 121421 STX b 66
67 141122 ETX c 67
68 141221 EOT d 68
69 112214 ENQ e 69
70 112412 ACK f 70
71 122114 BEL g 71
72 122411 BS h 72
73 142112 HT i 73
74 142211 LF j 74
75 241211 VT k 75
76 221114 FF l 76
77 413111 CR m 77
78 241112 SO n 78
79 134111 SI o 79
80 111242 DLE p 80
81 121142 DC1 q 81
82 121241 DC2 r 82
83 114212 DC3 s 83
84 124112 DC4 t 84
85 124211 NAK u 85
86 411212 SYN v 86
87 421112 ETB w 87
88 421211 CAN x 88
89 212141 EM y 89
90 214121 SUB z 90
91 412121 ESC { 91
92 111143 FS | 92
93 111341 GS } 93
94 131141 RS ~ 94
95 114113 US DEL 95
96 114311 FNC3 FNC3 96
97 411113 FNC2 FNC2 97
98 411311 ShiftB ShiftA 98
99 113141 CodeC CodeC 99
100 114131 CodeB FNC4 CodeB
101 311141 FNC4 CodeA CodeA
102 411131 FNC1 FNC1 FNC1
103 211412 StartA StartA StartA
104 211214 StartB StartB StartB
105 211232 StartC StartC StartC
106 2331112 Stop Stop Stop
""".split()
VALUES = [int(value) for value in CODE128_CHART[0::5]]
WEIGHTS = dict(zip(VALUES, CODE128_CHART[1::5]))
CODE128A = dict(zip(CODE128_CHART[2::5], VALUES))
CODE128B = dict(zip(CODE128_CHART[3::5], VALUES))
CODE128C = dict(zip(CODE128_CHART[4::5], VALUES))
for charset in (CODE128A, CODE128B):
charset[' '] = charset.pop('space')
def generate_code(data, show=False, check=False):
#img = code128_image(data)
img = qr_image(data)
if show:
img.show()
#img.show()
#print(data)
if(check):
from pyzbar.pyzbar import decode
from pyzbar.pyzbar import ZBarSymbol
print(decode(img, symbols=[ZBarSymbol.CODE128])[0].data.decode('ascii'))
#if(decode(img, symbols=[ZBarSymbol.CODE128])[0].data.decode('ascii') == data):
# return True
#else:
# return False
return img
def code128_format(data):
"""
Generate an optimal barcode from ASCII text
"""
text = str(data)
pos = 0
length = len(text)
# Start Code
if text[:2].isdigit():
charset = CODE128C
codes = [charset['StartC']]
else:
charset = CODE128B
codes = [charset['StartB']]
# Data
while pos < length:
if charset is CODE128C:
if text[pos:pos+2].isdigit() and length - pos > 1:
# Encode Code C two characters at a time
codes.append(int(text[pos:pos+2]))
pos += 2
else:
# Switch to Code B
codes.append(charset['CodeB'])
charset = CODE128B
elif text[pos:pos+4].isdigit() and length - pos >= 4:
# Switch to Code C
codes.append(charset['CodeC'])
charset = CODE128C
else:
# Encode Code B one character at a time
codes.append(charset[text[pos]])
pos += 1
# Checksum
checksum = 0
for weight, code in enumerate(codes):
checksum += max(weight, 1) * code
codes.append(checksum % 103)
# Stop Code
codes.append(charset['Stop'])
return codes
def code128_image(data, height=100, thickness=3, quiet_zone=False):
partnum = data
if not data[-1] == CODE128B['Stop']:
data = code128_format(data)
barcode_widths = []
for code in data:
for weight in WEIGHTS[code]:
barcode_widths.append(int(weight) * thickness)
width = sum(barcode_widths)
x = 0
if quiet_zone:
width += 20 * thickness
x = 10 * thickness
# Monochrome Image
img = Image.new('RGB', (int(width * 10), int(width * 10)), 'white')
draw = ImageDraw.Draw(img)
draw_bar = True
for bwidth in barcode_widths:
bwidth *= 4
if draw_bar:
draw.rectangle(((x + int(width * 3), width*6.25), (x + int(width * 3) + bwidth - 1, width*7)), fill='black')
draw_bar = not draw_bar
x += bwidth
#draw.arc(((width - width/5, width - width/5), (width*9 + width/5, width*9 + width/5)),0,360,fill='blue', width = int(width/8))
draw.arc(((width+int(width / 1.4), width+int(width / 1.4)), (width*9-int(width / 1.4), width*9-int(width / 1.4))),0,360,fill='blue', width = int(width/8))
font_path = find_data_file("OCRAEXT.TTF")
font_size = width/2
font = ImageFont.truetype(font_path, font_size)
text_width = font.getlength(partnum)
while text_width > width*4:
font_size -= 1
font = ImageFont.truetype(font_path, font_size)
text_width = font.getlength(partnum)
txtx = (int(width * 10) - text_width) / 2
txty = (int(width * 10)) / 2 + width / 2
draw.text((txtx,txty),partnum, "black", font)
return img
def qr_image(data, width=600):
partnum = data
# Monochrome Image
img = Image.new('RGB', (int(width * 10), int(width * 10)), 'white')
draw = ImageDraw.Draw(img)
#svg_path = find_data_file("belden-logo.svg")
#with open(svg_path, 'rb') as svg_file:
# png_image = cairosvg.svg2png(file_obj=svg_file,dpi=width*30, scale=30, background_color="white")
#with open("output.png", 'wb') as file:
# file.write(png_image)
png_image_io = "belden-logo-superhires.png"
png_image_pillow = Image.open(png_image_io)
png_width, png_height = png_image_pillow.size
png_image_pillow = png_image_pillow.resize((int(width*5.2), int(width*5.2/png_width*png_height)))
png_width, png_height = png_image_pillow.size
# paste belden logo first because it has a big border that would cover stuff up
img.paste(png_image_pillow, (int(width*5-png_width/2), int(width*4.25 - png_height/2)))
# draw circle border
#draw.arc(((width - width/5, width - width/5), (width*9 + width/5, width*9 + width/5)),0,360,fill='blue', width = int(width/8))
draw.arc(((width+int(width / 1.4), width+int(width / 1.4)), (width*9-int(width / 1.4), width*9-int(width / 1.4))),0,360,fill=(0, 73,144), width = int(width/8))
font_path = find_data_file("GothamCond-Medium.otf")
font_size = width/2
font = ImageFont.truetype(font_path, font_size)
text_width = font.getlength(partnum[2:])
# shrink font dynamically if it's too long of a name
while text_width > width*4:
font_size -= 1
font = ImageFont.truetype(font_path, font_size)
text_width = font.getlength(partnum[2:])
txtx = (int(width * 10) - text_width) / 2
txty = (int(width * 10)) / 2
# draw part number text
draw.text((txtx,txty),partnum[2:], "black", font)
# Draw QR code
partnum = partnum.replace(" ", "%20")
qrcode = segno.make('HTTPS://BLDN.APP/' + partnum,micro=False,boost_error=False,error="L",mask=3)
out = io.BytesIO()
qrx, _ = qrcode.symbol_size(1,0)
qrcode.save(out, scale=width*2/qrx, kind="PNG", border=0)
qrimg = Image.open(out)
img.paste(qrimg, box=(int(width*4),int(width*5.75)))
return img
if __name__ == "__main__":
#print(generate_code("BL10GXS13"))
#print(generate_code("BL10GXgd35j35S13"))
#print(generate_code("BL10GX54hS13"))
#print(generate_code("BL10Gj34qXS13", False, False))
#print(generate_code("BL104w5545dp7bfwp43643534/4563G-XS13"))
#adjust_image(cv2.imread('test_skew.jpg'))
path = "labels"
img = generate_code("BL10GXS13")
import os
os.makedirs(path, exist_ok=True)
img.save(path + "/" + "BL10GXS13" + ".png")

View File

@ -14,17 +14,32 @@ import cv2
import numpy as np
from uptime import uptime
sender = None
debug = True
config = None
leds = None
leds_size = None
leds_normalized = None
controllers = None
data = None
start = uptime()
def ping(host):
class LEDSystem():
sender = None
debug = True
config = None
leds = None
leds_size = None
leds_normalized = None
controllers = None
data = None
exactdata = None
rings = None
ringstatus = None
mode = "Startup"
firstrun = True
changecount = 0
animation_time = 0
start = uptime()
def __init__(self):
self.start = uptime()
#self.init()
#return self
def ping(self, host):
#Returns True if host (str) responds to a ping request.
# Option for the number of packets as a function of
@ -42,37 +57,49 @@ def ping(host):
return subprocess.call(command, stdout=subprocess.DEVNULL, stderr=subprocess.STDOUT) == 0
def map():
global config
global leds
global leds_size
global leds_normalized
global controllers
def map(self):
with open('config.yml', 'r') as fileread:
#global config
config = yaml.safe_load(fileread)
self.config = yaml.safe_load(fileread)
leds = list()
leds_size = list()
controllers = list()
self.animation_time = self.config["animation_time"]
self.leds = list()
self.leds_size = list()
self.controllers = list()
self.rings = list(range(len(self.config["position_map"])))
print("Setting ring status")
self.ringstatus = list(range(len(self.config["position_map"])))
#print(rings)
#fprint(config["led"]["map"])
for shape in config["led"]["map"]:
generate_map = False
map = list()
for shape in self.config["led"]["map"]:
if shape["type"] == "circle":
if generate_map:
map.append((shape["pos"][1],shape["pos"][0]))
#fprint(shape["pos"])
anglediv = 360.0 / shape["size"]
angle = 0
radius = shape["diameter"] / 2
lednum = shape["start"]
if len(leds) < lednum + shape["size"]:
for x in range(lednum + shape["size"] - len(leds)):
leds.append(None)
leds_size.append(None)
for item in self.config['position_map']:
# Check if the current item's position matches the target position
#print(item['pos'],(shape["pos"][1],shape["pos"][0]))
if tuple(item['pos']) == (shape["pos"][1],shape["pos"][0]):
self.rings[item["index"]] = (shape["pos"][1],shape["pos"][0],lednum,lednum+shape["size"]) # rings[index] = x, y, startpos, endpos
self.ringstatus[item["index"]] = [None, None]
break
if len(self.leds) < lednum + shape["size"]:
for x in range(lednum + shape["size"] - len(self.leds)):
self.leds.append(None)
self.leds_size.append(None)
while angle < 359.999:
tmpangle = angle + shape["angle"]
x = math.cos(tmpangle * (math.pi / 180.0)) * radius + shape["pos"][0]
y = math.sin(tmpangle * (math.pi / 180.0)) * radius + shape["pos"][1]
leds[lednum] = (x,y)
x = math.cos(tmpangle * (math.pi / 180.0)) * radius + shape["pos"][1] # flip by 90 degress when we changed layout
y = math.sin(tmpangle * (math.pi / 180.0)) * radius + shape["pos"][0]
self.leds[lednum] = (x,y)
lednum = lednum + 1
angle = angle + anglediv
@ -85,184 +112,395 @@ def map():
xmov = math.cos(angle * (math.pi / 180.0)) * distdiv
ymov = math.sin(angle * (math.pi / 180.0)) * distdiv
pos = shape["pos"]
if len(leds) < lednum + shape["size"]:
for x in range(lednum + shape["size"] - len(leds)):
leds.append(None)
leds_size.append(None)
if len(self.leds) < lednum + shape["size"]:
for x in range(lednum + shape["size"] - len(self.leds)):
self.leds.append(None)
self.leds_size.append(None)
while dist < length:
leds[lednum] = (pos[0], pos[1])
self.leds[lednum] = (pos[0], pos[1])
pos[0] += xmov
pos[1] += ymov
dist += distdiv
lednum = lednum + 1
if generate_map:
map = sorted(map, key=lambda x: (-x[1], x[0]))
print(map)
import matplotlib.pyplot as plt
plt.axis('equal')
x, y = zip(*map)
plt.scatter(x, y, s=12)
#plt.plot(x, y, marker='o')
#plt.scatter(*zip(*leds), s=3)
for i, (x_pos, y_pos) in enumerate(map):
plt.text(x_pos, y_pos, str(i), color="red", fontsize=12)
plt.savefig("map2.png", dpi=600, bbox_inches="tight")
data = {"map": [{"index": i, "pos": str(list(pos))} for i, pos in enumerate(map)]}
yaml_str = yaml.dump(data, default_flow_style=False)
print(yaml_str)
print(self.rings)
flag = 0
for x in leds:
for x in self.leds:
if x is None:
flag = flag + 1
if flag > 0:
fprint("Warning: Imperfect LED map ordering. Hiding undefined lights.")
for x in range(len(leds)):
if leds[x] is None:
leds[x] = (0, 0)
for x in range(len(self.leds)):
if self.leds[x] is None:
self.leds[x] = (0, 0)
#leds = tmpleds.reverse()
#fprint(leds)
# controller mapping
for ctrl in config["led"]["controllers"]:
if len(controllers) < ctrl["universe"]+1:
for x in range(ctrl["universe"]+1 - len(controllers)):
controllers.append(None)
for ctrl in self.config["led"]["controllers"]:
if len(self.controllers) < ctrl["universe"]+1:
for x in range(ctrl["universe"]+1 - len(self.controllers)):
self.controllers.append(None)
controllers[ctrl["universe"]] = (ctrl["ledstart"],ctrl["ledend"]+1,ctrl["ip"])
self.controllers[ctrl["universe"]] = (ctrl["ledstart"],ctrl["ledend"]+1,ctrl["ip"])
for x in range(ctrl["ledstart"],ctrl["ledend"]+1):
leds_size[x] = len(ctrl["mode"])
self.leds_size[x] = len(ctrl["mode"])
#fprint(controllers)
if(debug):
if(self.debug):
import matplotlib.pyplot as plt
plt.axis('equal')
for ctrl in controllers:
plt.scatter(*zip(*leds[ctrl[0]:ctrl[1]]), s=2)
for ctrl in self.controllers:
plt.scatter(*zip(*self.leds[ctrl[0]:ctrl[1]]), s=2)
#plt.scatter(*zip(*leds), s=3)
plt.savefig("map.png", dpi=600, bbox_inches="tight")
leds_adj = [(x-min([led[0] for led in leds]), # push to zero start
y-min([led[1] for led in leds]) )
for x, y in leds]
leds_adj = [(x-min([led[0] for led in self.leds]), # push to zero start
y-min([led[1] for led in self.leds]) )
for x, y in self.leds]
leds_normalized = [(x / max([led[0] for led in leds_adj]),
self.leds_normalized = [(x / max([led[0] for led in leds_adj]),
y / max([led[1] for led in leds_adj]))
for x, y in leds_adj]
#return leds, controllers
def init():
map()
global sender
global config
global leds
global leds_size
global controllers
global data
sender = sacn.sACNsender(fps=config["led"]["fps"], universeDiscovery=False)
sender.start() # start the sending thread
for x in range(len(controllers)):
print("Waiting for the controller at", controllers[x][2], "to be online...", end="")
def init(self):
self.map()
self.sender = sacn.sACNsender(fps=self.config["led"]["fps"], universeDiscovery=False)
self.sender.start() # start the sending thread
for x in range(len(self.controllers)):
print("Waiting for the controller at", self.controllers[x][2], "to be online...", end="", flush=True)
count = 0
while not ping(controllers[x][2]):
while not self.ping(self.controllers[x][2]):
count = count + 1
if count >= config["led"]["timeout"]:
fprint(" ERROR: controller still offline after " + str(count) + " seconds, continuing...")
if count >= self.config["led"]["timeout"]:
print(" ERROR: controller still offline after " + str(count) + " seconds, continuing...")
break
if count < config["led"]["timeout"]:
fprint(" done")
for x in range(len(controllers)):
print("Activating controller", x, "at", controllers[x][2], "with", controllers[x][1]-controllers[x][0], "LEDs.")
sender.activate_output(x+1) # start sending out data
sender[x+1].destination = controllers[x][2]
sender.manual_flush = True
else:
print(" done")
#if count < self.config["led"]["timeout"]:
time.sleep(1)
for x in range(len(self.controllers)):
print("Activating controller", x, "at", self.controllers[x][2], "with", self.controllers[x][1]-self.controllers[x][0], "LEDs.")
self.sender.activate_output(x+1) # start sending out data
self.sender[x+1].destination = self.controllers[x][2]
self.sender.manual_flush = True
# initialize global pixel data list
data = list()
for x in range(len(leds)):
if leds_size[x] == 3:
data.append((20,20,127))
elif leds_size[x] == 4:
data.append((50,50,255,0))
self.data = list()
self.exactdata = list()
for x in range(len(self.leds)):
if self.leds_size[x] == 3:
self.exactdata.append(None)
self.data.append((20,20,127))
elif self.leds_size[x] == 4:
self.exactdata.append(None)
self.data.append((50,50,255,0))
else:
data.append((0,0,0))
sendall(data)
self.exactdata.append(None)
self.data.append((0,0,0))
self.sendall(self.data)
#time.sleep(50000)
fprint("Running start-up test sequence...")
for y in range(1):
for x in range(len(leds)):
setpixel(5,5,5,x)
sendall(data)
#time.sleep(2)
#alloffsmooth()
# fprint("Running start-up test sequence...")
# for y in range(1):
# for x in range(len(self.leds)):
# self.setpixel(0,60,144,x)
# self.sendall(self.data)
# #time.sleep(2)
# self.alloffsmooth()
self.startup_animation(show=False)
def sendall(datain):
def sendall(self, datain):
# send all LED data to all controllers
# data must have all LED data in it as [(R,G,B,)] tuples in an array, 1 tuple per pixel
global controllers
global sender
sender.manual_flush = True
for x in range(len(controllers)):
sender[x+1].dmx_data = list(sum(datain[controllers[x][0]:controllers[x][1]] , ())) # flatten the subsection of the data array
self.sender.manual_flush = True
for x in range(len(self.controllers)):
self.sender[x+1].dmx_data = list(sum(datain[self.controllers[x][0]:self.controllers[x][1]] , ())) # flatten the subsection of the data array
sender.flush()
self.sender.flush()
time.sleep(0.002)
#sender.flush() # 100% reliable with 2 flushes, often fails with 1
#time.sleep(0.002)
#sender.flush()
def fastsendall(datain):
def fastsendall(self, datain):
# send all LED data to all controllers
# data must have all LED data in it as [(R,G,B,)] tuples in an array, 1 tuple per pixel
global controllers
global sender
sender.manual_flush = False
print(datain[controllers[0][0]:controllers[0][1]])
for x in range(len(controllers)):
sender[x+1].dmx_data = list(sum(datain[controllers[x][0]:controllers[x][1]] , ())) # flatten the subsection of the data array
self.sender.manual_flush = False
print(datain[self.controllers[0][0]:self.controllers[0][1]])
for x in range(len(self.controllers)):
self.sender[x+1].dmx_data = list(sum(datain[self.controllers[x][0]:self.controllers[x][1]] , ())) # flatten the subsection of the data array
sender.flush()
self.sender.flush()
def senduniverse(datain, lednum):
def senduniverse(self, datain, lednum):
# send all LED data for 1 controller/universe
# data must have all LED data in it as [(R,G,B,)] tuples in an array, 1 tuple per pixel
global controllers
global sender
for x in range(len(controllers)):
if lednum >= controllers[x][0] and lednum < controllers[x][1]:
sender[x+1].dmx_data = list(sum(datain[controllers[x][0]:controllers[x][1]] , ())) # flatten the subsection of the data array
for x in range(len(self.controllers)):
if lednum >= self.controllers[x][0] and lednum < self.controllers[x][1]:
self.sender[x+1].dmx_data = list(sum(datain[self.controllers[x][0]:self.controllers[x][1]] , ())) # flatten the subsection of the data array
sender.flush()
self.sender.flush()
time.sleep(0.004)
#sender.flush() # 100% reliable with 2 flushes, often fails with 1
#time.sleep(0.002)
#sender.flush()
def alloff():
def alloff(self):
tmpdata = list()
for x in range(len(leds)):
if leds_size[x] == 3:
for x in range(len(self.leds)):
if self.leds_size[x] == 3:
tmpdata.append((0,0,0))
elif leds_size[x] == 4:
elif self.leds_size[x] == 4:
tmpdata.append((0,0,0,0))
else:
tmpdata.append((0,0,0))
sendall(tmpdata)
self.sendall(tmpdata)
#sendall(tmpdata)
#sendall(tmpdata) #definitely make sure it's off
return self
def allon():
global data
sendall(data)
def allon(self):
self.sendall(self.data)
return self
def alloffsmooth():
tmpdata = data
def alloffsmooth(self):
tmpdata = self.data
for x in range(256):
for x in range(len(data)):
setpixel(tmpdata[x][0]-1,tmpdata[x][1]-1,tmpdata[x][2]-1, x)
sendall(tmpdata)
for x in range(len(self.data)):
self.setpixel(tmpdata[x][0]-1,tmpdata[x][1]-1,tmpdata[x][2]-1, x)
self.sendall(tmpdata)
alloff()
self.alloff()
return self
def setpixelnow(r, g, b, num):
def setpixelnow(self, r, g, b, num):
# slight optimization: send only changed universe
# unfortunately no way to manual flush data packets to only 1 controller with this sACN library
global data
setpixel(r,g,b,num)
senduniverse(data, num)
self.setpixel(r,g,b,num)
self.senduniverse(self.data, num)
return self
def setpixel(r, g, b, num):
global data
global leds_size
def setmode(self, stmode, r=0,g=0,b=0):
if stmode is not None:
if self.mode != stmode:
self.firstrun = True
self.mode = stmode
return self
def setring(self, r,g,b,idx):
ring = self.rings[idx]
for pixel in range(ring[2],ring[3]):
self.setpixel(r,g,b,pixel)
#global data
#senduniverse(data, ring[2])
return self
def runmodes(self, ring = -1, speed = 1):
fprint("Mode: " + str(self.mode))
if self.mode == "Startup":
# loading animation. cable check
if self.firstrun:
self.changecount = self.animation_time * 3
self.firstrun = False
for x in range(len(self.ringstatus)):
self.ringstatus[x] = [True, self.animation_time]
if self.changecount > 0:
fprint(self.changecount)
self.changecount = self.fadeorder(0,len(self.leds), self.changecount, 0,50,100)
else:
self.setmode("Startup2")
elif self.mode == "Startup2":
if self.firstrun:
self.firstrun = False
else:
for x in range(len(self.ringstatus)):
if self.ringstatus[x][0]:
self.setring(0, 50, 100, x)
else:
self.ringstatus[x][1] = self.fadeall(self.rings[x][2],self.rings[x][3], self.ringstatus[x][1], 100,0,0) # not ready
elif self.mode == "StartupCheck":
if self.firstrun:
self.firstrun = False
for x in range(len(self.ringstatus)):
self.ringstatus[x] = [False, self.animation_time]
else:
for x in range(len(self.ringstatus)):
if self.ringstatus[x][0]:
self.ringstatus[x][1] = self.fadeall(self.rings[x][2],self.rings[x][3], self.ringstatus[x][1], 0,50,100) # ready
else:
self.setring(100, 0, 0, x)
elif self.mode == "GrabA":
if self.firstrun:
self.firstrun = False
self.changecount = self.animation_time # 100hz
if self.changecount > 0:
self.changecount = self.fadeall(self.rings[ring][2],self.rings[ring][3], self.changecount, 100,0,0)
else:
self.setring(100,0,0,ring)
self.setmode("GrabB")
elif self.mode == "GrabB":
if self.firstrun:
self.firstrun = False
self.changecount = self.animation_time # 100hz
if self.changecount > 0:
self.changecount = self.fadeorder(self.rings[ring][2],self.rings[ring][3], self.changecount, 0,100,0)
else:
self.setring(0,100,0,ring)
self.setmode("idle")
elif self.mode == "GrabC":
if self.firstrun:
self.firstrun = False
self.changecount = self.animation_time # 100hz
if self.changecount > 0:
self.changecount = self.fadeall(self.rings[ring][2],self.rings[ring][3], self.changecount, 0,50,100)
else:
self.setring(0,50,100,ring)
self.setmode("idle")
elif self.mode == "idle":
time.sleep(0)
self.sendall(self.data)
return self
def fadeall(self, idxa,idxb,sizerem,r,g,b):
if sizerem < 1:
return 0
sum = 0
for x in range(idxa,idxb):
if self.exactdata[x] is None:
self.exactdata[x] = self.data[x]
old = self.exactdata[x]
dr = (r - old[0])/sizerem
sum += abs(dr)
dr += old[0]
dg = (g - old[1])/sizerem
sum += abs(dg)
dg += old[1]
db = (b - old[2])/sizerem
db += old[2]
sum += abs(db)
self.exactdata[x] = (dr, dg, db)
#print(new)
self.setpixel(dr, dg, db, x)
if sizerem == 1:
self.exactdata[x] = None
if sum == 0 and sizerem > 2:
sizerem = 2
return sizerem - 1
def fadeorder(self, idxa,idxb,sizerem,r,g,b):
if sizerem < 1:
return 0
drs = 0
dgs = 0
dbs = 0
sum = 0
for x in range(idxa,idxb):
if self.exactdata[x] is None:
self.exactdata[x] = self.data[x]
old = self.exactdata[x]
dr = (r - old[0])
dg = (g - old[1])
db = (b - old[2])
drs += dr
dgs += dg
dbs += db
drs /= sizerem
dgs /= sizerem
dbs /= sizerem
sum += abs(drs) + abs(dgs) + abs(dbs)
print(drs,dgs,dbs)
for x in range(idxa,idxb):
old = self.exactdata[x]
new = list(old)
if drs > 0:
if old[0] + drs > r:
new[0] = r
drs -= r - old[0]
else:
new[0] = old[0] + drs
drs = 0
if dgs > 0:
if old[1] + dgs > g:
new[1] = g
dgs -= g - old[1]
else:
new[1] = old[1] + dgs
dgs = 0
if dbs > 0:
if old[2] + dbs > b:
new[2] = b
dbs -= b - old[2]
else:
new[2] = old[2] + dbs
dbs = 0
if drs < 0:
if old[0] + drs < r:
new[0] = r
drs -= r - old[0]
else:
new[0] = old[0] + drs
drs = 0
if dgs < 0:
if old[1] + dgs < g:
new[1] = g
dgs -= g - old[1]
else:
new[1] = old[1] + dgs
dgs = 0
if dbs < 0:
if old[2] + dbs < b:
new[2] = b
dbs -= b - old[2]
else:
new[2] = old[2] + dbs
dbs = 0
if drs != 0 or dgs != 0 or dbs != 0:
self.exactdata[x] = new
self.setpixel(new[0],new[1],new[2],x)
if sizerem == 1:
self.exactdata[x] = None
if sum == 0 and sizerem > 2:
sizerem = 2
return sizerem - 1
def setpixel(self, r, g, b, num):
# constrain values
if r < 0:
r = 0
@ -277,29 +515,28 @@ def setpixel(r, g, b, num):
elif b > 255:
b = 255
if leds_size[num] == 3:
data[num] = (int(r), int(g), int(b))
elif leds_size[num] == 4: # cut out matching white and turn on white pixel instead
data[num] = (( int(r) - int(min(r,g,b)), int(g) - int(min(r,g,b)), int(b) - int(min(r,g,b)), int(min(r,g,b))) )
if self.leds_size[num] == 3:
self.data[num] = (int(r), int(g), int(b))
elif self.leds_size[num] == 4: # cut out matching white and turn on white pixel instead
self.data[num] = (( int(r) - int(min(r,g,b)), int(g) - int(min(r,g,b)), int(b) - int(min(r,g,b)), int(min(r,g,b))) )
else:
data[num] = (int(r), int(g), int(b))
self.data[num] = (int(r), int(g), int(b))
return self
def close():
global sender
def close(self):
time.sleep(0.5)
sender.stop()
self.sender.stop()
return self
def mapimage(image, fps=60):
global start
while uptime() - start < 1/fps:
def mapimage(self, image, fps=90):
while uptime() - self.start < 1/fps:
time.sleep(0.00001)
fprint(1 / (uptime() - start))
start = uptime()
fprint(1 / (uptime() - self.start))
self.start = uptime()
minsize = min(image.shape[0:2])
leds_normalized2 = [(x * minsize,
y * minsize)
for x, y in leds_normalized]
for x, y in self.leds_normalized]
cv2.imshow("video", image)
cv2.waitKey(1)
@ -316,28 +553,125 @@ def mapimage(image, fps=60):
#avgx += x
#avgy += y
color = tuple(image[y, x])
setpixel(color[2]/2,color[1]/2,color[0]/2,xx) # swap b & r
self.setpixel(color[2]/2,color[1]/2,color[0]/2,xx) # swap b & r
#print(color)
else:
#avgx += x
#avgy += y
setpixel(0,0,0,xx)
self.setpixel(0,0,0,xx)
#avgx /= len(leds)
#avgy /= len(leds)
#print((avgx,avgy, max([led[0] for led in leds_adj]), max([led[1] for led in leds_adj]) , min(image.shape[0:2]) ))
global data
fastsendall(data)
self.fastsendall(self.data)
return self
def mainloop(self, stmode, ring = -1, fps = 100, preview = False):
while uptime() - self.start < 1/fps:
time.sleep(0.00001)
fprint(1 / (uptime() - self.start))
self.start = uptime()
if self.mode is not None:
self.setmode(stmode)
self.runmodes(ring)
if preview:
self.drawdata()
return self
def drawdata(self):
#tmp = list()
#for x in len(leds):
# led = leds[x]
# tmp.append((led[0], led[1], data[x]))
x = [led[0] for led in self.leds]
y = [led[1] for led in self.leds]
colors = self.data
colors_normalized = [(x[0]/255, x[1]/255, x[2]/255) for x in colors]
# Plot the points
plt.scatter(x, y, c=colors_normalized)
# Optional: add grid, title, and labels
plt.grid(True)
plt.title('Colored Points')
plt.xlabel('X')
plt.ylabel('Y')
plt.show()
plt.savefig("map3.png", dpi=50, bbox_inches="tight")
plt.clf()
return self
def startup_animation(self, show):
stmode = "Startup"
self.mainloop(stmode, preview=show)
while self.mode == "Startup":
self.mainloop(None, preview=show)
for x in range(54):
self.ringstatus[x][0] = False
self.mainloop(None, preview=show)
for x in range(self.animation_time):
self.mainloop(None, preview=show)
self.clear_animations()
stmode = "StartupCheck"
self.mainloop(stmode, preview=show)
self.clear_animations()
return self
def clear_animations(self):
for x in range(len(self.leds)):
self.exactdata[x] = None
return self
def do_animation(self, stmode, ring=-1):
self.mainloop(stmode, ring, preview=show)
self.wait_for_animation(ring)
return self
def start_animation(self, stmode, ring=-1):
self.mainloop(stmode, ring, preview=show)
return self
def wait_for_animation(self, ring=-1):
while self.mode != "idle":
self.mainloop(None, ring, preview=show)
return self
if __name__ == "__main__":
init()
cap = cv2.VideoCapture('output.mp4')
import matplotlib.pyplot as plt
"""cap = cv2.VideoCapture('badapple.mp4')
while cap.isOpened():
ret, frame = cap.read()
if not ret:
break
mapimage(frame)
mapimage(frame, fps=30)"""
show = False
ring = 1
ledsys = LEDSystem()
ledsys.init()
ledsys.startup_animation(show)
for x in range(54):
ledsys.ringstatus[x][0] = True
ledsys.mainloop(None, preview=show)
for x in range(ledsys.animation_time):
ledsys.mainloop(None, preview=show)
time.sleep(1)
close()
ledsys.do_animation("GrabA", 1)
ledsys.do_animation("GrabA", 5)
ledsys.start_animation("GrabC", 1)
ledsys.wait_for_animation(1)
ledsys.do_animation("GrabC", 5)
ledsys.close()
#sys.exit(0)
# blue : default
# green : target
# yellow : crosshair
# red : missing
# uninitialized : red/purple?

BIN
map.png

Binary file not shown.

Before

Width:  |  Height:  |  Size: 381 KiB

After

Width:  |  Height:  |  Size: 370 KiB

BIN
map2.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 184 KiB

BIN
map3.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 41 KiB

View File

@ -8,13 +8,18 @@ from util import fprint
class qr_reader():
camera = None
def __init__(self, ip, port):
self.camera = banner_ivu_export.DriveImg(ip, port)
self.ip = ip
self.port = port
#self.camera = banner_ivu_export.DriveImg(ip, port)
def read_qr(self, tries=1):
print("Trying " + str(tries) + " frames.")
self.camera = banner_ivu_export.DriveImg(self.ip, self.port)
for x in range(tries):
try:
print(str(x) + " ", end="", flush=True)
imgtype, img = self.camera.read_img()
if True:
#fprint(imgtype)
image_array = np.frombuffer(img, np.uint8)
img = cv2.imdecode(image_array, cv2.IMREAD_COLOR)
@ -22,9 +27,13 @@ class qr_reader():
#cv2.waitKey(1)
detect = cv2.QRCodeDetector()
value, points, straight_qrcode = detect.detectAndDecode(img)
if value != "":
self.camera.close()
return value
except:
continue
self.camera.close()
return False
@ -41,5 +50,7 @@ class video_streamer():
if __name__ == "__main__":
test = qr_reader("192.168.1.125", 32200)
import time
while True:
fprint(test.read_qr(5))
fprint(test.read_qr(300))
time.sleep(1)

View File

@ -1,7 +1,8 @@
#!/usr/bin/env python3
# Parse Belden catalog techdata datasheets
# Parse Belden (100%) & Alphawire (75%) catalog techdata datasheets
import pandas as pd
from PyPDF2 import PdfReader
import camelot
import numpy as np
@ -9,48 +10,96 @@ from PIL import Image
import io
import json
from util import fprint
import uuid
from util import run_cmd
from util import win32
import os
import glob
import sys
def parse(filename, output_dir):
def touch(path):
with open(path, 'a'):
os.utime(path, None)
def find_data_file(filename):
if getattr(sys, "frozen", False):
# The application is frozen
datadir = os.path.dirname(sys.executable)
else:
# The application is not frozen
# Change this bit to match where you store your data files:
datadir = os.path.dirname(__file__)
return os.path.join(datadir, filename)
def extract_table_name(table_start, searchpage, reader, dstype, fallbackname):
if dstype == "Belden":
ymin = table_start
ymax = table_start + 10
elif dstype == "Alphawire":
ymin = table_start - 5
ymax = table_start + 10
page = reader.pages[searchpage - 1]
parts = []
def visitor_body(text, cm, tm, fontDict, fontSize):
y = tm[5]
if y > ymin and y < ymax:
parts.append(text)
page.extract_text(visitor_text=visitor_body)
text_body = "".join(parts).strip('\n')
if len(text_body) == 0:
text_body = str(fallbackname)
return text_body
#fprint(text_body)
def parse(filename, output_dir, partnum, dstype):
tables = []
# Extract table data
tables = camelot.read_pdf(filename, pages="1-end", flavor='lattice', backend="poppler", split_text=False, line_scale=100, process_background=True, resolution=600, interations=1, layout_kwargs={'detect_vertical': False, 'char_margin': 0.5}, shift_text=['r', 't'])
try:
if dstype == "Belden":
tables = camelot.read_pdf(filename, pages="1-end", flavor='lattice', backend="ghostscript", split_text=False, line_scale=100, process_background=True, resolution=600, interations=1, layout_kwargs={'detect_vertical': False, 'char_margin': 0.5}, shift_text=['r', 't'])
elif dstype == "Alphawire":
tables = camelot.read_pdf(filename, pages="1-end", flavor='lattice', backend="ghostscript", split_text=False, line_scale=50, process_background=True, resolution=600, interations=1, layout_kwargs={'detect_vertical': True, 'char_margin': 0.5}, shift_text=['l', 't'])
except (OSError, RuntimeError) as e:
print(e)
if win32:
print("Ghostscript is not installed! Launching installer...")
#subprocess.run([r".\\gs10030w64.exe"])
os.system(r'''Powershell -Command "& { Start-Process \"''' + find_data_file("gs10030w64.exe") + r'''\" -Verb RunAs } " ''')
# Will return once file launched...
print("Once the install is completed, try again.")
return False
else:
print("Ghostscript is not installed. You can install it with e.g. apt install ghostscript for Debian-based systems.")
return False
#fprint("Total tables extracted:", tables.n)
n = 0
pagenum = 0
#pagenum = 0
reader = PdfReader(filename)
page = reader.pages[0]
table_list = {}
table_list_raw = {}
pd.set_option('future.no_silent_downcasting', True)
for table in tables:
table.df.replace('', np.nan, inplace=True)
#with pd.options.context("future.no_silent_downcasting", True):
table.df.infer_objects(copy=False)
table.df = table.df.replace('', np.nan).infer_objects(copy=False)
table.df.dropna(inplace=True, how="all")
table.df.dropna(inplace=True, axis="columns", how="all")
table.df.replace(np.nan, '', inplace=True)
table.df = table.df.replace(np.nan, '').infer_objects(copy=False)
if not table.df.empty:
#fprint("\nTable " + str(n))
# Extract table names
table_start = table.cells[0][0].lt[1] # Read top-left cell's top-left coordinate
#fprint(table_start)
ymin = table_start
ymax = table_start + 10
if pagenum != table.page - 1:
pagenum = table.page - 1
page = reader.pages[table.page - 1]
parts = []
def visitor_body(text, cm, tm, fontDict, fontSize):
y = tm[5]
if y > ymin and y < ymax:
parts.append(text)
page.extract_text(visitor_text=visitor_body)
text_body = "".join(parts).strip('\n')
if len(text_body) == 0:
text_body = str(n)
#fprint(text_body)
text_body = extract_table_name(table_start, table.page, reader, dstype, n)
table_list[text_body] = table.df
if dstype == "Alphawire":
table_list_raw[text_body] = table
#table.to_html("table" + str(n) + ".html")
#fprint(table.df)
@ -60,7 +109,7 @@ def parse(filename, output_dir):
#tables.export(output_dir + '/techdata.json', f='json')
# fprint(table_list)
#fprint(table_list)
# Extract Basic details - part name & description, image, etc
reader = PdfReader(filename)
@ -87,25 +136,34 @@ def parse(filename, output_dir):
# Table parsing and reordring
tables = dict()
torename = dict()
previous_table = ""
#print(table_list.keys())
for table_name in table_list.keys():
# determine shape: horizontal or vertical
table = table_list[table_name]
rows = table.shape[0]
cols = table.shape[1]
vertical = None
#print(rows, cols, table_name)
if rows > 2 and cols == 2:
vertical = True
elif cols == 1:
elif cols == 1 and rows > 1:
vertical = False
elif rows == 1:
vertical = True
elif cols == 2: # and rows <= 2
# inconsistent
if dstype == "Belden":
if table.iloc[0, 0].find(":") == len(table.iloc[0, 0]) - 1: # check if last character is ":" indicating a vertical table
vertical = True
else:
vertical = False
elif dstype == "Alphawire":
if table.iloc[0, 0].find(")") == 1 or table.iloc[0, 0].find(")") == 2 or table.iloc[0, 0].find(":") == len(table.iloc[0, 0]) - 1: # check if last character is ":" indicating a vertical table
vertical = True
else:
vertical = False
elif cols > 2: # and rows <= 2
vertical = False
@ -113,18 +171,26 @@ def parse(filename, output_dir):
vertical = False
else: # 1 column, <= 2 rows
vertical = False
#print(vertical)
# missing name check
for table_name_2 in table_list.keys():
if table_name_2.find(table.iloc[-1, 0]) >= 0:
if dstype == "Alphawire" and table_name_2.find("\n") >= 0:
torename[table_name_2] = table_name_2[0:table_name_2.find("\n")]
if dstype == "Alphawire" and table_name_2.find(table.iloc[-1, 0]) >= 0:
# Name taken from table directly above - this table does not have a name
table_list["Specs " + str(len(tables))] = table_list.pop(table_name_2, None) # rename table to arbitrary altername name
torename[table_name_2] = "Specs " + str(len(tables))
#table_list["Specs " + str(len(tables))] = table_list[table_name_2] # rename table to arbitrary altername name
break
if vertical:
out = dict()
if rows > 1:
for row in table.itertuples(index=False, name=None):
out[row[0].replace("\n", " ").replace(":", "")] = row[1]
else:
for row in table.itertuples(index=False, name=None):
out[row[0].replace("\n", " ").replace(":", "")] = ""
else: # horizontal
out = dict()
@ -134,47 +200,184 @@ def parse(filename, output_dir):
tables[table_name] = out
# multi-page table check, Alphawire
if dstype == "Alphawire" and table_name.isdigit():
# table continues from previous page or has name on previous page
thistbl = table_list_raw[table_name]
prevtbl = table_list_raw[previous_table]
# multi-page table check
if table_name.isdigit() and len(tables) > 1:
fprint(table_name)
fprint(previous_table)
if prevtbl.cells[-1][0].lb[1] < 50 and thistbl.cells[0][0].lt[1] > 600:
# wraparound
#print("WRAP")
#print("PREV TABLE", prevtbl.df)
#print("THIS TABLE", thistbl.df)
#print("PREV TABLE CORNER", prevtbl.cells[-1][0].lb[1])
#print("THIS TABLE CORNER", thistbl.cells[0][0].lt[1])
main_key = previous_table
cont_key = table_name
fprint(tables)
#print(vertical)
if vertical == False:
main_keys = list(tables[main_key].keys())
for i, (cont_key, cont_values) in enumerate(tables[cont_key].items()):
if i < len(main_keys):
fprint(tables[main_key][main_keys[i]])
tables[main_key][main_keys[i]] = (tables[main_key][main_keys[i]] + (cont_key,) + cont_values)
#print(tables[main_key][main_keys[i]])
tables[main_key][main_keys[i]] = (tuple(tables[main_key][main_keys[i]]) + (cont_key,) + cont_values)
del tables[table_name]
else:
#print(tables[cont_key].keys())
for key in tables[cont_key].keys():
#print(main_key, key, cont_key, key)
tables[main_key][key] = tables[cont_key][key]
del tables[table_name]
elif thistbl.cells[0][0].lt[1] > 600:
# name on previous page (grrrr)
#print("NAMEABOVE")
#print("PREV TABLE", prevtbl.df)
#print("THIS TABLE", thistbl.df)
#print("PREV TABLE CORNER", prevtbl.cells[-1][0].lb[1])
#print("THIS TABLE CORNER", thistbl.cells[0][0].lt[1])
name = extract_table_name(50, prevtbl.page,reader,dstype,table_name).strip("\n").strip()
#print("FOUND NAME:", name)
torename[table_name] = name
# multi-page table check, Belden
if dstype == "Belden":
if table_name.isdigit() and len(tables) > 1:
#fprint(table_name)
#fprint(previous_table)
main_key = previous_table
cont_key = table_name
#fprint(tables)
if vertical == False:
main_keys = list(tables[main_key].keys())
for i, (cont_key, cont_values) in enumerate(tables[cont_key].items()):
if i < len(main_keys):
#fprint(tables[main_key][main_keys[i]])
tables[main_key][main_keys[i]] = (tuple(tables[main_key][main_keys[i]]) + (cont_key,) + cont_values)
del tables[table_name]
else:
#print(tables)
#print(main_key)
#print(cont_key)
for key in tables[cont_key].keys():
tables[main_key][key] = tables[cont_key][key]
del tables[table_name]
else:
previous_table = table_name
else:
previous_table = table_name
# remove & rename tables
#print(torename)
for table_name in torename.keys():
tables[torename[str(table_name)]] = tables[str(table_name)]
del tables[table_name]
# remove multi-line values that occasionally squeak through
def replace_newlines_in_dict(d):
for key, value in d.items():
if isinstance(value, str):
# Replace \n with " " if the value is a string
d[key] = value.replace('\n', ' ')
elif isinstance(value, dict):
# Recursively call the function if the value is another dictionary
replace_newlines_in_dict(value)
return d
fprint(tables)
with open(output_dir + "/tables.json", 'w') as json_file:
json.dump(tables, json_file)
tables = replace_newlines_in_dict(tables)
# summary
output_table = dict()
output_table["partnum"] = partnum
id = str(uuid.uuid4())
output_table["id"] = id
#output_table["position"] = id
#output_table["brand"] = brand
output_table["fullspecs"] = {"partnum": partnum, "id": id, **tables}
output_table["searchspecs"] = {"partnum": partnum, **flatten(tables)}
output_table["searchspecs"]["id"] = id
#print(output_table)
#run_cmd("rm \"" + output_dir + "\"/*.json") # not reliable!
pattern = os.path.join(output_dir, '*.json')
json_files = glob.glob(pattern)
for file_path in json_files:
os.remove(file_path)
#print(f"Deleted {file_path}")
with open(output_dir + "/search.json", 'w') as json_file:
json.dump(output_table["searchspecs"], json_file)
with open(output_dir + "/specs.json", 'w') as json_file:
json.dump(output_table["fullspecs"], json_file)
#print(json.dumps(output_table, indent=2))
touch(output_dir + "/parsed") # mark as parsed
return True
return tables
def flatten(tables):
def convert_to_number(s):
try:
# First, try converting to an integer.
return int(s)
except ValueError:
# If that fails, try converting to a float.
try:
return float(s)
except ValueError:
# If it fails again, return the original string.
return s
out = dict()
#print("{")
for table in tables.keys():
for key in tables[table].keys():
if len(key) < 64:
keyname = key
else:
keyname = key[0:64]
fullkeyname = (table + ": " + keyname).replace(".","")
if type(tables[table][key]) is not tuple:
if len(tables[table][key]) > 0:
out[fullkeyname] = convert_to_number(tables[table][key])
#print("\"" + keyname + "\":", "\"" + str(out[fullkeyname]) + "\",")
elif len(tables[table][key]) == 1:
if len(tables[table][key][0]) > 0:
out[fullkeyname] = convert_to_number(tables[table][key][0])
#print("\"" + keyname + "\":", "\"" + str(out[fullkeyname]) + "\",")
else:
tmp = []
for x in range(len(tables[table][key])):
if len(tables[table][key][x]) > 0:
tmp.append(tables[table][key][x].strip())
#out[fullkeyname + " " + str(x+1)] = convert_to_number(tables[table][key][x])
out[fullkeyname] = tmp
# if the item has at least two commas in it, split it
if tables[table][key].count(',') > 0:
out[fullkeyname] = list(map(lambda x: x.strip(), tables[table][key].split(",")))
#print("\"" + keyname + "\":", "\"" + str(out[fullkeyname]) + "\",")
# if the item has at least two commas in it, split it
if tables[table][key].count(',') > 0:
out[fullkeyname] = list(map(lambda x: x.strip(), tables[table][key].split(",")))
#print("\"" + keyname + "\":", "\"" + str(out[fullkeyname]) + "\",")
#print("}")
return out
if __name__ == "__main__":
parse("test2.pdf", "10GXS13")
print(parse("cables/3050/datasheet.pdf", "cables/3050", "3050", "Alphawire"))

View File

@ -1,17 +1,29 @@
# Runtime
camelot-py[base]
camelot-py
opencv-python
pypdf2==2.12.1
alive-progress
requests
math3d==4.0.0
git+https://github.com/Byeongdulee/python-urx.git
psycopg2
meilisearch
pyyaml
Flask
selenium
sacn
uptime
websockets
numpy
scipy
ipywidgets
pandas
pyarrow
ghostscript
pyzbar
segno
pyModbusTCP
# Development
matplotlib
#cx_Freeze # uncomment if building label generator app
# requires windows 10 SDK, visual C++, etc

486
run.py
View File

@ -1,5 +1,6 @@
#!/usr/bin/env python3
from alive_progress import alive_bar
import get_specs
import traceback
#import logging
@ -12,19 +13,25 @@ from util import fprint
from util import run_cmd
import sys
import ur5_control
from ur5_control import Rob
import os
import signal
import socket
from flask import Flask, render_template, request
import requests
import led_control
from led_control import LEDSystem
import server
import asyncio
import json
import process_video
import search
from search import JukeboxSearch
#multiprocessing.set_start_method('spawn', True)
from pyModbusTCP.client import ModbusClient
from uptime import uptime
mbconn = None
config = None
keeprunning = True
arm_ready = False
@ -32,25 +39,45 @@ led_ready = False
camera_ready = False
sensor_ready = False
vm_ready = False
cable_search_ready = False
killme = None
#pool = None
serverproc = None
camera = None
ledsys = None
arm = None
to_server_queue = Queue()
from_server_queue = Queue()
mainloop_get = Queue()
mode = "Startup"
counter = 0
jbs = None
scan_value = None
arm_state = None
cable_list = list()
parse_res = None
cable_list_state = list()
just_placed = -1
ring_animation = None
led_set_mode = None
def arm_start_callback(res):
fprint("Arm action complete.")
global arm_ready
arm_ready = True
def led_start_callback(res):
global led_ready
led_ready = True
global ledsys
ledsys = res
def camera_start_callback(res):
global camera_ready
camera_ready = True
global scan_value
scan_value = res
def sensor_start_callback(res):
global sensor_ready
@ -60,6 +87,12 @@ def vm_start_callback(res):
global vm_ready
vm_ready = True
def cable_search_callback(res):
global cable_search_ready
cable_search_ready = True
global parse_res
parse_res = res
def wait_for(val, name):
#global val
if val is False:
@ -67,7 +100,15 @@ def wait_for(val, name):
while val is False:
sleep(0.1)
def start_server_socket():
def send_data(type, call, data, client_id="*"):
out = dict()
out["type"] = type
out["call"] = call
out["data"] = data
to_server_queue.put((client_id, json.dumps(out)))
def start_server_socket(cable_list):
global jbs
"""app = Flask(__name__)
@app.route('/report_ip', methods=['POST'])
@ -89,6 +130,9 @@ def start_server_socket():
while True:
#print("HI")
# Handeling Server Requests Loop, will run forever
if not from_server_queue.empty():
client_id, message = from_server_queue.get()
fprint(f"Message from client {client_id}: {message}")
@ -96,6 +140,10 @@ def start_server_socket():
# Message handler
try:
decoded = json.loads(message)
except:
fprint("Non-JSON message recieved")
continue
if "type" not in decoded:
fprint("Missing \"type\" field.")
continue
@ -105,45 +153,79 @@ def start_server_socket():
if "data" not in decoded:
fprint("Missing \"data\" field.")
continue
# if we get here, we have a "valid" data packet
data = decoded["data"]
call = decoded["call"]
try:
match decoded["type"]:
case "log":
fprint("log message")
if call == "send":
fprint("webapp: " + data)
fprint("webapp: " + str(data), sendqueue=to_server_queue)
elif call == "request":
fprint("")
pass
case "cable_map":
fprint("cable_map message")
if call == "send":
fprint("")
pass
elif call == "request":
fprint("")
tmp = list()
for idx in range(len(cable_list)):
if cable_list[idx] is not False:
tmp1 = {"part_number": cable_list[idx], "position": idx, "name": cable_list[idx], "brand": "Belden", "description": "Blah", "short_description": "Bla"}
tmp.append(tmp1)
out = {"map": tmp}
fprint(out)
send_data(decoded["type"], "send", out, client_id)
case "ping":
fprint("Pong!!!")
# Lucas' notes
# Add a ping pong :) response/handler
# Add a get cable response/handler
# this will tell the robot arm to move
# Call for turning off everything
# TODO Helper for converting Python Dictionaries to JSON
# make function: pythonData --> { { "type": "...", "call": "...", "data": pythonData } }
# to send: to_server_queue.put(("*", "JSON STRING HERE")) # replace * with UUID of client to send to one specific location
case "cable_details":
fprint("cable_details message")
if call == "send":
fprint("")
pass
elif call == "request":
fprint("")
dataout = dict()
dataout["cables"] = list()
print(data)
if "part_number" in data:
for part in data["part_number"]:
#print(part)
#print(jbs.get_partnum(part))
dataout["cables"].append(jbs.get_partnum(part)["fullspecs"])
if "position" in data:
for pos in data["position"]:
#print(pos)
#print(jbs.get_position(str(pos)))
dataout["cables"].append(jbs.get_position(str(pos))["fullspecs"])
send_data(decoded["type"], "send", dataout, client_id)
case "cable_search":
fprint("cable_search message")
if call == "send":
fprint("")
pass
elif call == "request":
fprint("")
results = jbs.search(data["string"])["hits"]
dataout = dict()
dataout["cables"] = list()
for result in results:
dataout["cables"].append(result["fullspecs"])
send_data(decoded["type"], "send", dataout, client_id)
case "keyboard":
fprint("keyboard message")
if call == "send":
fprint("")
pass
elif call == "request":
fprint("")
if data["enabled"] == True:
# todo : send this to client
p = Process(target=run_cmd, args=("./keyboard-up.ps1",))
@ -151,21 +233,32 @@ def start_server_socket():
elif data["enabled"] == False:
p = Process(target=run_cmd, args=("./keyboard-down.ps1",))
p.start()
case "machine_settings":
fprint("machine_settings message")
if call == "send":
fprint("")
pass
elif call == "request":
fprint("")
pass
case "cable_get":
fprint("cable_get message")
if call == "send":
global mainloop_get
if "part_number" in data:
for cableidx in range(len(cable_list)):
cable = cable_list[cableidx]
if cable == data["part_number"]:
mainloop_get.put(("pickup", cableidx))
elif "position" in data:
mainloop_get.put(("pickup", data["position"]))
case _:
fprint("Unknown/unimplemented data type: " + decoded["type"])
except Exception as e:
fprint(traceback.format_exc())
fprint(e)
except:
fprint("Non-JSON message recieved")
continue
sleep(0.001) # Sleep to prevent tight loop
@ -213,57 +306,352 @@ def setup_server(pool):
global arm_ready
global serverproc
global camera
global arm
global jbs
pool.apply_async(ur5_control.init, (config["arm"]["ip"],), callback=arm_start_callback)
pool.apply_async(led_control.init, callback=led_start_callback)
arm = Rob(config)
pool.apply_async(ur5_control.powerup_arm, (arm,), callback=arm_start_callback, error_callback=handle_error)
global ledsys
ledsys = LEDSystem()
#pool.apply_async(ledsys.init, callback=led_start_callback)
#pool.apply_async(sensor_control.init, callback=sensor_start_callback)
serverproc = Process(target=start_server_socket)
serverproc.start()
jbs = JukeboxSearch()
if led_ready is False:
fprint("waiting for " + "LED controller initialization" + " to complete...", sendqueue=to_server_queue)
while led_ready is False:
sleep(0.1)
ledsys.init()
led_ready = True
fprint("LED controllers initialized.", sendqueue=to_server_queue)
#to_server_queue.put("[log] LED controllers initialized.")
sensor_ready = True
if sensor_ready is False:
fprint("waiting for " + "Sensor Initialization" + " to complete...", sendqueue=to_server_queue)
while sensor_ready is False:
sleep(0.1)
global mbconn
mbconn = ModbusClient(host="localhost", port=502, unit_id=1, auto_open=True, auto_close=True)
fprint("Sensors initialized.", sendqueue=to_server_queue)
if camera_ready is False:
fprint("waiting for " + "Camera initilization" + " to complete...", sendqueue=to_server_queue)
camera = process_video.qr_reader(config["cameras"]["banner"]["ip"], config["cameras"]["banner"]["port"])
camera = process_video.qr_reader(config["cameras"]["banner"]["ip"], int(config["cameras"]["banner"]["port"]))
fprint("Camera initialized.", sendqueue=to_server_queue)
arm_ready = True
#arm_ready = True
if arm_ready is False:
fprint("waiting for " + "UR5 initilization" + " to complete...", sendqueue=to_server_queue)
fprint("waiting for " + "UR5 powerup" + " to complete...", sendqueue=to_server_queue)
while arm_ready is False:
sleep(0.1)
fprint("Arm initialized.", sendqueue=to_server_queue)
ur5_control.init_arm(arm)
fprint("Arm initialized.", sendqueue=to_server_queue)
return True
def handle_error(error):
print(error, flush=True)
def get_sensors():
global mbconn
global sensors
oldsens = sensors
"""
port 1: 256
port 2: 272
port 3: 288
port 4: 304
port 5: 320
port 6: 336
port 7: 352
port 8: 368
"""
out = list()
for reg in [352, 288, 304, 368]:
val = mbconn.read_holding_registers(reg)
if val == 1:
out.append(1)
else:
out.append(0)
sensors = out
for x in range(len(oldsens)):
if oldsens[x] == 0 and out[x] == 1:
# cable newly detected on tray
return x
return -1
def get_open_spot(sensordata):
for x in range(len(sensordata)):
sens = sensordata[x]
if not sens:
return x
# if we get here, every spot is full
return False
def mainloop_server(pool):
# NON-blocking loop
global ring_animation
global led_set_mode
global just_placed
global config
global counter
global killme
global mode
global jbs
global arm
global ledsys
global camera
global arm_ready
global arm_state
global camera_ready
global cable_search_ready
global cable_list
global mainloop_get
global cable_list_state
if killme.value > 0:
killall()
counter = counter + 1
if mode == "Startup":
#counter = 54 # remove for demo
if counter < 54:
# scanning cables
ring_animation = counter
led_set_mode = "GrabA"
if arm_state is None:
#pool.apply_async(arm_start_callback, ("",))
arm_ready = False
pool.apply_async(ur5_control.to_camera, (arm,counter), callback=arm_start_callback, error_callback=handle_error)
fprint("Getting cable index " + str(counter) + " and scanning...")
arm_state = "GET"
#ur5_control.to_camera(arm, counter)
#arm_ready = True
elif arm_ready and arm_state == "GET":
fprint("Looking for QR code...")
print(camera.read_qr(30))
pool.apply_async(camera.read_qr, (10,), callback=camera_start_callback, error_callback=handle_error)
arm_ready = False
elif camera_ready:
fprint("Adding cable to list...")
global scan_value
if scan_value is False:
cable_list.append(scan_value)
elif scan_value.find("bldn.app/") > -1:
scan_value = scan_value[scan_value.find("bldn.app/")+9:]
else:
cable_list.append(scan_value)
fprint(scan_value)
pool.apply_async(ur5_control.return_camera, (arm,counter), callback=arm_start_callback, error_callback=handle_error)
#ur5_control.return_camera(arm, counter)
#arm_ready = True
arm_state = "RETURN"
camera_ready = False
elif arm_ready and arm_state == "RETURN":
counter += 1
arm_state = None
else:
# just wait til arm/camera is ready
pass
else:
# scanned everything
ring_animation = None
led_set_mode == "idle"
tmp = [
# Actual cables in Jukebox
"BLTF-1LF-006-RS5",
"BLTF-SD9-006-RI5",
"BLTT-SLG-024-HTN",
"BLFISX012W0",
"BLFI4X012W0",
"BLSPE101",
"BLSPE102",
"BL7922A",
"BL7958A",
"BLIOP6U",
"BL10GXW13",
"BL10GXW53",
"BL29501F",
"BL29512",
"BL3106A",
"BL9841",
"BL3105A",
"BL3092A",
"BL8760",
"BL6300UE",
"BL6300FE",
"BLRA500P",
"AW86104CY",
"AW3050",
"AW6714",
"AW1172C",
"AWFIT-221-1_4"
]
while len(tmp) < 54:
tmp.append(False) # must have 54 entries
#cable_list = tmp # comment out for real demo
for idx in range(len(cable_list)):
cable_list_state.append(True)
pool.apply_async(get_specs.get_multi, (cable_list, 0.3), callback=cable_search_callback, error_callback=handle_error)
mode = "Parsing"
fprint("All cables scanned. Finding & parsing datasheets...")
if mode == "Parsing":
# waiting for search & parse to complete
#cable_search_ready = True
if cable_search_ready is False:
pass
else:
# done
global parse_res
success, partnums = parse_res
for idx in range(len(partnums)):
if partnums[idx] is not False:
cable_list[idx] = partnums[idx][0].replace("/", "_")
else:
cable_list[idx] = False
print(partnums)
if success:
# easy mode
fprint("All cables inventoried and parsed.")
fprint("Adding to database...")
for idx in range(len(cable_list)):
partnum = cable_list[idx]
if partnum is not False:
with open("cables/" + partnum + "/search.json", "rb") as f:
searchdata = json.load(f)
searchdata["position"] = idx
with open("cables/" + partnum + "/specs.json", "rb") as f:
specs = json.load(f)
searchdata["fullspecs"] = specs
searchdata["fullspecs"]["position"] = idx
jbs.add_document(searchdata)
#sleep(0.5)
#print(jbs.get_position("1"))
fprint("All cables added to database.")
mode = "Idle"
serverproc = Process(target=start_server_socket, args=(cable_list,), error_callback=handle_error)
serverproc.start()
else:
# TODO: manual input
pass
if mode == "Idle":
# do nothing
if arm_ready is False:
pool.apply_async(ur5_control.move_to_home, (arm,), callback=arm_start_callback, error_callback=handle_error)
#arm_ready = True
else:
global mainloop_get
newtube = get_sensors()
if newtube >= 0 and newtube != just_placed:
# need to return a cable
mainloop_get.put(("return", newtube))
just_placed = -1
if not mainloop_get.empty():
action, get_cable = mainloop_get.get()
if get_cable > -1:
global sensors
if action == "pickup":
spot = get_open_spot(sensors)
if spot is not False:
arm_ready = False
pool.apply_async(ur5_control.pick_up_routine, (arm, get_cable, True, spot), callback=arm_start_callback, error_callback=handle_error)
mode = "Pickup"
cable_list_state[get_cable] = False # mark as removed
get_sensors(sensors,flag=get_open_spot(sensors))
if action == "return":
arm_ready = False
pool.apply_async(ur5_control.return_routine, (arm, get_cable), callback=arm_start_callback, error_callback=handle_error)
mode = "ReturnC"
else:
# LED idle anim
pass
if mode == "Pickup":
# complete
if arm_ready == True:
mode = "Idle"
arm_ready = False
else:
# getting cable and bringing to tray
# led animation
pass
if mode == "ReturnC":
# complete
if arm_ready == True:
mode = "Scan"
arm_ready = False
camera_ready = False
pool.apply_async(camera.read_qr, (10,), callback=camera_start_callback, error_callback=handle_error)
else:
# getting cable from and bringing to camera
# led animation
pass
if mode == "Scan":
if camera_ready == True:
global scan_value
if scan_value is False:
# unable to scan ???? not good
fprint("Unable to scan cable. Gonna retry.")
camera_ready = False
pool.apply_async(camera.read_qr, (10,), callback=camera_start_callback, error_callback=handle_error)
pass
elif scan_value.find("bldn.app/") > -1:
scan_value = scan_value[scan_value.find("bldn.app/")+9:]
fprint("Got cable: " + scan_value)
for idx in range(len(cable_list)):
cable = cable_list[idx]
if cable == scan_value and cable_list_state[idx] == False:
cable_list_state[idx] = True # mark cable as returned
arm_ready = False
pool.apply_async(ur5_control.return_camera, (arm, idx), callback=arm_start_callback, error_callback=handle_error)
mode = "Return"
break
if mode == "Return":
if arm_ready == True:
mode = "Idle"
arm_ready = False
# movement finished
else:
# cable going from camera to holder
# led animation
pass
if True:
# do every loop!
if ring_animation is not None and ledsys.mode != "idle":
ledsys.mainloop(None, ring_animation)
elif ring_animation is not None:
ledsys.mainloop(led_set_mode, ring_animation)
def run_loading_app():
@ -371,19 +759,20 @@ class LogExceptions(object):
return result
class LoggingPool(Pool):
def apply_async(self, func, args=(), kwds={}, callback=None):
return Pool.apply_async(self, LogExceptions(func), args, kwds, callback)
def apply_async(self, func, args=(), kwds={}, callback=None, error_callback=None):
return Pool.apply_async(self, LogExceptions(func), args, kwds, callback, error_callback)
if __name__ == "__main__":
#sys.stdout = Logger(filename="output.log")
#sys.stderr = Logger(filename="output.log")
#log_to_stderr(logging.DEBUG)
fprint("Starting Jukebox control system...")
with open('config.yml', 'r') as fileread:
#global config
config = yaml.safe_load(fileread)
fprint("Config loaded.")
with Manager() as manager:
fprint("Spawning threads...")
pool = LoggingPool(processes=10)
@ -404,5 +793,18 @@ if __name__ == "__main__":
fprint("Entering main loop...")
while(keeprunning):
mainloop_server(pool)
else:
fprint("Mode unspecified - assuming server")
fprint("Starting in server mode.")
if setup_server(pool):
fprint("Entering main loop...")
start = 0
speed = config["loopspeed"]
while(keeprunning):
start = uptime()
mainloop_server(pool)
# limit to certain "framerate"
while start + 1.0/speed < uptime():
pass

121
search.py Normal file
View File

@ -0,0 +1,121 @@
#!/usr/bin/env python3
"""Interactions with the Meilisearch API for adding and searching cables."""
from meilisearch import Client
from meilisearch.task import TaskInfo
from meilisearch.errors import MeilisearchApiError
import time
DEFAULT_URL = "http://127.0.0.1:7700"
DEFAULT_APIKEY = "fluffybunnyrabbit" # I WOULD RECOMMEND SOMETHING MORE SECURE
DEFAULT_INDEX = "cables"
DEFAULT_FILTERABLE_ATTRS = ["partnum", "uuid", "position"] # default filterable attributes
class JukeboxSearch:
"""Class for interacting with the Meilisearch API."""
def __init__(self,
url: str = None,
api_key: str = None,
index: str = None,
filterable_attrs: list = None):
"""Connect to Meilisearch and perform first-run tasks as necessary.
:param url: Address of the Meilisearch server. Defaults to ``http://localhost:7700`` if unspecified.
:param api_key: API key used to authenticate with Meilisearch. It is highly recommended to set this as something
secure if you can access this endpoint publicly, but you can ignore this and set Meilisearch's default API key
to ``fluffybunnyrabbit``.
:param index: The name of the index to configure. Defaults to ``cables`` if unspecified.
:param filterable_attrs: List of all the attributes we want to filter by."""
# connect to Meilisearch
url = url or DEFAULT_URL
api_key = api_key or DEFAULT_APIKEY
filterable_attrs = filterable_attrs or DEFAULT_FILTERABLE_ATTRS
self.index = index or DEFAULT_INDEX
self.client = Client(url, api_key)
# create the index if it does not exist already
try:
self.client.get_index(self.index)
self.client.delete_index(self.index)
self.client.create_index(self.index)
except MeilisearchApiError as _:
self.client.create_index(self.index)
# make a variable to easily reference the index
self.idxref = self.client.index(self.index)
time.sleep(0.05)
# update filterable attributes if needed
self.idxref.update_distinct_attribute('partnum')
self.update_filterables(filterable_attrs)
def add_document(self, document: dict) -> TaskInfo:
"""Add a cable to the Meilisearch index.
:param document: Dictionary containing all the cable data.
:returns: A TaskInfo object for the addition of the new document."""
return self.idxref.add_documents(document)
def add_documents(self, documents: list):
"""Add a list of cables to the Meilisearch index.
:param documents: List of dictionaries containing all the cable data.
:returns: A TaskInfo object for the last new document."""
taskinfo = None
for i in documents:
taskinfo = self.add_document(i)
return taskinfo
def update_filterables(self, filterables: list):
"""Update filterable attributes and wait for database to fully index. If the filterable attributes matches the
current attributes in the database, don't update (saves reindexing).
:param filterables: List of all filterable attributes"""
#existing_filterables = self.idxref.get_filterable_attributes()
#if len(set(existing_filterables).difference(set(filterables))) > 0:
taskref = self.idxref.update_filterable_attributes(filterables)
#self.client.wait_for_task(taskref.index_uid)
def search(self, query: str, filters: str = None):
"""Execute a search query on the Meilisearch index.
:param query: Seach query
:param filters: A meilisearch compatible filter statement.
:returns: The search results dict. Actual results are in a list under "hits", but there are other nice values that are useful in the root element."""
if filters:
q = self.idxref.search(query, {"filter": filters})
else:
q = self.idxref.search(query)
return q
def _filter_one(self, filter: str):
"""Get the first item to match a filter.
:param filter: A meilisearch compatible filter statement.
:returns: A dict containing the results; If no results found, an empty dict."""
q = self.search("", filter)
if q["estimatedTotalHits"] != 0:
return q["hits"][0]
else:
return dict()
def get_position(self, position: str):
"""Get a part by position.
:param partnum: The position to search for."""
return self._filter_one(f"position = {position}")
def get_uuid(self, uuid: str):
"""Get a specific UUID.
:param uuid: The UUID to search for."""
return self._filter_one(f"uuid = {uuid}")
def get_partnum(self, partnum: str):
"""Get a specific part number.
:param partnum: The part number to search for."""
return self._filter_one(f"partnum = {partnum}")
# entrypoint
if __name__ == "__main__":
jbs = JukeboxSearch()

20
setup-alpine-vm.sh Normal file
View File

@ -0,0 +1,20 @@
#!/bin/sh
# This script must run as root!
echo "https://dl-cdn.alpinelinux.org/alpine/latest-stable/main
https://dl-cdn.alpinelinux.org/alpine/latest-stable/community" > /etc/apk/repositories
apk upgrade
apk add git docker docker-cli-compose
rc-update add docker
service docker start
git clone https://git.myitr.org/Jukebox/jukebox-software
cd jukebox-software
git submodule init
git submodule update
docker compose build
docker compose up -d

31
setup-label-generator.py Normal file
View File

@ -0,0 +1,31 @@
import sys
from cx_Freeze import setup, Executable
debug = True
debug = not debug
# Dependencies are automatically detected, but it might need fine tuning.
# "packages": ["os"] is used as example only
import opcode
import os
import distutils
#distutils_path = os.path.join(os.path.dirname(opcode.__file__), 'distutils')
build_exe_options = {"include_msvcr": True, "packages": ["camelot", "setuptools", "segno"], "optimize": 0, "silent": True, "include_files": ["gs10030w64.exe", "GothamCond-Medium.otf", "belden-logo-superhires.png"], "excludes": ["scipy", "torch"]}
# base="Win32GUI" should be used only for Windows GUI app
base = "console"
#if sys.platform == "win32" and not debug:
# base = "Win32GUI"
if sys.platform == "linux" or sys.platform == "linux2" or sys.platform == "darwin":
name = "jukebox-labelgen"
else:
name = "jukebox-labelgen.exe"
setup(
name="IP Pigeon",
version="0.2.4",
description="IP Pigeon client application",
options={"build_exe": build_exe_options},
executables=[Executable("label_generator.py", base=base, uac_admin=False, target_name=name)],
)

1
source.fish Normal file
View File

@ -0,0 +1 @@
source venv/bin/activate.fish

1
source.sh Normal file
View File

@ -0,0 +1 @@
source venv/bin/activate

2
tempCodeRunnerFile.py Normal file
View File

@ -0,0 +1,2 @@
drop_off_tray(robot, 0)

BIN
test.pdf

Binary file not shown.

148
test.py Normal file
View File

@ -0,0 +1,148 @@
from pyModbusTCP.client import ModbusClient
def get_sensors():
mbconn = ModbusClient(host="192.168.1.20", port=502, auto_open=True, auto_close=True)
"""
port 1: 256
port 2: 272
port 3: 288
port 4: 304
port 5: 320
port 6: 336
port 7: 352
port 8: 368
"""
out = list()
for reg in [352, 288, 304, 368]:
val = mbconn.read_holding_registers(reg)[0] # read only one register
print(val)
if val == 1:
out.append(True)
else:
out.append(False)
return out
def get_open_spot(sensordata):
for x in range(len(sensordata)):
sens = sensordata[x]
if not sens:
return x
# if we get here, every spot is full
return False
testmb = get_sensors()
print(testmb)
print("Spot open", get_open_spot(testmb))
exit()
class Ring:
def __init__(self) -> None:
self.leds = [0] * 24
self.id = 0
self.dirty = False
def __iter__(self) -> iter:
yield from self.leds
def __repr__(self) -> str:
return f"Ring<id={self.id}, led_state={' '.join(list(map(lambda x: str(x+1), self.leds)))}, dirty={self.dirty}>"
def __add__(self, other):
self.leds.extend(other)
return self
def __bool__(self):
return self.dirty
def __getitem__(self, index):
return self.leds[index]
def __setitem__(self, index, value):
ivalue = self.leds[index]
if ivalue != value:
self.dirty = True
self.leds[index] = value
def __getattr__(self, name):
import word2num
name = int(word2num.word2num(name))
print(name)
if 0 <= name < len(self.leds):
return self.leds[name]
a = Ring()
print(a)
b = Ring()
b.leds[2] = 3
print(a + b)
b.active = True
if b:
print("Bexist")
c = [a, b, b, a, a]
d = list(filter(lambda x: bool(x), c))
print(d)
for i, ring in enumerate(c):
ring[0] = i
print(ring)
print(a, b)
print(f"\u001b[32m{a}")
print(f"\u001b[37ma")
print(getattr(a, "twenty two"))
# eval(f"getattr(a,\"{input()}\")")
# a = r"wow this string is cursed; for example \n"
# SEARCHDATA=r"""{ "q": "{QUERY}", "sortCriteria": "relevancy", "numberOfResults": "250", "sortCriteria": "@catalogitemwebdisplaypriority ascending", "searchHub": "products-only-search", "pipeline": "Site Search", "maximumAge": "900000", "tab": "products-search", "locale": "en", "aq": "(NOT @z95xtemplate==(ADB6CA4F03EF4F47B9AC9CE2BA53FF97,FE5DD82648C6436DB87A7C4210C7413B)) ((@syssource==\"website_001002_catalog_index-rg-nc-prod-sitecore-prod\" @catalogitemprimarycategorypublished==true)) ((@catalogitemregionavailable=Global) (@z95xlanguage==en))", "cq": "((@z95xlanguage==en) (@z95xlatestversion==1) (@source==\"Coveo_web_index - rg-nc-prod-sitecore-prod\")) OR (@source==(\"website_001002_catalog_index-rg-nc-prod-sitecore-prod\",\"website_001002_Category_index-rg-nc-prod-sitecore-prod\"))", "firstResult": "0" }, "categoryFacets": "[{\"field\":\"@catalogitemcategories\",\"path\":[],\"injectionDepth\":1000,\"maximumNumberOfValues\":6,\"delimitingCharacter\":\"|\"}]", "facetOptions": "{}", "groupBy": " [{\"field\":\"@contenttype\",\"maximumNumberOfValues\":6,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[\"Products\"],\"queryOverride\":\"{QUERY}\",\"advancedQueryOverride\":\"(NOT @z95xtemplate==(ADB6CA4F03EF4F47B9AC9CE2BA53FF97,FE5DD82648C6436DB87A7C4210C7413B)) ((((((((@z95xpath=3324AF2D58F64C0FB725521052F679D2 @z95xid<>3324AF2D58F64C0FB725521052F679D2) ((@z95xpath=C292F3A37B3A4E6BAB345DF87ADDE516 @z95xid<>C292F3A37B3A4E6BAB345DF87ADDE516) @z95xtemplate==E4EFEB787BDC4B1A908EFC64D56CB2A4)) OR ((@z95xpath=723501A864754FEEB8AE377E4C710271 @z95xid<>723501A864754FEEB8AE377E4C710271) ((@z95xpath=600114EAB0E5407A84AAA9F0985B6575 @z95xid<>600114EAB0E5407A84AAA9F0985B6575) @z95xtemplate==2BE4FD6B3B2C49EBBD9E1F6C92238B05))) OR (@syssource==\\"website_001002_catalog_index-rg-nc-prod-sitecore-prod\\" @catalogitemprimarycategorypublished==true)) OR ((@z95xpath=3324AF2D58F64C0FB725521052F679D2 @z95xid<>3324AF2D58F64C0FB725521052F679D2) @z95xpath<>C292F3A37B3A4E6BAB345DF87ADDE516)) OR @syssource==\\"website_001002_Category_index-rg-nc-prod-sitecore-prod\\") NOT @z95xtemplate==(ADB6CA4F03EF4F47B9AC9CE2BA53FF97,FE5DD82648C6436DB87A7C4210C7413B))) ((@catalogitemregionavailable=Global) (@z95xlanguage==en) OR (@contenttype=(Blogs,Resources,Other)) (NOT @ez120xcludefromcoveo==1))\",\"constantQueryOverride\":\"((@z95xlanguage==en) (@z95xlatestversion==1) (@source==\\"Coveo_web_index - rg-nc-prod-sitecore-prod\\")) OR (@source==(\\"website_001002_catalog_index-rg-nc-prod-sitecore-prod\\",\\"website_001002_Category_index-rg-nc-prod-sitecore-prod\\"))\"},{\"field\":\"@catalogitembrand\",\"maximumNumberOfValues\":6,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@catalogitemenvironment\",\"maximumNumberOfValues\":6,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@catalogitemregionalavailability\",\"maximumNumberOfValues\":6,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@prez45xtez120xt\",\"maximumNumberOfValues\":5,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@tags\",\"maximumNumberOfValues\":4,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@facetassettype\",\"maximumNumberOfValues\":3,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@facetbrand\",\"maximumNumberOfValues\":3,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@facetmarket\",\"maximumNumberOfValues\":6,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@facetsolution\",\"maximumNumberOfValues\":6,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]},{\"field\":\"@facetsearchcontentpagetype\",\"maximumNumberOfValues\":6,\"sortCriteria\":\"occurrences\",\"injectionDepth\":1000,\"completeFacetWithStandardValues\":true,\"allowedValues\":[]}]" }"""
# QUERY = "AAAAAAAAAAAA"
# b = SEARCHDATA.replace(r"{QUERY}", QUERY)
q = [i * 2 for i in range(10)]
d = {a : b for a,b in enumerate(q)}
print(q)
print(d)
def stalin_sort(a):
b = sum(a)
b /= len(a)
return [b for _ in range(len(a))]
def mao_sort(a):
i = 0
while i < len(a) - 1:
if a[i+1] < a[i]:
del a[i]
else:
i += 1
return a
print(stalin_sort(list(range(10))))
print(mao_sort([1, 3, 2, 4, 5, 8, 7, 6, 9]))
# i l

BIN
test2.pdf

Binary file not shown.

View File

@ -1,52 +1,113 @@
import urx
import math3d as m3d
from scipy.optimize import fsolve
import math
import numpy as np
import time
import os
import logging
from urx.robotiq_two_finger_gripper import Robotiq_Two_Finger_Gripper
#import logging
import yaml
import sys
from util import fprint
from pyModbusTCP.client import ModbusClient
rob = None
import subprocess
from util import win32
def init(ip):
global rob
class Rob():
robot = None
#offset_x, offset_y, offset_z = (0, 0, 0.14) # Tool offset
#
def __init__(self, config):
self.config = config
armc = config["arm"]
self.ip = armc["ip"]
tool = armc["tool"]
limbs = armc["limbs"]
self.offset_x, self.offset_y, self.offset_z = (tool["offset_x"], tool["offset_y"], tool["offset_z"])
self.limb_base = limbs["limb_base"]
self.limb1 = limbs["limb1"]
self.limb2 = limbs["limb2"]
self.limb3 = limbs["limb3"]
self.limb_wrist = limbs["limb_wrist"]
#self.init_arm()
def ping(host):
#Returns True if host (str) responds to a ping request.
# Option for the number of packets as a function of
if win32:
param1 = '-n'
param2 = '-w'
param3 = '250'
else:
param1 = '-c'
param2 = '-W'
param3 = '0.25'
# Building the command. Ex: "ping -c 1 google.com"
command = ['ping', param1, '1', param2, param3, host]
return subprocess.call(command, stdout=subprocess.DEVNULL, stderr=subprocess.STDOUT) == 0
def powerup_arm(robot):
#sys.stdout = Logger()
fprint("Starting UR5 power up...")
# power up robot here via PCB
# power up robot here
#
# wait for power up (this function runs async)
while not ping(robot.ip):
time.sleep(0.5)
# trigger auto-initialize
fprint("Arm online. Waiting for calibration.")
# wait for auto-initialize
# init urx
def connect(robot):
if robot.robot is None:
newrobot = Rob(robot.config)
robot = newrobot
ip = robot.ip
fprint("Connecting to arm at " + ip)
trying = True
while trying:
try:
rob = urx.Robot(ip)
robot.robot = urx.Robot(ip)
trying = False
except:
time.sleep(1)
robotiqgrip = Robotiq_Two_Finger_Gripper(rob)
# Sets robot arm endpoint offset (x,y,z,rx,ry,rz)
rob.set_tcp((0, 0, 0.15, 0, 0, 0))
robot.robot.set_tcp((robot.offset_x, robot.offset_y, robot.offset_z, 0, 0, 0))
# Set weight
rob.set_payload(2, (0, 0, 0.1))
robot.robot.set_payload(2, (0, 0, 0.1))
return robot
def init_arm(robot):
robot = connect(robot)
# init urx
#rob.set_payload(2, (0, 0, 0.1))
time.sleep(0.2)
fprint("UR5 ready.")
#return robot.robot
def set_pos_abs(x, y, z, xb, yb, zb):
global rob
# setup - in case of fail. open gripper, move up, then go home.
rob = robot.robot
open_gripper()
curr_pos = rob.getl()
new_pos = curr_pos
new_pos[2] += 0.025
rob.movel(new_pos, vel=0.05, acc=1)
move_to_home(robot, speed=0.5)
return True
def set_pos_abs(robot, x, y, z, xb, yb, zb, threshold=None):
rob = robot.robot
new_orientation = m3d.Transform()
new_orientation.orient.rotate_xb(xb) # Replace rx with the desired rotation around X-axis
new_orientation.orient.rotate_yb(yb) # Replace ry with the desired rotation around Y-axis
@ -60,10 +121,10 @@ def set_pos_abs(x, y, z, xb, yb, zb):
new_trans.pos.y = y
new_trans.pos.z = z
#rob.speedj(0.2, 0.5, 99999)
rob.set_pose(new_trans, acc=2, vel=2, command="movej") # apply the new pose
rob.set_pose(new_trans, acc=2, vel=2, command="movej", threshold=threshold) # apply the new pose
def set_pos_rel_rot_abs(x, y, z, xb, yb, zb):
global rob
def set_pos_rel_rot_abs(robot, x, y, z, xb, yb, zb):
rob = robot.robot
new_orientation = m3d.Transform()
new_orientation.orient.rotate_xb(xb) # Replace rx with the desired rotation around X-axis
new_orientation.orient.rotate_yb(yb) # Replace ry with the desired rotation around Y-axis
@ -80,21 +141,591 @@ def set_pos_rel_rot_abs(x, y, z, xb, yb, zb):
#rob.speedj(0.2, 0.5, 99999)
rob.set_pose(new_trans, acc=0.1, vel=0.4, command="movej") # apply the new pose
def set_pos_abs_rot_rel(robot, x, y, z, xb, yb, zb):
rob = robot.robot
new_orientation = m3d.Transform()
new_orientation.orient.rotate_xb(xb) # Replace rx with the desired rotation around X-axis
new_orientation.orient.rotate_yb(yb) # Replace ry with the desired rotation around Y-axis
new_orientation.orient.rotate_zb(zb) # Replace rz with the desired rotation around Z-axis
# Get the current pose
trans = rob.getl()
# Apply the new orientation while keeping the current position
new_trans = m3d.Transform(new_orientation.orient, m3d.Vector(trans[0:3]))
new_trans.pos.x = x
new_trans.pos.y = y
new_trans.pos.z = z
#rob.speedj(0.2, 0.5, 99999)
rob.set_pose(new_trans, acc=0.1, vel=0.4, command="movej") # apply the new pose
def is_safe_move(start_pose, end_pose, r=0.25):
start_x, start_y = (start_pose[0], start_pose[1])
end_x, end_y = (end_pose[0], end_pose[1])
try:
m = (end_y-start_y)/(end_x-start_x)
b = start_y - m*start_x
# print('m = y/x =', m)
# print('b =', b)
except:
m = (end_x-start_x)/(end_y-start_y)
b = start_x - m*start_y
# print('m = x/y =', m)
# print('b =', b)
return r**2 - b**2 + m**2 * r**2 < 0
def cartesian_to_polar(x, y):
r = np.sqrt(x**2 + y**2)
theta = np.arctan2(y, x)
return r, theta
def polar_to_cartesian(r, theta):
x = r * np.cos(theta)
y = r * np.sin(theta)
return x, y
def move_to_polar(robot, start_pos, end_pos):
rob = robot.robot
# Convert to polar coordinates
start_r, start_theta = cartesian_to_polar(start_pos[0], start_pos[1])
end_r, end_theta = cartesian_to_polar(end_pos[0], end_pos[1])
# Interpolate for xy (spiral arc)
n_points = 30
r_intermediate = np.linspace(start_r, end_r, n_points)
theta_intermediate = np.linspace(start_theta, end_theta, n_points)
# Interpolate for z (height)
start_z = start_pos[2]
end_z = end_pos[2]
z_intermediate = np.linspace(start_z, end_z, n_points)
# Interpolate for rz (keep tool rotation fixed relative to robot)
curr_rot = rob.getl()
theta_delta = theta_intermediate[1]-theta_intermediate[0]
rx_intermediate = [curr_rot[5] + theta_delta*i for i in range(n_points)]
# curr_rot = rob.getj()
# start_rz = curr_rot[5]
# rot = end_theta - start_theta
# end_base_joint = curr_rot[0]-start_theta + rot
# end_rz = curr_rot[0] + rot
# # rob.movel([*polar_to_cartesian(end_r, end_theta), *rob.getl()[2:]], acc=2, vel=2)
# print('start_theta = ', math.degrees(start_theta))
# print('end_theta = ', math.degrees(curr_rot[0]-start_theta+rot))
# print('start_rz =', math.degrees(start_rz))
# print('rot =', math.degrees(rot))
# print('end_rz =', math.degrees(end_rz))
# rz_intermediate = np.linspace(start_rz, end_rz, n_points)
# Convert back to cartesian coordinates
curr_pos = rob.getl()
intermediate_points = [[*polar_to_cartesian(r, theta), z, *curr_pos[3:]]
for r, theta, z, rx in zip(r_intermediate,
theta_intermediate,
z_intermediate,
rx_intermediate)]
# Move robot
rob.movels(intermediate_points, acc=2, vel=2, radius=0.1)
return rx_intermediate
def move_to_home(robot, keep_flip=False, speed=2):
rob = robot.robot
if is_flipped(robot) and not keep_flip:
flip(robot)
# Move robot to home position
rob.movej(offset_gripper_angle(robot, *(-0.18, -0.108, 0.35), flip=is_flipped(robot)), vel=2, acc=2) # Move to safe position
return True
def move_to_packup(robot, speed=0.25):
rob = robot.robot
# known good starting point to reach store position
goto_holder_index(robot, 12, 0.3, flip=False, use_closest_path=False)
# Home position in degrees
store_pos = [-1.5708,
-1.3,
2.362,
0.7056,
-1.425,
1.5708]
# Move robot
rob.movej(store_pos, acc=0.1, vel=speed)
return True
def normalize_degree(theta):
# Normalizes degree theta from -1.5pi to 1.5pi
multiplier = 1
normalized_theta = theta % (math.pi * multiplier)
# Maintain the negative sign if the original angle is negative
if theta < 0:
normalized_theta -= math.pi * multiplier
# Return angle
return normalized_theta
def get_joints_from_xyz_rel(robot, x, y, z, rx=0, ry=-math.pi/2, rz=0, initial_guess = (math.pi/2, math.pi/2, 0), l3offset=0):
# Get limbs and offsets
#l3=0.15
l_bs, l1, l2, l3, l_wt = (robot.limb_base, robot.limb1, robot.limb2, robot.limb3, robot.limb_wrist) # Limb lengths
l3 += l3offset # add wrist offset, used for gripper angle calculations
offset_x = robot.offset_x
offset_y = robot.offset_y
offset_z = robot.offset_z
# Calculate base angle and r relative to shoulder joint
def calculate_theta(x, y, a):
# Calculate if we need the + or - in our equations
if (x>-a and y>=0) or (x>a and y<0):
flip = 1
elif (x<-a and y>=0) or (x<a and y<0):
flip = -1
else:
# Critical section (x=a, or x=-a). Infinite slope
# Return 0 or 180 depending on sign
return math.atan2(y, 0)
# Calculate tangent line y = mx + b
m = (x*y - math.sqrt(x*x*y*y-(x*x-a*a)*(y*y-a*a)))/(x*x-a*a)
b = flip * a * math.sqrt(1+m*m)
# Calculate equivalent tangent point on circle
cx = (-flip*m*b)/(1+m*m)
cy = m*cx + flip*b
# Calculate base angle, make angle negative if flip=1
theta = math.atan2(cy, cx) + (-math.pi if flip==1 else 0)
return theta
base_theta = calculate_theta(x, y, l_bs)
cx, cy = l_bs*math.cos(base_theta), l_bs*math.sin(base_theta)
r = math.sqrt((x+offset_x+cx)**2 + (y+offset_y+cy)**2)
# Formulas to find out joint positions for (r, z)
def inv_kin_r_z(p):
a, b, c = p
return (l1*math.cos(a) + l2*math.cos(a-b) + l3*math.cos(a-b-c) - r, # r
l1*math.sin(a) + l2*math.sin(a-b) - l3*math.sin(a-b-c) - (l3*math.sin(a-b-c)) - (z + offset_z), # z
a-b-c) # wrist angle
# Normalize angles
base, shoulder, elbow, wrist1 = [normalize_degree(deg) for deg in [base_theta, *fsolve(inv_kin_r_z, initial_guess)]]
wrist1 += rx
# Return result
return base, shoulder, elbow, wrist1, ry, rz
def get_joints_from_xyz_abs(robot, x, y, z, rx=0, ry=-math.pi/2, rz=math.pi/2, l3offset=0, use_closest_path=True):
rob = robot.robot
joints = get_joints_from_xyz_rel(robot, x, y, z, rx, ry, rz, l3offset=l3offset)
# Return current positions if coordinates don't make sense
if z<0:
return rob.getj()
# Joint offsets
# Base, Shoulder, Elbow, Wrist
inverse = [1, -1, 1, 1, 1, 1]
offsets = [-math.pi/2, 0, 0, -math.pi/2, 0, 0]
if math.degrees(joints[1]) > 137:
print("CRASH! Shoulder at", joints[1] * 180/math.pi)
#else:
#print("Shoulder at", joints[1] * 180/math.pi)
# Get adjusted joint positions
adjusted_joints = [o+j*i for j, o, i in zip(joints, offsets, inverse)]
curr_joints = rob.getj()
def get_complimentary_angle(joint_angle):
if joint_angle<0:
new_angle = joint_angle + 2*math.pi
else:
new_angle = joint_angle - 2*math.pi
if abs(new_angle) > math.radians(350):
return joint_angle
else:
return new_angle
# Use closest path (potentially going beyond 180 degrees)
if use_closest_path:
if abs(get_complimentary_angle(adjusted_joints[0])-curr_joints[0]) < abs(adjusted_joints[0]-curr_joints[0]):
adjusted_joints[0] = get_complimentary_angle(adjusted_joints[0])
# final_joint_positions = []
# for curr_joint, adjusted_joint in zip(curr_joints, adjusted_joints):
# if abs(curr_joint - adjusted_joint) < abs(curr_joint - get_complimentary_angle(adjusted_joint)):
# final_joint_positions.append(adjusted_joint)
# else:
# final_joint_positions.append(get_complimentary_angle(adjusted_joint))
# return final_joint_positions
return adjusted_joints
def move_arc(robot, x, y, z, rx=0, ry=-math.pi/2, rz=math.pi/2):
rob = robot.robot
start_joints = rob.getj()
end_joint = get_joints_from_xyz_abs(robot, x, y, z, rx, ry, rz)
n_points = 50
intermediate_joints = []
for i in range(0, 6):
intermediate_joints.append(np.linspace(start_joints[i], end_joint[i], n_points))
joints = [joint_position for joint_position in zip(*intermediate_joints)]
rob.movejs(joints, acc=2, vel=2, radius=0.1)
def offset_gripper_angle(robot, x, y, z, gripperangle=30, gripperlength=0.20+0.018, flip=False, use_closest_path=True, rzoffset=0):
# gripper angle: from vertical
# gripper length: from joint to start of grip
# to flip, you can use flip=True or make gripper angle negative
limb3 = robot.limb3
# Determine tool rotation depending on gripper angle
if gripperangle < 0:
rz = - math.pi / 2
else:
rz = math.pi / 2
if flip:
gripperangle = -math.radians(gripperangle)
grippery = gripperlength - math.cos(gripperangle) * gripperlength
grippery += math.sin(gripperangle) * limb3
gripperx = math.sin(gripperangle) * gripperlength + limb3 * 2
gripperx -= (1-math.cos(gripperangle)) * limb3
rz = math.pi / 2
# flip the whole wrist
return get_joints_from_xyz_abs(robot, x, y, z-grippery, rx=gripperangle + math.radians(180), l3offset=-gripperx, ry=-3*math.pi/2, rz=rz + rzoffset, use_closest_path=use_closest_path)
else:
gripperangle = math.radians(gripperangle)
grippery = gripperlength - math.cos(gripperangle) * gripperlength
grippery -= math.sin(gripperangle) * limb3
gripperx = math.sin(gripperangle) * gripperlength
gripperx += (1-math.cos(gripperangle)) * limb3
return get_joints_from_xyz_abs(robot, x, y, z-grippery, rx=gripperangle, l3offset=-gripperx, rz=rz, use_closest_path=use_closest_path)
def goto_holder_index(robot, idx, z=0.05, gripperangle=30, flip=False, use_closest_path=True, verbose=False):
joint = robot.config["position_map"][idx]
if verbose:
print("Going to cable holder index", joint["index"], "at position", joint["pos"])
safe_move(robot, joint["pos"][0]/1000, joint["pos"][1]/1000, z, use_closest_path=use_closest_path)
#angles = offset_gripper_angle(joint["pos"][1]/1000, joint["pos"][0]/1000, z, gripperangle=gripperangle, flip=flip)
#rob.movej(angles, acc=2, vel=2)
#return angles
#angles = get_joints_from_xyz_abs(joint["pos"][1]/1000, joint["pos"][0]/1000, 0.05, )
return True
def is_flipped(robot):
rob = robot.robot
wrist1 = rob.getj()[3]
if wrist1 > 0:
return True
else:
return False
def flip(robot):
rob = robot.robot
# A list of safe positions to flip
safe_positions = [(-0.18, -0.108, 0.35),
(0.18, -0.108, 0.35)]
# Find the closest safe position
curr_pos = rob.getl()[:3]
def dist_from_robot(pos):
x, y, z = pos
rx, ry, rz = curr_pos
return math.sqrt((rx-x)**2+(ry-y)**2+(rz-z)**2)
pos_dist_pairs = zip(safe_positions, [dist_from_robot(pos) for pos in safe_positions])
safe_pos = min(pos_dist_pairs, key=lambda x:x[1])[0]
# Flip at safe position
rob.movej(offset_gripper_angle(robot, *safe_pos, flip=is_flipped(robot)), vel=2, acc=2) # Move to safe position
rob.movej(offset_gripper_angle(robot, *safe_pos, flip=(not is_flipped(robot))), vel=2, acc=2) # Flip gripper
# print('flip?: ', is_flipped(robot))
return True
def safe_move(robot, x, y, z, use_closest_path=True):
rob = robot.robot
flip_radius = 0.22 # Min radius on which to flip
r = math.sqrt(x**2 + y**2) # Get position radius
# Flip gripper if needed
if (r <= flip_radius and is_flipped(robot)) or (r > flip_radius and not is_flipped(robot)):
flip(robot)
rob.movej(offset_gripper_angle(robot, x, y, z, flip=is_flipped(robot), use_closest_path=use_closest_path), vel=4, acc=3)
return True
def holder_routine(robot, holder_index, pick_up, verbose=False):
robot = connect(robot)
rob = robot.robot
# Don't attempt to place a tube in the camera slot
if holder_index == 49:
return
if verbose:
fprint('Pickup routine for index' + str(holder_index))
# Go to the correct holder
if pick_up:
goto_holder_index(robot, holder_index, 0.05, use_closest_path=False)
else:
goto_holder_index(robot, holder_index, 0.2, use_closest_path=False)
if pick_up:
open_gripper()
# Move down
curr_pos = rob.getl()
new_pos = curr_pos
new_pos[2] = 0.005
rob.movel(new_pos, vel=0.1, acc=1)
# Pick up or drop off
if pick_up:
close_gripper()
else:
open_gripper()
# Move up
new_pos[2] = 0.2
rob.movel(new_pos, vel=2, acc=1)
was_flipped = is_flipped(robot)
# goto_holder_index(robot, 25, z=0.2)
def pick_up_holder(robot, holder_index, verbose=False):
holder_routine(robot, holder_index, True, verbose=verbose)
def drop_off_holder(robot, holder_index, verbose=False):
holder_routine(robot, holder_index, False, verbose=verbose)
def tray_routine(robot, slot=0, pick_up=True):
robot = connect(robot)
rob = robot.robot
# Default to 0 if invalid value
if slot not in [0, 1, 2, 3]:
slot = 0
slot_prepositions = [(-9.93, -112.67, 144.02, -116.69, -54.13, -10.29),
(-12.35, -124.95, 148.61, -107.27, -54.36, -13.26),
(-16.45, -96.97, 137.85, 58.39, -305.08, 161.75),
(-16.66, -97.28, 138.16, 58.54, -305.05, 161.50)]
# Initial position depending on slot and robot orientation
if slot in [0, 1]:
if is_flipped(robot):
flip(robot)
else:
move_to_home(robot, keep_flip=True)
else:
goto_holder_index(robot, 25, z=0.3)
# Align robot to the slot
if slot in [2,3]:
angles = [(-2.77, -99.64, 131.02, 67.67, 70.04-360, 153.03),
slot_prepositions[slot]]
else:
angles = [(-58, -114.45, 100.52, -45.24, -96.95, 120),
(-39.98, -124.92, 132.28, -61.56, -55.60, -50.77),
slot_prepositions[slot]]
angles = [[x*math.pi/180 for x in move] for move in angles]
rob.movejs(angles,vel=2,acc=1)
# Positions for each slot
slot_distance = .052
slot_height = -.015-.0095
first_slot = -0.3084+0.02
slot_position = [
[first_slot, -0.3426, slot_height, 1.5899, 1.5526, -0.9411],
[first_slot+slot_distance, -0.3426, slot_height, 1.5899, 1.5526, -0.9411],
[first_slot+2*slot_distance, -0.3426, slot_height, 1.5899, 1.5526, -0.9411],
[first_slot+3*slot_distance, -0.3426, slot_height, 1.5899, 1.5526, -0.9411],
]
rob.movel(slot_position[slot],vel=0.2, acc=1)
# Place/Grab the tube
if pick_up:
close_gripper()
else:
open_gripper()
# Move back
tilt = 0.3
curr_pos = rob.getl()
new_pos = curr_pos
if slot==3:
new_pos[0] -= 0.05 #x
new_pos[1] += 0.15 #y
new_pos[2] = 0.09 #z
new_pos[3] += tilt
new_pos[4] += tilt
new_pos[5] += tilt
rob.movel(new_pos, vel=0.2, acc=1)
# Go home to safe position
move_to_home(robot, speed=1, keep_flip=True)
def pick_up_tray(robot, slot=0):
tray_routine(robot, slot, True)
def drop_off_tray(robot, slot=0):
tray_routine(robot, slot, False)
def return_routine(robot, slot, holder_index=None, verbose=False):
robot = connect(robot)
rob = robot.robot
open_gripper()
was_flipped = is_flipped(robot)
if slot is None:
rob.movej(offset_gripper_angle(robot, -0.15, -0.15, 0.3, flip=was_flipped, use_closest_path=False), vel=4, acc=3)
rob.movej(get_joints_from_xyz_abs(robot, -0.35, -0.15, 0.0, math.pi/2, 0.1), vel=4, acc=3)
close_gripper()
else:
xoffset = 0.051 * slot
rob.movej(offset_gripper_angle(robot, -0.15, -0.15, 0.3, flip=was_flipped, use_closest_path=False), vel=4, acc=3)
rob.movej(get_joints_from_xyz_abs(robot, -0.35+xoffset, -0.15, 0.0, math.pi/2, 0.1), vel=4, acc=3)
close_gripper()
if holder_index is not None:
goto_holder_index(robot, holder_index, 0.2, use_closest_path=False)
curr_pos = rob.getl()
new_pos = curr_pos
new_pos[2] = 0.015
rob.movel(new_pos, vel=0.1, acc=1)
open_gripper()
new_pos[2] = 0.1
rob.movel(new_pos, vel=2, acc=1)
return True
else:
# go to camera
rob.movej(offset_gripper_angle(robot, 0.35, -0.35, 0.3, flip=was_flipped, use_closest_path=False), vel=2, acc=2)
return True
def goto_camera(robot):
robot = connect(robot)
goto_holder_index(robot, 49, 0.2)
def tray_to_camera(robot, slot):
pick_up_tray(robot, slot)
goto_camera(robot)
def holder_to_tray(robot, holder_index, slot):
pick_up_holder(robot, holder_index)
drop_off_tray(robot, slot)
def holder_to_camera(robot, holder_index, verbose=False):
robot = connect(robot)
fprint("Bringing tube at " + str(holder_index) + " to camera")
rob = robot.robot
pick_up_holder(robot, holder_index)
goto_camera(robot)
def camera_to_holder(robot, holder_index, verbose=False):
robot = connect(robot)
rob = robot.robot
drop_off_holder(robot, holder_index)
def open_gripper():
fprint("Opening gripper")
c = ModbusClient(host="192.168.1.21", port=502, auto_open=True, auto_close=False)
c.write_single_register(112, 0b0)
c.write_single_register(435, 0b10000000)
c.write_single_register(112, 0b0)
c.write_single_register(435, 0b10000000)
time.sleep(0.5)
c.close()
#c.close()
def close_gripper():
fprint("Closing gripper")
c = ModbusClient(host="192.168.1.21", port=502, auto_open=True, auto_close=False)
c.write_single_register(435, 0b00000000)
c.write_single_register(112, 0b1)
c.write_single_register(435, 0b00000000)
c.write_single_register(112, 0b1)
time.sleep(0.5)
c.close()
#
if __name__ == "__main__":
#rob.movej((0, 0, 0, 0, 0, 0), 0.1, 0.2)
#rob.movel((x, y, z, rx, ry, rz), a, v)
init("192.168.1.145")
fprint("Current tool pose is: ", rob.getl())
#set_pos_rel_rot_abs(0, 0, -0.2, math.pi, 0, -math.pi)
set_pos_abs(0.3, -0.2, 0.5, math.pi, 0, -math.pi)
set_pos_abs(0, 0.2, 0.6, math.pi, 0, -math.pi)
set_pos_abs(-0.5, -0.2, 0.4, math.pi, 0, -math.pi)
#set_pos_rel_rot_abs(0, 0, 0, math.pi, 0, -math.pi)
fprint("Current tool pose is: ", rob.getl())
#init("192.168.1.145")
with open('config.yml', 'r') as fileread:
#global config
config = yaml.safe_load(fileread)
robot = Rob(config) # robot of type Rob is the custom class above
#powerup_arm(robot)
robot = connect(robot)
init_arm(robot)
rob = robot.robot # rob is robot.robot is the urx robot class, what we've been using previously
#move_to_packup(robot)
# for i in range(3):
# pick_up_holder(robot, i)
# print('Drop off', i+1)
# drop_off_holder(robot, i+1)
holder_to_camera(robot, 0)
camera_to_holder(robot, 0)
print("Current tool pose is: ", rob.getl())
curr_pos = rob.getl()
config = None
rob.stop()
os.kill(os.getpid(), 9) # dirty kill of self
sys.exit(0)

View File

@ -70,7 +70,7 @@ def fprint(msg, settings = None, sendqueue = None):
except Exception as e:
try:
print('[????:' + frm.function + ']:', str(msg))
print('[util:fprint]: ' + str(e))
#print('[util:fprint]: ' + str(e))
except:
print('[????]:', str(msg))
@ -123,7 +123,7 @@ class Logger(object):
self.terminal = sys.stdout
def write(self, message):
self.log.write(message)
#self.log.write(message)
#close(filename)
#self.log = open(filename, "a")
try:

View File

@ -1,6 +1,7 @@
#!/bin/sh
# change this to #!/bin/bash for windows
python -m venv ./venv
python3 -m venv ./venv
source ./venv/bin/activate
pip install --upgrade pip

View File

@ -1,15 +1,61 @@
<!DOCTYPE html>
<html>
<head>
<title>WebSocket Test</title>
<style>
footer {
background-color: #333;
color: #fff;
text-align: center;
padding: 10px 0;
position: fixed;
bottom: 0;
width: 100%;
display: flex;
justify-content: space-around;
}
.service-box {
width: 150px;
padding: 10px;
border-radius: 5px;
}
.service-up {
background-color: green;
}
.service-down {
background-color: red;
}
</style>
<script>
document.addEventListener("DOMContentLoaded", function() {
// class Service {
// constructor(name, status) {
// this.name = name
// this.status = status
// }
// }
var updatedTime = new Date();
// Initial status of services
// var serviceA = new Service("234234", 'down');
// var serviceBStatus = 'down';
// var serviceCStatus = 'down';
document.addEventListener("DOMContentLoaded", function () {
// Create WebSocket connection.
const socket = new WebSocket('ws://localhost:9000');
// Connection opened
socket.addEventListener('open', function (event) {
console.log("Connected to WebSocket server");
updatedTime = new Date();
});
// Listen for messages
@ -19,6 +65,7 @@
let message = document.createElement('li');
message.textContent = "Received: " + event.data;
messages.appendChild(message);
updatedTime = new Date();
});
// Send a message to the server
@ -28,15 +75,82 @@
console.log('Message sent', message);
}
// This function just sends a ping to make sure the server is there and it is able to responds
function ping() {
let message = `{ "call": "send", "type": "log", "data": "This is a ping!!" }`;
socket.send(message);
console.log('Message sent', message);
}
//setInterval(ping, 1500);
// setInterval(() => {
// updateServiceStatus('serviceA', 'down');
// }, 2000);
// Bind send message function to button click
document.getElementById('sendMessage').addEventListener('click', sendMessage);
});
</script>
</head>
<body>
<h2>WebSocket Test</h2>
<input type="text" id="messageInput" placeholder="Type a message...">
<textarea rows="4" cols="50" id="messageInput" placeholder="Type a message..."> </textarea>
<button id="sendMessage">Send Message</button>
<p>Example JSON</p>
<p>{ "type": "cable_map", "call": "request", "data": { } }</p>
<p>{ "type": "log", "call": "send", "data": "123123" }</p>
<p>Messages/Logs</p>
<ul id="messages"></ul>
<footer>
<!-- <div id="serviceA" class="service-box"></div>
<div id="serviceB" class="service-box"></div>
<div id="serviceC" class="service-box"></div> -->
<div id="clock"></div>
</footer>
<script>
// // Function to update service status
// function updateServiceStatus(service) {
// // serviceId, status
// var serviceElement = document.getElementById(service.serviceId);
// // updateClock();
// if (service.status === 'up') {
// serviceElement.innerHTML = '<h3>' + service.serviceId + '</h3><p>Running</p>';
// serviceElement.classList.remove('service-down');
// serviceElement.classList.add('service-up');
// } else {
// serviceElement.innerHTML = '<h3>' + service.serviceId + '</h3><p>Down</p>';
// serviceElement.classList.remove('service-up');
// serviceElement.classList.add('service-down');
// }
// }
// // Update service statuses
// updateServiceStatus('node.js (for this page)', serviceAStatus);
// updateServiceStatus('Python WebSocket', serviceBStatus);
// updateServiceStatus('serviceC', serviceCStatus);
// Function to update clock
function updateClock() {
var now = new Date();
now = now.getTime() - updatedTime.getTime();
// console.log(now)
document.getElementById('clock').textContent = 'Milliseconds Since Update: ' + now.toString().padStart(6, '0');
}
// Update clock every second
setInterval(updateClock, 100);
</script>
</body>
</html>