kopia lustrzana https://github.com/dl9rdz/rdz_ttgo_sonde
Finally, a new master version v0.8 with a lots of changes in the devel version over several months,
including (probably incomplete list) - spectrum from large TFT - bug fixes by cixio - use PWR button as button2 on T-Beam 1.0 - additional display variants - possibility to show kill timer values - battery information display - simple gpx export - internal button pullup; touch calibration mode - flip oled support - circle diagram (on tft) - better support for Heltec v2 board and T-Beam 1.0pull/36/head
rodzic
26dd3b53aa
commit
7e817f303b
|
@ -47,8 +47,7 @@ script:
|
|||
- arduino --board esp32:esp32:t-beam --verify $PWD/RX_FSK/RX_FSK.ino
|
||||
- find build
|
||||
- find /home/travis/.arduino15/packages/esp32/hardware/esp32/
|
||||
- $MKSPIFFS -c $PWD/RX_FSK/data -b 4096 -p 256 -s 1503232 $PWD/spiffs.bin
|
||||
- $PWD/scripts/makeimage.py $ESP32TOOLS $PWD/build/RX_FSK.ino.bin $PWD/spiffs.bin $PWD/out.bin
|
||||
- $PWD/scripts/makeimage.py $ESP32TOOLS $PWD/build/RX_FSK.ino.bin $PWD/RX_FSK/data $PWD/out.bin
|
||||
after_success:
|
||||
- .travis/push.sh
|
||||
notifications:
|
||||
|
|
|
@ -24,13 +24,24 @@ generate_website_index() {
|
|||
if [ -z "$TS" ]; then TS=`date`; fi
|
||||
echo "<li><a href=\"devel/$i\">$i</a> ($TS)</li>\n" >> download.html;
|
||||
done
|
||||
echo "</ul></section></body></html>" >> download.html
|
||||
echo "</ul>
|
||||
<br>
|
||||
<p>Last latter/number of version number indicate SPIFFS file system version. If the first (upper-case)
|
||||
letter has changed, then this version is incompabible with prevision versions and you have to flash
|
||||
the full image. If the second part (number) has changed, then this version has some changes
|
||||
(e.g. internal web page layout, LCD/TFT display layout) in the file system which you will not get with
|
||||
a code-only (OTA or flashing update.bin) update, but it should not break anything.</p>
|
||||
</section></body></html>" >> download.html
|
||||
git add download.html
|
||||
git commit --amend --message "Travis build: $TRAVIS_BUILD_NUMBER"
|
||||
}
|
||||
commit_website_files() {
|
||||
BRANCH=$TRAVIS_BRANCH
|
||||
VERSION=`cat RX_FSK/version.h | tail -1 | egrep -o '".*"' | sed 's/"//g' | sed 's/ /_/g'`
|
||||
VERSION=`cat RX_FSK/version.h | grep version_id | egrep -o '".*"' | sed 's/"//g' | sed 's/ /_/g'`
|
||||
FSMAJOR=`cat RX_FSK/version.h | grep SPIFFS_MAJOR | perl -e '$_=<>;print /=(.*);/?chr($1+64):""'`
|
||||
FSMINOR=`cat RX_FSK/version.h | grep SPIFFS_MINOR | perl -e '$_=<>;print /=(.*);/?$1:""'`
|
||||
VERSION=$VERSION-$FSMAJOR$FSMINOR
|
||||
|
||||
MYPATH=$PWD
|
||||
echo "On branch $BRANCH"
|
||||
echo "Version $VERSION"
|
||||
|
|
|
@ -4,3 +4,8 @@ GPL License Exceptions:
|
|||
https://github.com/pdelmo/lora_shield_arduino.git
|
||||
and licensed under
|
||||
GNU Lesser General Public License, version 2.1 (SPDX short identifier: LGPL-2.1)
|
||||
|
||||
- Leaflet sidebar v2 plugin is (c) 2013 Tobias Bieniek based on
|
||||
https://github.com/Turbo87/sidebar-v2/
|
||||
and licensed under
|
||||
MIT License
|
||||
|
|
Plik diff jest za duży
Load Diff
|
@ -7,8 +7,9 @@
|
|||
# No specification in config file: try autodetection (gpio4 pin level at startup)
|
||||
#button_pin=0
|
||||
#button2_pin=255
|
||||
#button2_axp=0
|
||||
# LED port
|
||||
led_pout=9
|
||||
#led_pout=-1
|
||||
# OLED Setup is depending on hardware of LoRa board
|
||||
# TTGO v1: SDA=4 SCL=15, RST=16
|
||||
# TTGO v2: SDA=21 SCL=22, RST=16
|
||||
|
@ -23,8 +24,13 @@ led_pout=9
|
|||
#oled_rst=16
|
||||
#tft_rs=2
|
||||
#tft_cs=0
|
||||
tft_orient=1
|
||||
#gps_rxd=-1
|
||||
gps_txd=-1
|
||||
# Show AFC value (for RS41 only, maybe also DFM, but useful for RS92 or M10)
|
||||
# showafc=1
|
||||
# Frequency correction, in Hz
|
||||
# freqofs=0
|
||||
#-------------------------------#
|
||||
# General config settings
|
||||
#-------------------------------#
|
||||
|
@ -35,15 +41,19 @@ wifi=3
|
|||
# TCP/IP KISS TNC in port 14590 for APRSdroid (0=disabled, 1=enabled)
|
||||
kisstnc.active = 1
|
||||
|
||||
# display mode: 1=standard 2=fieldmode 3=field w/sondetype
|
||||
display=1
|
||||
# display configuration. List of "displays"
|
||||
# first entry: "Scanner" display
|
||||
# second entry: default "Receiver" display
|
||||
# additional entries: alternative receiver display, activated by button
|
||||
display=0,1,2,3,4
|
||||
# set to -1 to disable (used for "N" values in timers in screens.txt). Value in seconds
|
||||
norx_timeout=20
|
||||
#-------------------------------#
|
||||
# Spectrum display settings
|
||||
#-------------------------------#
|
||||
startfreq=400
|
||||
channelbw=10
|
||||
spectrum=10
|
||||
timer=1
|
||||
spectrum=-1 #10
|
||||
noisefloor=-125
|
||||
marker=1
|
||||
#-------------------------------#
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
|
||||
<div class="tab">
|
||||
<button class="tablinks" onclick="selTab(event,'QRG')" id="defaultTab">QRG</button>
|
||||
<button class="tablinks" onclick="selTab(event,'WLAN')">WLAN</button>
|
||||
<button class="tablinks" onclick="selTab(event,'WiFi')">WiFi</button>
|
||||
<button class="tablinks" onclick="selTab(event,'Data')">Data</button>
|
||||
<button class="tablinks" onclick="selTab(event,'SondeMap')">SondeMap</button>
|
||||
<button class="tablinks" onclick="selTab(event,'Config')">Config</button>
|
||||
|
@ -29,8 +29,8 @@
|
|||
<iframe src="qrg.html" style="border:none;" width="100%%" height="100%%"></iframe>
|
||||
</div>
|
||||
|
||||
<div id="WLAN" class="tabcontent">
|
||||
<h3> WLAN - Settings</h3>
|
||||
<div id="WiFi" class="tabcontent">
|
||||
<h3> WiFi - Settings</h3>
|
||||
<iframe src="wifi.html" style="border:none;" width="100%%" height="100%%"></iframe>
|
||||
</div>
|
||||
|
||||
|
@ -40,7 +40,7 @@
|
|||
</div>
|
||||
|
||||
<div id="SondeMap" class="tabcontent" data-src="https://wx.dl2mf.de/#?">
|
||||
<iframe src="https://wx.dl2mf.de/#?" style="border:none;" width="98%%" height="98%%"></iframe>
|
||||
<iframe src="" style="border:none;" width="98%%" height="98%%"></iframe>
|
||||
</div>
|
||||
|
||||
<div id="Config" class="tabcontent">
|
||||
|
@ -59,6 +59,8 @@
|
|||
Copyright © 2019 by Hansi Reiser, DL9RDZ<br>
|
||||
(version %VERSION_ID%)<br>
|
||||
with mods by <a href="https://www.dl2mf.de/" target="_blank">Meinhard Guenther, DL2MF</a><br>
|
||||
<br>
|
||||
Autodetect info: %AUTODETECT_INFO%<br>
|
||||
<br>
|
||||
This program is free software; you can redistribute it and/or<br>
|
||||
modify it under the terms of the GNU General Public License as<br>
|
||||
|
|
|
@ -12,30 +12,86 @@
|
|||
# - W: activate WiFi scan
|
||||
# - F: activate frequency spectrum display
|
||||
# - 0: activate "Scan:" display (this is basically just display mode 0)
|
||||
# - x: (1..N): activate display mode x
|
||||
# - x: (1..N): activate display mode x [deprecated]
|
||||
# - >: activate next display mode
|
||||
# - D: activate default receiver display (display mode specified in config)
|
||||
# - +: advance to next active sonde from QRG config
|
||||
# - #: no action
|
||||
#
|
||||
# Display content (lower/upper case: small/large font)
|
||||
# line,column=content
|
||||
# for ILI9225 its also possible to indicate
|
||||
# line,column,width=content for text within a box of width 'width'
|
||||
# line,column,-width=content for right-justified text
|
||||
#
|
||||
# XText : Text
|
||||
# F(suffix): frequency (with suffix, e.g., " MHz")
|
||||
# L latitade
|
||||
# O lOngitute
|
||||
# A altitude
|
||||
# H hor. speed
|
||||
# V vert. speef
|
||||
# Hm(suffix) hor. speed m/s (suffix: e.g. "m/s"; no suffix=>m/s as 16x8 bitmap for SSD1306 display only)
|
||||
# Hk(suffix) hor. speed km/h (suffix: e.g. "km/h"; no suffix=>km/h as 16x8 bitmap for SSD1306 display only)
|
||||
# V(suffix) vert. speef (suffix: e.g. "m/s"; no suffix=>m/s as 16x8 bitmap for SSD1306 display only)
|
||||
# Ix sonde ID (dfm format by x: d=>dxlaprs, a=>autorx, s=>real serial number)
|
||||
# Q signal quality statistics bar
|
||||
# T type string (RS41/DFM9/DFM6/RS92)
|
||||
# C afC value
|
||||
# N ip address (only tiny font)
|
||||
# S launch site
|
||||
# Mx telemetry value x (t temp p preassure h hyg)
|
||||
# Gx value relativ to GPS reference point (x: D dist, I direction) GV. GPS valid symbol; GL, GO, GA: ref lat long alt
|
||||
# S scan list entry info: l/empty: launch site name, #=entry nr, t=total entries, a=active entries, /: #/t
|
||||
# K RS41 kill timer values: Kl launch timer, Kb burst timer, Kc kill countdown
|
||||
# format: K_4: h:mm k_6: h:mm:ss k_s: sssss, nothing shown for other sonde
|
||||
# Mx telemetry value x (t temp p preassure h hyg) [not yet implemented, maybe some day in future]
|
||||
# Gx GPS-related data
|
||||
# raw data from GPS: GA, GO, GH, GC: LAtitude, lOngitude, Altutide(Height), Course over ground
|
||||
# relative to sonde: GD, GI, GB: Distance, dIrection (absolute), relative Bearing
|
||||
# G0 GPS circle diagram e.g. 3,5=g0NCS,50,ff0000,000033,5,ffff00,4,ffffff
|
||||
# "N" (what is on top: N=north C=course)
|
||||
# "C" (where does the arrow point to: C=course, S=sonde)
|
||||
# "S" (what is shown by the bullet: C=course, S=sonde)
|
||||
# 50: circle radius, followed by fg and bg color
|
||||
# 5: bullet radius, followed by fg color
|
||||
# 4: arrow width, followed by fg color
|
||||
# R RSSI
|
||||
# B battery(T-Beam 1.0) S=status V=Batt.Volt C=charge current D=discharge current
|
||||
# U=USB volt I=USB current T=IC temp
|
||||
#
|
||||
# fonts=x,y can be used to select font (x=small, y=large) for all items below
|
||||
# for SSD1306, x and y can be used to select one of those fonts:
|
||||
# (y should be a 1x2 font (1,5,6,7), x a small font)
|
||||
# u8x8_font_chroma48medium8_r, // 0 ** default small
|
||||
# u8x8_font_7x14_1x2_f, // 1 ** default large
|
||||
# u8x8_font_amstrad_cpc_extended_f, // 2
|
||||
# u8x8_font_5x7_f, // 3
|
||||
# u8x8_font_5x8_f, // 4
|
||||
# u8x8_font_8x13_1x2_f, // 5
|
||||
# u8x8_font_8x13B_1x2_f, // 6
|
||||
# u8x8_font_7x14B_1x2_f, // 7
|
||||
# u8x8_font_artossans8_r, // 8
|
||||
# u8x8_font_artosserif8_r, // 9
|
||||
# u8x8_font_torussansbold8_r, // 10
|
||||
# u8x8_font_victoriabold8_r, // 11
|
||||
# u8x8_font_victoriamedium8_r, // 12
|
||||
# u8x8_font_pressstart2p_f, // 13
|
||||
# u8x8_font_pcsenior_f, // 14
|
||||
# u8x8_font_pxplusibmcgathin_f, // 15
|
||||
# u8x8_font_pxplusibmcga_f, // 16
|
||||
# u8x8_font_pxplustandynewtv_f, // 17
|
||||
#
|
||||
# for ILI9225, these fonts are available:
|
||||
# Terminal6x8 // 0
|
||||
# Terminal11x16 // 1
|
||||
# Terminal12x16 // 2
|
||||
# FreeMono9pt7b, // 3
|
||||
# FreeMono12pt7b, // 4
|
||||
# FreeSans9pt7b, // 5
|
||||
# FreeSans12pt7b, // 6
|
||||
# Picopixel, // 7
|
||||
#
|
||||
# color=rrggbb,rrggbb can be used to select color (foreground, background)
|
||||
# see https://github.com/Nkawu/TFT_22_ILI9225/wiki#color-reference for example (use without "#"-sign)
|
||||
#
|
||||
# for TFT display, coordinates and width are multiplied by xscale,yscale and later used in pixels
|
||||
# with scale=1,1 you can directly use pixel coordinates. (default: xscale=13,yscale=22 => 8 lines, 16 columns)
|
||||
###########
|
||||
#
|
||||
# Default configuration for "Scanner" display:
|
||||
|
@ -46,20 +102,21 @@
|
|||
# => Button press activates default receiver view, double press does nothing
|
||||
# Mid press activates Spectrum display, long press activates Wifi scan
|
||||
# - key2 has no function
|
||||
@Scanner:5
|
||||
@Scanner
|
||||
timer=-1,0,0
|
||||
key1action=D,#,F,W
|
||||
key2action=#,#,#,#
|
||||
timeaction=#,D,+
|
||||
0,0=XScan:
|
||||
0,8=T
|
||||
0,0=XScan
|
||||
0,5=S#:
|
||||
0,9=T
|
||||
3,0=F MHz
|
||||
5,0=S
|
||||
7,5=n
|
||||
|
||||
############
|
||||
# Default configuration for "Legacy" display:
|
||||
# - view timer=-1, rx timer=-1 (disabled); norx timer=20000 (or -1 for "old" behaviour)
|
||||
# - view timer=-1, rx timer=-1 (disabled); norx timer=20 (or -1 for "old" behaviour)
|
||||
# => norx timer fires after not receiving a singla for 20 seconds
|
||||
# - key1 actions: +,0,F,W
|
||||
# => Button1 press: next sonde; double press => @Scanner display
|
||||
|
@ -69,10 +126,10 @@ timeaction=#,D,+
|
|||
# - timer actions: #,#,0
|
||||
# (norx timer: if no signal for >20 seconds: go back to scanner mode)
|
||||
#
|
||||
@Legacy:11
|
||||
timer=-1,-1,20000
|
||||
@Legacy
|
||||
timer=-1,-1,N
|
||||
key1action=+,0,F,W
|
||||
key2action=2,#,#,#
|
||||
key2action=>,#,#,#
|
||||
timeaction=#,#,0
|
||||
0,5=f MHz
|
||||
1,8=c
|
||||
|
@ -89,10 +146,10 @@ timeaction=#,#,0
|
|||
############
|
||||
# Configuratoon for "Field" display (display 2)
|
||||
# similar to @Legacy, but no norx timer, and Key2 goes to display 4
|
||||
@Field:7
|
||||
timer=-1,-1,-1
|
||||
@Field
|
||||
timer=-1,-1,N
|
||||
key1action=+,0,F,W
|
||||
key2action=3,#,#,#
|
||||
key2action=>,#,#,#
|
||||
timeaction=#,#,#
|
||||
2,0=L
|
||||
4,0=O
|
||||
|
@ -105,10 +162,10 @@ timeaction=#,#,#
|
|||
############
|
||||
# Configuration for "Field2" display (display 3)
|
||||
# similar to @Field
|
||||
@Field2:9
|
||||
timer=-1,-1,-1
|
||||
@Field2
|
||||
timer=-1,-1,N
|
||||
key1action=+,0,F,W
|
||||
key2action=4,#,#,#
|
||||
key2action=>,#,#,#
|
||||
timeaction=#,#,#
|
||||
2,0=L
|
||||
4,0=O
|
||||
|
@ -123,10 +180,10 @@ timeaction=#,#,#
|
|||
#############
|
||||
# Configuration for "GPS" display
|
||||
# not yet the final version, just for testing
|
||||
@GPSDIST:14
|
||||
@GPSDIST
|
||||
timer=-1,-1,-1
|
||||
key1action=+,0,F,W
|
||||
key2action=1,#,#,#
|
||||
key2action=>,#,#,#
|
||||
timeaction=#,#,#
|
||||
0,0=Is
|
||||
0,9=f
|
||||
|
@ -136,8 +193,265 @@ timeaction=#,#,#
|
|||
2,10=a
|
||||
3,10=h
|
||||
4,9=v
|
||||
5,9=gC
|
||||
5,13=gB
|
||||
6,7=Q
|
||||
7,0=gV
|
||||
7,2=xd=
|
||||
7,4=gD
|
||||
7,12=gI°
|
||||
|
||||
############
|
||||
# Scan display for large 2" TFT dispaly
|
||||
@ScannerTFT
|
||||
timer=-1,0,0
|
||||
key1action=D,#,F,W
|
||||
key2action=#,#,#,#
|
||||
timeaction=#,D,+
|
||||
fonts=5,6
|
||||
0,0=XScan
|
||||
0,5,-3=S#:
|
||||
0,9,5=T
|
||||
3,0=F MHz
|
||||
5,0,16=S
|
||||
7,5=n
|
||||
|
||||
############
|
||||
@MainTFT
|
||||
timer=-1,-1,N
|
||||
key1action=+,0,F,W
|
||||
key2action=>,#,#,#
|
||||
timeaction=#,#,0
|
||||
color=FFD700
|
||||
0,0=Id
|
||||
color=0000FF
|
||||
0,11,-5.5=f
|
||||
1,1,6=c
|
||||
1,12.5,-4=t
|
||||
color=00ff00
|
||||
2,0=L
|
||||
4,0=O
|
||||
color=FFA500
|
||||
2,9.5,-7=A
|
||||
3,9.5,-7=vm/s
|
||||
color=AA5522
|
||||
4,9.5,-7=hkkm/h
|
||||
color=FFFFFF
|
||||
6,2=r
|
||||
7,0=xd=
|
||||
7,2,6=gD
|
||||
7,12=gI
|
||||
|
||||
############
|
||||
@PeilungTFT
|
||||
timer=-1,-1,N
|
||||
key1action=+,0,F,W
|
||||
key2action=>,#,#,#
|
||||
timeaction=#,#,#
|
||||
color=ffff00,000033
|
||||
color=bbbbbb,000000
|
||||
0,2=xN Top:
|
||||
0,8=xCourse Top:
|
||||
color=ffff00,000033
|
||||
1,0=g0NCS,48,ffff00,000044,6,33ff33,5,eeaa00
|
||||
1,8=g0CCS,48,ffff00,000044,6,55ff55,5,eeaa00
|
||||
color=ffffff,000000
|
||||
6,0=xDirection:
|
||||
6,8,4=gI
|
||||
7,0=xCOG:
|
||||
7,4,4=gC
|
||||
7,8=xturn:
|
||||
7,12,4=gB
|
||||
|
||||
|
||||
############
|
||||
@GPSdataTFT
|
||||
timer=-1,-1,N
|
||||
key1action=+,0,F,W
|
||||
key2action=>,#,#,#
|
||||
timeaction=#,#,#
|
||||
0,0=xOn-board GPS:
|
||||
1,0,8=gA
|
||||
2,0,8=gO
|
||||
3,0,8=gH
|
||||
4,0,8=gC
|
||||
5,0=xGPS vs Sonde:
|
||||
6,0,8=gD
|
||||
7,0,8=gI
|
||||
7,8,8=gB
|
||||
|
||||
############
|
||||
@BatteryTFT
|
||||
timer=-1,-1,-1
|
||||
key1action=+,0,F,W
|
||||
key2action=>,#,#,#
|
||||
timeaction=#,#,#
|
||||
0,0=xBattery status:
|
||||
0,14=bS
|
||||
1,0=xBatt:
|
||||
1,5,5=bVV
|
||||
2,0,16=bCmA(charging)
|
||||
3,0,16=bDmA(discharging)
|
||||
4.4,0=xUSB:
|
||||
4.4,5,5=bUV
|
||||
5.4,0,10=bImA
|
||||
6.4,0=xTemp:
|
||||
6.4,5,5=bT C
|
||||
|
||||
############
|
||||
@BatteryOLED
|
||||
timer=-1,-1,-1
|
||||
key1action=+,0,F,W
|
||||
key2action=>,#,#,#
|
||||
timeaction=#,#,#
|
||||
fonts=0,1
|
||||
0,0=xBat.Status:
|
||||
0,12=bS
|
||||
1,0=xBatt:
|
||||
1,6=bVV
|
||||
2,0=bCmA (charge)
|
||||
3,0=bDmA (disch.)
|
||||
4,0=xUSB:
|
||||
4,5=bUV
|
||||
5,5=bImA
|
||||
6,0=xTemp:
|
||||
6,5=bT C
|
||||
|
||||
### Alternative display layouts based on https://gist.github.com/bazjo
|
||||
# Scan display for large 2" TFT dispaly
|
||||
@Scan.TFT.Bazjo
|
||||
timer=-1,0,0
|
||||
key1action=D,#,F,W
|
||||
key2action=#,#,#,#
|
||||
timeaction=#,D,+
|
||||
scale=11,10
|
||||
fonts=0,2
|
||||
color=e0e0e0
|
||||
#Row 1
|
||||
0.5,0=XScanning...
|
||||
#Row 2
|
||||
3,0=xIndex
|
||||
4,0=S/
|
||||
3,9=xSite
|
||||
4,9=S
|
||||
#Row 3
|
||||
6,0=xType
|
||||
7,0=T
|
||||
6,9=xFrequency
|
||||
7,9=F
|
||||
#Row 4
|
||||
9,0=xWeb UI IP
|
||||
10,0=N
|
||||
#Row 5
|
||||
#Footer
|
||||
color=6C757D
|
||||
15,0=xScan Mode
|
||||
15,18=bVV
|
||||
|
||||
############
|
||||
@Decode/General.TFT.Bazjo
|
||||
timer=-1,-1,N
|
||||
key1action=+,0,F,W
|
||||
key2action=>,#,#,#
|
||||
timeaction=#,#,0
|
||||
scale=11,10
|
||||
fonts=0,2
|
||||
#Row 1
|
||||
color=996A06
|
||||
0,0=xSerial
|
||||
0,5=t
|
||||
color=FFB10B
|
||||
1,0=Is
|
||||
color=996A06
|
||||
0,11=xFreq.
|
||||
0,16=c
|
||||
color=FFB10B
|
||||
1,11=F
|
||||
#Row 2
|
||||
color=3C5C99
|
||||
3,0=xLatitude
|
||||
color=639AFF
|
||||
4,0=L
|
||||
color=3C5C99
|
||||
3,11=xLongitude
|
||||
color=639AFF
|
||||
4,11=O
|
||||
#Row 3
|
||||
color=3C5C99
|
||||
6,0=xHoriz. Speed
|
||||
color=639AFF
|
||||
7,0=Hkkm/h
|
||||
color=3C5C99
|
||||
6,11=xVert. Speed
|
||||
color=639AFF
|
||||
7,11=Vm/s
|
||||
#Row 4
|
||||
color=99004A
|
||||
9,0=xAltitude
|
||||
color=FF007B
|
||||
10,0=A
|
||||
color=99004A
|
||||
9,11=xBearing
|
||||
color=FF007B
|
||||
10,11=GB
|
||||
#Row 5
|
||||
color=06998E
|
||||
12,0=xRSSI
|
||||
color=0AFFEF
|
||||
13,0=R
|
||||
color=06998E
|
||||
12,11=xHistory
|
||||
color=0AFFEF
|
||||
13.5,11=Q4
|
||||
#Footer
|
||||
color=6C757D
|
||||
15,0=xDecode Mode / General View
|
||||
15,18=bVV
|
||||
|
||||
|
||||
############
|
||||
@Decode/Battery.TFT.Bazjo
|
||||
timer=-1,-1,N
|
||||
key1action=+,0,F,W
|
||||
key2action=>,#,#,#
|
||||
timeaction=#,#,#
|
||||
scale=11,10
|
||||
fonts=0,2
|
||||
#Row 1
|
||||
color=99001F
|
||||
0,0=xBattery Status
|
||||
0,11=xBattery Voltage
|
||||
color=FF0035
|
||||
1,0=BS
|
||||
1,11=BVV
|
||||
#Row 2
|
||||
color=99001F
|
||||
3,0=xCharge Current
|
||||
3,11=xDischarge Current
|
||||
color=FF0035
|
||||
4,0=BCmA
|
||||
4,11=BDmA
|
||||
#Row 3
|
||||
color=99001F
|
||||
6,0=xUSB Voltage
|
||||
6,11=xUSB Current
|
||||
color=FF0035
|
||||
7,0=BUV
|
||||
7,11=BImA
|
||||
#Row 4
|
||||
color=99001F
|
||||
9,0=xIC Temperature
|
||||
#9,11=xKey
|
||||
color=FF0035
|
||||
10,0=BTC
|
||||
#10,11=XValue
|
||||
#Row 5
|
||||
#12,0=xKey
|
||||
#12,11=xKey
|
||||
#13,0=XValue
|
||||
#13,11=XValue
|
||||
#Footer
|
||||
color=99001F
|
||||
15,0=xDecode Mode/Battery View
|
||||
15,18=bVV
|
||||
|
||||
|
|
|
@ -10,6 +10,12 @@ table, th, td {
|
|||
background-color: #ddd
|
||||
}
|
||||
|
||||
td#caption {
|
||||
text-align: center;
|
||||
background-color: #aaa;
|
||||
font-weight: bold;
|
||||
}
|
||||
|
||||
td#sfreq {
|
||||
background-color: #ccc;
|
||||
}
|
||||
|
|
|
@ -1,2 +1,4 @@
|
|||
const char *version_name = "rdzTTGOsonde";
|
||||
const char *version_id = "master_v0.7.1";
|
||||
const char *version_id = "master_v0.8.0";
|
||||
const int SPIFFS_MAJOR=2;
|
||||
const int SPIFFS_MINOR=4;
|
||||
|
|
|
@ -679,9 +679,6 @@ uint8_t SX1278FSK::receive()
|
|||
return state;
|
||||
}
|
||||
|
||||
// ugly. shouldn't be here in a nice software design
|
||||
extern int hasKeyPress();
|
||||
|
||||
/*
|
||||
Function: Configures the module to receive a packet
|
||||
Returns: Integer that determines if there has been any error
|
||||
|
@ -726,8 +723,10 @@ uint8_t SX1278FSK::receivePacketTimeout(uint32_t wait, byte *data)
|
|||
if(di==1 || di==290 ) {
|
||||
int rssi=getRSSI();
|
||||
int afc=getAFC();
|
||||
#if 0
|
||||
Serial.printf("Test(%d): RSSI=%d", rxtask.currentSonde, rssi/2);
|
||||
Serial.print("Test: AFC="); Serial.println(afc);
|
||||
#endif
|
||||
sonde.sondeList[rxtask.currentSonde].rssi = rssi;
|
||||
sonde.sondeList[rxtask.currentSonde].afc = afc;
|
||||
if(rxtask.receiveResult==0xFFFF)
|
||||
|
|
|
@ -72,6 +72,7 @@ int DFM::setup(float frequency, int inv)
|
|||
Serial.println(frequency);
|
||||
|
||||
int retval = sx1278.setFrequency(frequency);
|
||||
sx1278.clearIRQFlags();
|
||||
DFM_DBG(Serial.println("Setting SX1278 config for DFM finished\n"); Serial.println());
|
||||
return retval;
|
||||
}
|
||||
|
@ -183,23 +184,39 @@ void DFM::decodeCFG(uint8_t *cfg)
|
|||
if(idgood==3) {
|
||||
uint32_t dfmid = (highid<<16) | lowid;
|
||||
Serial.print("DFM-09 ID: "); Serial.print(dfmid);
|
||||
snprintf(sonde.si()->id, 10, "%d", dfmid);
|
||||
snprintf(sonde.si()->ser, 10, "%d", dfmid);
|
||||
// dxlAPRS sonde number (DF6 (why??) and 5 last digits of serial number as hex number
|
||||
snprintf(sonde.si()->id, 9, "DF6%05X", dfmid&0xfffff);
|
||||
sonde.si()->validID = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static int bitCount(int x) {
|
||||
int m4 = 0x1 | (0x1<<8) | (0x1<<16) | (0x1<<24);
|
||||
int m1 = 0xFF;
|
||||
int s4 = (x&m4) + ((x>>1)&m4) + ((x>>2)&m4) + ((x>>3)&m4) + ((x>>4)&m4) + ((x>>5)&m4) + ((x>>6)&m4) + ((x>>7)&m4);
|
||||
int s1 = (s4&m1) + ((s4>>8)&m1) + ((s4>>16)&m1) + ((s4>>24)&m1);
|
||||
return s1;
|
||||
}
|
||||
|
||||
static uint16_t MON[]={0,0,31,59,90,120,151,181,212,243,273,304,334};
|
||||
|
||||
void DFM::decodeDAT(uint8_t *dat)
|
||||
{
|
||||
Serial.print(" DAT["); Serial.print(dat[6]); Serial.print("]: ");
|
||||
switch(dat[6]) {
|
||||
case 0:
|
||||
Serial.print("Packet counter: "); Serial.print(dat[3]);
|
||||
Serial.print("Packet counter: "); Serial.print(dat[3]);
|
||||
sonde.si()->frame = dat[3];
|
||||
break;
|
||||
case 1:
|
||||
{
|
||||
int val = (((uint16_t)dat[4])<<8) + (uint16_t)dat[5];
|
||||
Serial.print("UTC-msec: "); Serial.print(val);
|
||||
sonde.si()->sec = val/1000;
|
||||
uint32_t tmp = ((uint32_t)dat[0]<<24) + ((uint32_t)dat[1]<<16) + ((uint32_t)dat[2]<<8) + ((uint32_t)dat[3]);
|
||||
sonde.si()->sats = bitCount(tmp); // maybe!?!?!?
|
||||
}
|
||||
break;
|
||||
case 2:
|
||||
|
@ -248,6 +265,11 @@ void DFM::decodeDAT(uint8_t *dat)
|
|||
char buf[100];
|
||||
snprintf(buf, 100, "%04d-%02d-%02d %02d:%02dz", y, m, d, h, mi);
|
||||
Serial.print("Date: "); Serial.print(buf);
|
||||
// convert to unix time
|
||||
int tt = (y-1970)*365 + (y-1969)/4; // days since 1970
|
||||
if(m<=12) { tt += MON[m]; if((y%4)==0 && m>2) tt++; }
|
||||
tt = (tt+d-1)*(60*60*24) + h*3600 + mi*60;
|
||||
sonde.si()->time = tt;
|
||||
}
|
||||
break;
|
||||
default:
|
||||
|
|
Plik diff jest za duży
Load Diff
|
@ -8,20 +8,43 @@
|
|||
#include <SPI.h>
|
||||
#include <TFT22_ILI9225.h>
|
||||
#include <U8x8lib.h>
|
||||
#include <SPIFFS.h>
|
||||
|
||||
|
||||
#define WIDTH_AUTO 9999
|
||||
struct DispEntry {
|
||||
int8_t y;
|
||||
int8_t x;
|
||||
int16_t fmt;
|
||||
int16_t y;
|
||||
int16_t x;
|
||||
int16_t fmt, width;
|
||||
uint16_t fg,bg;
|
||||
void (*func)(DispEntry *de);
|
||||
const char *extra;
|
||||
};
|
||||
|
||||
#define GPSUSE_BASE 1
|
||||
#define GPSUSE_DIST 2
|
||||
#define GPSUSE_BEARING 4
|
||||
struct DispInfo {
|
||||
DispEntry *de;
|
||||
uint8_t *actions;
|
||||
int16_t *timeouts;
|
||||
const char *label;
|
||||
uint8_t usegps;
|
||||
};
|
||||
|
||||
struct StatInfo {
|
||||
uint8_t len;
|
||||
uint8_t size;
|
||||
};
|
||||
|
||||
struct CircleInfo { // 3,5=g0NCS,50,ff0000,000033,5,ffff00,4,ffffff
|
||||
char type;
|
||||
char top,bul,arr; // what to point to with top, bullet, array
|
||||
uint16_t fgcol, bgcol;
|
||||
uint8_t radius;
|
||||
uint8_t brad;
|
||||
uint16_t bcol;
|
||||
uint8_t awidth;
|
||||
uint16_t acol;
|
||||
};
|
||||
|
||||
// Now starting towards supporting different Display types / libraries
|
||||
|
@ -29,25 +52,37 @@ class RawDisplay {
|
|||
public:
|
||||
virtual void begin() = 0;
|
||||
virtual void clear() = 0;
|
||||
virtual void setFont(int nr) = 0;
|
||||
virtual void drawString(uint8_t x, uint8_t y, const char *s) = 0;
|
||||
virtual void setFont(uint8_t fontindex) = 0;
|
||||
virtual void getDispSize(uint8_t *height, uint8_t *width, uint8_t *lineskip, uint8_t *colskip) = 0;
|
||||
virtual void drawString(uint8_t x, uint8_t y, const char *s, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0 ) = 0;
|
||||
virtual void drawTile(uint8_t x, uint8_t y, uint8_t cnt, uint8_t *tile_ptr) = 0;
|
||||
virtual void drawTriangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t x3, uint16_t y3, uint16_t color, bool fill) = 0;
|
||||
virtual void drawBitmap(uint16_t x1, uint16_t y1, const uint16_t* bitmap, int16_t w, int16_t h) = 0;
|
||||
virtual void welcome() = 0;
|
||||
virtual void drawIP(uint8_t x, uint8_t y, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0 ) = 0;
|
||||
virtual void drawQS(uint8_t x, uint8_t y, uint8_t len, uint8_t size, uint8_t *stat, uint16_t fg=0xffff, uint16_t bg=0) = 0;
|
||||
};
|
||||
|
||||
class U8x8Display : public RawDisplay {
|
||||
private:
|
||||
U8X8 *u8x8 = NULL; // initialize later after reading config file
|
||||
int _type;
|
||||
const uint8_t **fontlist;
|
||||
int nfonts;
|
||||
|
||||
public:
|
||||
U8x8Display(int type = 0) { _type = type; }
|
||||
void begin();
|
||||
void clear();
|
||||
void setFont(int nr);
|
||||
void drawString(uint8_t x, uint8_t y, const char *s);
|
||||
void setFont(uint8_t fontindex);
|
||||
void getDispSize(uint8_t *height, uint8_t *width, uint8_t *lineskip, uint8_t *colskip);
|
||||
void drawString(uint8_t x, uint8_t y, const char *s, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0);
|
||||
void drawTile(uint8_t x, uint8_t y, uint8_t cnt, uint8_t *tile_ptr);
|
||||
void drawTriangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t x3, uint16_t y3, uint16_t color, bool fill);
|
||||
void drawBitmap(uint16_t x1, uint16_t y1, const uint16_t* bitmap, int16_t w, int16_t h);
|
||||
void welcome();
|
||||
void drawIP(uint8_t x, uint8_t y, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0);
|
||||
void drawQS(uint8_t x, uint8_t y, uint8_t len, uint8_t size, uint8_t *stat, uint16_t fg=0xffff, uint16_t bg=0);
|
||||
};
|
||||
|
||||
class MY_ILI9225 : public TFT22_ILI9225 {
|
||||
|
@ -59,31 +94,64 @@ public:
|
|||
|
||||
class ILI9225Display : public RawDisplay {
|
||||
private:
|
||||
MY_ILI9225 *tft = NULL; // initialize later after reading config file
|
||||
uint8_t yofs=0;
|
||||
uint8_t fsize=0;
|
||||
|
||||
uint8_t findex=0;
|
||||
|
||||
public:
|
||||
MY_ILI9225 *tft = NULL; // initialize later after reading config file
|
||||
void begin();
|
||||
void clear();
|
||||
void setFont(int nr);
|
||||
void drawString(uint8_t x, uint8_t y, const char *s);
|
||||
void setFont(uint8_t fontindex);
|
||||
void getDispSize(uint8_t *height, uint8_t *width, uint8_t *lineskip, uint8_t *colskip);
|
||||
void drawString(uint8_t x, uint8_t y, const char *s, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0);
|
||||
void drawTile(uint8_t x, uint8_t y, uint8_t cnt, uint8_t *tile_ptr);
|
||||
void drawTriangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t x3, uint16_t y3, uint16_t color, bool fill);
|
||||
void drawBitmap(uint16_t x1, uint16_t y1, const uint16_t* bitmap, int16_t w, int16_t h);
|
||||
void welcome();
|
||||
void drawIP(uint8_t x, uint8_t y, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0);
|
||||
void drawQS(uint8_t x, uint8_t y, uint8_t len, uint8_t size, uint8_t *stat, uint16_t fg=0xffff, uint16_t bg=0);
|
||||
};
|
||||
|
||||
class Display {
|
||||
private:
|
||||
void freeLayouts();
|
||||
int allocDispInfo(int entries, DispInfo *d);
|
||||
void replaceLayouts(DispInfo *newlayout, int nnew);
|
||||
int allocDispInfo(int entries, DispInfo *d, char *label);
|
||||
void parseDispElement(char *text, DispEntry *de);
|
||||
|
||||
int xscale=13, yscale=22;
|
||||
int fontsma=0, fontlar=1;
|
||||
uint16_t colfg, colbg;
|
||||
static void circ(uint16_t *bm, int16_t w, int16_t x0, int16_t y0, int16_t r, uint16_t fg, boolean fill, uint16_t bg);
|
||||
static int countEntries(File f);
|
||||
void calcGPS();
|
||||
boolean gpsValid;
|
||||
float gpsLat, gpsLon;
|
||||
int gpsAlt;
|
||||
int gpsDist; // -1: invalid
|
||||
int gpsCourse, gpsDir, gpsBear; // 0..360; -1: invalid
|
||||
boolean gpsCourseOld;
|
||||
static const int LINEBUFLEN{ 255 };
|
||||
static char lineBuf[LINEBUFLEN];
|
||||
static const char *trim(char *s) {
|
||||
char *ret = s;
|
||||
while(*ret && isspace(*ret)) { ret++; }
|
||||
int lastidx;
|
||||
while(1) {
|
||||
lastidx = strlen(ret)-1;
|
||||
if(lastidx>=0 && isspace(ret[lastidx]))
|
||||
ret[lastidx] = 0;
|
||||
else
|
||||
break;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
public:
|
||||
void initFromFile();
|
||||
|
||||
void setLayout(DispInfo *layout);
|
||||
int layoutIdx;
|
||||
DispInfo *layout;
|
||||
|
||||
DispInfo *layouts;
|
||||
int nLayouts;
|
||||
static RawDisplay *rdis;
|
||||
|
||||
Display();
|
||||
|
@ -103,8 +171,11 @@ public:
|
|||
static void drawIP(DispEntry *de);
|
||||
static void drawSite(DispEntry *de);
|
||||
static void drawTelemetry(DispEntry *de);
|
||||
static void drawKilltimer(DispEntry *de);
|
||||
static void drawGPS(DispEntry *de);
|
||||
static void drawText(DispEntry *de);
|
||||
static void drawBatt(DispEntry *de);
|
||||
static void drawString(DispEntry *de, const char *str);
|
||||
void clearIP();
|
||||
void setIP(const char *ip, bool AP);
|
||||
void updateDisplayPos();
|
||||
|
|
|
@ -0,0 +1,529 @@
|
|||
|
||||
/* M10 decoder functions */
|
||||
#include "M10.h"
|
||||
#include "SX1278FSK.h"
|
||||
#include "rsc.h"
|
||||
#include "Sonde.h"
|
||||
#include <SPIFFS.h>
|
||||
|
||||
// well...
|
||||
//#include "rs92gps.h"
|
||||
|
||||
#define M10_DEBUG 1
|
||||
|
||||
#if M10_DEBUG
|
||||
#define M10_DBG(x) x
|
||||
#else
|
||||
#define M10_DBG(x)
|
||||
#endif
|
||||
|
||||
|
||||
static byte data1[512];
|
||||
static byte *dataptr=data1;
|
||||
|
||||
static uint8_t rxbitc;
|
||||
static uint16_t rxbyte;
|
||||
static int rxp=0;
|
||||
static int haveNewFrame = 0;
|
||||
static int lastFrame = 0;
|
||||
static int headerDetected = 0;
|
||||
|
||||
int M10::setup(float frequency)
|
||||
{
|
||||
#if M10_DEBUG
|
||||
Serial.println("Setup sx1278 for M10 sonde");
|
||||
#endif
|
||||
//if(!initialized) {
|
||||
//Gencrctab();
|
||||
//initrsc();
|
||||
// not here for now.... get_eph("/brdc.19n");
|
||||
// initialized = true;
|
||||
//}
|
||||
|
||||
if(sx1278.ON()!=0) {
|
||||
M10_DBG(Serial.println("Setting SX1278 power on FAILED"));
|
||||
return 1;
|
||||
}
|
||||
if(sx1278.setFSK()!=0) {
|
||||
M10_DBG(Serial.println("Setting FSJ mode FAILED"));
|
||||
return 1;
|
||||
}
|
||||
if(sx1278.setBitrate(9600)!=0) {
|
||||
M10_DBG(Serial.println("Setting bitrate 9600bit/s FAILED"));
|
||||
return 1;
|
||||
}
|
||||
#if M10_DEBUG
|
||||
float br = sx1278.getBitrate();
|
||||
Serial.print("Exact bitrate is ");
|
||||
Serial.println(br);
|
||||
#endif
|
||||
if(sx1278.setAFCBandwidth(sonde.config.rs92.rxbw)!=0) {
|
||||
M10_DBG(Serial.printf("Setting AFC bandwidth %d Hz FAILED", sonde.config.rs92.rxbw));
|
||||
return 1;
|
||||
}
|
||||
if(sx1278.setRxBandwidth(sonde.config.rs92.rxbw)!=0) {
|
||||
M10_DBG(Serial.printf("Setting RX bandwidth to %d Hz FAILED", sonde.config.rs92.rxbw));
|
||||
return 1;
|
||||
}
|
||||
|
||||
// Enable auto-AFC, auto-AGC, RX Trigger by preamble
|
||||
if(sx1278.setRxConf(0x1E)!=0) {
|
||||
M10_DBG(Serial.println("Setting RX Config FAILED"));
|
||||
return 1;
|
||||
}
|
||||
// Set autostart_RX to 01, preamble 0, SYNC detect==on, syncsize=3 (==4 byte
|
||||
//char header[] = "0110.0101 0110.0110 1010.0101 1010.1010";
|
||||
|
||||
//const char *SYNC="\x10\xB6\xCA\x11\x22\x96\x12\xF8";
|
||||
//const char *SYNC="\x08\x6D\x53\x88\x44\x69\x48\x1F";
|
||||
// was 0x57
|
||||
//const char *SYNC="\x99\x9A";
|
||||
#if 1
|
||||
// version 1, working with continuous RX
|
||||
const char *SYNC="\x66\x65";
|
||||
if(sx1278.setSyncConf(0x70, 2, (const uint8_t *)SYNC)!=0) {
|
||||
M10_DBG(Serial.println("Setting SYNC Config FAILED"));
|
||||
return 1;
|
||||
}
|
||||
//if(sx1278.setPreambleDetect(0xA8)!=0) {
|
||||
if(sx1278.setPreambleDetect(0x9F)!=0) {
|
||||
M10_DBG(Serial.println("Setting PreambleDetect FAILED"));
|
||||
return 1;
|
||||
}
|
||||
#endif
|
||||
#if 0
|
||||
// version 2, with per-packet rx start, untested
|
||||
// header is 2a 10 65, i.e. with lsb first
|
||||
// 0 0101 0100 1 0 0000 1000 1 0 1010 0110 1
|
||||
// 10 10011001 10011010 01 10 10101010 01101010 01 10 01100110 10010110 01
|
||||
// preamble 0x6A 0x66 0x6A
|
||||
// i.e. preamble detector on (0x80), preamble detector size 1 (0x00), preample chip errors??? (0x0A)
|
||||
// after 2a2a2a2a2a1065
|
||||
if(sx1278.setPreambleDetect(0xA8)!=0) {
|
||||
M10_DBG(Serial.println("Setting PreambleDetect FAILED"));
|
||||
return 1;
|
||||
}
|
||||
// sync config: ato restart (01), preamble polarity AA (0), sync on (1), resevered (0), syncsize 2+1 (010) => 0x52
|
||||
const char *SYNC="\x6A\x66\x69";
|
||||
if(sx1278.setSyncConf(0x52, 3, (const uint8_t *)SYNC)!=0) {
|
||||
M10_DBG(Serial.println("Setting SYNC Config FAILED"));
|
||||
return 1;
|
||||
}
|
||||
// payload length is ((240 - 7)*10 +6)/8 = 292
|
||||
#endif
|
||||
|
||||
// Packet config 1: fixed len, no mancecer, no crc, no address filter
|
||||
// Packet config 2: packet mode, no home ctrl, no beackn, msb(packetlen)=0)
|
||||
if(sx1278.setPacketConfig(0x08, 0x40)!=0) {
|
||||
M10_DBG(Serial.println("Setting Packet config FAILED"));
|
||||
return 1;
|
||||
}
|
||||
|
||||
Serial.print("M10: setting RX frequency to ");
|
||||
Serial.println(frequency);
|
||||
int res = sx1278.setFrequency(frequency);
|
||||
// enable RX
|
||||
sx1278.setPayloadLength(0); // infinite for now...
|
||||
//sx1278.setPayloadLength(292);
|
||||
sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE);
|
||||
|
||||
#if M10_DEBUG
|
||||
M10_DBG(Serial.println("Setting SX1278 config for M10 finished\n"); Serial.println());
|
||||
#endif
|
||||
return res;
|
||||
}
|
||||
|
||||
#if 0
|
||||
int M10::setFrequency(float frequency) {
|
||||
Serial.print("M10: setting RX frequency to ");
|
||||
Serial.println(frequency);
|
||||
int res = sx1278.setFrequency(frequency);
|
||||
// enable RX
|
||||
sx1278.setPayloadLength(0); // infinite for now...
|
||||
|
||||
sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE);
|
||||
return res;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if 0
|
||||
uint32_t M10::bits2val(const uint8_t *bits, int len) {
|
||||
uint32_t val = 0;
|
||||
for (int j = 0; j < len; j++) {
|
||||
val |= (bits[j] << (len-1-j));
|
||||
}
|
||||
return val;
|
||||
}
|
||||
#endif
|
||||
|
||||
M10::M10() {
|
||||
}
|
||||
|
||||
#define M10_FRAMELEN 101
|
||||
#define M10_CRCPOS 99
|
||||
|
||||
void M10::printRaw(uint8_t *data, int len)
|
||||
{
|
||||
char buf[3];
|
||||
int i;
|
||||
for(i=0; i<len; i++) {
|
||||
snprintf(buf, 3, "%02X ", data[i]);
|
||||
Serial.print(buf);
|
||||
}
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
static int update_checkM10(int c, uint8_t b) {
|
||||
int c0, c1, t, t6, t7, s;
|
||||
c1 = c & 0xFF;
|
||||
// B
|
||||
b = (b >> 1) | ((b & 1) << 7);
|
||||
b ^= (b >> 2) & 0xFF;
|
||||
// A1
|
||||
t6 = ( c & 1) ^ ((c >> 2) & 1) ^ ((c >> 4) & 1);
|
||||
t7 = ((c >> 1) & 1) ^ ((c >> 3) & 1) ^ ((c >> 5) & 1);
|
||||
t = (c & 0x3F) | (t6 << 6) | (t7 << 7);
|
||||
// A2
|
||||
s = (c >> 7) & 0xFF;
|
||||
s ^= (s >> 2) & 0xFF;
|
||||
c0 = b ^ t ^ s;
|
||||
return ((c1 << 8) | c0) & 0xFFFF;
|
||||
}
|
||||
static bool checkM10crc(uint8_t *msg) {
|
||||
int i, cs, cs1;
|
||||
cs = 0;
|
||||
for (i = 0; i < M10_CRCPOS; i++) {
|
||||
cs = update_checkM10(cs, msg[i]);
|
||||
}
|
||||
cs = cs & 0xFFFF;
|
||||
cs1 = (msg[M10_CRCPOS] << 8) | msg[M10_CRCPOS+1];
|
||||
return (cs1 == cs);
|
||||
}
|
||||
|
||||
typedef uint32_t SET256[8];
|
||||
static SET256 sondeudp_VARSET = {0x03BBBBF0UL,0x80600000UL,0x06A001A0UL,
|
||||
0x0000001CUL,0x00000000UL,0x00000000UL,0x00000000UL,
|
||||
0x00000000UL};
|
||||
// VARSET=SET256{4..9,11..13,15..17,19..21,23..25,53..54,63,69,71,72,85,87,89,90,98..100};
|
||||
|
||||
static uint8_t fixcnt[M10_FRAMELEN];
|
||||
static uint8_t fixbytes[M10_FRAMELEN];
|
||||
|
||||
static int32_t getint32(uint8_t *data) {
|
||||
return (int32_t)( data[3]|(data[2]<<8)|(data[1]<<16)|(data[0]<<24) );
|
||||
}
|
||||
static int16_t getint16(uint8_t *data) {
|
||||
return (int16_t)(data[1]|((uint16_t)data[0]<<8));
|
||||
}
|
||||
|
||||
static char dez(uint8_t nr) {
|
||||
nr = nr%10;
|
||||
return '0'+nr;
|
||||
}
|
||||
static char hex(uint8_t nr) {
|
||||
nr = nr&0x0f;
|
||||
if(nr<10) return '0'+nr;
|
||||
else return 'A'+nr-10;
|
||||
}
|
||||
const static float DEGMUL = 1.0/0xB60B60;
|
||||
#define VMUL 0.005
|
||||
#ifndef PI
|
||||
#define PI (3.1415926535897932384626433832795)
|
||||
#endif
|
||||
#define RAD (PI/180)
|
||||
|
||||
|
||||
// ret: 1=frame ok; 2=frame with errors; 0=ignored frame (m10dop-alternativ)
|
||||
int M10::decodeframeM10(uint8_t *data) {
|
||||
int repairstep = 16;
|
||||
int repl = 0;
|
||||
bool crcok;
|
||||
// error correction, inspired by oe5dxl's sondeudp
|
||||
do {
|
||||
crcok = checkM10crc(data);
|
||||
if(crcok) break;
|
||||
repl = 0;
|
||||
for(int i=0; i<M10_CRCPOS; i++) {
|
||||
if( ((sondeudp_VARSET[i/32]&(1<<(i%32))) != 1) && (fixcnt[i]>=repairstep) ) {
|
||||
repl++;
|
||||
data[i] = fixbytes[i];
|
||||
}
|
||||
}
|
||||
repairstep >>= 1;
|
||||
} while(repairstep>0);
|
||||
if(crcok) {
|
||||
for(int i=0; i<M10_CRCPOS; i++) {
|
||||
if(fixbytes[i]==data[i] &&fixcnt[i]<255) fixcnt[i]++;
|
||||
else { fixcnt[i]=0; fixbytes[i]=data[i]; }
|
||||
}
|
||||
}
|
||||
Serial.println(crcok?"CRC OK":"CRC NOT OK");
|
||||
|
||||
if(data[1]==0x9F && data[2]==0x20) {
|
||||
Serial.println("Decoding...");
|
||||
// Its a M10
|
||||
// getid...
|
||||
char ids[11];
|
||||
ids[0] = 'M';
|
||||
ids[1] = 'E';
|
||||
ids[2] = hex(data[95]/16);
|
||||
ids[3] = hex(data[95]);
|
||||
ids[4] = hex(data[93]);
|
||||
uint32_t id = data[96] + data[97]*256;
|
||||
ids[5] = hex(id/4096);
|
||||
ids[6] = hex(id/256);
|
||||
ids[7] = hex(id/16);
|
||||
ids[8] = hex(id);
|
||||
ids[9] = 0;
|
||||
strncpy(sonde.si()->id, ids, 10);
|
||||
ids[0] = hex(data[95]/16);
|
||||
ids[1] = dez((data[95]&0x0f)/10);
|
||||
ids[2] = dez((data[95]&0x0f));
|
||||
ids[3] = dez(data[93]);
|
||||
ids[4] = dez(id>>13);
|
||||
id &= 0x1fff;
|
||||
ids[5] = dez(id/1000);
|
||||
ids[6] = dez((id/100)%10);
|
||||
ids[7] = dez((id/10)%10);
|
||||
ids[8] = dez(id%10);
|
||||
strncpy(sonde.si()->ser, ids, 10);
|
||||
sonde.si()->validID = true;
|
||||
Serial.printf("ID is %s [%02x %02x %d]\n", ids, data[95], data[93], id);
|
||||
// ID printed on sonde is ...-.-abbbb, with a=id>>13, bbbb=id&0x1fff in decimal
|
||||
// position data
|
||||
sonde.si()->lat = getint32(data+14) * DEGMUL;
|
||||
sonde.si()->lon = getint32(data+18) * DEGMUL;
|
||||
sonde.si()->alt = getint32(data+22) * 0.001;
|
||||
float ve = getint16(data+4)*VMUL;
|
||||
float vn = getint16(data+6)*VMUL;
|
||||
sonde.si()->vs = getint16(data+8) * VMUL;
|
||||
sonde.si()->hs = sqrt(ve*ve+vn*vn);
|
||||
float dir = atan2(vn, ve)*(1.0/RAD);
|
||||
if(dir<0) dir+=360;
|
||||
sonde.si()->dir = dir;
|
||||
sonde.si()->validPos = 0x3f;
|
||||
|
||||
uint32_t gpstime = getint32(data+10);
|
||||
uint16_t gpsweek = getint16(data+32);
|
||||
// UTC is GPSTIME - 18s (24*60*60-18 = 86382)
|
||||
// one week = 7*24*60*60 = 604800 seconds
|
||||
// unix epoch starts jan 1st 1970 0:00
|
||||
// gps time starts jan 6, 1980 0:00. thats 315964800 epoch seconds.
|
||||
// subtracting 86400 yields 315878400UL
|
||||
sonde.si()->time = (gpstime/1000) + 86382 + gpsweek*604800 + 315878400UL;
|
||||
sonde.si()->validTime = true;
|
||||
} else {
|
||||
Serial.printf("data is %02x %02x %02x\n", data[0], data[1], data[2]);
|
||||
return 0;
|
||||
}
|
||||
return crcok?1:2;
|
||||
}
|
||||
|
||||
static uint32_t rxdata;
|
||||
static bool rxsearching=true;
|
||||
|
||||
// search for
|
||||
// //101001100110011010011010011001100110100110101010100110101001
|
||||
// //1010011001100110100110100110 0110.0110 1001.1010 1010.1001 1010.1001 => 0x669AA9A9
|
||||
void M10::processM10data(uint8_t dt)
|
||||
{
|
||||
for(int i=0; i<8; i++) {
|
||||
uint8_t d = (dt&0x80)?1:0;
|
||||
dt <<= 1;
|
||||
rxdata = (rxdata<<1) | d;
|
||||
//uint8_t value = ((rxdata>>1)^rxdata)&0x01;
|
||||
//if((rxbitc&1)==1) { rxbyte = (rxbyte>>1) + ((value)<<8); } // mancester decoded data
|
||||
//rxbyte = (rxbyte>>1) | (d<<8);
|
||||
if( (rxbitc&1)==0 ) {
|
||||
// "bit1"
|
||||
rxbyte = (rxbyte<<1) | d;
|
||||
} else {
|
||||
// "bit2" ==> 01 or 10 => 1, otherweise => 0
|
||||
rxbyte = rxbyte ^ d;
|
||||
}
|
||||
//
|
||||
if(rxsearching) {
|
||||
if( rxdata == 0xcccca64c || rxdata == 0x333359b3 ) {
|
||||
rxsearching = false;
|
||||
rxbitc = 0;
|
||||
rxp = 0;
|
||||
#if 1
|
||||
int rssi=sx1278.getRSSI();
|
||||
int fei=sx1278.getFEI();
|
||||
int afc=sx1278.getAFC();
|
||||
Serial.print("Test: RSSI="); Serial.print(rssi);
|
||||
Serial.print(" FEI="); Serial.print(fei);
|
||||
Serial.print(" AFC="); Serial.println(afc);
|
||||
sonde.si()->rssi = rssi;
|
||||
sonde.si()->afc = afc;
|
||||
#endif
|
||||
}
|
||||
} else {
|
||||
rxbitc = (rxbitc+1)%16; // 16;
|
||||
if(rxbitc == 0) { // got 8 data bit
|
||||
//Serial.printf("%03x ",rxbyte);
|
||||
dataptr[rxp++] = rxbyte&0xff; // (rxbyte>>1)&0xff;
|
||||
#if 0
|
||||
if(rxp==7 && dataptr[6] != 0x65) {
|
||||
Serial.printf("wrong start: %02x\n",dataptr[6]);
|
||||
rxsearching = true;
|
||||
}
|
||||
#endif
|
||||
if(rxp>=M10_FRAMELEN) {
|
||||
rxsearching = true;
|
||||
haveNewFrame = decodeframeM10(dataptr);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int M10::receive() {
|
||||
unsigned long t0 = millis();
|
||||
Serial.printf("M10::receive() start at %ld\n",t0);
|
||||
while( millis() - t0 < 1000 ) {
|
||||
uint8_t value = sx1278.readRegister(REG_IRQ_FLAGS2);
|
||||
if ( bitRead(value, 7) ) {
|
||||
Serial.println("FIFO full");
|
||||
}
|
||||
if ( bitRead(value, 4) ) {
|
||||
Serial.println("FIFO overflow");
|
||||
}
|
||||
if ( bitRead(value, 2) == 1 ) {
|
||||
Serial.println("FIFO: ready()");
|
||||
sx1278.clearIRQFlags();
|
||||
}
|
||||
if(bitRead(value, 6) == 0) { // while FIFO not empty
|
||||
byte data = sx1278.readRegister(REG_FIFO);
|
||||
//Serial.printf("%02x",data);
|
||||
processM10data(data);
|
||||
value = sx1278.readRegister(REG_IRQ_FLAGS2);
|
||||
} else {
|
||||
if(headerDetected) {
|
||||
t0 = millis(); // restart timer... don't time out if header detected...
|
||||
headerDetected = 0;
|
||||
}
|
||||
if(haveNewFrame) {
|
||||
Serial.printf("M10::receive(): new frame complete after %ldms\n", millis()-t0);
|
||||
printRaw(dataptr, M10_FRAMELEN);
|
||||
int retval = haveNewFrame==1 ? RX_OK: RX_ERROR;
|
||||
haveNewFrame = 0;
|
||||
return retval;
|
||||
}
|
||||
delay(2);
|
||||
}
|
||||
}
|
||||
Serial.printf("M10::receive() timed out\n");
|
||||
return RX_TIMEOUT; // TODO RX_OK;
|
||||
}
|
||||
|
||||
#define M10MAXLEN (240)
|
||||
int M10::waitRXcomplete() {
|
||||
// called after complete...
|
||||
#if 0
|
||||
Serial.printf("decoding frame %d\n", lastFrame);
|
||||
print_frame(lastFrame==1?data1:data2, 240);
|
||||
SondeInfo *si = sonde.sondeList+rxtask.receiveSonde;
|
||||
si->lat = gpx.lat;
|
||||
si->lon = gpx.lon;
|
||||
si->alt = gpx.alt;
|
||||
si->vs = gpx.vU;
|
||||
si->hs = gpx.vH;
|
||||
si->dir = gpx.vD;
|
||||
si->validPos = 0x3f;
|
||||
memcpy(si->id, gpx.id, 9);
|
||||
si->validID = true;
|
||||
|
||||
int res=0;
|
||||
uint32_t t0 = millis();
|
||||
while( rxtask.receiveResult == 0xFFFF && millis()-t0 < 2000) { delay(20); }
|
||||
|
||||
if( rxtask.receiveResult<0 || rxtask.receiveResult==RX_TIMEOUT) {
|
||||
res = RX_TIMEOUT;
|
||||
} else if ( rxtask.receiveResult==0) {
|
||||
res = RX_OK;
|
||||
} else {
|
||||
res = RX_ERROR;
|
||||
}
|
||||
rxtask.receiveResult = 0xFFFF;
|
||||
Serial.printf("M10::waitRXcomplete returning %d (%s)\n", res, RXstr[res]);
|
||||
return res;
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
#if 0
|
||||
int oldwaitRXcomplete() {
|
||||
Serial.println("M10: receive frame...\n");
|
||||
sx1278receiveData = true;
|
||||
delay(6000); // done in other task....
|
||||
//sx1278receiveData = false;
|
||||
#if 0
|
||||
//sx1278.setPayloadLength(518-8); // Expect 320-8 bytes or 518-8 bytes (8 byte header)
|
||||
//sx1278.setPayloadLength(0); // infinite for now...
|
||||
|
||||
////// test code for continuous reception
|
||||
// sx1278.receive(); /// active FSK RX mode -- already done above...
|
||||
uint8_t value = sx1278.readRegister(REG_IRQ_FLAGS2);
|
||||
unsigned long previous = millis();
|
||||
|
||||
byte ready=0;
|
||||
uint32_t wait = 8000;
|
||||
// while not yet done or FIFO not yet empty
|
||||
// bit 6: FIFO Empty
|
||||
// bit 2 payload ready
|
||||
int by=0;
|
||||
while( (!ready || bitRead(value,6)==0) && (millis() - previous < wait) )
|
||||
{
|
||||
if( bitRead(value, 7) ) { Serial.println("FIFO full"); }
|
||||
if( bitRead(value, 4) ) { Serial.println("FIFO overflow"); }
|
||||
if( bitRead(value,2)==1 ) ready=1;
|
||||
if( bitRead(value, 6) == 0 ) { // FIFO not empty
|
||||
byte data = sx1278.readRegister(REG_FIFO);
|
||||
process8N1data(data);
|
||||
by++;
|
||||
#if 0
|
||||
if(di==1) {
|
||||
int rssi=getRSSI();
|
||||
int fei=getFEI();
|
||||
int afc=getAFC();
|
||||
Serial.print("Test: RSSI="); Serial.println(rssi);
|
||||
Serial.print("Test: FEI="); Serial.println(fei);
|
||||
Serial.print("Test: AFC="); Serial.println(afc);
|
||||
sonde.si()->rssi = rssi;
|
||||
sonde.si()->afc = afc;
|
||||
}
|
||||
if(di>520) {
|
||||
// TODO
|
||||
Serial.println("TOO MUCH DATA");
|
||||
break;
|
||||
}
|
||||
previous = millis(); // reset timeout after receiving data
|
||||
#endif
|
||||
}
|
||||
value = sx1278.readRegister(REG_IRQ_FLAGS2);
|
||||
}
|
||||
Serial.printf("processed %d bytes before end/timeout\n", by);
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
/////
|
||||
#if 0
|
||||
int e = sx1278.receivePacketTimeout(1000, data+8);
|
||||
if(e) { Serial.println("TIMEOUT"); return RX_TIMEOUT; } //if timeout... return 1
|
||||
|
||||
printRaw(data, M10MAXLEN);
|
||||
//for(int i=0; i<M10MAXLEN; i++) { data[i] = reverse(data[i]); }
|
||||
//printRaw(data, MAXLEN);
|
||||
//for(int i=0; i<M10MAXLEN; i++) { data[i] = data[i] ^ scramble[i&0x3F]; }
|
||||
//printRaw(data, MAXLEN);
|
||||
//int res = decode41(data, M10MAXLEN);
|
||||
#endif
|
||||
int res=0;
|
||||
return res==0 ? RX_OK : RX_ERROR;
|
||||
}
|
||||
#endif
|
||||
|
||||
M10 m10 = M10();
|
|
@ -0,0 +1,96 @@
|
|||
/*
|
||||
* M10.h
|
||||
* Functions for decoding Meteomodem M10 sondes with SX127x chips
|
||||
* Copyright (C) 2019 Hansi Reiser, dl9rdz
|
||||
*
|
||||
* SPDX-License-Identifier: GPL-2.0+
|
||||
*/
|
||||
|
||||
#ifndef M10_h
|
||||
#define M10_h
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <stdint.h>
|
||||
#include <Arduino.h>
|
||||
#ifndef inttypes_h
|
||||
#include <inttypes.h>
|
||||
#endif
|
||||
|
||||
#if 0
|
||||
struct CONTEXTR9 {
|
||||
char calibdata[512];
|
||||
uint32_t calibok;
|
||||
char mesok;
|
||||
char posok;
|
||||
char framesent;
|
||||
double lat;
|
||||
double lon;
|
||||
double heig;
|
||||
double speed;
|
||||
double dir;
|
||||
double climb;
|
||||
double lastlat;
|
||||
double laslong;
|
||||
double lastalt;
|
||||
double lastspeed;
|
||||
double lastdir;
|
||||
double lastclb;
|
||||
float hrmsc;
|
||||
float vrmsc;
|
||||
double hp;
|
||||
double hyg;
|
||||
double temp;
|
||||
double ozontemp;
|
||||
double ozon;
|
||||
uint32_t goodsats;
|
||||
uint32_t timems;
|
||||
uint32_t framenum;
|
||||
};
|
||||
#endif
|
||||
|
||||
/* Main class */
|
||||
class M10
|
||||
{
|
||||
private:
|
||||
void printRaw(uint8_t *data, int len);
|
||||
void processM10data(uint8_t data);
|
||||
int decodeframeM10(uint8_t *data);
|
||||
#if 0
|
||||
void stobyte92(uint8_t byte);
|
||||
void dogps(const uint8_t *sf, int sf_len,
|
||||
struct CONTEXTR9 * cont, uint32_t * timems,
|
||||
uint32_t * gpstime);
|
||||
uint32_t bits2val(const uint8_t *bits, int len);
|
||||
int bitsToBytes(uint8_t *bits, uint8_t *bytes, int len);
|
||||
int decode92(byte *data, int maxlen);
|
||||
|
||||
uint8_t hamming_conf[ 7*8]; // 7*8=56
|
||||
uint8_t hamming_dat1[13*8]; // 13*8=104
|
||||
uint8_t hamming_dat2[13*8];
|
||||
|
||||
uint8_t block_conf[ 7*4]; // 7*4=28
|
||||
uint8_t block_dat1[13*4]; // 13*4=52
|
||||
uint8_t block_dat2[13*4];
|
||||
|
||||
uint8_t H[4][8] = // extended Hamming(8,4) particy check matrix
|
||||
{{ 0, 1, 1, 1, 1, 0, 0, 0},
|
||||
{ 1, 0, 1, 1, 0, 1, 0, 0},
|
||||
{ 1, 1, 0, 1, 0, 0, 1, 0},
|
||||
{ 1, 1, 1, 0, 0, 0, 0, 1}};
|
||||
uint8_t He[8] = { 0x7, 0xB, 0xD, 0xE, 0x8, 0x4, 0x2, 0x1}; // Spalten von H:
|
||||
// 1-bit-error-Syndrome
|
||||
boolean initialized = false;
|
||||
#endif
|
||||
|
||||
public:
|
||||
M10();
|
||||
int setup(float frequency);
|
||||
int receive();
|
||||
int waitRXcomplete();
|
||||
|
||||
//int use_ecc = 1;
|
||||
};
|
||||
|
||||
extern M10 m10;
|
||||
|
||||
#endif
|
|
@ -143,9 +143,11 @@ int RS41::setup(float frequency)
|
|||
#if RS41_DEBUG
|
||||
RS41_DBG(Serial.println("Setting SX1278 config for RS41 finished\n"); Serial.println());
|
||||
#endif
|
||||
// go go go
|
||||
sx1278.setPayloadLength(RS41MAXLEN-8); // Expect 320-8 bytes or 518-8 bytes (8 byte header)
|
||||
sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE);
|
||||
sx1278.clearIRQFlags();
|
||||
|
||||
// the following is already done in receivePacketTimeout()
|
||||
// sx1278.setPayloadLength(RS41MAXLEN-8); // Expect 320-8 bytes or 518-8 bytes (8 byte header)
|
||||
// sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE);
|
||||
return retval;
|
||||
}
|
||||
|
||||
|
@ -304,6 +306,8 @@ static void wgs84r(double x, double y, double z,
|
|||
/* lat:=atan(z/(rh*(1.0 - E2))); */
|
||||
/* heig:=sqrt(h + z*z) - EARTHA; */
|
||||
} /* end wgs84r() */
|
||||
|
||||
// returns: 0=ok, -1=error
|
||||
static void posrs41(const byte b[], uint32_t b_len, uint32_t p)
|
||||
{
|
||||
double dir;
|
||||
|
@ -360,13 +364,19 @@ static void posrs41(const byte b[], uint32_t b_len, uint32_t p)
|
|||
Serial.print((float)vu);
|
||||
sonde.si()->vs = vu;
|
||||
Serial.print("m/s ");
|
||||
Serial.print(getcard16(b, b_len, p+18UL)&255UL);
|
||||
uint8_t sats = getcard16(b, b_len, p+18UL)&255UL;
|
||||
Serial.print(sats);
|
||||
Serial.print("Sats");
|
||||
sonde.si()->sats = sats;
|
||||
sonde.si()->alt = heig;
|
||||
if( 0==(int)(lat*10000) && 0==(int)(long0*10000) )
|
||||
sonde.si()->validPos = 0;
|
||||
if( 0==(int)(lat*10000) && 0==(int)(long0*10000) ) {
|
||||
if(sonde.si()->validPos) {
|
||||
// we have an old position, so keep previous position and mark it as old
|
||||
sonde.si()->validPos |= 0x80;
|
||||
}
|
||||
}
|
||||
else
|
||||
sonde.si()->validPos = 0x3f;
|
||||
sonde.si()->validPos = 0x7f;
|
||||
} /* end posrs41() */
|
||||
|
||||
|
||||
|
@ -381,16 +391,18 @@ int RS41::decode41(byte *data, int maxlen)
|
|||
if(corr<0) {
|
||||
corr = reedsolomon41(data, 560, 230); // try long frame
|
||||
}
|
||||
#if 0
|
||||
Serial.print("RS result:");
|
||||
Serial.print(corr);
|
||||
Serial.println();
|
||||
#endif
|
||||
int p = 57; // 8 byte header, 48 byte RS
|
||||
while(p<maxlen) { /* why 555? */
|
||||
uint8_t typ = data[p++];
|
||||
uint32_t len = data[p++]+2UL;
|
||||
if(p+len>maxlen) break;
|
||||
|
||||
#if 1
|
||||
#if 0
|
||||
// DEBUG OUTPUT
|
||||
Serial.print("@");
|
||||
Serial.print(p-2);
|
||||
|
@ -416,17 +428,50 @@ int RS41::decode41(byte *data, int maxlen)
|
|||
Serial.print("#");
|
||||
uint16_t fnr = data[p]+(data[p+1]<<8);
|
||||
Serial.print(fnr);
|
||||
sonde.si()->frame = fnr;
|
||||
Serial.print("; RS41 ID ");
|
||||
snprintf(buf, 10, "%.8s ", data+p+2);
|
||||
Serial.print(buf);
|
||||
sonde.si()->type=STYPE_RS41;
|
||||
strncpy(sonde.si()->id, (const char *)(data+p+2), 8);
|
||||
sonde.si()->id[8]=0;
|
||||
strncpy(sonde.si()->ser, (const char *)(data+p+2), 8);
|
||||
sonde.si()->ser[8]=0;
|
||||
sonde.si()->validID=true;
|
||||
int calnr = data[p+23];
|
||||
// not sure about this
|
||||
if(calnr==0x31) {
|
||||
uint16_t bt = data[p+30] + 256*data[p+31];
|
||||
sonde.si()->burstKT = bt;
|
||||
}
|
||||
// this should be right...
|
||||
if(calnr==0x02) {
|
||||
uint16_t kt = data[p+31] + 256*data[p+32];
|
||||
sonde.si()->launchKT = kt;
|
||||
}
|
||||
// and this seems fine as well...
|
||||
if(calnr==0x32) {
|
||||
uint16_t cntdown = data[p+24] + (data[p+25]<<8);
|
||||
uint16_t min = cntdown - (cntdown/3600)*3600;
|
||||
Serial.printf("Countdown value: %d\n [%2d:%02d:%02d]", cntdown, cntdown/3600, min/60, min-(min/60)*60);
|
||||
sonde.si()->countKT = cntdown;
|
||||
sonde.si()->crefKT = fnr;
|
||||
}
|
||||
}
|
||||
// TODO: some more data
|
||||
break;
|
||||
case '|': // date
|
||||
{
|
||||
uint32_t gpstime = getint32(data, 560, p+2);
|
||||
uint16_t gpsweek = getint16(data, 560, p);
|
||||
// UTC is GPSTIME - 18s (24*60*60-18 = 86382)
|
||||
// one week = 7*24*60*60 = 604800 seconds
|
||||
// unix epoch starts jan 1st 1970 0:00
|
||||
// gps time starts jan 6, 1980 0:00. thats 315964800 epoch seconds.
|
||||
// subtracting 86400 yields 315878400UL
|
||||
sonde.si()->time = (gpstime/1000) + 86382 + gpsweek*604800 + 315878400UL;
|
||||
sonde.si()->validTime = true;
|
||||
}
|
||||
break;
|
||||
case '{': // pos
|
||||
posrs41(data+p, len, 0);
|
||||
|
|
|
@ -183,6 +183,8 @@ int RS92::setup(float frequency)
|
|||
Serial.print("RS92: setting RX frequency to ");
|
||||
Serial.println(frequency);
|
||||
int res = sx1278.setFrequency(frequency);
|
||||
sx1278.clearIRQFlags();
|
||||
|
||||
// enable RX
|
||||
sx1278.setPayloadLength(0); // infinite for now...
|
||||
//sx1278.setPayloadLength(292);
|
||||
|
@ -622,7 +624,12 @@ int RS92::waitRXcomplete() {
|
|||
si->dir = gpx.vD;
|
||||
si->validPos = 0x3f;
|
||||
memcpy(si->id, gpx.id, 9);
|
||||
memcpy(si->ser, gpx.id, 9);
|
||||
si->validID = true;
|
||||
si->frame = gpx.frnr;
|
||||
si->sats = gpx.k;
|
||||
si->time = (gpx.gpssec/1000) + 86382 + gpx.week*604800 + 315878400UL;
|
||||
si->validTime = true;
|
||||
|
||||
#if 0
|
||||
int res=0;
|
||||
|
|
|
@ -5,83 +5,136 @@
|
|||
#include "Sonde.h"
|
||||
#include "Display.h"
|
||||
|
||||
#define CHANBW 10
|
||||
#define PIXSAMPL (50/CHANBW)
|
||||
#define SMOOTH 3
|
||||
|
||||
double STARTF;
|
||||
|
||||
|
||||
struct scancfg {
|
||||
int PLOT_W; // Width of plot, in pixel
|
||||
int PLOT_H8; // Height of plot, in 8 pixel units
|
||||
int TICK1; // Pixel per MHz marker
|
||||
int TICK2; // Pixel per sub-Mhz marker (250k or 200k)
|
||||
double CHANSTEP; // Scanner frequenz steps
|
||||
int SMPL_PIX; // Frequency steps per pixel
|
||||
int NCHAN; // number of channels to scan, PLOT_W * SMPL_PIX
|
||||
int SMOOTH;
|
||||
};
|
||||
|
||||
struct scancfg scanLCD={ 121, 7, 120/6, 120/6/4, 6000.0/120.0/10.0, 10, 120*10, 2 };
|
||||
struct scancfg scanTFT={ 210, 16, 210/6, 210/6/5, 6000.0/210.0/10.0, 10, 210*10, 1 };
|
||||
|
||||
struct scancfg &scanconfig = scanTFT;
|
||||
|
||||
#define CHANBW 12500
|
||||
//#define PIXSAMPL (50/CHANBW)
|
||||
//#define STARTF 401000000
|
||||
#define NCHAN ((int)(6000/CHANBW))
|
||||
|
||||
double STARTF = (sonde.config.startfreq * 1000000);
|
||||
//int CHANBW = (sonde.config.channelbw);
|
||||
//int NCHAN = ((int)(6000/CHANBW));
|
||||
//int PIXSAMPL = (50/CHANBW);
|
||||
// max of 120*5 and 210*3
|
||||
#define MAXN 210*10
|
||||
// max of 120 and 210 (ceil(210/8)*8))
|
||||
#define MAXDISP 216
|
||||
|
||||
int scanresult[NCHAN];
|
||||
int scandisp[NCHAN/PIXSAMPL];
|
||||
int scanresult[MAXN];
|
||||
int scandisp[MAXDISP];
|
||||
double peakf=0;
|
||||
|
||||
#define PLOT_N 128
|
||||
#define TICK1 (128/6)
|
||||
#define TICK2 (TICK1/4)
|
||||
//#define PLOT_MIN -250
|
||||
#define PLOT_MIN (sonde.config.noisefloor*2)
|
||||
#define PLOT_SCALE(x) (x<PLOT_MIN?0:(x-PLOT_MIN)/2)
|
||||
|
||||
const byte tilepatterns[9]={0,0x80,0xC0,0xE0,0xF0,0xF8,0xFC,0xFE,0xFF};
|
||||
void Scanner::fillTiles(uint8_t *row, int value) {
|
||||
for(int y=0; y<8; y++) {
|
||||
int nbits = value - 8*(7-y);
|
||||
for(int y=0; y<scanconfig.PLOT_H8; y++) {
|
||||
int nbits = value - 8*(scanconfig.PLOT_H8-1-y);
|
||||
if(nbits<0) { row[8*y]=0; continue; }
|
||||
if(nbits>=8) { row[8*y]=255; continue; }
|
||||
row[8*y] = tilepatterns[nbits];
|
||||
}
|
||||
}
|
||||
/*
|
||||
/* LCD:
|
||||
* There are 16*8 columns to plot, NPLOT must be lower than that
|
||||
* currently, we use 128 * 50kHz channels
|
||||
* There are 8*8 values to plot; MIN is bottom end,
|
||||
* TFT:
|
||||
* There are 210 columns to plot
|
||||
* Currently we use 210 * (6000/120)kHz channels, i.e. 28.5714kHz
|
||||
*/
|
||||
uint8_t tiles[16] = { 0x0f,0x0f,0x0f,0x0f,0xf0,0xf0,0xf0,0xf0, 1, 3, 7, 15, 31, 63, 127, 255};
|
||||
///// unused???? uint8_t tiles[16] = { 0x0f,0x0f,0x0f,0x0f,0xf0,0xf0,0xf0,0xf0, 1, 3, 7, 15, 31, 63, 127, 255};
|
||||
void Scanner::plotResult()
|
||||
{
|
||||
uint8_t row[8*8];
|
||||
for(int i=0; i<PLOT_N; i+=8) {
|
||||
int yofs = 0;
|
||||
char buf[30];
|
||||
if(sonde.config.disptype != 0) {
|
||||
yofs = 2;
|
||||
if (sonde.config.marker != 0) {
|
||||
itoa((sonde.config.startfreq), buf, 10);
|
||||
disp.rdis->drawString(0, 1, buf);
|
||||
disp.rdis->drawString(95, 1, "MHz");
|
||||
itoa((sonde.config.startfreq + 6), buf, 10);
|
||||
disp.rdis->drawString(195, 1, buf);
|
||||
}
|
||||
}
|
||||
else {
|
||||
if (sonde.config.marker != 0) {
|
||||
itoa((sonde.config.startfreq), buf, 10);
|
||||
disp.rdis->drawString(0, 1, buf);
|
||||
disp.rdis->drawString(7, 1, "MHz");
|
||||
itoa((sonde.config.startfreq + 6), buf, 10);
|
||||
disp.rdis->drawString(13, 1, buf);
|
||||
}
|
||||
}
|
||||
uint8_t row[scanconfig.PLOT_H8*8];
|
||||
for(int i=0; i<scanconfig.PLOT_W; i+=8) {
|
||||
for(int j=0; j<8; j++) {
|
||||
fillTiles(row+j, PLOT_SCALE(scandisp[i+j]));
|
||||
if( ((i+j)%TICK1)==0) { row[j] |= 0x07; }
|
||||
if( ((i+j)%TICK2)==0) { row[j] |= 0x01; }
|
||||
if( (i+j)>=scanconfig.PLOT_W ) { for(int y=0; y<scanconfig.PLOT_H8; y++) row[j+8*y]=0; }
|
||||
if( ((i+j)%scanconfig.TICK1)==0) { row[j] |= 0x07; }
|
||||
if( ((i+j)%scanconfig.TICK2)==0) { row[j] |= 0x01; }
|
||||
}
|
||||
for(int y=0; y<8; y++) {
|
||||
if(sonde.config.marker && y==1) {
|
||||
for(int y=0; y<scanconfig.PLOT_H8; y++) {
|
||||
if(sonde.config.marker && y==1 && sonde.config.disptype==0 ) {
|
||||
// don't overwrite MHz marker text
|
||||
if(i<3*8 || (i>=7*8&&i<10*8) || i>=13*8) continue;
|
||||
}
|
||||
disp.rdis->drawTile(i/8, y, 1, row+8*y);
|
||||
disp.rdis->drawTile(i/8, y+yofs, 1, row+8*y);
|
||||
}
|
||||
}
|
||||
if(sonde.config.disptype != 0) { // large TFT
|
||||
sprintf(buf, "Peak: %03.3f MHz", peakf*0.000001);
|
||||
disp.rdis->drawString(0, (yofs+scanconfig.PLOT_H8+1)*8, buf);
|
||||
} else {
|
||||
sprintf(buf, "Peak: %03.3fMHz", peakf*0.000001);
|
||||
disp.rdis->drawString(0, 7, buf);
|
||||
}
|
||||
}
|
||||
|
||||
void Scanner::scan()
|
||||
{
|
||||
#if 0
|
||||
// Test only
|
||||
for(int i=0; i<PLOT_N; i++) {
|
||||
scandisp[i] = 30*sin(2*3.1415*i/50)-180;
|
||||
if(sonde.config.disptype==0) { // LCD small
|
||||
scanconfig = scanLCD;
|
||||
} else {
|
||||
scanconfig = scanTFT;
|
||||
}
|
||||
return;
|
||||
#endif
|
||||
// Configure
|
||||
STARTF = (sonde.config.startfreq * 1000000);
|
||||
sx1278.writeRegister(REG_PLL_HOP, 0x80); // FastHopOn
|
||||
sx1278.setRxBandwidth(CHANBW*1000);
|
||||
sx1278.writeRegister(REG_RSSI_CONFIG, SMOOTH&0x07);
|
||||
sx1278.setRxBandwidth((int)(scanconfig.CHANSTEP*1000));
|
||||
double bw = sx1278.getRxBandwidth();
|
||||
Serial.print("RX Bandwith for scan: "); Serial.println(bw);
|
||||
sx1278.writeRegister(REG_RSSI_CONFIG, scanconfig.SMOOTH&0x07);
|
||||
sx1278.setFrequency(STARTF);
|
||||
Serial.print("Start freq = "); Serial.println(STARTF);
|
||||
sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE);
|
||||
delay(20);
|
||||
|
||||
unsigned long start = millis();
|
||||
uint32_t lastfrf=-1;
|
||||
for(int iter=0; iter<2; iter++) { // two interations, to catch all RS41 transmissions
|
||||
for(int i=0; i<NCHAN; i++) {
|
||||
float freq = STARTF + 1000.0*i*CHANBW;
|
||||
uint32_t lastfrf= STARTF * (1<<19) / SX127X_CRYSTAL_FREQ;
|
||||
float freq;
|
||||
int wait = 20 + 1000*(1<<(scanconfig.SMOOTH+1))/4/(0.001*CHANBW);
|
||||
for(int iter=0; iter<3; iter++) { // two interations, to catch all RS41 transmissions
|
||||
delayMicroseconds(20000);
|
||||
for(int i=0; i<scanconfig.PLOT_W*scanconfig.SMPL_PIX; i++) {
|
||||
freq = STARTF + 1000.0*i*scanconfig.CHANSTEP;
|
||||
//freq = 404000000 + 100*i*scanconfig.CHANSTEP;
|
||||
uint32_t frf = freq * 1.0 * (1<<19) / SX127X_CRYSTAL_FREQ;
|
||||
if( (lastfrf>>16)!=(frf>>16) ) {
|
||||
sx1278.writeRegister(REG_FRF_MSB, (frf&0xff0000)>>16);
|
||||
|
@ -91,9 +144,8 @@ void Scanner::scan()
|
|||
}
|
||||
sx1278.writeRegister(REG_FRF_LSB, (frf&0x0000ff));
|
||||
lastfrf = frf;
|
||||
// Wait TS_HOP (20us) + TS_RSSI ( 2^(SMOOTH+1) / 4 / CHANBW us)
|
||||
int wait = 20 + 1000*(1<<(SMOOTH+1))/4/CHANBW;
|
||||
delayMicroseconds(wait+5);
|
||||
// Wait TS_HOP (20us) + TS_RSSI ( 2^(scacconfig.SMOOTH+1) / 4 / CHANBW us)
|
||||
delayMicroseconds(wait);
|
||||
int rssi = -(int)sx1278.readRegister(REG_RSSI_VALUE_FSK);
|
||||
if(iter==0) { scanresult[i] = rssi; } else {
|
||||
if(rssi>scanresult[i]) scanresult[i]=rssi;
|
||||
|
@ -101,20 +153,37 @@ void Scanner::scan()
|
|||
}
|
||||
}
|
||||
unsigned long duration = millis()-start;
|
||||
Serial.print("wait: ");
|
||||
Serial.println(wait);
|
||||
Serial.print("Scan time: ");
|
||||
Serial.println(duration);
|
||||
for(int i=0; i<NCHAN; i+=PIXSAMPL) {
|
||||
scandisp[i/PIXSAMPL]=scanresult[i];
|
||||
for(int j=1; j<PIXSAMPL; j++) { scandisp[i/PIXSAMPL]+=scanresult[i+j]; }
|
||||
Serial.print("Final freq: ");
|
||||
Serial.println(freq);
|
||||
int peakidx=-1;
|
||||
int peakres=-9999;
|
||||
for(int i=0; i<scanconfig.PLOT_W; i+=1) {
|
||||
scandisp[i]=scanresult[i*scanconfig.SMPL_PIX];
|
||||
for(int j=1; j<scanconfig.SMPL_PIX; j++) {
|
||||
int r = scanresult[i*scanconfig.SMPL_PIX+j];
|
||||
scandisp[i]+=r;
|
||||
if(r>peakres+1) { peakres=r; peakidx=i*scanconfig.SMPL_PIX+j; }
|
||||
}
|
||||
//for(int j=1; j<PIXSAMPL; j++) { if(scanresult[i+j]>scandisp[i/PIXSAMPL]) scandisp[i/PIXSAMPL] = scanresult[i+j]; }
|
||||
Serial.print(scanresult[i]); Serial.print(", ");
|
||||
}
|
||||
peakidx--;
|
||||
double newpeakf = STARTF + scanconfig.CHANSTEP*1000.0*peakidx;
|
||||
if(newpeakf<peakf-20000 || newpeakf>peakf+20000) peakf=newpeakf; // different frequency
|
||||
else if (newpeakf < peakf) peakf = 0.75*newpeakf + 0.25*peakf; // averaging on frequency, some bias towards lower...
|
||||
else peakf = 0.25*newpeakf + 0.75*peakf;
|
||||
Serial.println("\n");
|
||||
for(int i=0; i<NCHAN/PIXSAMPL; i++) {
|
||||
scandisp[i]/=PIXSAMPL;
|
||||
for(int i=0; i<scanconfig.PLOT_W; i++) {
|
||||
scandisp[i]/=scanconfig.SMPL_PIX;
|
||||
Serial.print(scandisp[i]); Serial.print(", ");
|
||||
}
|
||||
Serial.println("\n");
|
||||
Serial.print("Peak: ");
|
||||
Serial.print(peakf);
|
||||
}
|
||||
|
||||
Scanner scanner = Scanner();
|
||||
|
|
|
@ -5,8 +5,10 @@
|
|||
#include "RS41.h"
|
||||
#include "RS92.h"
|
||||
#include "DFM.h"
|
||||
#include "M10.h"
|
||||
#include "SX1278FSK.h"
|
||||
#include "Display.h"
|
||||
#include <Wire.h>
|
||||
|
||||
extern SX1278FSK sx1278;
|
||||
|
||||
|
@ -17,6 +19,18 @@ const char *evstring[]={"NONE", "KEY1S", "KEY1D", "KEY1M", "KEY1L", "KEY2S", "KE
|
|||
|
||||
const char *RXstr[]={"RX_OK", "RX_TIMEOUT", "RX_ERROR", "RX_UNKNOWN"};
|
||||
|
||||
int fingerprintValue[]={ 17, 31, 64, 4, 55, 48, 23, 128+23, -1 };
|
||||
const char *fingerprintText[]={
|
||||
"TTGO T-Beam (new version 1.0), I2C not working after powerup, assuming 0.9\" OLED@21,22",
|
||||
"TTGO LORA32 v2.1_1.6 (0.9\" OLED@21,22)",
|
||||
"TTGO LORA v1.0 (0.9\" OLED@4,15)",
|
||||
"Heltec v1/v2 (0.9\"OLED@4,15)",
|
||||
"TTGO T-Beam (old version), 0.9\" OLED@21,22",
|
||||
"TTGO T-Beam (old version), SPI TFT@4,21,22",
|
||||
"TTGO T-Beam (new version 1.0), 0.9\" OLED@21,22",
|
||||
"TTGO T-Beam (new version 1.0), SPI TFT@4,13,14",
|
||||
};
|
||||
|
||||
int getKeyPressEvent(); /* in RX_FSK.ino */
|
||||
|
||||
/* Task model:
|
||||
|
@ -39,72 +53,115 @@ Sonde::Sonde() {
|
|||
for (int i = 0; i < 39; i++) {
|
||||
initlevels[i] = gpio_get_level((gpio_num_t)i);
|
||||
}
|
||||
for (int i = 0; i < 39*3; i++) {
|
||||
initlevels[i%39] += gpio_get_level((gpio_num_t)(i%39));
|
||||
}
|
||||
}
|
||||
|
||||
void Sonde::defaultConfig() {
|
||||
fingerprint = initlevels[4];
|
||||
fingerprint = (fingerprint<<1) | initlevels[12];
|
||||
fingerprint = (fingerprint<<1) | initlevels[16];
|
||||
fingerprint = (fingerprint<<1) | initlevels[17];
|
||||
fingerprint = (fingerprint<<1) | initlevels[21];
|
||||
fingerprint = (fingerprint<<1) | initlevels[22];
|
||||
fingerprint = (fingerprint<<1) | initlevels[23];
|
||||
Serial.printf("Board fingerprint is %d\n", fingerprint);
|
||||
|
||||
sondeList = (SondeInfo *)malloc((MAXSONDE+1)*sizeof(SondeInfo));
|
||||
memset(sondeList, 0, (MAXSONDE+1)*sizeof(SondeInfo));
|
||||
config.touch_thresh = 70;
|
||||
config.led_pout = 9;
|
||||
config.led_pout = -1;
|
||||
config.power_pout = -1;
|
||||
config.spectrum=10;
|
||||
// Try autodetecting board type
|
||||
// Seems like on startup, GPIO4 is 1 on v1 boards, 0 on v2.1 boards?
|
||||
config.gps_rxd = -1;
|
||||
config.gps_txd = -1;
|
||||
config.oled_rst = 16;
|
||||
config.disptype = 0;
|
||||
config.tft_orient = 1;
|
||||
config.button2_axp = 0;
|
||||
config.norx_timeout = 20;
|
||||
if(initlevels[16]==0) {
|
||||
config.oled_sda = 4;
|
||||
config.oled_scl = 15;
|
||||
config.button_pin = 0;
|
||||
config.button2_pin = T4 + 128; // T4 == GPIO13
|
||||
config.power_pout = 21; // for Heltec v2
|
||||
config.led_pout = 2;
|
||||
Serial.println("Autoconfig: looks like TTGO v1 / Heltec v1/V2 board");
|
||||
} else {
|
||||
config.oled_sda = 21;
|
||||
config.oled_scl = 22;
|
||||
if(initlevels[17]==0) { // T-Beam
|
||||
if(initlevels[12]==0) { // T-Beam v1.0
|
||||
Serial.println("Autoconfig: looks like T-Beam 1.0 board");
|
||||
config.button_pin = 38;
|
||||
config.button2_pin = -1; //T4 + 128; // T4 = GPIO13
|
||||
config.button2_pin = 15 + 128; //T4 + 128; // T4 = GPIO13
|
||||
// Maybe in future use as default only PWR as button2?
|
||||
//config.button2_pin = 255;
|
||||
config.button2_axp = 1;
|
||||
config.gps_rxd = 34;
|
||||
// for now, lets assume TFT display / SPI
|
||||
// CS=0, RST=14, RS=2, SDA=4, CLK=13
|
||||
config.disptype = 1;
|
||||
config.oled_sda = 4;
|
||||
config.oled_scl = 13;
|
||||
config.oled_rst = 14;
|
||||
config.tft_rs = 2;
|
||||
config.tft_cs = 0;
|
||||
// Check for I2C-Display@21,22
|
||||
#define SSD1306_ADDRESS 0x3c
|
||||
Wire.begin(21, 22);
|
||||
Wire.beginTransmission(SSD1306_ADDRESS);
|
||||
byte err = Wire.endTransmission();
|
||||
delay(100); // otherwise its too fast?!
|
||||
Wire.beginTransmission(SSD1306_ADDRESS);
|
||||
err = Wire.endTransmission();
|
||||
if(err!=0 && fingerprint!=17) { // hmm. 17 after powerup with oled commected and no i2c answer!?!?
|
||||
fingerprint |= 128;
|
||||
Serial.println("no I2C display found, assuming large TFT display\n");
|
||||
// CS=0, RST=14, RS=2, SDA=4, CLK=13
|
||||
Serial.println("... with large TFT display\n");
|
||||
config.disptype = 1;
|
||||
config.oled_sda = 4;
|
||||
config.oled_scl = 13;
|
||||
config.oled_rst = 14;
|
||||
config.tft_rs = 2;
|
||||
config.tft_cs = 0;
|
||||
config.spectrum = -1; // no spectrum for now on large display
|
||||
} else {
|
||||
// OLED display, pins 21,22 ok...
|
||||
config.disptype = 0;
|
||||
Serial.println("... with small OLED display\n");
|
||||
}
|
||||
} else {
|
||||
Serial.println("Autoconfig: looks like T-Beam v0.7 board");
|
||||
config.button_pin = 39;
|
||||
config.button2_pin = T4 + 128; // T4 == GPIO13
|
||||
config.gps_rxd = 12;
|
||||
// Check if we possibly have a large display
|
||||
if(initlevels[21]==0) {
|
||||
Serial.println("Autoconfig: looks like T-Beam v0.7 board with large TFT display");
|
||||
config.disptype = 1;
|
||||
config.oled_sda = 4;
|
||||
config.oled_scl = 21;
|
||||
config.oled_rst = 22;
|
||||
config.tft_rs = 2;
|
||||
config.tft_cs = 0;
|
||||
config.spectrum = -1; // no spectrum for now on large display
|
||||
}
|
||||
}
|
||||
} else {
|
||||
config.button_pin = 2 + 128; // GPIO2 / T2
|
||||
config.button2_pin = 14 + 128; // GPIO14 / T6
|
||||
config.led_pout = 25;
|
||||
}
|
||||
}
|
||||
//
|
||||
config.noisefloor = -125;
|
||||
strcpy(config.call,"NOCALL");
|
||||
strcpy(config.passcode, "---");
|
||||
strcpy(config.mdnsname, "rdzsonde");
|
||||
config.maxsonde=15;
|
||||
config.debug=0;
|
||||
config.wifi=1;
|
||||
config.wifiap=1;
|
||||
config.display=1;
|
||||
config.display[0]=0;
|
||||
config.display[1]=1;
|
||||
config.display[2]=-1;
|
||||
config.startfreq=400;
|
||||
config.channelbw=10;
|
||||
config.spectrum=10;
|
||||
config.timer=0;
|
||||
config.marker=0;
|
||||
config.showafc=0;
|
||||
config.freqofs=0;
|
||||
|
@ -128,6 +185,7 @@ Sonde::Sonde() {
|
|||
config.tcpfeed.port = 12345;
|
||||
config.tcpfeed.highrate = 10;
|
||||
config.tcpfeed.idformat = ID_DFMDXL;
|
||||
config.kisstnc.active = 0;
|
||||
}
|
||||
|
||||
void Sonde::setConfig(const char *cfg) {
|
||||
|
@ -144,16 +202,21 @@ void Sonde::setConfig(const char *cfg) {
|
|||
if(config.noisefloor==0) config.noisefloor=-130;
|
||||
} else if(strcmp(cfg,"call")==0) {
|
||||
strncpy(config.call, val, 9);
|
||||
config.call[9]=0;
|
||||
} else if(strcmp(cfg,"passcode")==0) {
|
||||
strncpy(config.passcode, val, 9);
|
||||
} else if(strcmp(cfg,"button_pin")==0) {
|
||||
config.button_pin = atoi(val);
|
||||
} else if(strcmp(cfg,"button2_pin")==0) {
|
||||
config.button2_pin = atoi(val);
|
||||
} else if(strcmp(cfg,"button2_axp")==0) {
|
||||
config.button2_axp = atoi(val);
|
||||
} else if(strcmp(cfg,"touch_thresh")==0) {
|
||||
config.touch_thresh = atoi(val);
|
||||
} else if(strcmp(cfg,"led_pout")==0) {
|
||||
config.led_pout = atoi(val);
|
||||
} else if(strcmp(cfg,"power_pout")==0) {
|
||||
config.power_pout = atoi(val);
|
||||
} else if(strcmp(cfg,"disptype")==0) {
|
||||
config.disptype = atoi(val);
|
||||
} else if(strcmp(cfg,"oled_sda")==0) {
|
||||
|
@ -166,6 +229,8 @@ void Sonde::setConfig(const char *cfg) {
|
|||
config.tft_rs = atoi(val);
|
||||
} else if(strcmp(cfg,"tft_cs")==0) {
|
||||
config.tft_cs = atoi(val);
|
||||
} else if(strcmp(cfg,"tft_orient")==0) {
|
||||
config.tft_orient = atoi(val);
|
||||
} else if(strcmp(cfg,"gps_rxd")==0) {
|
||||
config.gps_rxd = atoi(val);
|
||||
} else if(strcmp(cfg,"gps_txd")==0) {
|
||||
|
@ -179,17 +244,27 @@ void Sonde::setConfig(const char *cfg) {
|
|||
config.wifi = atoi(val);
|
||||
} else if(strcmp(cfg,"wifiap")==0) {
|
||||
config.wifiap = atoi(val);
|
||||
} else if(strcmp(cfg,"mdnsname")==0) {
|
||||
strncpy(config.mdnsname, val, 14);
|
||||
} else if(strcmp(cfg,"display")==0) {
|
||||
config.display = atoi(val);
|
||||
disp.setLayout(config.display);
|
||||
int i = 0;
|
||||
char *ptr;
|
||||
while(val) {
|
||||
ptr = strchr(val,',');
|
||||
if(ptr) *ptr = 0;
|
||||
config.display[i++] = atoi(val);
|
||||
val = ptr?ptr+1:NULL;
|
||||
Serial.printf("appending value %d next is %s\n", config.display[i-1], val?val:"");
|
||||
}
|
||||
config.display[i] = -1;
|
||||
} else if (strcmp(cfg, "norx_timeout")==0) {
|
||||
config.norx_timeout = atoi(val);
|
||||
} else if(strcmp(cfg,"startfreq")==0) {
|
||||
config.startfreq = atoi(val);
|
||||
} else if(strcmp(cfg,"channelbw")==0) {
|
||||
config.channelbw = atoi(val);
|
||||
} else if(strcmp(cfg,"spectrum")==0) {
|
||||
config.spectrum = atoi(val);
|
||||
} else if(strcmp(cfg,"timer")==0) {
|
||||
config.timer = atoi(val);
|
||||
} else if(strcmp(cfg,"marker")==0) {
|
||||
config.marker = atoi(val);
|
||||
} else if(strcmp(cfg,"showafc")==0) {
|
||||
|
@ -206,6 +281,10 @@ void Sonde::setConfig(const char *cfg) {
|
|||
config.dfm.rxbw = atoi(val);
|
||||
} else if(strcmp(cfg,"rs92.alt2d")==0) {
|
||||
config.rs92.alt2d= atoi(val);
|
||||
} else if(strcmp(cfg,"kisstnc.active")==0) {
|
||||
config.kisstnc.active = atoi(val);
|
||||
} else if(strcmp(cfg,"kisstnc.idformat")==0) {
|
||||
config.kisstnc.idformat = atoi(val);
|
||||
} else if(strcmp(cfg,"rs92.rxbw")==0) {
|
||||
config.rs92.rxbw = atoi(val);
|
||||
} else if(strcmp(cfg,"axudp.active")==0) {
|
||||
|
@ -237,12 +316,9 @@ void Sonde::setConfig(const char *cfg) {
|
|||
}
|
||||
}
|
||||
|
||||
void Sonde::clearIP() {
|
||||
disp.clearIP();
|
||||
}
|
||||
|
||||
void Sonde::setIP(const char *ip, bool AP) {
|
||||
disp.setIP(ip, AP);
|
||||
void Sonde::setIP(String ip, bool AP) {
|
||||
ipaddr = ip;
|
||||
isAP = AP;
|
||||
}
|
||||
|
||||
void Sonde::clearSonde() {
|
||||
|
@ -269,7 +345,7 @@ void Sonde::nextConfig() {
|
|||
currentSonde=0;
|
||||
}
|
||||
// Skip non-active entries (but don't loop forever if there are no active ones)
|
||||
for(int i=0; i<config.maxsonde; i++) {
|
||||
for(int i=0; i<config.maxsonde - 1; i++) {
|
||||
if(!sondeList[currentSonde].active) {
|
||||
currentSonde++;
|
||||
if(currentSonde>=nSonde) currentSonde=0;
|
||||
|
@ -281,7 +357,7 @@ void Sonde::nextRxSonde() {
|
|||
if(rxtask.currentSonde>=nSonde) {
|
||||
rxtask.currentSonde=0;
|
||||
}
|
||||
for(int i=0; i<config.maxsonde; i++) {
|
||||
for(int i=0; i<config.maxsonde - 1; i++) {
|
||||
if(!sondeList[rxtask.currentSonde].active) {
|
||||
rxtask.currentSonde++;
|
||||
if(rxtask.currentSonde>=nSonde) rxtask.currentSonde=0;
|
||||
|
@ -289,6 +365,15 @@ void Sonde::nextRxSonde() {
|
|||
}
|
||||
Serial.printf("nextRxSonde: %d\n", rxtask.currentSonde);
|
||||
}
|
||||
void Sonde::nextRxFreq(int addkhz) {
|
||||
// last entry is for the variable frequency
|
||||
rxtask.currentSonde = nSonde - 1;
|
||||
sondeList[rxtask.currentSonde].active = 1;
|
||||
sondeList[rxtask.currentSonde].freq += addkhz*0.001;
|
||||
if(sondeList[rxtask.currentSonde].freq>406)
|
||||
sondeList[rxtask.currentSonde].freq = 400;
|
||||
Serial.printf("nextRxFreq: %d\n", rxtask.currentSonde);
|
||||
}
|
||||
SondeInfo *Sonde::si() {
|
||||
return &sondeList[currentSonde];
|
||||
}
|
||||
|
@ -298,7 +383,14 @@ void Sonde::setup() {
|
|||
Serial.print("Invalid rxtask.currentSonde: ");
|
||||
Serial.println(rxtask.currentSonde);
|
||||
rxtask.currentSonde = 0;
|
||||
}
|
||||
for(int i=0; i<config.maxsonde - 1; i++) {
|
||||
if(!sondeList[rxtask.currentSonde].active) {
|
||||
rxtask.currentSonde++;
|
||||
if(rxtask.currentSonde>=nSonde) rxtask.currentSonde=0;
|
||||
}
|
||||
}
|
||||
sonde.currentSonde = rxtask.currentSonde;
|
||||
}
|
||||
|
||||
// update receiver config
|
||||
Serial.print("\nSonde::setup() on sonde index ");
|
||||
|
@ -313,6 +405,10 @@ void Sonde::setup() {
|
|||
break;
|
||||
case STYPE_RS92:
|
||||
rs92.setup( sondeList[rxtask.currentSonde].freq * 1000000);
|
||||
break;
|
||||
case STYPE_M10:
|
||||
m10.setup( sondeList[rxtask.currentSonde].freq * 1000000);
|
||||
break;
|
||||
}
|
||||
// debug
|
||||
float afcbw = sx1278.getAFCBandwidth();
|
||||
|
@ -320,6 +416,8 @@ void Sonde::setup() {
|
|||
Serial.printf("AFC BW: %f RX BW: %f\n", afcbw, rxbw);
|
||||
}
|
||||
|
||||
extern void flashLed(int ms);
|
||||
|
||||
void Sonde::receive() {
|
||||
uint16_t res = 0;
|
||||
SondeInfo *si = &sondeList[rxtask.currentSonde];
|
||||
|
@ -330,6 +428,9 @@ void Sonde::receive() {
|
|||
case STYPE_RS92:
|
||||
res = rs92.receive();
|
||||
break;
|
||||
case STYPE_M10:
|
||||
res = m10.receive();
|
||||
break;
|
||||
case STYPE_DFM06:
|
||||
case STYPE_DFM09:
|
||||
res = dfm.receive();
|
||||
|
@ -338,17 +439,20 @@ void Sonde::receive() {
|
|||
|
||||
// state information for RX_TIMER / NORX_TIMER events
|
||||
if(res==0) { // RX OK
|
||||
flashLed(700);
|
||||
if(si->lastState != 1) {
|
||||
si->rxStart = millis();
|
||||
si->lastState = 1;
|
||||
}
|
||||
} else { // RX not ok
|
||||
if(res==RX_ERROR) flashLed(100);
|
||||
Serial.printf("RX result %d, laststate was %d\n", res, si->lastState);
|
||||
if(si->lastState != 0) {
|
||||
si->norxStart = millis();
|
||||
si->lastState = 0;
|
||||
}
|
||||
}
|
||||
Serial.printf("debug: res was %d, now lastState is %d\n", res, si->lastState);
|
||||
// Serial.printf("debug: res was %d, now lastState is %d\n", res, si->lastState);
|
||||
|
||||
|
||||
// we should handle timer events here, because after returning from receive,
|
||||
|
@ -362,9 +466,12 @@ void Sonde::receive() {
|
|||
// If action is to move to a different sonde index, we do update things here, set activate
|
||||
// to force the sx1278 task to call sonde.setup(), and pass information about sonde to
|
||||
// main loop (display update...)
|
||||
if(action == ACT_NEXTSONDE || action==ACT_PREVSONDE) {
|
||||
if(action == ACT_NEXTSONDE || action==ACT_PREVSONDE || (action>64&&action<128) ) {
|
||||
// handled here...
|
||||
nextRxSonde();
|
||||
if(action==ACT_NEXTSONDE||action==ACT_PREVSONDE)
|
||||
nextRxSonde();
|
||||
else
|
||||
nextRxFreq( action-64 );
|
||||
action = ACT_SONDE(rxtask.currentSonde);
|
||||
if(rxtask.activate==-1) {
|
||||
// race condition here. maybe better use mutex. TODO
|
||||
|
@ -382,15 +489,16 @@ uint16_t Sonde::waitRXcomplete() {
|
|||
uint16_t res=0;
|
||||
uint32_t t0 = millis();
|
||||
rxloop:
|
||||
while( rxtask.receiveResult==0xFFFF && millis()-t0 < 2000) { delay(50); }
|
||||
while( rxtask.receiveResult==0xFFFF && millis()-t0 < 3000) { delay(50); }
|
||||
if( rxtask.receiveResult == RX_UPDATERSSI ) {
|
||||
Serial.println("RSSI update");
|
||||
rxtask.receiveResult = 0xFFFF;
|
||||
Serial.print("RSSI update: ");
|
||||
disp.updateDisplayRSSI();
|
||||
goto rxloop;
|
||||
}
|
||||
|
||||
if( rxtask.receiveResult==0xFFFF) {
|
||||
Serial.println("TIMEOUT in waitRXcomplete. Should never happen!\n");
|
||||
res = RX_TIMEOUT;
|
||||
} else {
|
||||
res = rxtask.receiveResult;
|
||||
|
@ -406,6 +514,9 @@ rxloop:
|
|||
case STYPE_RS92:
|
||||
rs92.waitRXcomplete();
|
||||
break;
|
||||
case STYPE_M10:
|
||||
m10.waitRXcomplete();
|
||||
break;
|
||||
case STYPE_DFM06:
|
||||
case STYPE_DFM09:
|
||||
dfm.waitRXcomplete();
|
||||
|
@ -456,14 +567,31 @@ uint8_t Sonde::updateState(uint8_t event) {
|
|||
}
|
||||
int n = event;
|
||||
if(event==ACT_DISPLAY_DEFAULT) {
|
||||
n = config.display;
|
||||
n = config.display[1];
|
||||
} else if(event==ACT_DISPLAY_SCANNER) {
|
||||
n= config.display[0];
|
||||
} else if(event==ACT_DISPLAY_NEXT) {
|
||||
int i;
|
||||
for(i=0; config.display[i]!=-1; i++) {
|
||||
if(config.display[i] == disp.layoutIdx) break;
|
||||
}
|
||||
if(config.display[i]==-1 || config.display[i+1]==-1) {
|
||||
//unknown index, or end of list => loop to start
|
||||
n = config.display[1];
|
||||
} else {
|
||||
n = config.display[i+1];
|
||||
}
|
||||
}
|
||||
if(n>=0&&n<5) {
|
||||
if(n>=0 && n<ACT_MAXDISPLAY) {
|
||||
if(n>=disp.nLayouts) {
|
||||
Serial.println("WARNNG: next layout out of range");
|
||||
n = config.display[1];
|
||||
}
|
||||
Serial.printf("Setting display mode %d\n", n);
|
||||
disp.setLayout(n);
|
||||
sonde.clearDisplay();
|
||||
return 0xFF;
|
||||
}
|
||||
}
|
||||
|
||||
// Moving to a different value for currentSonde
|
||||
// TODO: THis should be done in sx1278 task, not in main loop!!!!!
|
||||
|
@ -513,15 +641,11 @@ void Sonde::updateDisplayIP() {
|
|||
disp.updateDisplayIP();
|
||||
}
|
||||
|
||||
void Sonde::updateDisplayScanner() {
|
||||
disp.setLayout(0);
|
||||
disp.updateDisplay();
|
||||
disp.setLayout(config.display);
|
||||
}
|
||||
|
||||
void Sonde::updateDisplay()
|
||||
{
|
||||
int t = millis();
|
||||
disp.updateDisplay();
|
||||
Serial.printf("updateDisplay took %d ms\n", (int)(millis()-t));
|
||||
}
|
||||
|
||||
void Sonde::clearDisplay() {
|
||||
|
|
|
@ -2,8 +2,6 @@
|
|||
#ifndef Sonde_h
|
||||
#define Sonde_h
|
||||
|
||||
#include "aprs.h"
|
||||
|
||||
// RX_TIMEOUT: no header detected
|
||||
// RX_ERROR: header detected, but data not decoded (crc error, etc.)
|
||||
// RX_OK: header and data ok
|
||||
|
@ -33,19 +31,63 @@ extern const char *RXstr[];
|
|||
//int8_t actions[EVT_MAX];
|
||||
#define ACT_NONE 255
|
||||
#define ACT_DISPLAY(n) (n)
|
||||
#define ACT_MAXDISPLAY 50
|
||||
#define ACT_DISPLAY_SCANNER 0
|
||||
#define ACT_DISPLAY_NEXT 64
|
||||
#define ACT_DISPLAY_DEFAULT 63
|
||||
#define ACT_DISPLAY_SPECTRUM 62
|
||||
#define ACT_DISPLAY_WIFI 61
|
||||
#define ACT_NEXTSONDE 65
|
||||
#define ACT_PREVSONDE 66
|
||||
#define ACT_ADDFREQ(n) ((n)+64)
|
||||
#define ACT_SONDE(n) ((n)+128)
|
||||
|
||||
// 0000nnnn => goto display nnnn
|
||||
// 01000000 => goto sonde -1
|
||||
// 01000001 => goto sonde +1
|
||||
|
||||
enum SondeType { STYPE_DFM06, STYPE_DFM09, STYPE_RS41, STYPE_RS92 };
|
||||
extern const char *sondeTypeStr[5];
|
||||
#define NSondeTypes 5
|
||||
enum SondeType { STYPE_DFM06, STYPE_DFM09, STYPE_RS41, STYPE_RS92, STYPE_M10 };
|
||||
extern const char *sondeTypeStr[NSondeTypes];
|
||||
|
||||
typedef struct st_sondeinfo {
|
||||
// receiver configuration
|
||||
bool active;
|
||||
SondeType type;
|
||||
float freq;
|
||||
// decoded ID
|
||||
char id[10];
|
||||
char ser[12];
|
||||
bool validID;
|
||||
char launchsite[18];
|
||||
// decoded position
|
||||
float lat; // latitude
|
||||
float lon; // longitude
|
||||
float alt; // altitude
|
||||
float vs; // vertical speed
|
||||
float hs; // horizontal speed
|
||||
float dir; // 0..360
|
||||
uint8_t sats; // number of sats
|
||||
uint8_t validPos; // bit pattern for validity of above 7 fields; 0x80: position is old
|
||||
// decoded GPS time
|
||||
uint32_t time;
|
||||
uint16_t sec;
|
||||
uint32_t frame;
|
||||
bool validTime;
|
||||
// RSSI from receiver
|
||||
int rssi; // signal strength
|
||||
int32_t afc; // afc correction value
|
||||
// statistics
|
||||
uint8_t rxStat[20];
|
||||
uint32_t rxStart; // millis() timestamp of continuous rx start
|
||||
uint32_t norxStart; // millis() timestamp of continuous no rx start
|
||||
uint32_t viewStart; // millis() timestamp of viewinf this sonde with current display
|
||||
int8_t lastState; // -1: disabled; 0: norx; 1: rx
|
||||
// shut down timers, currently only for RS41; -1=disabled
|
||||
int16_t launchKT, burstKT, countKT;
|
||||
uint16_t crefKT; // frame number in which countKT was last sent
|
||||
} SondeInfo;
|
||||
// rxStat: 3=undef[empty] 1=timeout[.] 2=errro[E] 0=ok[|] 4=no valid position[°]
|
||||
|
||||
// Used for interacting with the RX background task
|
||||
typedef struct st_RXTask {
|
||||
|
@ -80,94 +122,103 @@ struct st_dfmconfig {
|
|||
int rxbw;
|
||||
};
|
||||
|
||||
|
||||
enum IDTYPE { ID_DFMDXL, ID_DFMGRAW, ID_DFMAUTO };
|
||||
|
||||
struct st_feedinfo {
|
||||
bool active;
|
||||
int type; // 0:UDP(axudp), 1:TCP(aprs.fi)
|
||||
char host[64];
|
||||
int port;
|
||||
char symbol[3];
|
||||
int lowrate;
|
||||
int highrate;
|
||||
int lowlimit;
|
||||
int idformat; // 0: dxl 1: real 2: auto
|
||||
};
|
||||
|
||||
// maybe extend for external Bluetooth interface?
|
||||
// internal bluetooth consumes too much memory
|
||||
struct st_kisstnc {
|
||||
bool active;
|
||||
int idformat;
|
||||
};
|
||||
|
||||
|
||||
typedef struct st_rdzconfig {
|
||||
// hardware configuration
|
||||
int button_pin; // PIN port number menu button (+128 for touch mode)
|
||||
int button2_pin; // PIN port number menu button (+128 for touch mode)
|
||||
int button2_axp; // Use AXP192 power button as button2
|
||||
int touch_thresh; // Threshold value (0..100) for touch input button
|
||||
int led_pout; // POUT port number of LED (used as serial monitor)
|
||||
int power_pout; // Power control pin (for Heltec v2)
|
||||
int disptype; // 0=OLED; 1=ILI9225
|
||||
int oled_sda; // OLED/TFT data pin
|
||||
int oled_scl; // OLED/TFT clock pin
|
||||
int oled_rst; // OLED/TFT reset pin
|
||||
int tft_rs; // TFT RS pin
|
||||
int tft_cs; // TFT CS pin
|
||||
int tft_orient; // TFT orientation (default: 1)
|
||||
int gps_rxd; // GPS module RXD pin. We expect 9600 baud NMEA data.
|
||||
int gps_txd; // GPS module TXD pin
|
||||
// software configuration
|
||||
int debug; // show port and config options after reboot
|
||||
int wifi; // connect to known WLAN 0=skip
|
||||
int wifiap; // enable/disable WiFi AccessPoint mode 0=disable
|
||||
int display; // select display mode (0=default, 1=default, 2=fieldmode)
|
||||
int8_t display[30]; // list of display mode (0:scanner, 1:default, 2,... additional modes)
|
||||
int startfreq; // spectrum display start freq (400, 401, ...)
|
||||
int channelbw; // spectrum channel bandwidth (valid: 5, 10, 20, 25, 50, 100 kHz)
|
||||
int spectrum; // show freq spectrum for n seconds 0=disable
|
||||
int timer; // show remaining time in spectrum 0=disable
|
||||
int spectrum; // show freq spectrum for n seconds -1=disable; 0=forever
|
||||
int marker; // show freq marker in spectrum 0=disable
|
||||
int maxsonde; // number of max sonde in scan (range=1-99)
|
||||
int norx_timeout; // Time after which rx mode switches to scan mode (without rx signal)
|
||||
int noisefloor; // for spectrum display
|
||||
char mdnsname[15]; // mDNS-Name, defaults to rdzsonde
|
||||
// receiver configuration
|
||||
int showafc; // show afc value in rx screen
|
||||
int freqofs; // frequency offset (tuner config = rx frequency + freqofs) in Hz
|
||||
char call[9]; // APRS callsign
|
||||
char passcode[9]; // APRS passcode
|
||||
struct st_rs41config rs41; // configuration options specific for RS41 receiver
|
||||
struct st_rs92config rs92;
|
||||
struct st_dfmconfig dfm;
|
||||
// data feed configuration
|
||||
// for now, one feed for each type is enough, but might get extended to more?
|
||||
char call[10]; // APRS callsign
|
||||
char passcode[9]; // APRS passcode
|
||||
struct st_feedinfo udpfeed; // target for AXUDP messages
|
||||
struct st_feedinfo tcpfeed; // target for APRS-IS TCP connections
|
||||
struct st_kisstnc kisstnc; // target for KISS TNC (via TCP, mainly for APRSdroid)
|
||||
} RDZConfig;
|
||||
|
||||
typedef struct st_sondeinfo {
|
||||
// receiver configuration
|
||||
bool active;
|
||||
SondeType type;
|
||||
float freq;
|
||||
// decoded ID
|
||||
char id[10];
|
||||
bool validID;
|
||||
char launchsite[18];
|
||||
// decoded position
|
||||
float lat; // latitude
|
||||
float lon; // longitude
|
||||
float alt; // altitude
|
||||
float vs; // vertical speed
|
||||
float hs; // horizontal speed
|
||||
float dir; // 0..360
|
||||
uint8_t validPos; // bit pattern for validity of above 6 fields
|
||||
// RSSI from receiver
|
||||
int rssi; // signal strength
|
||||
int32_t afc; // afc correction value
|
||||
// statistics
|
||||
uint8_t rxStat[20];
|
||||
uint32_t rxStart; // millis() timestamp of continuous rx start
|
||||
uint32_t norxStart; // millis() timestamp of continuous no rx start
|
||||
uint32_t viewStart; // millis() timestamp of viewinf this sonde with current display
|
||||
int8_t lastState; // -1: disabled; 0: norx; 1: rx
|
||||
} SondeInfo;
|
||||
// rxStat: 3=undef[empty] 1=timeout[.] 2=errro[E] 3=ok[1] 5=no valid position[°]
|
||||
|
||||
|
||||
#define MAXSONDE 99
|
||||
|
||||
extern int fingerprintValue[];
|
||||
extern const char *fingerprintText[];
|
||||
|
||||
class Sonde
|
||||
{
|
||||
private:
|
||||
public:
|
||||
RDZConfig config;
|
||||
int fingerprint = 0;
|
||||
int currentSonde = 0;
|
||||
int nSonde;
|
||||
String ipaddr;
|
||||
bool isAP;
|
||||
// moved to heap, saving space in .bss
|
||||
//SondeInfo sondeList[MAXSONDE+1];
|
||||
SondeInfo *sondeList;
|
||||
|
||||
Sonde();
|
||||
void defaultConfig();
|
||||
void setConfig(const char *str);
|
||||
|
||||
void clearSonde();
|
||||
void addSonde(float frequency, SondeType type, int active, char *launchsite);
|
||||
void nextConfig();
|
||||
void nextRxSonde();
|
||||
void nextRxFreq(int addkhz);
|
||||
|
||||
/* new interface */
|
||||
void setup();
|
||||
|
@ -192,10 +243,9 @@ public:
|
|||
void updateStat();
|
||||
void updateDisplayIP();
|
||||
void updateDisplay();
|
||||
void updateDisplayScanner();
|
||||
void clearDisplay();
|
||||
void setIP(const char *ip, bool isAP);
|
||||
void clearIP();
|
||||
|
||||
void setIP(String ip, bool isAP);
|
||||
};
|
||||
|
||||
extern Sonde sonde;
|
||||
|
|
|
@ -1343,6 +1343,38 @@ uint16_t TFT22_ILI9225::drawGFXChar(int16_t x, int16_t y, unsigned char c, uint1
|
|||
return (uint16_t)xa;
|
||||
}
|
||||
|
||||
// Write a character to a bitmap
|
||||
uint16_t TFT22_ILI9225::drawGFXcharBM(int16_t x, int16_t y, unsigned char c, uint16_t color, uint16_t *bm, int bmwd) {
|
||||
c -= (uint8_t)pgm_read_byte(&gfxFont->first);
|
||||
GFXglyph *glyph = &(((GFXglyph *)pgm_read_pointer(&gfxFont->glyph))[c]);
|
||||
uint8_t *bitmap = (uint8_t *)pgm_read_pointer(&gfxFont->bitmap);
|
||||
|
||||
uint16_t bo = pgm_read_word(&glyph->bitmapOffset);
|
||||
uint8_t w = pgm_read_byte(&glyph->width),
|
||||
h = pgm_read_byte(&glyph->height),
|
||||
xa = pgm_read_byte(&glyph->xAdvance);
|
||||
int8_t xo = pgm_read_byte(&glyph->xOffset),
|
||||
yo = pgm_read_byte(&glyph->yOffset);
|
||||
uint8_t xx, yy, bits = 0, bit = 0;
|
||||
|
||||
for(yy=0; yy<h; yy++) {
|
||||
if(y+yo+yy>=bmwd) continue;
|
||||
if(y+yo+yy<0) continue; // yo can be negative
|
||||
for(xx=0; xx<w; xx++) {
|
||||
if(x+xo+xx>=bmwd) continue;
|
||||
if(!(bit++ & 7)) {
|
||||
bits = pgm_read_byte(&bitmap[bo++]);
|
||||
}
|
||||
if(bits & 0x80) {
|
||||
bm[x+xo+xx + bmwd*(y+yo+yy)] = color;
|
||||
}
|
||||
bits <<= 1;
|
||||
}
|
||||
}
|
||||
|
||||
return (uint16_t)xa;
|
||||
}
|
||||
|
||||
|
||||
void TFT22_ILI9225::getGFXCharExtent(uint8_t c, int16_t *gw, int16_t *gh, int16_t *xa) {
|
||||
uint8_t first = pgm_read_byte(&gfxFont->first),
|
||||
|
@ -1373,7 +1405,8 @@ void TFT22_ILI9225::getGFXTextExtent(STRING str, int16_t x, int16_t y, int16_t *
|
|||
if(gh > *h) {
|
||||
*h = gh;
|
||||
}
|
||||
*w += xa;
|
||||
*w += xa + 1;
|
||||
}
|
||||
if(*w>0) (*w)--;
|
||||
}
|
||||
|
||||
|
|
|
@ -389,6 +389,9 @@ class TFT22_ILI9225 {
|
|||
/// @return width of character in display pixels
|
||||
uint16_t drawGFXChar(int16_t x, int16_t y, unsigned char c, uint16_t color);
|
||||
|
||||
uint16_t drawGFXcharBM(int16_t x, int16_t y, unsigned char c, uint16_t color, uint16_t *bm, int bmwd);
|
||||
|
||||
void getGFXCharExtent(uint8_t c, int16_t *gw, int16_t *gh, int16_t *xa);
|
||||
|
||||
private:
|
||||
|
||||
|
@ -458,7 +461,6 @@ class TFT22_ILI9225 {
|
|||
void startWrite(void);
|
||||
void endWrite(void);
|
||||
|
||||
void getGFXCharExtent(uint8_t c, int16_t *gw, int16_t *gh, int16_t *xa);
|
||||
|
||||
GFXfont *gfxFont;
|
||||
};
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <WString.h>
|
||||
#include <stdlib.h>
|
||||
//#include <arpa/inet.h>
|
||||
//#include <sys/socket.h>
|
||||
|
@ -274,8 +274,8 @@ static uint32_t dao91(double x)
|
|||
char b[201];
|
||||
char raw[201];
|
||||
|
||||
char * aprs_senddata(float lat, float lon, float alt, float speed, float dir, float climb, const char *type, const char *objname, const char *usercall, const char *sym)
|
||||
{
|
||||
char *aprs_senddata(SondeInfo *s, const char *usercall, const char *sym) {
|
||||
// float lat, float lon, float alt, float speed, float dir, float climb, const char *type, const char *objname, const char *usercall, const char *sym, const char *comm)
|
||||
*b=0;
|
||||
aprsstr_append(b, usercall);
|
||||
aprsstr_append(b, ">");
|
||||
|
@ -284,39 +284,43 @@ char * aprs_senddata(float lat, float lon, float alt, float speed, float dir, fl
|
|||
// uncompressed
|
||||
aprsstr_append(b, ":;");
|
||||
char tmp[10];
|
||||
snprintf(tmp,10,"%s ",objname);
|
||||
snprintf(tmp,10,"%s ",s->id);
|
||||
aprsstr_append(b, tmp);
|
||||
aprsstr_append(b, "*");
|
||||
// TODO: time
|
||||
//aprsstr_append_data(time, ds);
|
||||
aprsstr_append(b, "121212z");
|
||||
// time
|
||||
int i = strlen(b);
|
||||
int lati = abs((int)lat);
|
||||
int latm = (fabs(lat)-lati)*6000;
|
||||
snprintf(b+i, APRS_MAXLEN-i, "%02d%02d.%02d%c%c", lati, latm/100, latm%100, lat<0?'S':'N', sym[0]);
|
||||
int sec = s->time % 86400;
|
||||
snprintf(b+i, APRS_MAXLEN-1, "%02d%02d%02dz", sec/(60*60), (sec%(60*60))/60, sec%60);
|
||||
i = strlen(b);
|
||||
int loni = abs((int)lon);
|
||||
int lonm = (fabs(lon)-loni)*6000;
|
||||
snprintf(b+i, APRS_MAXLEN-i, "%03d%02d.%02d%c%c", loni, lonm/100, lonm%100, lon<0?'W':'E', sym[1]);
|
||||
#if 1
|
||||
if(speed>0.5) {
|
||||
//aprsstr_append_data(time, ds);
|
||||
int lati = abs((int)s->lat);
|
||||
int latm = (fabs(s->lat)-lati)*6000;
|
||||
snprintf(b+i, APRS_MAXLEN-i, "%02d%02d.%02d%c%c", lati, latm/100, latm%100, s->lat<0?'S':'N', sym[0]);
|
||||
i = strlen(b);
|
||||
int loni = abs((int)s->lon);
|
||||
int lonm = (fabs(s->lon)-loni)*6000;
|
||||
snprintf(b+i, APRS_MAXLEN-i, "%03d%02d.%02d%c%c", loni, lonm/100, lonm%100, s->lon<0?'W':'E', sym[1]);
|
||||
if(s->hs>0.5) {
|
||||
i=strlen(b);
|
||||
snprintf(b+i, APRS_MAXLEN-i, "%03d/%03d", realcard(dir+1.5), realcard(speed*1.0/KNOTS+0.5));
|
||||
snprintf(b+i, APRS_MAXLEN-i, "%03d/%03d", realcard(s->dir+1.5), realcard(s->hs*1.0/KNOTS+0.5));
|
||||
}
|
||||
#endif
|
||||
if(alt>0.5) {
|
||||
if(s->alt>0.5) {
|
||||
i=strlen(b);
|
||||
snprintf(b+i, APRS_MAXLEN-i, "/A=%06d", realcard(alt*FEET+0.5));
|
||||
snprintf(b+i, APRS_MAXLEN-i, "/A=%06d", realcard(s->alt*FEET+0.5));
|
||||
}
|
||||
#if 1
|
||||
int dao=1;
|
||||
if(dao) {
|
||||
i=strlen(b);
|
||||
snprintf(b+i, APRS_MAXLEN-i, "!w%c%c!", 33+dao91(lat), 33+dao91(lon));
|
||||
snprintf(b+i, APRS_MAXLEN-i, "!w%c%c!", 33+dao91(s->lat), 33+dao91(s->lon));
|
||||
}
|
||||
#endif
|
||||
const char *comm="&test";
|
||||
strcat(b, "&");
|
||||
char comm[100];
|
||||
snprintf(comm, 100, "Clb=%.1fm/s %.3fMHz Type=%s", s->vs, s->freq, sondeTypeStr[s->type]);
|
||||
strcat(b, comm);
|
||||
if(s->type==STYPE_M10||s->type==STYPE_DFM06||s->type==STYPE_DFM09) {
|
||||
snprintf(comm, 100, " ser=%s", s->ser);
|
||||
strcat(b, comm);
|
||||
}
|
||||
return b;
|
||||
}
|
||||
|
||||
|
|
|
@ -1,34 +1,14 @@
|
|||
|
||||
#ifndef _aprs_h
|
||||
#define _aprs_h
|
||||
|
||||
enum IDTYPE { ID_DFMDXL, ID_DFMGRAW, ID_DFMAUTO };
|
||||
|
||||
struct st_feedinfo {
|
||||
bool active;
|
||||
int type; // 0:UDP(axudp), 1:TCP(aprs.fi)
|
||||
char host[64];
|
||||
int port;
|
||||
char symbol[3];
|
||||
int lowrate;
|
||||
int highrate;
|
||||
int lowlimit;
|
||||
int idformat; // 0: dxl 1: real 2: auto
|
||||
};
|
||||
|
||||
// maybe extend for external Bluetooth interface?
|
||||
// internal bluetooth consumes too much memory
|
||||
struct st_kisstnc {
|
||||
bool active;
|
||||
int idformat;
|
||||
};
|
||||
#include "Sonde.h"
|
||||
|
||||
|
||||
#define APRS_MAXLEN 201
|
||||
void aprs_gencrctab(void);
|
||||
int aprsstr_mon2raw(const char *mon, char raw[], int raw_len);
|
||||
int aprsstr_mon2kiss(const char *mon, char raw[], int raw_len);
|
||||
char * aprs_senddata(float lat, float lon, float alt, float speed, float dir, float climb, const char *type, const char *objname, const char *usercall, const char *sym);
|
||||
char *aprs_senddata(SondeInfo *s, const char *usercall, const char *sym);
|
||||
|
||||
|
||||
#endif
|
||||
|
|
|
@ -1,33 +1,39 @@
|
|||
Heltec board
|
||||
Heltec board v1 => fingerprint 0000100 => 4
|
||||
(sda,scl: 4,15) (same as LORA v1.0)
|
||||
0:1 1:0 2:0 3:1 4:0 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:0 13:0 14:1 15:0 16:0 17:0 18:0 19:0 20:0 21:1 22:0 23:0 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0
|
||||
|
||||
TTGO LORA32 v2.1_1.6 (button1: touch gpio 2 => 130; button2: touch gpio14 => 142)
|
||||
Heltec board v2
|
||||
(sda,scl: 4,15) (similar to v1.0, but GPIO21 switches 3V3) => fingerprint 4
|
||||
0:1 1:0 2:0 3:1 4:0 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:0 13:0 14:1 15:0 16:0 17:0 18:0 19:0 20:0 21:1 22:0 23:0 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0
|
||||
0:1 1:1 2:0 3:1 4:0 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:0 13:0 14:1 15:0 16:0 17:0 18:0 19:0 20:0 21:1 22:0 23:0 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0 (before setup
|
||||
|
||||
TTGO LORA32 v2.1_1.6 (button1: touch gpio 2 => 130; button2: touch gpio14 => 142) fingerprint 0011111 => 31
|
||||
(sda,scl: 21,22)
|
||||
0:1 1:0 2:0 3:1 4:0 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:0 13:0 14:1 15:1 16:1 17:1 18:0 19:0 20:0 21:1 22:1 23:1 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0
|
||||
0:4 1:4 2:0 3:4 4:0 5:4 6:0 7:4 8:0 9:4 10:4 11:4 12:0 13:0 14:4 15:4 16:4 17:4 18:0 19:0 20:0 21:4 22:4 23:4 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0 (in Sonde())
|
||||
|
||||
TTGO LORA v1.0
|
||||
TTGO LORA v1.0 => fingerprint 1000000 => 64
|
||||
(sda,scl: 4,15) (button1: 0) (button2: touch gpio13 = 141)
|
||||
0:1 1:0 2:0 3:1 4:1 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:0 13:0 14:1 15:1 16:0 17:0 18:0 19:0 20:0 21:0 22:0 23:0 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0
|
||||
0:4 1:4 2:0 3:4 4:4 5:4 6:0 7:4 8:0 9:4 10:4 11:4 12:0 13:0 14:4 15:4 16:0 17:0 18:0 19:0 20:0 21:0 22:0 23:0 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0 (in Sonde())
|
||||
|
||||
TTGO T-Beam
|
||||
TTGO T-Beam => fingerprint 0110111 => 55
|
||||
(sda,scl: 21,22) (button1: 39) (button2: touch gpio13 = 141) (gps rx: 12)
|
||||
0:1 1:0 2:0 3:1 4:0 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:1 13:0 14:1 15:1 16:1 17:0 18:0 19:0 20:0 21:1 22:1 23:1 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0
|
||||
0:4 1:4 2:0 3:4 4:0 5:4 6:0 7:4 8:0 9:4 10:4 11:4 12:4 13:0 14:4 15:4 16:4 17:0 18:0 19:0 20:0 21:4 22:4 23:4 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0 (before setup)
|
||||
|
||||
TTGO T-Beam 1.0 with OLED display
|
||||
TTGO T-Beam with extern 2" ILI9225 Display => fingerprint 0110000 => 48
|
||||
0:1 1:0 2:0 3:1 4:0 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:1 13:0 14:1 15:1 16:1 17:0 18:0 19:0 20:0 21:0 22:0 23:1 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0
|
||||
0:4 1:4 2:0 3:4 4:0 5:4 6:0 7:4 8:0 9:4 10:4 11:4 12:4 13:0 14:4 15:4 16:4 17:0 18:0 19:0 20:0 21:0 22:0 23:4 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0 (before setup)
|
||||
|
||||
TTGO T-Beam 1.0 with OLED display => fingerprint 0010111 => 23
|
||||
0:1 1:0 2:0 3:1 4:0 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:0 13:0 14:1 15:1 16:1 17:0 18:0 19:0 20:0 21:1 22:1 23:1 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0
|
||||
0:4 1:4 2:0 3:4 4:0 5:4 6:0 7:4 8:0 9:4 10:4 11:4 12:0 13:0 14:4 15:4 16:4 17:0 18:0 19:0 20:0 21:4 22:4 23:4 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0 (before setup)
|
||||
|
||||
|
||||
|
||||
TTGO T-Beam with extern 2" ILI9225 Display
|
||||
0:1 1:0 2:0 3:1 4:0 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:1 13:0 14:1 15:1 16:1 17:0 18:0 19:0 20:0 21:0 22:0 23:1 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0
|
||||
0:4 1:4 2:0 3:4 4:0 5:4 6:0 7:4 8:0 9:4 10:4 11:4 12:4 13:0 14:4 15:4 16:4 17:0 18:0 19:0 20:0 21:0 22:0 23:4 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0 (before setup)
|
||||
1
|
||||
|
||||
Fingerprint GPIOs: 4, 12, 16, 17, 21, 22, 23,
|
||||
|
||||
Current autodetect strategy:
|
||||
RST always set to 16
|
||||
|
||||
|
|
|
@ -1,6 +1,7 @@
|
|||
|
||||
/*
|
||||
Quellen:
|
||||
/* SPDX-License-Identifier: GPL-3.0
|
||||
* based on https://github.com/rs1729/RS/blob/master/rs92/nav_gps_vel.c
|
||||
*
|
||||
Quellen:
|
||||
- IS-GPS-200H (bis C: ICD-GPS-200):
|
||||
http://www.gps.gov/technical/icwg/
|
||||
- Borre: http://kom.aau.dk/~borre
|
||||
|
|
|
@ -1,5 +1,6 @@
|
|||
|
||||
/*
|
||||
/* SPDX-License-Identifier: GPL-3.0
|
||||
* based on https://github.com/rs1729/RS/blob/master/rs92/rs92gps.c
|
||||
*
|
||||
* radiosonde RS92
|
||||
*
|
||||
*
|
||||
|
@ -1362,6 +1363,7 @@ int print_position() { // GPS-Hoehe ueber Ellipsoid
|
|||
|
||||
if (!err2 && (almanac || ephem)) {
|
||||
k = get_pseudorange();
|
||||
gpx.k = k;
|
||||
Serial.printf("k=%d\n", k);
|
||||
if (k >= 4) {
|
||||
n = get_GPSkoord(k);
|
||||
|
|
|
@ -8,6 +8,7 @@ typedef struct {
|
|||
int std; int min; float sek;
|
||||
double lat; double lon; double alt;
|
||||
double vH; double vD; double vU;
|
||||
int k;
|
||||
int sats[4];
|
||||
double dop;
|
||||
int freq;
|
||||
|
|
|
@ -0,0 +1,227 @@
|
|||
const uint8_t FreeMono12pt7bBitmaps[] PROGMEM = {
|
||||
0x49, 0x24, 0x92, 0x48, 0x01, 0xF8, 0xE7, 0xE7, 0x67, 0x42, 0x42, 0x42,
|
||||
0x42, 0x09, 0x02, 0x41, 0x10, 0x44, 0x11, 0x1F, 0xF1, 0x10, 0x4C, 0x12,
|
||||
0x3F, 0xE1, 0x20, 0x48, 0x12, 0x04, 0x81, 0x20, 0x48, 0x04, 0x07, 0xA2,
|
||||
0x19, 0x02, 0x40, 0x10, 0x03, 0x00, 0x3C, 0x00, 0x80, 0x10, 0x06, 0x01,
|
||||
0xE0, 0xA7, 0xC0, 0x40, 0x10, 0x04, 0x00, 0x3C, 0x19, 0x84, 0x21, 0x08,
|
||||
0x66, 0x0F, 0x00, 0x0C, 0x1C, 0x78, 0x01, 0xE0, 0xCC, 0x21, 0x08, 0x43,
|
||||
0x30, 0x78, 0x3E, 0x30, 0x10, 0x08, 0x02, 0x03, 0x03, 0x47, 0x14, 0x8A,
|
||||
0x43, 0x11, 0x8F, 0x60, 0xFD, 0xA4, 0x90, 0x05, 0x25, 0x24, 0x92, 0x48,
|
||||
0x92, 0x24, 0x11, 0x24, 0x89, 0x24, 0x92, 0x92, 0x90, 0x00, 0x04, 0x02,
|
||||
0x11, 0x07, 0xF0, 0xC0, 0x50, 0x48, 0x42, 0x00, 0x08, 0x04, 0x02, 0x01,
|
||||
0x00, 0x87, 0xFC, 0x20, 0x10, 0x08, 0x04, 0x02, 0x00, 0x3B, 0x9C, 0xCE,
|
||||
0x62, 0x00, 0xFF, 0xE0, 0xFF, 0x80, 0x00, 0x80, 0xC0, 0x40, 0x20, 0x20,
|
||||
0x10, 0x10, 0x08, 0x08, 0x04, 0x04, 0x02, 0x02, 0x01, 0x01, 0x00, 0x80,
|
||||
0x80, 0x40, 0x00, 0x1C, 0x31, 0x90, 0x58, 0x38, 0x0C, 0x06, 0x03, 0x01,
|
||||
0x80, 0xC0, 0x60, 0x30, 0x34, 0x13, 0x18, 0x70, 0x30, 0xE1, 0x44, 0x81,
|
||||
0x02, 0x04, 0x08, 0x10, 0x20, 0x40, 0x81, 0x1F, 0xC0, 0x1E, 0x10, 0x90,
|
||||
0x68, 0x10, 0x08, 0x0C, 0x04, 0x04, 0x04, 0x06, 0x06, 0x06, 0x06, 0x0E,
|
||||
0x07, 0xFE, 0x3E, 0x10, 0x40, 0x08, 0x02, 0x00, 0x80, 0x40, 0xE0, 0x04,
|
||||
0x00, 0x80, 0x10, 0x04, 0x01, 0x00, 0xD8, 0x63, 0xE0, 0x06, 0x0A, 0x0A,
|
||||
0x12, 0x22, 0x22, 0x42, 0x42, 0x82, 0x82, 0xFF, 0x02, 0x02, 0x02, 0x0F,
|
||||
0x7F, 0x20, 0x10, 0x08, 0x04, 0x02, 0xF1, 0x8C, 0x03, 0x00, 0x80, 0x40,
|
||||
0x20, 0x18, 0x16, 0x18, 0xF0, 0x0F, 0x8C, 0x08, 0x08, 0x04, 0x04, 0x02,
|
||||
0x79, 0x46, 0xC1, 0xE0, 0x60, 0x28, 0x14, 0x19, 0x08, 0x78, 0xFF, 0x81,
|
||||
0x81, 0x02, 0x02, 0x02, 0x02, 0x04, 0x04, 0x04, 0x04, 0x08, 0x08, 0x08,
|
||||
0x08, 0x3E, 0x31, 0xB0, 0x70, 0x18, 0x0C, 0x05, 0x8C, 0x38, 0x63, 0x40,
|
||||
0x60, 0x30, 0x18, 0x1B, 0x18, 0xF8, 0x3C, 0x31, 0x30, 0x50, 0x28, 0x0C,
|
||||
0x0F, 0x06, 0x85, 0x3C, 0x80, 0x40, 0x40, 0x20, 0x20, 0x63, 0xE0, 0xFF,
|
||||
0x80, 0x07, 0xFC, 0x39, 0xCE, 0x00, 0x00, 0x06, 0x33, 0x98, 0xC4, 0x00,
|
||||
0x00, 0xC0, 0x60, 0x18, 0x0C, 0x06, 0x01, 0x80, 0x0C, 0x00, 0x60, 0x03,
|
||||
0x00, 0x30, 0x01, 0x00, 0xFF, 0xF0, 0x00, 0x00, 0x0F, 0xFF, 0xC0, 0x06,
|
||||
0x00, 0x30, 0x01, 0x80, 0x18, 0x01, 0x80, 0xC0, 0x30, 0x18, 0x0C, 0x02,
|
||||
0x00, 0x00, 0x3E, 0x60, 0xA0, 0x20, 0x10, 0x08, 0x08, 0x18, 0x10, 0x08,
|
||||
0x00, 0x00, 0x00, 0x01, 0xC0, 0xE0, 0x1C, 0x31, 0x10, 0x50, 0x28, 0x14,
|
||||
0x3A, 0x25, 0x22, 0x91, 0x4C, 0xA3, 0xF0, 0x08, 0x02, 0x01, 0x80, 0x7C,
|
||||
0x3F, 0x00, 0x0C, 0x00, 0x48, 0x01, 0x20, 0x04, 0x40, 0x21, 0x00, 0x84,
|
||||
0x04, 0x08, 0x1F, 0xE0, 0x40, 0x82, 0x01, 0x08, 0x04, 0x20, 0x13, 0xE1,
|
||||
0xF0, 0xFF, 0x08, 0x11, 0x01, 0x20, 0x24, 0x04, 0x81, 0x1F, 0xC2, 0x06,
|
||||
0x40, 0x68, 0x05, 0x00, 0xA0, 0x14, 0x05, 0xFF, 0x00, 0x1E, 0x48, 0x74,
|
||||
0x05, 0x01, 0x80, 0x20, 0x08, 0x02, 0x00, 0x80, 0x20, 0x04, 0x01, 0x01,
|
||||
0x30, 0x87, 0xC0, 0xFE, 0x10, 0x44, 0x09, 0x02, 0x40, 0x50, 0x14, 0x05,
|
||||
0x01, 0x40, 0x50, 0x14, 0x0D, 0x02, 0x41, 0x3F, 0x80, 0xFF, 0xC8, 0x09,
|
||||
0x01, 0x20, 0x04, 0x00, 0x88, 0x1F, 0x02, 0x20, 0x40, 0x08, 0x01, 0x00,
|
||||
0xA0, 0x14, 0x03, 0xFF, 0xC0, 0xFF, 0xE8, 0x05, 0x00, 0xA0, 0x04, 0x00,
|
||||
0x88, 0x1F, 0x02, 0x20, 0x40, 0x08, 0x01, 0x00, 0x20, 0x04, 0x01, 0xF0,
|
||||
0x00, 0x1F, 0x46, 0x19, 0x01, 0x60, 0x28, 0x01, 0x00, 0x20, 0x04, 0x00,
|
||||
0x83, 0xF0, 0x0B, 0x01, 0x20, 0x23, 0x0C, 0x3E, 0x00, 0xE1, 0xD0, 0x24,
|
||||
0x09, 0x02, 0x40, 0x90, 0x27, 0xF9, 0x02, 0x40, 0x90, 0x24, 0x09, 0x02,
|
||||
0x40, 0xB8, 0x70, 0xFE, 0x20, 0x40, 0x81, 0x02, 0x04, 0x08, 0x10, 0x20,
|
||||
0x40, 0x81, 0x1F, 0xC0, 0x0F, 0xE0, 0x10, 0x02, 0x00, 0x40, 0x08, 0x01,
|
||||
0x00, 0x20, 0x04, 0x80, 0x90, 0x12, 0x02, 0x40, 0xC6, 0x30, 0x7C, 0x00,
|
||||
0xF1, 0xE4, 0x0C, 0x41, 0x04, 0x20, 0x44, 0x04, 0x80, 0x5C, 0x06, 0x60,
|
||||
0x43, 0x04, 0x10, 0x40, 0x84, 0x08, 0x40, 0xCF, 0x07, 0xF8, 0x04, 0x00,
|
||||
0x80, 0x10, 0x02, 0x00, 0x40, 0x08, 0x01, 0x00, 0x20, 0x04, 0x04, 0x80,
|
||||
0x90, 0x12, 0x03, 0xFF, 0xC0, 0xE0, 0x3B, 0x01, 0x94, 0x14, 0xA0, 0xA4,
|
||||
0x89, 0x24, 0x49, 0x14, 0x48, 0xA2, 0x45, 0x12, 0x10, 0x90, 0x04, 0x80,
|
||||
0x24, 0x01, 0x78, 0x3C, 0xE0, 0xF6, 0x02, 0x50, 0x25, 0x02, 0x48, 0x24,
|
||||
0xC2, 0x44, 0x24, 0x22, 0x43, 0x24, 0x12, 0x40, 0xA4, 0x0A, 0x40, 0x6F,
|
||||
0x06, 0x0F, 0x03, 0x0C, 0x60, 0x64, 0x02, 0x80, 0x18, 0x01, 0x80, 0x18,
|
||||
0x01, 0x80, 0x18, 0x01, 0x40, 0x26, 0x06, 0x30, 0xC0, 0xF0, 0xFF, 0x10,
|
||||
0x64, 0x05, 0x01, 0x40, 0x50, 0x34, 0x19, 0xFC, 0x40, 0x10, 0x04, 0x01,
|
||||
0x00, 0x40, 0x3E, 0x00, 0x0F, 0x03, 0x0C, 0x60, 0x64, 0x02, 0x80, 0x18,
|
||||
0x01, 0x80, 0x18, 0x01, 0x80, 0x18, 0x01, 0x40, 0x26, 0x06, 0x30, 0xC1,
|
||||
0xF0, 0x0C, 0x01, 0xF1, 0x30, 0xE0, 0xFF, 0x04, 0x18, 0x40, 0xC4, 0x04,
|
||||
0x40, 0x44, 0x0C, 0x41, 0x87, 0xE0, 0x43, 0x04, 0x10, 0x40, 0x84, 0x04,
|
||||
0x40, 0x4F, 0x03, 0x1F, 0x48, 0x34, 0x05, 0x01, 0x40, 0x08, 0x01, 0xC0,
|
||||
0x0E, 0x00, 0x40, 0x18, 0x06, 0x01, 0xE1, 0xA7, 0xC0, 0xFF, 0xF0, 0x86,
|
||||
0x10, 0x82, 0x00, 0x40, 0x08, 0x01, 0x00, 0x20, 0x04, 0x00, 0x80, 0x10,
|
||||
0x02, 0x00, 0x40, 0x7F, 0x00, 0xF0, 0xF4, 0x02, 0x40, 0x24, 0x02, 0x40,
|
||||
0x24, 0x02, 0x40, 0x24, 0x02, 0x40, 0x24, 0x02, 0x40, 0x22, 0x04, 0x30,
|
||||
0xC0, 0xF0, 0xF8, 0x7C, 0x80, 0x22, 0x01, 0x04, 0x04, 0x10, 0x20, 0x40,
|
||||
0x80, 0x82, 0x02, 0x10, 0x08, 0x40, 0x11, 0x00, 0x48, 0x01, 0xA0, 0x03,
|
||||
0x00, 0x0C, 0x00, 0xF8, 0x7C, 0x80, 0x22, 0x00, 0x88, 0xC2, 0x23, 0x10,
|
||||
0x8E, 0x42, 0x29, 0x09, 0x24, 0x24, 0x90, 0x91, 0x41, 0x85, 0x06, 0x14,
|
||||
0x18, 0x70, 0x60, 0x80, 0xF0, 0xF2, 0x06, 0x30, 0x41, 0x08, 0x09, 0x80,
|
||||
0x50, 0x06, 0x00, 0x60, 0x0D, 0x00, 0x88, 0x10, 0xC2, 0x04, 0x60, 0x2F,
|
||||
0x0F, 0xF0, 0xF2, 0x02, 0x10, 0x41, 0x04, 0x08, 0x80, 0x50, 0x05, 0x00,
|
||||
0x20, 0x02, 0x00, 0x20, 0x02, 0x00, 0x20, 0x02, 0x01, 0xFC, 0xFF, 0x40,
|
||||
0xA0, 0x90, 0x40, 0x40, 0x40, 0x20, 0x20, 0x20, 0x10, 0x50, 0x30, 0x18,
|
||||
0x0F, 0xFC, 0xF2, 0x49, 0x24, 0x92, 0x49, 0x24, 0x9C, 0x80, 0x60, 0x10,
|
||||
0x08, 0x02, 0x01, 0x00, 0x40, 0x20, 0x08, 0x04, 0x01, 0x00, 0x80, 0x20,
|
||||
0x10, 0x04, 0x02, 0x00, 0x80, 0x40, 0xE4, 0x92, 0x49, 0x24, 0x92, 0x49,
|
||||
0x3C, 0x08, 0x0C, 0x09, 0x0C, 0x4C, 0x14, 0x04, 0xFF, 0xFC, 0x84, 0x21,
|
||||
0x3E, 0x00, 0x60, 0x08, 0x02, 0x3F, 0x98, 0x28, 0x0A, 0x02, 0xC3, 0x9F,
|
||||
0x30, 0xE0, 0x01, 0x00, 0x08, 0x00, 0x40, 0x02, 0x00, 0x13, 0xE0, 0xA0,
|
||||
0x86, 0x02, 0x20, 0x09, 0x00, 0x48, 0x02, 0x40, 0x13, 0x01, 0x14, 0x1B,
|
||||
0x9F, 0x00, 0x1F, 0x4C, 0x19, 0x01, 0x40, 0x28, 0x01, 0x00, 0x20, 0x02,
|
||||
0x00, 0x60, 0x43, 0xF0, 0x00, 0xC0, 0x08, 0x01, 0x00, 0x20, 0x04, 0x3C,
|
||||
0x98, 0x52, 0x06, 0x80, 0x50, 0x0A, 0x01, 0x40, 0x24, 0x0C, 0xC2, 0x87,
|
||||
0x98, 0x3F, 0x18, 0x68, 0x06, 0x01, 0xFF, 0xE0, 0x08, 0x03, 0x00, 0x60,
|
||||
0xC7, 0xC0, 0x0F, 0x98, 0x08, 0x04, 0x02, 0x07, 0xF8, 0x80, 0x40, 0x20,
|
||||
0x10, 0x08, 0x04, 0x02, 0x01, 0x03, 0xF8, 0x1E, 0x6C, 0x39, 0x03, 0x40,
|
||||
0x28, 0x05, 0x00, 0xA0, 0x12, 0x06, 0x61, 0x43, 0xC8, 0x01, 0x00, 0x20,
|
||||
0x08, 0x3E, 0x00, 0xC0, 0x10, 0x04, 0x01, 0x00, 0x40, 0x13, 0x87, 0x11,
|
||||
0x82, 0x40, 0x90, 0x24, 0x09, 0x02, 0x40, 0x90, 0x2E, 0x1C, 0x08, 0x04,
|
||||
0x02, 0x00, 0x00, 0x03, 0xC0, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01, 0x00,
|
||||
0x80, 0x43, 0xFE, 0x04, 0x08, 0x10, 0x00, 0x1F, 0xC0, 0x81, 0x02, 0x04,
|
||||
0x08, 0x10, 0x20, 0x40, 0x81, 0x02, 0x0B, 0xE0, 0xE0, 0x02, 0x00, 0x20,
|
||||
0x02, 0x00, 0x20, 0x02, 0x3C, 0x21, 0x02, 0x60, 0x2C, 0x03, 0x80, 0x24,
|
||||
0x02, 0x20, 0x21, 0x02, 0x08, 0xE1, 0xF0, 0x78, 0x04, 0x02, 0x01, 0x00,
|
||||
0x80, 0x40, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01, 0x00, 0x80, 0x43, 0xFE,
|
||||
0xDC, 0xE3, 0x19, 0x90, 0x84, 0x84, 0x24, 0x21, 0x21, 0x09, 0x08, 0x48,
|
||||
0x42, 0x42, 0x17, 0x18, 0xC0, 0x67, 0x83, 0x84, 0x20, 0x22, 0x02, 0x20,
|
||||
0x22, 0x02, 0x20, 0x22, 0x02, 0x20, 0x2F, 0x07, 0x1F, 0x04, 0x11, 0x01,
|
||||
0x40, 0x18, 0x03, 0x00, 0x60, 0x0A, 0x02, 0x20, 0x83, 0xE0, 0xCF, 0x85,
|
||||
0x06, 0x60, 0x24, 0x01, 0x40, 0x14, 0x01, 0x40, 0x16, 0x02, 0x50, 0x44,
|
||||
0xF8, 0x40, 0x04, 0x00, 0x40, 0x0F, 0x00, 0x1E, 0x6C, 0x3B, 0x03, 0x40,
|
||||
0x28, 0x05, 0x00, 0xA0, 0x12, 0x06, 0x61, 0x43, 0xC8, 0x01, 0x00, 0x20,
|
||||
0x04, 0x03, 0xC0, 0xE3, 0x8B, 0x13, 0x80, 0x80, 0x20, 0x08, 0x02, 0x00,
|
||||
0x80, 0x20, 0x3F, 0x80, 0x1F, 0x58, 0x34, 0x05, 0x80, 0x1E, 0x00, 0x60,
|
||||
0x06, 0x01, 0xC0, 0xAF, 0xC0, 0x20, 0x04, 0x00, 0x80, 0x10, 0x0F, 0xF0,
|
||||
0x40, 0x08, 0x01, 0x00, 0x20, 0x04, 0x00, 0x80, 0x10, 0x03, 0x04, 0x3F,
|
||||
0x00, 0xC1, 0xC8, 0x09, 0x01, 0x20, 0x24, 0x04, 0x80, 0x90, 0x12, 0x02,
|
||||
0x61, 0xC7, 0xCC, 0xF8, 0xF9, 0x01, 0x08, 0x10, 0x60, 0x81, 0x08, 0x08,
|
||||
0x40, 0x22, 0x01, 0x20, 0x05, 0x00, 0x30, 0x00, 0xF0, 0x7A, 0x01, 0x10,
|
||||
0x08, 0x8C, 0x42, 0x62, 0x12, 0x90, 0xA5, 0x05, 0x18, 0x28, 0xC0, 0x86,
|
||||
0x00, 0x78, 0xF3, 0x04, 0x18, 0x80, 0xD0, 0x06, 0x00, 0x70, 0x09, 0x81,
|
||||
0x0C, 0x20, 0x6F, 0x8F, 0xF0, 0xF2, 0x02, 0x20, 0x41, 0x04, 0x10, 0x80,
|
||||
0x88, 0x09, 0x00, 0x50, 0x06, 0x00, 0x20, 0x04, 0x00, 0x40, 0x08, 0x0F,
|
||||
0xE0, 0xFF, 0x41, 0x00, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x40, 0xBF,
|
||||
0xC0, 0x19, 0x08, 0x42, 0x10, 0x84, 0x64, 0x18, 0x42, 0x10, 0x84, 0x20,
|
||||
0xC0, 0xFF, 0xFF, 0xC0, 0xC1, 0x08, 0x42, 0x10, 0x84, 0x10, 0x4C, 0x42,
|
||||
0x10, 0x84, 0x26, 0x00, 0x38, 0x13, 0x38, 0x38 };
|
||||
|
||||
const GFXglyph FreeMono12pt7bGlyphs[] PROGMEM = {
|
||||
{ 0, 0, 0, 14, 0, 1 }, // 0x20 ' '
|
||||
{ 0, 3, 15, 14, 6, -14 }, // 0x21 '!'
|
||||
{ 6, 8, 7, 14, 3, -14 }, // 0x22 '"'
|
||||
{ 13, 10, 16, 14, 2, -14 }, // 0x23 '#'
|
||||
{ 33, 10, 17, 14, 2, -14 }, // 0x24 '$'
|
||||
{ 55, 10, 15, 14, 2, -14 }, // 0x25 '%'
|
||||
{ 74, 9, 12, 14, 3, -11 }, // 0x26 '&'
|
||||
{ 88, 3, 7, 14, 5, -14 }, // 0x27 '''
|
||||
{ 91, 3, 18, 14, 7, -14 }, // 0x28 '('
|
||||
{ 98, 3, 18, 14, 4, -14 }, // 0x29 ')'
|
||||
{ 105, 9, 9, 14, 3, -14 }, // 0x2A '*'
|
||||
{ 116, 9, 11, 14, 3, -11 }, // 0x2B '+'
|
||||
{ 129, 5, 7, 14, 3, -3 }, // 0x2C ','
|
||||
{ 134, 11, 1, 14, 2, -6 }, // 0x2D '-'
|
||||
{ 136, 3, 3, 14, 5, -2 }, // 0x2E '.'
|
||||
{ 138, 9, 18, 14, 3, -15 }, // 0x2F '/'
|
||||
{ 159, 9, 15, 14, 3, -14 }, // 0x30 '0'
|
||||
{ 176, 7, 14, 14, 4, -13 }, // 0x31 '1'
|
||||
{ 189, 9, 15, 14, 2, -14 }, // 0x32 '2'
|
||||
{ 206, 10, 15, 14, 2, -14 }, // 0x33 '3'
|
||||
{ 225, 8, 15, 14, 3, -14 }, // 0x34 '4'
|
||||
{ 240, 9, 15, 14, 3, -14 }, // 0x35 '5'
|
||||
{ 257, 9, 15, 14, 3, -14 }, // 0x36 '6'
|
||||
{ 274, 8, 15, 14, 3, -14 }, // 0x37 '7'
|
||||
{ 289, 9, 15, 14, 3, -14 }, // 0x38 '8'
|
||||
{ 306, 9, 15, 14, 3, -14 }, // 0x39 '9'
|
||||
{ 323, 3, 10, 14, 5, -9 }, // 0x3A ':'
|
||||
{ 327, 5, 13, 14, 3, -9 }, // 0x3B ';'
|
||||
{ 336, 11, 11, 14, 2, -11 }, // 0x3C '<'
|
||||
{ 352, 12, 4, 14, 1, -8 }, // 0x3D '='
|
||||
{ 358, 11, 11, 14, 2, -11 }, // 0x3E '>'
|
||||
{ 374, 9, 14, 14, 3, -13 }, // 0x3F '?'
|
||||
{ 390, 9, 16, 14, 3, -14 }, // 0x40 '@'
|
||||
{ 408, 14, 14, 14, 0, -13 }, // 0x41 'A'
|
||||
{ 433, 11, 14, 14, 2, -13 }, // 0x42 'B'
|
||||
{ 453, 10, 14, 14, 2, -13 }, // 0x43 'C'
|
||||
{ 471, 10, 14, 14, 2, -13 }, // 0x44 'D'
|
||||
{ 489, 11, 14, 14, 2, -13 }, // 0x45 'E'
|
||||
{ 509, 11, 14, 14, 2, -13 }, // 0x46 'F'
|
||||
{ 529, 11, 14, 14, 2, -13 }, // 0x47 'G'
|
||||
{ 549, 10, 14, 14, 2, -13 }, // 0x48 'H'
|
||||
{ 567, 7, 14, 14, 4, -13 }, // 0x49 'I'
|
||||
{ 580, 11, 14, 14, 2, -13 }, // 0x4A 'J'
|
||||
{ 600, 12, 14, 14, 2, -13 }, // 0x4B 'K'
|
||||
{ 621, 11, 14, 14, 2, -13 }, // 0x4C 'L'
|
||||
{ 641, 13, 14, 14, 1, -13 }, // 0x4D 'M'
|
||||
{ 664, 12, 14, 14, 1, -13 }, // 0x4E 'N'
|
||||
{ 685, 12, 14, 14, 1, -13 }, // 0x4F 'O'
|
||||
{ 706, 10, 14, 14, 2, -13 }, // 0x50 'P'
|
||||
{ 724, 12, 17, 14, 1, -13 }, // 0x51 'Q'
|
||||
{ 750, 12, 14, 14, 2, -13 }, // 0x52 'R'
|
||||
{ 771, 10, 14, 14, 2, -13 }, // 0x53 'S'
|
||||
{ 789, 11, 14, 14, 2, -13 }, // 0x54 'T'
|
||||
{ 809, 12, 14, 14, 1, -13 }, // 0x55 'U'
|
||||
{ 830, 14, 14, 14, 0, -13 }, // 0x56 'V'
|
||||
{ 855, 14, 14, 14, 0, -13 }, // 0x57 'W'
|
||||
{ 880, 12, 14, 14, 1, -13 }, // 0x58 'X'
|
||||
{ 901, 12, 14, 14, 1, -13 }, // 0x59 'Y'
|
||||
{ 922, 9, 14, 14, 3, -13 }, // 0x5A 'Z'
|
||||
{ 938, 3, 18, 14, 7, -14 }, // 0x5B '['
|
||||
{ 945, 9, 18, 14, 3, -15 }, // 0x5C '\'
|
||||
{ 966, 3, 18, 14, 5, -14 }, // 0x5D ']'
|
||||
{ 973, 9, 6, 14, 3, -14 }, // 0x5E '^'
|
||||
{ 980, 14, 1, 14, 0, 3 }, // 0x5F '_'
|
||||
{ 982, 4, 4, 14, 4, -15 }, // 0x60 '`'
|
||||
{ 984, 10, 10, 14, 2, -9 }, // 0x61 'a'
|
||||
{ 997, 13, 15, 14, 0, -14 }, // 0x62 'b'
|
||||
{ 1022, 11, 10, 14, 2, -9 }, // 0x63 'c'
|
||||
{ 1036, 11, 15, 14, 2, -14 }, // 0x64 'd'
|
||||
{ 1057, 10, 10, 14, 2, -9 }, // 0x65 'e'
|
||||
{ 1070, 9, 15, 14, 4, -14 }, // 0x66 'f'
|
||||
{ 1087, 11, 14, 14, 2, -9 }, // 0x67 'g'
|
||||
{ 1107, 10, 15, 14, 2, -14 }, // 0x68 'h'
|
||||
{ 1126, 9, 15, 14, 3, -14 }, // 0x69 'i'
|
||||
{ 1143, 7, 19, 14, 3, -14 }, // 0x6A 'j'
|
||||
{ 1160, 12, 15, 14, 1, -14 }, // 0x6B 'k'
|
||||
{ 1183, 9, 15, 14, 3, -14 }, // 0x6C 'l'
|
||||
{ 1200, 13, 10, 14, 1, -9 }, // 0x6D 'm'
|
||||
{ 1217, 12, 10, 14, 1, -9 }, // 0x6E 'n'
|
||||
{ 1232, 11, 10, 14, 2, -9 }, // 0x6F 'o'
|
||||
{ 1246, 12, 14, 14, 1, -9 }, // 0x70 'p'
|
||||
{ 1267, 11, 14, 14, 2, -9 }, // 0x71 'q'
|
||||
{ 1287, 10, 10, 14, 3, -9 }, // 0x72 'r'
|
||||
{ 1300, 10, 10, 14, 2, -9 }, // 0x73 's'
|
||||
{ 1313, 11, 14, 14, 1, -13 }, // 0x74 't'
|
||||
{ 1333, 11, 10, 14, 2, -9 }, // 0x75 'u'
|
||||
{ 1347, 13, 10, 14, 1, -9 }, // 0x76 'v'
|
||||
{ 1364, 13, 10, 14, 1, -9 }, // 0x77 'w'
|
||||
{ 1381, 12, 10, 14, 1, -9 }, // 0x78 'x'
|
||||
{ 1396, 12, 14, 14, 1, -9 }, // 0x79 'y'
|
||||
{ 1417, 9, 10, 14, 3, -9 }, // 0x7A 'z'
|
||||
{ 1429, 5, 18, 14, 5, -14 }, // 0x7B '{'
|
||||
{ 1441, 1, 18, 14, 7, -14 }, // 0x7C '|'
|
||||
{ 1444, 5, 18, 14, 5, -14 }, // 0x7D '}'
|
||||
{ 1456, 10, 3, 14, 2, -7 } }; // 0x7E '~'
|
||||
|
||||
const GFXfont FreeMono12pt7b PROGMEM = {
|
||||
(uint8_t *)FreeMono12pt7bBitmaps,
|
||||
(GFXglyph *)FreeMono12pt7bGlyphs,
|
||||
0x20, 0x7E, 24 };
|
||||
|
||||
// Approx. 2132 bytes
|
|
@ -0,0 +1,176 @@
|
|||
const uint8_t FreeMono9pt7bBitmaps[] PROGMEM = {
|
||||
0xAA, 0xA8, 0x0C, 0xED, 0x24, 0x92, 0x48, 0x24, 0x48, 0x91, 0x2F, 0xE4,
|
||||
0x89, 0x7F, 0x28, 0x51, 0x22, 0x40, 0x08, 0x3E, 0x62, 0x40, 0x30, 0x0E,
|
||||
0x01, 0x81, 0xC3, 0xBE, 0x08, 0x08, 0x71, 0x12, 0x23, 0x80, 0x23, 0xB8,
|
||||
0x0E, 0x22, 0x44, 0x70, 0x38, 0x81, 0x02, 0x06, 0x1A, 0x65, 0x46, 0xC8,
|
||||
0xEC, 0xE9, 0x24, 0x5A, 0xAA, 0xA9, 0x40, 0xA9, 0x55, 0x5A, 0x80, 0x10,
|
||||
0x22, 0x4B, 0xE3, 0x05, 0x11, 0x00, 0x10, 0x20, 0x47, 0xF1, 0x02, 0x04,
|
||||
0x00, 0x6B, 0x48, 0xFF, 0x00, 0xF0, 0x02, 0x08, 0x10, 0x60, 0x81, 0x04,
|
||||
0x08, 0x20, 0x41, 0x02, 0x08, 0x00, 0x38, 0x8A, 0x0C, 0x18, 0x30, 0x60,
|
||||
0xC1, 0x82, 0x88, 0xE0, 0x27, 0x28, 0x42, 0x10, 0x84, 0x21, 0x3E, 0x38,
|
||||
0x8A, 0x08, 0x10, 0x20, 0x82, 0x08, 0x61, 0x03, 0xF8, 0x7C, 0x06, 0x02,
|
||||
0x02, 0x1C, 0x06, 0x01, 0x01, 0x01, 0x42, 0x3C, 0x18, 0xA2, 0x92, 0x8A,
|
||||
0x28, 0xBF, 0x08, 0x21, 0xC0, 0x7C, 0x81, 0x03, 0xE4, 0x40, 0x40, 0x81,
|
||||
0x03, 0x88, 0xE0, 0x1E, 0x41, 0x04, 0x0B, 0x98, 0xB0, 0xC1, 0xC2, 0x88,
|
||||
0xE0, 0xFE, 0x04, 0x08, 0x20, 0x40, 0x82, 0x04, 0x08, 0x20, 0x40, 0x38,
|
||||
0x8A, 0x0C, 0x14, 0x47, 0x11, 0x41, 0x83, 0x8C, 0xE0, 0x38, 0x8A, 0x1C,
|
||||
0x18, 0x68, 0xCE, 0x81, 0x04, 0x13, 0xC0, 0xF0, 0x0F, 0x6C, 0x00, 0xD2,
|
||||
0xD2, 0x00, 0x03, 0x04, 0x18, 0x60, 0x60, 0x18, 0x04, 0x03, 0xFF, 0x80,
|
||||
0x00, 0x1F, 0xF0, 0x40, 0x18, 0x03, 0x00, 0x60, 0x20, 0x60, 0xC0, 0x80,
|
||||
0x3D, 0x84, 0x08, 0x30, 0xC2, 0x00, 0x00, 0x00, 0x30, 0x3C, 0x46, 0x82,
|
||||
0x8E, 0xB2, 0xA2, 0xA2, 0x9F, 0x80, 0x80, 0x40, 0x3C, 0x3C, 0x01, 0x40,
|
||||
0x28, 0x09, 0x01, 0x10, 0x42, 0x0F, 0xC1, 0x04, 0x40, 0x9E, 0x3C, 0xFE,
|
||||
0x21, 0x90, 0x48, 0x67, 0xE2, 0x09, 0x02, 0x81, 0x41, 0xFF, 0x80, 0x3E,
|
||||
0xB0, 0xF0, 0x30, 0x08, 0x04, 0x02, 0x00, 0x80, 0x60, 0x8F, 0x80, 0xFE,
|
||||
0x21, 0x90, 0x68, 0x14, 0x0A, 0x05, 0x02, 0x83, 0x43, 0x7F, 0x00, 0xFF,
|
||||
0x20, 0x90, 0x08, 0x87, 0xC2, 0x21, 0x00, 0x81, 0x40, 0xFF, 0xC0, 0xFF,
|
||||
0xA0, 0x50, 0x08, 0x87, 0xC2, 0x21, 0x00, 0x80, 0x40, 0x78, 0x00, 0x1E,
|
||||
0x98, 0x6C, 0x0A, 0x00, 0x80, 0x20, 0xF8, 0x0B, 0x02, 0x60, 0x87, 0xC0,
|
||||
0xE3, 0xA0, 0x90, 0x48, 0x27, 0xF2, 0x09, 0x04, 0x82, 0x41, 0x71, 0xC0,
|
||||
0xF9, 0x08, 0x42, 0x10, 0x84, 0x27, 0xC0, 0x1F, 0x02, 0x02, 0x02, 0x02,
|
||||
0x02, 0x82, 0x82, 0xC6, 0x78, 0xE3, 0xA1, 0x11, 0x09, 0x05, 0x83, 0x21,
|
||||
0x08, 0x84, 0x41, 0x70, 0xC0, 0xE0, 0x40, 0x40, 0x40, 0x40, 0x40, 0x41,
|
||||
0x41, 0x41, 0xFF, 0xE0, 0xEC, 0x19, 0x45, 0x28, 0xA4, 0xA4, 0x94, 0x91,
|
||||
0x12, 0x02, 0x40, 0x5C, 0x1C, 0xC3, 0xB0, 0x94, 0x4A, 0x24, 0x92, 0x49,
|
||||
0x14, 0x8A, 0x43, 0x70, 0x80, 0x1E, 0x31, 0x90, 0x50, 0x18, 0x0C, 0x06,
|
||||
0x02, 0x82, 0x63, 0x0F, 0x00, 0xFE, 0x43, 0x41, 0x41, 0x42, 0x7C, 0x40,
|
||||
0x40, 0x40, 0xF0, 0x1C, 0x31, 0x90, 0x50, 0x18, 0x0C, 0x06, 0x02, 0x82,
|
||||
0x63, 0x1F, 0x04, 0x07, 0x92, 0x30, 0xFE, 0x21, 0x90, 0x48, 0x24, 0x23,
|
||||
0xE1, 0x10, 0x84, 0x41, 0x70, 0xC0, 0x3A, 0xCD, 0x0A, 0x03, 0x01, 0x80,
|
||||
0xC1, 0xC7, 0x78, 0xFF, 0xC4, 0x62, 0x21, 0x00, 0x80, 0x40, 0x20, 0x10,
|
||||
0x08, 0x1F, 0x00, 0xE3, 0xA0, 0x90, 0x48, 0x24, 0x12, 0x09, 0x04, 0x82,
|
||||
0x22, 0x0E, 0x00, 0xF1, 0xE8, 0x10, 0x82, 0x10, 0x42, 0x10, 0x22, 0x04,
|
||||
0x80, 0x50, 0x0C, 0x00, 0x80, 0xF1, 0xE8, 0x09, 0x11, 0x25, 0x44, 0xA8,
|
||||
0x55, 0x0C, 0xA1, 0x8C, 0x31, 0x84, 0x30, 0xE3, 0xA0, 0x88, 0x82, 0x80,
|
||||
0x80, 0xC0, 0x90, 0x44, 0x41, 0x71, 0xC0, 0xE3, 0xA0, 0x88, 0x82, 0x81,
|
||||
0x40, 0x40, 0x20, 0x10, 0x08, 0x1F, 0x00, 0xFD, 0x0A, 0x20, 0x81, 0x04,
|
||||
0x10, 0x21, 0x83, 0xFC, 0xEA, 0xAA, 0xAA, 0xC0, 0x80, 0x81, 0x03, 0x02,
|
||||
0x04, 0x04, 0x08, 0x08, 0x10, 0x10, 0x20, 0x20, 0xD5, 0x55, 0x55, 0xC0,
|
||||
0x10, 0x51, 0x22, 0x28, 0x20, 0xFF, 0xE0, 0x88, 0x80, 0x7E, 0x00, 0x80,
|
||||
0x47, 0xEC, 0x14, 0x0A, 0x0C, 0xFB, 0xC0, 0x20, 0x10, 0x0B, 0xC6, 0x12,
|
||||
0x05, 0x02, 0x81, 0x40, 0xB0, 0xB7, 0x80, 0x3A, 0x8E, 0x0C, 0x08, 0x10,
|
||||
0x10, 0x9E, 0x03, 0x00, 0x80, 0x47, 0xA4, 0x34, 0x0A, 0x05, 0x02, 0x81,
|
||||
0x21, 0x8F, 0x60, 0x3C, 0x43, 0x81, 0xFF, 0x80, 0x80, 0x61, 0x3E, 0x3D,
|
||||
0x04, 0x3E, 0x41, 0x04, 0x10, 0x41, 0x0F, 0x80, 0x3D, 0xA1, 0xA0, 0x50,
|
||||
0x28, 0x14, 0x09, 0x0C, 0x7A, 0x01, 0x01, 0x87, 0x80, 0xC0, 0x20, 0x10,
|
||||
0x0B, 0xC6, 0x32, 0x09, 0x04, 0x82, 0x41, 0x20, 0xB8, 0xE0, 0x10, 0x01,
|
||||
0xC0, 0x81, 0x02, 0x04, 0x08, 0x11, 0xFC, 0x10, 0x3E, 0x10, 0x84, 0x21,
|
||||
0x08, 0x42, 0x3F, 0x00, 0xC0, 0x40, 0x40, 0x4F, 0x44, 0x58, 0x70, 0x48,
|
||||
0x44, 0x42, 0xC7, 0x70, 0x20, 0x40, 0x81, 0x02, 0x04, 0x08, 0x10, 0x23,
|
||||
0xF8, 0xB7, 0x64, 0x62, 0x31, 0x18, 0x8C, 0x46, 0x23, 0x91, 0x5E, 0x31,
|
||||
0x90, 0x48, 0x24, 0x12, 0x09, 0x05, 0xC7, 0x3E, 0x31, 0xA0, 0x30, 0x18,
|
||||
0x0C, 0x05, 0x8C, 0x7C, 0xDE, 0x30, 0x90, 0x28, 0x14, 0x0A, 0x05, 0x84,
|
||||
0xBC, 0x40, 0x20, 0x38, 0x00, 0x3D, 0xA1, 0xA0, 0x50, 0x28, 0x14, 0x09,
|
||||
0x0C, 0x7A, 0x01, 0x00, 0x80, 0xE0, 0xCE, 0xA1, 0x82, 0x04, 0x08, 0x10,
|
||||
0x7C, 0x3A, 0x8D, 0x0B, 0x80, 0xF0, 0x70, 0xDE, 0x40, 0x40, 0xFC, 0x40,
|
||||
0x40, 0x40, 0x40, 0x40, 0x41, 0x3E, 0xC3, 0x41, 0x41, 0x41, 0x41, 0x41,
|
||||
0x43, 0x3D, 0xE3, 0xA0, 0x90, 0x84, 0x42, 0x20, 0xA0, 0x50, 0x10, 0xE3,
|
||||
0xC0, 0x92, 0x4B, 0x25, 0x92, 0xA9, 0x98, 0x44, 0xE3, 0x31, 0x05, 0x01,
|
||||
0x01, 0x41, 0x11, 0x05, 0xC7, 0xE3, 0xA0, 0x90, 0x84, 0x42, 0x40, 0xA0,
|
||||
0x60, 0x10, 0x10, 0x08, 0x3E, 0x00, 0xFD, 0x08, 0x20, 0x82, 0x08, 0x10,
|
||||
0xBF, 0x29, 0x24, 0xA2, 0x49, 0x26, 0xFF, 0xF8, 0x89, 0x24, 0x8A, 0x49,
|
||||
0x2C, 0x61, 0x24, 0x30 };
|
||||
|
||||
const GFXglyph FreeMono9pt7bGlyphs[] PROGMEM = {
|
||||
{ 0, 0, 0, 11, 0, 1 }, // 0x20 ' '
|
||||
{ 0, 2, 11, 11, 4, -10 }, // 0x21 '!'
|
||||
{ 3, 6, 5, 11, 2, -10 }, // 0x22 '"'
|
||||
{ 7, 7, 12, 11, 2, -10 }, // 0x23 '#'
|
||||
{ 18, 8, 12, 11, 1, -10 }, // 0x24 '$'
|
||||
{ 30, 7, 11, 11, 2, -10 }, // 0x25 '%'
|
||||
{ 40, 7, 10, 11, 2, -9 }, // 0x26 '&'
|
||||
{ 49, 3, 5, 11, 4, -10 }, // 0x27 '''
|
||||
{ 51, 2, 13, 11, 5, -10 }, // 0x28 '('
|
||||
{ 55, 2, 13, 11, 4, -10 }, // 0x29 ')'
|
||||
{ 59, 7, 7, 11, 2, -10 }, // 0x2A '*'
|
||||
{ 66, 7, 7, 11, 2, -8 }, // 0x2B '+'
|
||||
{ 73, 3, 5, 11, 2, -1 }, // 0x2C ','
|
||||
{ 75, 9, 1, 11, 1, -5 }, // 0x2D '-'
|
||||
{ 77, 2, 2, 11, 4, -1 }, // 0x2E '.'
|
||||
{ 78, 7, 13, 11, 2, -11 }, // 0x2F '/'
|
||||
{ 90, 7, 11, 11, 2, -10 }, // 0x30 '0'
|
||||
{ 100, 5, 11, 11, 3, -10 }, // 0x31 '1'
|
||||
{ 107, 7, 11, 11, 2, -10 }, // 0x32 '2'
|
||||
{ 117, 8, 11, 11, 1, -10 }, // 0x33 '3'
|
||||
{ 128, 6, 11, 11, 3, -10 }, // 0x34 '4'
|
||||
{ 137, 7, 11, 11, 2, -10 }, // 0x35 '5'
|
||||
{ 147, 7, 11, 11, 2, -10 }, // 0x36 '6'
|
||||
{ 157, 7, 11, 11, 2, -10 }, // 0x37 '7'
|
||||
{ 167, 7, 11, 11, 2, -10 }, // 0x38 '8'
|
||||
{ 177, 7, 11, 11, 2, -10 }, // 0x39 '9'
|
||||
{ 187, 2, 8, 11, 4, -7 }, // 0x3A ':'
|
||||
{ 189, 3, 11, 11, 3, -7 }, // 0x3B ';'
|
||||
{ 194, 8, 8, 11, 1, -8 }, // 0x3C '<'
|
||||
{ 202, 9, 4, 11, 1, -6 }, // 0x3D '='
|
||||
{ 207, 9, 8, 11, 1, -8 }, // 0x3E '>'
|
||||
{ 216, 7, 10, 11, 2, -9 }, // 0x3F '?'
|
||||
{ 225, 8, 12, 11, 2, -10 }, // 0x40 '@'
|
||||
{ 237, 11, 10, 11, 0, -9 }, // 0x41 'A'
|
||||
{ 251, 9, 10, 11, 1, -9 }, // 0x42 'B'
|
||||
{ 263, 9, 10, 11, 1, -9 }, // 0x43 'C'
|
||||
{ 275, 9, 10, 11, 1, -9 }, // 0x44 'D'
|
||||
{ 287, 9, 10, 11, 1, -9 }, // 0x45 'E'
|
||||
{ 299, 9, 10, 11, 1, -9 }, // 0x46 'F'
|
||||
{ 311, 10, 10, 11, 1, -9 }, // 0x47 'G'
|
||||
{ 324, 9, 10, 11, 1, -9 }, // 0x48 'H'
|
||||
{ 336, 5, 10, 11, 3, -9 }, // 0x49 'I'
|
||||
{ 343, 8, 10, 11, 2, -9 }, // 0x4A 'J'
|
||||
{ 353, 9, 10, 11, 1, -9 }, // 0x4B 'K'
|
||||
{ 365, 8, 10, 11, 2, -9 }, // 0x4C 'L'
|
||||
{ 375, 11, 10, 11, 0, -9 }, // 0x4D 'M'
|
||||
{ 389, 9, 10, 11, 1, -9 }, // 0x4E 'N'
|
||||
{ 401, 9, 10, 11, 1, -9 }, // 0x4F 'O'
|
||||
{ 413, 8, 10, 11, 1, -9 }, // 0x50 'P'
|
||||
{ 423, 9, 13, 11, 1, -9 }, // 0x51 'Q'
|
||||
{ 438, 9, 10, 11, 1, -9 }, // 0x52 'R'
|
||||
{ 450, 7, 10, 11, 2, -9 }, // 0x53 'S'
|
||||
{ 459, 9, 10, 11, 1, -9 }, // 0x54 'T'
|
||||
{ 471, 9, 10, 11, 1, -9 }, // 0x55 'U'
|
||||
{ 483, 11, 10, 11, 0, -9 }, // 0x56 'V'
|
||||
{ 497, 11, 10, 11, 0, -9 }, // 0x57 'W'
|
||||
{ 511, 9, 10, 11, 1, -9 }, // 0x58 'X'
|
||||
{ 523, 9, 10, 11, 1, -9 }, // 0x59 'Y'
|
||||
{ 535, 7, 10, 11, 2, -9 }, // 0x5A 'Z'
|
||||
{ 544, 2, 13, 11, 5, -10 }, // 0x5B '['
|
||||
{ 548, 7, 13, 11, 2, -11 }, // 0x5C '\'
|
||||
{ 560, 2, 13, 11, 4, -10 }, // 0x5D ']'
|
||||
{ 564, 7, 5, 11, 2, -10 }, // 0x5E '^'
|
||||
{ 569, 11, 1, 11, 0, 2 }, // 0x5F '_'
|
||||
{ 571, 3, 3, 11, 3, -11 }, // 0x60 '`'
|
||||
{ 573, 9, 8, 11, 1, -7 }, // 0x61 'a'
|
||||
{ 582, 9, 11, 11, 1, -10 }, // 0x62 'b'
|
||||
{ 595, 7, 8, 11, 2, -7 }, // 0x63 'c'
|
||||
{ 602, 9, 11, 11, 1, -10 }, // 0x64 'd'
|
||||
{ 615, 8, 8, 11, 1, -7 }, // 0x65 'e'
|
||||
{ 623, 6, 11, 11, 3, -10 }, // 0x66 'f'
|
||||
{ 632, 9, 11, 11, 1, -7 }, // 0x67 'g'
|
||||
{ 645, 9, 11, 11, 1, -10 }, // 0x68 'h'
|
||||
{ 658, 7, 10, 11, 2, -9 }, // 0x69 'i'
|
||||
{ 667, 5, 13, 11, 3, -9 }, // 0x6A 'j'
|
||||
{ 676, 8, 11, 11, 2, -10 }, // 0x6B 'k'
|
||||
{ 687, 7, 11, 11, 2, -10 }, // 0x6C 'l'
|
||||
{ 697, 9, 8, 11, 1, -7 }, // 0x6D 'm'
|
||||
{ 706, 9, 8, 11, 1, -7 }, // 0x6E 'n'
|
||||
{ 715, 9, 8, 11, 1, -7 }, // 0x6F 'o'
|
||||
{ 724, 9, 11, 11, 1, -7 }, // 0x70 'p'
|
||||
{ 737, 9, 11, 11, 1, -7 }, // 0x71 'q'
|
||||
{ 750, 7, 8, 11, 3, -7 }, // 0x72 'r'
|
||||
{ 757, 7, 8, 11, 2, -7 }, // 0x73 's'
|
||||
{ 764, 8, 10, 11, 2, -9 }, // 0x74 't'
|
||||
{ 774, 8, 8, 11, 1, -7 }, // 0x75 'u'
|
||||
{ 782, 9, 8, 11, 1, -7 }, // 0x76 'v'
|
||||
{ 791, 9, 8, 11, 1, -7 }, // 0x77 'w'
|
||||
{ 800, 9, 8, 11, 1, -7 }, // 0x78 'x'
|
||||
{ 809, 9, 11, 11, 1, -7 }, // 0x79 'y'
|
||||
{ 822, 7, 8, 11, 2, -7 }, // 0x7A 'z'
|
||||
{ 829, 3, 13, 11, 4, -10 }, // 0x7B '{'
|
||||
{ 834, 1, 13, 11, 5, -10 }, // 0x7C '|'
|
||||
{ 836, 3, 13, 11, 4, -10 }, // 0x7D '}'
|
||||
{ 841, 7, 3, 11, 2, -6 } }; // 0x7E '~'
|
||||
|
||||
const GFXfont FreeMono9pt7b PROGMEM = {
|
||||
(uint8_t *)FreeMono9pt7bBitmaps,
|
||||
(GFXglyph *)FreeMono9pt7bGlyphs,
|
||||
0x20, 0x7E, 18 };
|
||||
|
||||
// Approx. 1516 bytes
|
|
@ -0,0 +1,123 @@
|
|||
// Picopixel by Sebastian Weber. A tiny font
|
||||
// with all characters within a 6 pixel height.
|
||||
|
||||
const uint8_t PicopixelBitmaps[] PROGMEM = {
|
||||
0xE8, 0xB4, 0x57, 0xD5, 0xF5, 0x00, 0x4E, 0x3E, 0x80, 0xA5, 0x4A, 0x4A,
|
||||
0x5A, 0x50, 0xC0, 0x6A, 0x40, 0x95, 0x80, 0xAA, 0x80, 0x5D, 0x00, 0x60,
|
||||
0xE0, 0x80, 0x25, 0x48, 0x56, 0xD4, 0x75, 0x40, 0xC5, 0x4E, 0xC5, 0x1C,
|
||||
0x97, 0x92, 0xF3, 0x1C, 0x53, 0x54, 0xE5, 0x48, 0x55, 0x54, 0x55, 0x94,
|
||||
0xA0, 0x46, 0x64, 0xE3, 0x80, 0x98, 0xC5, 0x04, 0x56, 0xC6, 0x57, 0xDA,
|
||||
0xD7, 0x5C, 0x72, 0x46, 0xD6, 0xDC, 0xF3, 0xCE, 0xF3, 0x48, 0x72, 0xD4,
|
||||
0xB7, 0xDA, 0xF8, 0x24, 0xD4, 0xBB, 0x5A, 0x92, 0x4E, 0x8E, 0xEB, 0x58,
|
||||
0x80, 0x9D, 0xB9, 0x90, 0x56, 0xD4, 0xD7, 0x48, 0x56, 0xD4, 0x40, 0xD7,
|
||||
0x5A, 0x71, 0x1C, 0xE9, 0x24, 0xB6, 0xD4, 0xB6, 0xA4, 0x8C, 0x6B, 0x55,
|
||||
0x00, 0xB5, 0x5A, 0xB5, 0x24, 0xE5, 0x4E, 0xEA, 0xC0, 0x91, 0x12, 0xD5,
|
||||
0xC0, 0x54, 0xF0, 0x90, 0xC7, 0xF0, 0x93, 0x5E, 0x71, 0x80, 0x25, 0xDE,
|
||||
0x5E, 0x30, 0x6E, 0x80, 0x77, 0x9C, 0x93, 0x5A, 0xB8, 0x45, 0x60, 0x92,
|
||||
0xEA, 0xAA, 0x40, 0xD5, 0x6A, 0xD6, 0x80, 0x55, 0x00, 0xD7, 0x40, 0x75,
|
||||
0x90, 0xE8, 0x71, 0xE0, 0xBA, 0x40, 0xB5, 0x80, 0xB5, 0x00, 0x8D, 0x54,
|
||||
0xAA, 0x80, 0xAC, 0xE0, 0xE5, 0x70, 0x6A, 0x26, 0xFC, 0xC8, 0xAC, 0x5A };
|
||||
|
||||
const GFXglyph PicopixelGlyphs[] PROGMEM = {
|
||||
{ 0, 0, 0, 2, 0, 1 }, // 0x20 ' '
|
||||
{ 0, 1, 5, 2, 0, -4 }, // 0x21 '!'
|
||||
{ 1, 3, 2, 4, 0, -4 }, // 0x22 '"'
|
||||
{ 2, 5, 5, 6, 0, -4 }, // 0x23 '#'
|
||||
{ 6, 3, 6, 4, 0, -4 }, // 0x24 '$'
|
||||
{ 9, 3, 5, 4, 0, -4 }, // 0x25 '%'
|
||||
{ 11, 4, 5, 5, 0, -4 }, // 0x26 '&'
|
||||
{ 14, 1, 2, 2, 0, -4 }, // 0x27 '''
|
||||
{ 15, 2, 5, 3, 0, -4 }, // 0x28 '('
|
||||
{ 17, 2, 5, 3, 0, -4 }, // 0x29 ')'
|
||||
{ 19, 3, 3, 4, 0, -3 }, // 0x2A '*'
|
||||
{ 21, 3, 3, 4, 0, -3 }, // 0x2B '+'
|
||||
{ 23, 2, 2, 3, 0, 0 }, // 0x2C ','
|
||||
{ 24, 3, 1, 4, 0, -2 }, // 0x2D '-'
|
||||
{ 25, 1, 1, 2, 0, 0 }, // 0x2E '.'
|
||||
{ 26, 3, 5, 4, 0, -4 }, // 0x2F '/'
|
||||
{ 28, 3, 5, 4, 0, -4 }, // 0x30 '0'
|
||||
{ 30, 2, 5, 3, 0, -4 }, // 0x31 '1'
|
||||
{ 32, 3, 5, 4, 0, -4 }, // 0x32 '2'
|
||||
{ 34, 3, 5, 4, 0, -4 }, // 0x33 '3'
|
||||
{ 36, 3, 5, 4, 0, -4 }, // 0x34 '4'
|
||||
{ 38, 3, 5, 4, 0, -4 }, // 0x35 '5'
|
||||
{ 40, 3, 5, 4, 0, -4 }, // 0x36 '6'
|
||||
{ 42, 3, 5, 4, 0, -4 }, // 0x37 '7'
|
||||
{ 44, 3, 5, 4, 0, -4 }, // 0x38 '8'
|
||||
{ 46, 3, 5, 4, 0, -4 }, // 0x39 '9'
|
||||
{ 48, 1, 3, 2, 0, -3 }, // 0x3A ':'
|
||||
{ 49, 2, 4, 3, 0, -3 }, // 0x3B ';'
|
||||
{ 50, 2, 3, 3, 0, -3 }, // 0x3C '<'
|
||||
{ 51, 3, 3, 4, 0, -3 }, // 0x3D '='
|
||||
{ 53, 2, 3, 3, 0, -3 }, // 0x3E '>'
|
||||
{ 54, 3, 5, 4, 0, -4 }, // 0x3F '?'
|
||||
{ 56, 3, 5, 4, 0, -4 }, // 0x40 '@'
|
||||
{ 58, 3, 5, 4, 0, -4 }, // 0x41 'A'
|
||||
{ 60, 3, 5, 4, 0, -4 }, // 0x42 'B'
|
||||
{ 62, 3, 5, 4, 0, -4 }, // 0x43 'C'
|
||||
{ 64, 3, 5, 4, 0, -4 }, // 0x44 'D'
|
||||
{ 66, 3, 5, 4, 0, -4 }, // 0x45 'E'
|
||||
{ 68, 3, 5, 4, 0, -4 }, // 0x46 'F'
|
||||
{ 70, 3, 5, 4, 0, -4 }, // 0x47 'G'
|
||||
{ 72, 3, 5, 4, 0, -4 }, // 0x48 'H'
|
||||
{ 74, 1, 5, 2, 0, -4 }, // 0x49 'I'
|
||||
{ 75, 3, 5, 4, 0, -4 }, // 0x4A 'J'
|
||||
{ 77, 3, 5, 4, 0, -4 }, // 0x4B 'K'
|
||||
{ 79, 3, 5, 4, 0, -4 }, // 0x4C 'L'
|
||||
{ 81, 5, 5, 6, 0, -4 }, // 0x4D 'M'
|
||||
{ 85, 4, 5, 5, 0, -4 }, // 0x4E 'N'
|
||||
{ 88, 3, 5, 4, 0, -4 }, // 0x4F 'O'
|
||||
{ 90, 3, 5, 4, 0, -4 }, // 0x50 'P'
|
||||
{ 92, 3, 6, 4, 0, -4 }, // 0x51 'Q'
|
||||
{ 95, 3, 5, 4, 0, -4 }, // 0x52 'R'
|
||||
{ 97, 3, 5, 4, 0, -4 }, // 0x53 'S'
|
||||
{ 99, 3, 5, 4, 0, -4 }, // 0x54 'T'
|
||||
{ 101, 3, 5, 4, 0, -4 }, // 0x55 'U'
|
||||
{ 103, 3, 5, 4, 0, -4 }, // 0x56 'V'
|
||||
{ 105, 5, 5, 6, 0, -4 }, // 0x57 'W'
|
||||
{ 109, 3, 5, 4, 0, -4 }, // 0x58 'X'
|
||||
{ 111, 3, 5, 4, 0, -4 }, // 0x59 'Y'
|
||||
{ 113, 3, 5, 4, 0, -4 }, // 0x5A 'Z'
|
||||
{ 115, 2, 5, 3, 0, -4 }, // 0x5B '['
|
||||
{ 117, 3, 5, 4, 0, -4 }, // 0x5C '\'
|
||||
{ 119, 2, 5, 3, 0, -4 }, // 0x5D ']'
|
||||
{ 121, 3, 2, 4, 0, -4 }, // 0x5E '^'
|
||||
{ 122, 4, 1, 4, 0, 1 }, // 0x5F '_'
|
||||
{ 123, 2, 2, 3, 0, -4 }, // 0x60 '`'
|
||||
{ 124, 3, 4, 4, 0, -3 }, // 0x61 'a'
|
||||
{ 126, 3, 5, 4, 0, -4 }, // 0x62 'b'
|
||||
{ 128, 3, 3, 4, 0, -2 }, // 0x63 'c'
|
||||
{ 130, 3, 5, 4, 0, -4 }, // 0x64 'd'
|
||||
{ 132, 3, 4, 4, 0, -3 }, // 0x65 'e'
|
||||
{ 134, 2, 5, 3, 0, -4 }, // 0x66 'f'
|
||||
{ 136, 3, 5, 4, 0, -3 }, // 0x67 'g'
|
||||
{ 138, 3, 5, 4, 0, -4 }, // 0x68 'h'
|
||||
{ 140, 1, 5, 2, 0, -4 }, // 0x69 'i'
|
||||
{ 141, 2, 6, 3, 0, -4 }, // 0x6A 'j'
|
||||
{ 143, 3, 5, 4, 0, -4 }, // 0x6B 'k'
|
||||
{ 145, 2, 5, 3, 0, -4 }, // 0x6C 'l'
|
||||
{ 147, 5, 3, 6, 0, -2 }, // 0x6D 'm'
|
||||
{ 149, 3, 3, 4, 0, -2 }, // 0x6E 'n'
|
||||
{ 151, 3, 3, 4, 0, -2 }, // 0x6F 'o'
|
||||
{ 153, 3, 4, 4, 0, -2 }, // 0x70 'p'
|
||||
{ 155, 3, 4, 4, 0, -2 }, // 0x71 'q'
|
||||
{ 157, 2, 3, 3, 0, -2 }, // 0x72 'r'
|
||||
{ 158, 3, 4, 4, 0, -3 }, // 0x73 's'
|
||||
{ 160, 2, 5, 3, 0, -4 }, // 0x74 't'
|
||||
{ 162, 3, 3, 4, 0, -2 }, // 0x75 'u'
|
||||
{ 164, 3, 3, 4, 0, -2 }, // 0x76 'v'
|
||||
{ 166, 5, 3, 6, 0, -2 }, // 0x77 'w'
|
||||
{ 168, 3, 3, 4, 0, -2 }, // 0x78 'x'
|
||||
{ 170, 3, 4, 4, 0, -2 }, // 0x79 'y'
|
||||
{ 172, 3, 4, 4, 0, -3 }, // 0x7A 'z'
|
||||
{ 174, 3, 5, 4, 0, -4 }, // 0x7B '{'
|
||||
{ 176, 1, 6, 2, 0, -4 }, // 0x7C '|'
|
||||
{ 177, 3, 5, 4, 0, -4 }, // 0x7D '}'
|
||||
{ 179, 4, 2, 5, 0, -3 } }; // 0x7E '~'
|
||||
|
||||
const GFXfont Picopixel PROGMEM = {
|
||||
(uint8_t *)PicopixelBitmaps,
|
||||
(GFXglyph *)PicopixelGlyphs,
|
||||
0x20, 0x7E, 7 };
|
||||
|
||||
// Approx. 852 bytes
|
|
@ -1,20 +1,62 @@
|
|||
#!/usr/bin/python
|
||||
import os
|
||||
import sys
|
||||
import csv
|
||||
import subprocess
|
||||
|
||||
#default.csv content:
|
||||
#nvs, data, nvs, 0x9000, 0x5000,
|
||||
#otadata, data, ota, 0xe000, 0x2000,
|
||||
#app0, app, ota_0, 0x10000, 0x140000,
|
||||
#app1, app, ota_1, 0x150000,0x140000,
|
||||
#spiffs, data, spiffs, 0x290000,0x170000,
|
||||
|
||||
MKSPIFFS = os.environ['MKSPIFFS']
|
||||
print "mkspiffs is "+MKSPIFFS
|
||||
|
||||
OFFSET_BOOTLOADER = 0x1000
|
||||
OFFSET_PARTITIONS = 0x8000
|
||||
|
||||
## now taken from default.csv
|
||||
OFFSET_BOOTAPP0 = 0xE000
|
||||
OFFSET_APPLICATION = 0x10000
|
||||
OFFSET_SPIFFS = 0x291000
|
||||
SIZE_SPIFFS = 0x16F000
|
||||
|
||||
esp32tools = sys.argv[1]
|
||||
file_in = sys.argv[2]
|
||||
file_spiffs = sys.argv[3]
|
||||
data_dir = sys.argv[3]
|
||||
file_out = sys.argv[4]
|
||||
|
||||
partition = esp32tools + "/partitions/default.csv"
|
||||
with open(partition, 'rb') as csvfile:
|
||||
partreader = csv.reader(csvfile, delimiter=',')
|
||||
for row in partreader:
|
||||
if row[0] == "otadata":
|
||||
OFFSET_BOOTAPP0 = int(row[3],16)
|
||||
if row[0] == "app0":
|
||||
OFFSET_APPLICATION = int(row[3],16)
|
||||
if row[0] == "spiffs":
|
||||
OFFSET_SPIFFS = int(row[3],16)
|
||||
SIZE_SPIFFS = int(row[4],16)
|
||||
|
||||
print "bootapp0: "+hex(OFFSET_BOOTAPP0)
|
||||
print "app0: "+hex(OFFSET_APPLICATION)
|
||||
print "spiffs: "+hex(OFFSET_SPIFFS)+" size "+hex(SIZE_SPIFFS)
|
||||
|
||||
# create binary partition
|
||||
file_part = "/tmp/partition.bin"
|
||||
partproc = subprocess.Popen(['python', esp32tools+'/gen_esp32part.py', partition, file_part]);
|
||||
partproc.wait();
|
||||
|
||||
# create SPI file system
|
||||
file_spiffs = "/tmp/spiffs.bin"
|
||||
spiproc = subprocess.Popen([MKSPIFFS,'-c',data_dir,'-b','4096','-p','256','-s',str(SIZE_SPIFFS),file_spiffs]);
|
||||
spiproc.wait();
|
||||
|
||||
files_in = [
|
||||
('bootloader', OFFSET_BOOTLOADER, esp32tools+"/sdk/bin/bootloader_dio_80m.bin"),
|
||||
('partitions', OFFSET_PARTITIONS, esp32tools+"/partitions/default.bin"),
|
||||
('partitions', OFFSET_PARTITIONS, file_part),
|
||||
('bootapp0', OFFSET_BOOTAPP0, esp32tools+"/partitions/boot_app0.bin"),
|
||||
('application', OFFSET_APPLICATION, file_in),
|
||||
('spiffs', OFFSET_SPIFFS, file_spiffs),
|
||||
|
|
Ładowanie…
Reference in New Issue