You've already forked TEF6686_ESP32
way better start sequence, faster too
This commit is contained in:
35518
docs/Schematic_DP-666_V2.5.3.pdf
Normal file
35518
docs/Schematic_DP-666_V2.5.3.pdf
Normal file
File diff suppressed because it is too large
Load Diff
@@ -7,12 +7,6 @@
|
||||
#include "change_detector.h"
|
||||
#include "rtc.hpp"
|
||||
|
||||
extern const unsigned char tuner_init_tab[] PROGMEM;
|
||||
extern const unsigned char tuner_init_tab9216[] PROGMEM;
|
||||
extern const unsigned char tuner_init_tab4000[] PROGMEM;
|
||||
extern const unsigned char tuner_init_tab12000[] PROGMEM;
|
||||
extern const unsigned char tuner_init_tab55000[] PROGMEM;
|
||||
|
||||
enum RDS_GROUPS {
|
||||
RDS_GROUP_0A, RDS_GROUP_0B, RDS_GROUP_1A, RDS_GROUP_1B, RDS_GROUP_2A, RDS_GROUP_2B, RDS_GROUP_3A, RDS_GROUP_3B,
|
||||
RDS_GROUP_4A, RDS_GROUP_4B, RDS_GROUP_5A, RDS_GROUP_5B, RDS_GROUP_6A, RDS_GROUP_6B, RDS_GROUP_7A, RDS_GROUP_7B,
|
||||
|
||||
@@ -8,11 +8,12 @@ typedef enum {
|
||||
TEF_FM = 32,
|
||||
TEF_AM = 33,
|
||||
TEF_AUDIO = 48,
|
||||
TEF_APPL = 64
|
||||
TEF_APPL = 64,
|
||||
TEF_INIT = 20
|
||||
} TEF_MODULE;
|
||||
|
||||
typedef enum {
|
||||
Cmd_Tune_To = 1,
|
||||
Cmd_Tune_To = 1,
|
||||
Cmd_Set_Bandwidth = 10,
|
||||
Cmd_Set_RFAGC = 11,
|
||||
Cmd_Set_Antenna = 12,
|
||||
@@ -29,10 +30,13 @@ typedef enum {
|
||||
Cmd_Set_Highcut_Noise = 53,
|
||||
Cmd_Set_Highcut_Mph = 54,
|
||||
Cmd_Set_Highcut_Max = 55,
|
||||
Cmd_Set_LowCut_Max = 57,
|
||||
Cmd_Set_Stereo_Time = 60,
|
||||
Cmd_Set_Stereo_Level = 62,
|
||||
Cmd_Set_Stereo_Noise = 63,
|
||||
Cmd_Set_Stereo_Mph = 64,
|
||||
Cmd_Set_Stereo_Min = 66,
|
||||
Cmd_Set_StHiBlend_Time = 70,
|
||||
Cmd_Set_StHiBlend_Level = 72,
|
||||
Cmd_Set_StHiBlend_Noise = 73,
|
||||
Cmd_Set_StHiBlend_Mph = 74,
|
||||
@@ -54,13 +58,18 @@ typedef enum {
|
||||
typedef enum {
|
||||
Cmd_Set_Volume = 10,
|
||||
Cmd_Set_Mute = 11,
|
||||
Cmd_Set_Output_Source = 13,
|
||||
Cmd_Set_Input = 12,
|
||||
Cmd_Set_Ana_Out = 21,
|
||||
Cmd_Set_Dig_IO = 22,
|
||||
Cmd_Set_WaveGen = 24
|
||||
} TEF_AUDIO_COMMAND;
|
||||
|
||||
typedef enum {
|
||||
Cmd_Set_OperationMode = 1,
|
||||
Cmd_Set_GPIO = 3,
|
||||
Cmd_Set_ReferenceClock = 4,
|
||||
Cmd_Set_Activate = 5,
|
||||
Cmd_Get_Operation_Status = 128,
|
||||
Cmd_Get_Identification = 130
|
||||
} TEF_APPL_COMMAND;
|
||||
|
||||
@@ -1,9 +1,12 @@
|
||||
#pragma once
|
||||
|
||||
void Tuner_I2C_Init();
|
||||
#ifndef DEEPELEC_DP_66X
|
||||
#define FORBIDDEN_TUNER(x) ((x) != 102 && (x) != 205)
|
||||
#else
|
||||
#define FORBIDDEN_TUNER(x) ((x) != 102)
|
||||
#endif
|
||||
|
||||
void Tuner_Patch(byte TEF);
|
||||
void Tuner_Init(const unsigned char *table);
|
||||
bool Tuner_WriteBuffer(unsigned char *buf, uint16_t len);
|
||||
bool Tuner_ReadBuffer(unsigned char *buf, uint16_t len);
|
||||
bool Tuner_Table_Write(const unsigned char *tab);
|
||||
void Tuner_Reset();
|
||||
@@ -13,13 +13,15 @@
|
||||
#define BWBUTTON 25
|
||||
#define MODEBUTTON 26
|
||||
#define CONTRASTPIN 2
|
||||
#define STANDBYLED 19
|
||||
#define SMETERPIN 27
|
||||
#define TOUCHIRQ 33
|
||||
#define EXT_IRQ 14
|
||||
|
||||
#ifndef DEEPELEC_DP_66X
|
||||
#define STANDBYLED 19
|
||||
#define SMETERPIN 27
|
||||
#endif
|
||||
|
||||
#define XL9555_ADDRESS 0x20 // GPIO driver used in the DP666 for the 0-9 + DX(Backspace) + Enter buttons
|
||||
// Assumes that A0 = A1 = A2 = 0 of the chip, this can range from 0x20 to 0x27
|
||||
|
||||
#define TEF668X_ADDRESS 0x64 // I2C address of the TEF itself! Not sure if this even changes
|
||||
|
||||
@@ -37,11 +39,10 @@
|
||||
typeof (Y) y_ = (Y);\
|
||||
(x_ < y_) ? x_ : y_; }
|
||||
|
||||
#define TIMER_OFFSET_TIMER (TIMER_500_TICK)
|
||||
#define TIMER_BW_TIMER (TIMER_500_TICK)
|
||||
#define TIMER_SNR_TIMER 50
|
||||
#define TIMER_BAT_TIMER (TIMER_500_TICK)
|
||||
#define TIMER_500_TICK 500
|
||||
#define TIMER_OFFSET_TIMER 250
|
||||
#define TIMER_BW_TIMER 300
|
||||
#define TIMER_SNR_TIMER 30
|
||||
#define TIMER_BAT_TIMER 750
|
||||
|
||||
#define BAT_LEVEL_STAGE 8
|
||||
#define BATTERY_LOW_VALUE 3.2
|
||||
@@ -376,7 +377,7 @@ enum LONGBANDBUTTONPRESS {
|
||||
enum menupage {INDEX, MAINSETTINGS, AUDIOSETTINGS, DISPLAYSETTINGS, RDSSETTINGS, FMSETTINGS, AMSETTINGS, CONNECTIVITY, DXMODE, AUTOMEM};
|
||||
|
||||
enum AUTOMEMPIMODES {
|
||||
MEMPI_OFF = 0, MEMPI_RANGE, MEMPI_FULL
|
||||
MEMPI_OFF = 0, MEMPI_RANGE
|
||||
};
|
||||
|
||||
enum SCAN_CANCEL {
|
||||
@@ -384,7 +385,7 @@ enum SCAN_CANCEL {
|
||||
};
|
||||
|
||||
enum RADIO_BAND {
|
||||
BAND_OIRT = 0, BAND_FM, BAND_GAP, BAND_LW, BAND_MW, BAND_SW, BAND_NONEXISTENT
|
||||
BAND_OIRT = 0, BAND_FM, BAND_GAP, BAND_LW, BAND_MW, BAND_SW
|
||||
};
|
||||
|
||||
enum RADIO_FM_BAND_SELECTION {
|
||||
|
||||
@@ -105,24 +105,45 @@ uint16_t TEF6686::TestAF() {
|
||||
return currentfreq;
|
||||
}
|
||||
|
||||
|
||||
void TEF6686::init(byte TEF) {
|
||||
Tuner_I2C_Init();
|
||||
Tuner_Reset();
|
||||
|
||||
uint8_t bootstatus = devTEF_APPL_Get_Operation_Status();
|
||||
if (bootstatus == 0) {
|
||||
Tuner_Patch(TEF);
|
||||
delay(50);
|
||||
while(devTEF_APPL_Get_Operation_Status() != 0) delay(5);
|
||||
|
||||
int xtalADC = analogRead(15);
|
||||
if (xtalADC < XTAL_0V_ADC + XTAL_ADC_TOL) Tuner_Init(tuner_init_tab9216);
|
||||
else if (xtalADC > XTAL_1V_ADC - XTAL_ADC_TOL && xtalADC < XTAL_1V_ADC + XTAL_ADC_TOL) Tuner_Init(tuner_init_tab12000);
|
||||
else if (xtalADC > XTAL_2V_ADC - XTAL_ADC_TOL && xtalADC < XTAL_2V_ADC + XTAL_ADC_TOL) Tuner_Init(tuner_init_tab55000);
|
||||
else Tuner_Init(tuner_init_tab4000);
|
||||
uint32_t clock = 12000000;
|
||||
|
||||
power(1);
|
||||
Tuner_Init(tuner_init_tab);
|
||||
}
|
||||
#ifndef DEEPELEC_DP_66X
|
||||
int xtalADC = analogRead(15);
|
||||
if (xtalADC < XTAL_0V_ADC + XTAL_ADC_TOL) clock = 9216000;
|
||||
else if (xtalADC > XTAL_1V_ADC - XTAL_ADC_TOL && xtalADC < XTAL_1V_ADC + XTAL_ADC_TOL);
|
||||
else if (xtalADC > XTAL_2V_ADC - XTAL_ADC_TOL && xtalADC < XTAL_2V_ADC + XTAL_ADC_TOL) clock = 55466670;
|
||||
else clock = 4000000;
|
||||
#endif
|
||||
|
||||
// Send the firmware to the device
|
||||
Tuner_Patch(TEF);
|
||||
|
||||
// Start the firmware
|
||||
devTEF_Set_Cmd(TEF_INIT, 0, 3);
|
||||
|
||||
while(devTEF_APPL_Get_Operation_Status() != 1) delay(5); // Wait for it to load
|
||||
|
||||
if(clock != 9216000) devTEF_Set_Cmd(TEF_APPL, Cmd_Set_ReferenceClock, 9, (clock >> 16) & 0xffff, clock & 0xffff, (clock == 55466670) ? 1 : 0);
|
||||
devTEF_Set_Cmd(TEF_APPL, Cmd_Set_Activate, 5, 1); // Setup done, start radio
|
||||
|
||||
while(devTEF_APPL_Get_Operation_Status() != 2) delay(5); // Wait for it to start
|
||||
|
||||
devTEF_Set_Cmd(TEF_FM, Cmd_Set_Highcut_Mph, 9, 0, 360, 300);
|
||||
devTEF_Set_Cmd(TEF_FM, Cmd_Set_Highcut_Max, 7, 0, 4000);
|
||||
devTEF_Set_Cmd(TEF_FM, Cmd_Set_LowCut_Max, 7, 0, 100);
|
||||
devTEF_Set_Cmd(TEF_FM, Cmd_Set_Stereo_Time, 11, 60, 120, 100, 200);
|
||||
devTEF_Set_Cmd(TEF_FM, Cmd_Set_StHiBlend_Time, 11, 500, 2000, 200, 200);
|
||||
devTEF_Set_Cmd(TEF_FM, Cmd_Set_StHiBlend_Level, 9, 0, 600, 240);
|
||||
devTEF_Set_Cmd(TEF_FM, Cmd_Set_StHiBlend_Noise, 9, 0, 160, 140);
|
||||
devTEF_Set_Cmd(TEF_FM, Cmd_Set_StHiBlend_Mph, 9, 0, 160, 140);
|
||||
devTEF_Set_Cmd(TEF_FM, Cmd_Set_StHiBlend_Max, 7, 0, 4000);
|
||||
devTEF_Set_Cmd(TEF_AUDIO, Cmd_Set_Ana_Out, 7, 128, 1);
|
||||
devTEF_Set_Cmd(TEF_AUDIO, Cmd_Set_Output_Source, 7, 128, 224);
|
||||
}
|
||||
|
||||
void TEF6686::getIdentification(uint16_t *device, uint16_t *hw_version, uint16_t *sw_version) {
|
||||
@@ -1251,11 +1272,11 @@ void TEF6686::readRDS(byte showrdserrors) {
|
||||
rds.hasCT = true;
|
||||
rds.offset = timeoffset;
|
||||
rtcset = true;
|
||||
|
||||
|
||||
time_t rds_utc_time = rdstime + timeoffset;
|
||||
int32_t current_correction = rtc_time - rds_utc_time;
|
||||
rds.clock_correction = current_correction;
|
||||
|
||||
|
||||
if (!NTPupdated) {
|
||||
time_t corrected_time = rds_utc_time - (current_correction / 2);
|
||||
rtc.setTime(corrected_time);
|
||||
|
||||
@@ -32,7 +32,7 @@ bool devTEF_Get_Cmd(TEF_MODULE module, uint8_t cmd, uint8_t *receive, uint16_t l
|
||||
|
||||
uint8_t devTEF_APPL_Get_Operation_Status() {
|
||||
uint8_t buf[2];
|
||||
devTEF_Get_Cmd(TEF_APPL, Cmd_Get_Operation_Status, buf, sizeof(buf));
|
||||
while(!devTEF_Get_Cmd(TEF_APPL, Cmd_Get_Operation_Status, buf, sizeof(buf))) delay(1);
|
||||
return Convert8bto16b(buf);
|
||||
}
|
||||
|
||||
|
||||
@@ -1,60 +1,15 @@
|
||||
#include "globals.h"
|
||||
#include "Tuner_Patch_Lithio_V102_p224.h"
|
||||
#ifndef DEEPELEC_DP_66X
|
||||
#include "Tuner_Patch_Lithio_V205_p512.h"
|
||||
#endif
|
||||
#include <Wire.h>
|
||||
|
||||
const unsigned char tuner_init_tab[] PROGMEM = {
|
||||
9, 0x20, 0x36, 0x01, 0x00, 0x00, 0x01, 0x68, 0x01, 0x2C,
|
||||
7, 0x20, 0x37, 0x01, 0x00, 0x00, 0x0F, 0xA0,
|
||||
7, 0x20, 0x39, 0x01, 0x00, 0x00, 0x00, 0x64,
|
||||
11, 0x20, 0x3C, 0x01, 0x00, 0x3C, 0x00, 0x78, 0x00, 0x64, 0x00, 0xC8,
|
||||
11, 0x20, 0x46, 0x01, 0x01, 0xF4, 0x07, 0xD0, 0x00, 0xC8, 0x00, 0xC8,
|
||||
9, 0x20, 0x48, 0x01, 0x00, 0x00, 0x02, 0x58, 0x00, 0xF0,
|
||||
9, 0x20, 0x49, 0x01, 0x00, 0x00, 0x00, 0xA0, 0x00, 0x8C,
|
||||
9, 0x20, 0x4A, 0x01, 0x00, 0x00, 0x00, 0xA0, 0x00, 0x8C,
|
||||
7, 0x20, 0x4B, 0x01, 0x00, 0x00, 0x0F, 0xA0,
|
||||
7, 0x30, 0x15, 0x01, 0x00, 0x80, 0x00, 0x01,
|
||||
13, 0x30, 0x16, 0x01, 0x00, 0x21, 0x00, 0x02, 0x00, 0x10, 0x01, 0x00, 0x12, 0xc0,
|
||||
7, 0x30, 0x0d, 0x01, 0x00, 0x80, 0x00, 0xe0
|
||||
};
|
||||
|
||||
const unsigned char tuner_init_tab4000[] PROGMEM = {
|
||||
3, 0x14, 0x00, 0x01,
|
||||
2, 0xff, 50,
|
||||
9, 0x40, 0x04, 0x01, 0x00, 0x3D, 0x09, 0x00, 0x00, 0x00,
|
||||
5, 0x40, 0x05, 0x01, 0x00, 0x01,
|
||||
2, 0xff, 100,
|
||||
};
|
||||
|
||||
const unsigned char tuner_init_tab9216[] PROGMEM = {
|
||||
3, 0x14, 0x00, 0x01,
|
||||
2, 0xff, 50,
|
||||
9, 0x40, 0x04, 0x01, 0x00, 0x8C, 0xA0, 0x00, 0x00, 0x00,
|
||||
5, 0x40, 0x05, 0x01, 0x00, 0x01,
|
||||
2, 0xff, 100,
|
||||
};
|
||||
|
||||
const unsigned char tuner_init_tab12000[] PROGMEM = {
|
||||
3, 0x14, 0x00, 0x01,
|
||||
2, 0xff, 50,
|
||||
9, 0x40, 0x04, 0x01, 0x00, 0xB7, 0x1B, 0x00, 0x00, 0x00,
|
||||
5, 0x40, 0x05, 0x01, 0x00, 0x01,
|
||||
2, 0xff, 100,
|
||||
};
|
||||
|
||||
const unsigned char tuner_init_tab55000[] PROGMEM = {
|
||||
3, 0x14, 0x00, 0x01,
|
||||
2, 0xff, 50,
|
||||
9, 0x40, 0x04, 0x01, 0x03, 0x4E, 0x5A, 0xAE, 0x00, 0x01,
|
||||
5, 0x40, 0x05, 0x01, 0x00, 0x01,
|
||||
2, 0xff, 100,
|
||||
};
|
||||
|
||||
bool Tuner_WriteBuffer(unsigned char *buf, uint16_t len) {
|
||||
Wire.beginTransmission(TEF668X_ADDRESS);
|
||||
for (uint16_t i = 0; i < len; i++) Wire.write(buf[i]);
|
||||
uint8_t r = Wire.endTransmission();
|
||||
if (!Data_Accelerator) delay(2);
|
||||
if (!Data_Accelerator) delay(1);
|
||||
return (r == 0) ? true : false;
|
||||
}
|
||||
|
||||
@@ -84,14 +39,7 @@ static void Tuner_Patch_Load(const unsigned char *pLutBytes, uint16_t size) {
|
||||
}
|
||||
}
|
||||
|
||||
bool Tuner_Table_Write(const unsigned char *tab) {
|
||||
if (tab[1] == 0xff) {
|
||||
delay(tab[2]);
|
||||
return true;
|
||||
} else return Tuner_WriteBuffer((unsigned char *)&tab[1], tab[0]);
|
||||
}
|
||||
|
||||
void Tuner_Reset(void) {
|
||||
void Tuner_Reset() {
|
||||
Wire.beginTransmission(TEF668X_ADDRESS);
|
||||
Wire.write(0x1e);
|
||||
Wire.write(0x5a);
|
||||
@@ -102,14 +50,11 @@ void Tuner_Reset(void) {
|
||||
}
|
||||
|
||||
void Tuner_Patch(byte TEF) {
|
||||
Tuner_Reset();
|
||||
delay(100);
|
||||
Wire.beginTransmission(TEF668X_ADDRESS);
|
||||
Wire.write(0x1c);
|
||||
Wire.write(0x00);
|
||||
Wire.write(0x00);
|
||||
Wire.endTransmission();
|
||||
delay(100);
|
||||
Wire.beginTransmission(TEF668X_ADDRESS);
|
||||
Wire.write(0x1c);
|
||||
Wire.write(0x00);
|
||||
@@ -119,16 +64,17 @@ void Tuner_Patch(byte TEF) {
|
||||
case 102:
|
||||
Tuner_Patch_Load(pPatchBytes102, PatchSize102);
|
||||
break;
|
||||
#ifndef DEEPELEC_DP_66X
|
||||
case 205:
|
||||
Tuner_Patch_Load(pPatchBytes205, PatchSize205);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
Wire.beginTransmission(TEF668X_ADDRESS);
|
||||
Wire.write(0x1c);
|
||||
Wire.write(0x00);
|
||||
Wire.write(0x00);
|
||||
Wire.endTransmission();
|
||||
delay(100);
|
||||
Wire.beginTransmission(TEF668X_ADDRESS);
|
||||
Wire.write(0x1c);
|
||||
Wire.write(0x00);
|
||||
@@ -138,28 +84,15 @@ void Tuner_Patch(byte TEF) {
|
||||
case 102:
|
||||
Tuner_Patch_Load(pLutBytes102, LutSize102);
|
||||
break;
|
||||
#ifndef DEEPELEC_DP_66X
|
||||
case 205:
|
||||
Tuner_Patch_Load(pLutBytes205, LutSize205);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
Wire.beginTransmission(TEF668X_ADDRESS);
|
||||
Wire.write(0x1c);
|
||||
Wire.write(0x00);
|
||||
Wire.write(0x00);
|
||||
Wire.endTransmission();
|
||||
}
|
||||
|
||||
void Tuner_I2C_Init() {
|
||||
Wire.begin();
|
||||
Wire.setClock(400000);
|
||||
delay(5);
|
||||
}
|
||||
|
||||
void Tuner_Init(const unsigned char *table) {
|
||||
uint16_t r;
|
||||
const unsigned char *p = table;
|
||||
|
||||
for (uint16_t i = 0; i < sizeof(tuner_init_tab); i += (pgm_read_byte(p + i) + 1)) {
|
||||
if (1 != (r = Tuner_Table_Write(p + i))) break;
|
||||
}
|
||||
}
|
||||
@@ -2878,7 +2878,9 @@ void BuildMenu() {
|
||||
ShowOneLine(ITEM10, 9, (menuoption == ITEM10 ? true : false));
|
||||
}
|
||||
|
||||
#ifdef SMETERPIN
|
||||
analogWrite(SMETERPIN, 0);
|
||||
#endif
|
||||
}
|
||||
|
||||
void BuildAdvancedRDS() {
|
||||
|
||||
73
src/main.cpp
73
src/main.cpp
@@ -60,9 +60,13 @@ void Touch_IRQ_Handler() {
|
||||
}
|
||||
|
||||
void deepSleep() {
|
||||
#ifdef SMETERPIN
|
||||
analogWrite(SMETERPIN, 0);
|
||||
#endif
|
||||
#ifdef STANDBYLED
|
||||
pinMode(STANDBYLED, OUTPUT);
|
||||
digitalWrite(STANDBYLED, LOW);
|
||||
#endif
|
||||
MuteScreen(1);
|
||||
StoreFrequency();
|
||||
radio.power(1);
|
||||
@@ -179,7 +183,7 @@ void ShowBW() {
|
||||
else if(!BWtune) return;
|
||||
|
||||
if (BW != BWOld || BWreset) {
|
||||
if (BWset == 0) tftReplace(ARIGHT, String (BWOld, DEC), String (BW, DEC), 203, 4, BWAutoColor, BWAutoColorSmooth, BackgroundColor, 28); else tftReplace(ARIGHT, String (BWOld, DEC), String (BW, DEC), 203, 4, PrimaryColor, PrimaryColorSmooth, BackgroundColor, 28);
|
||||
if (BWset == 0) tftReplace(ARIGHT, String(BWOld, DEC), String(BW, DEC), 203, 4, BWAutoColor, BWAutoColorSmooth, BackgroundColor, 28); else tftReplace(ARIGHT, String (BWOld, DEC), String(BW, DEC), 203, 4, PrimaryColor, PrimaryColorSmooth, BackgroundColor, 28);
|
||||
BWOld = BW;
|
||||
BWreset = false;
|
||||
if (wifi) {
|
||||
@@ -233,7 +237,7 @@ void updateCodetect() {
|
||||
}
|
||||
|
||||
void SetTunerPatch() {
|
||||
if (TEF != 102 && TEF != 205) {
|
||||
if(FORBIDDEN_TUNER(TEF)) {
|
||||
radio.init(102);
|
||||
uint16_t device, hw, sw;
|
||||
radio.getIdentification(&device, &hw, &sw);
|
||||
@@ -241,7 +245,7 @@ void SetTunerPatch() {
|
||||
tft.fillScreen(BackgroundColor);
|
||||
analogWrite(CONTRASTPIN, map(ContrastSet, 0, 100, 15, 255));
|
||||
|
||||
if (TEF != 102 && TEF != 205) {
|
||||
if(FORBIDDEN_TUNER(TEF)) {
|
||||
tftPrint(ACENTER, textUI(35), 150, 78, ActiveColor, ActiveColorSmooth, 28);
|
||||
for (;;);
|
||||
}
|
||||
@@ -827,19 +831,37 @@ void ShowNum(int val) {
|
||||
byte numval[16] = {2, 3, 127, 5, 6, 0, 9, 13, 8, 7, 4, 1, 0, 0, 0, 0};
|
||||
|
||||
int GetNum() {
|
||||
int16_t temp;
|
||||
int cnt = 0;
|
||||
unsigned int num;
|
||||
|
||||
// Get input port 0 and 1
|
||||
Wire.beginTransmission(XL9555_ADDRESS);
|
||||
Wire.write(0x00);
|
||||
Wire.endTransmission();
|
||||
Wire.requestFrom(XL9555_ADDRESS, 2);
|
||||
|
||||
if (Wire.available() == 2) {
|
||||
// According to the schematic of the DP666, this is the table that the buttons are connected to:
|
||||
// IO0_0 = NUM2
|
||||
// IO0_1 = NUM3
|
||||
// IO0_2 = BACKSPACE (DX is printed on the case)
|
||||
// IO0_3 = NUM5
|
||||
// IO0_4 = NUM6
|
||||
// IO0_5 = NUM0
|
||||
// IO0_6 = NUM9
|
||||
// IO0_7 = ENTER
|
||||
// IO1_0 = NUM8
|
||||
// IO1_1 = NUM7
|
||||
// IO1_2 = NUM4
|
||||
// IO1_3 = NUM1
|
||||
// Rest is NC
|
||||
// According to the docs, register 0 contains pins IO0_x where x is equal to the bit from the right (x = 7, is MSB)
|
||||
|
||||
int cnt = 0;
|
||||
int16_t temp;
|
||||
unsigned int num;
|
||||
if(Wire.available() == 2) {
|
||||
keypadtimer = millis();
|
||||
|
||||
temp = Wire.read() & 0xFF;
|
||||
temp |= (Wire.read() & 0xFF) * 256;
|
||||
temp |= (Wire.read() & 0xFF) << 8;
|
||||
for (int i = 0; i < 16; i++) {
|
||||
if ((temp & 0x01) == 0) {
|
||||
num = numval[i];
|
||||
@@ -1135,10 +1157,13 @@ void setup() {
|
||||
|
||||
setupmode = true;
|
||||
|
||||
Tuner_I2C_Init();
|
||||
Wire.begin();
|
||||
Wire.setClock(400000);
|
||||
delay(5);
|
||||
|
||||
Serial.begin(115200);
|
||||
byte error, address;
|
||||
for (address = 1; address < 127; address++) { // I2C addresses 0x01–0x7F
|
||||
for (address = 1; address < 127; address++) {
|
||||
Wire.beginTransmission(address);
|
||||
error = Wire.endTransmission();
|
||||
|
||||
@@ -1262,8 +1287,10 @@ void setup() {
|
||||
pinMode(ROTARY_BUTTON, INPUT);
|
||||
pinMode(ROTARY_PIN_A, INPUT);
|
||||
pinMode(ROTARY_PIN_B, INPUT);
|
||||
#ifdef STANDBYLED
|
||||
pinMode(STANDBYLED, OUTPUT);
|
||||
digitalWrite(STANDBYLED, HIGH);
|
||||
#endif
|
||||
pinMode(TOUCHIRQ, INPUT);
|
||||
pinMode(EXT_IRQ, INPUT_PULLUP);
|
||||
|
||||
@@ -1348,12 +1375,16 @@ void setup() {
|
||||
}
|
||||
|
||||
if (digitalRead(BWBUTTON) == HIGH && digitalRead(ROTARY_BUTTON) == HIGH && digitalRead(MODEBUTTON) == HIGH && digitalRead(BANDBUTTON) == LOW) {
|
||||
#ifdef SMETERPIN
|
||||
analogWrite(SMETERPIN, 511);
|
||||
#endif
|
||||
analogWrite(CONTRASTPIN, map(ContrastSet, 0, 100, 15, 255));
|
||||
Infoboxprint(textUI(4));
|
||||
tftPrint(ACENTER, textUI(2), 155, 130, ActiveColor, ActiveColorSmooth, 28);
|
||||
while (digitalRead(BANDBUTTON) == LOW) delay(50);
|
||||
#ifdef SMETERPIN
|
||||
analogWrite(SMETERPIN, 0);
|
||||
#endif
|
||||
}
|
||||
|
||||
if (digitalRead(BWBUTTON) == HIGH && digitalRead(ROTARY_BUTTON) == LOW && digitalRead(MODEBUTTON) == HIGH && digitalRead(BANDBUTTON) == HIGH) {
|
||||
@@ -1419,13 +1450,13 @@ void setup() {
|
||||
|
||||
for (int x = 0; x <= ContrastSet; x++) {
|
||||
analogWrite(CONTRASTPIN, map(x, 0, 100, 15, 255));
|
||||
delay(30);
|
||||
delay(10);
|
||||
}
|
||||
|
||||
tft.fillRect(120, 230, 16, 6, PrimaryColor);
|
||||
|
||||
TEF = EEPROM.readByte(EE_BYTE_TEF);
|
||||
if (TEF != 102 && TEF != 205) SetTunerPatch();
|
||||
if(FORBIDDEN_TUNER(TEF)) SetTunerPatch();
|
||||
radio.init(TEF);
|
||||
|
||||
uint16_t device, hw, sw;
|
||||
@@ -1438,6 +1469,7 @@ void setup() {
|
||||
chipmodel = 0;
|
||||
tft.fillRect(152, 230, 16, 6, PrimaryColor);
|
||||
tftPrint(ACENTER, "TEF6686 Lithio", 160, 172, ActiveColor, ActiveColorSmooth, 28);
|
||||
#ifndef DEEPELEC_DP_66X
|
||||
} else if (lowByte(device) == 1) {
|
||||
fullsearchrds = true;
|
||||
chipmodel = 1;
|
||||
@@ -1454,14 +1486,15 @@ void setup() {
|
||||
chipmodel = 3;
|
||||
tft.fillRect(152, 230, 16, 6, PrimaryColor);
|
||||
tftPrint(ACENTER, "TEF6689 Lithio FMSI DR", 160, 172, ActiveColor, ActiveColorSmooth, 28);
|
||||
#endif
|
||||
} else {
|
||||
tftPrint(ACENTER, textUI(9), 160, 172, SignificantColor, SignificantColorSmooth, 28);
|
||||
tft.fillRect(152, 230, 16, 6, SignificantColor);
|
||||
while (true);
|
||||
for (;;);
|
||||
}
|
||||
tftPrint(ACENTER, "Patch: v" + String(TEF), 160, 202, ActiveColor, ActiveColorSmooth, 28);
|
||||
|
||||
// Configures the GPIO chip for input in every pin
|
||||
Wire.beginTransmission(XL9555_ADDRESS);
|
||||
Wire.write(0x06);
|
||||
Wire.write(0xFF);
|
||||
@@ -1480,7 +1513,8 @@ void setup() {
|
||||
Udp.stop();
|
||||
tft.fillRect(184, 230, 16, 6, SignificantColor);
|
||||
}
|
||||
delay(750);
|
||||
|
||||
while(digitalRead(ROTARY_BUTTON) == LOW) delay(50);
|
||||
|
||||
radio.setVolume(VolSet);
|
||||
radio.setOffset(LevelOffset);
|
||||
@@ -1506,13 +1540,6 @@ void setup() {
|
||||
if (fmsi) radio.setFMSI(2); else radio.setFMSI(1);
|
||||
LowLevelInit = true;
|
||||
|
||||
if (ConverterSet >= 200) {
|
||||
Wire.beginTransmission(0x12);
|
||||
Wire.write(ConverterSet >> 8);
|
||||
Wire.write(ConverterSet & (0xFF));
|
||||
Wire.endTransmission();
|
||||
}
|
||||
|
||||
BuildDisplay();
|
||||
SelectBand();
|
||||
if (tunemode == TUNE_MEM) DoMemoryPosTune();
|
||||
@@ -2975,6 +3002,7 @@ void ShowSignalLevel() {
|
||||
SAvg4 = (((SAvg4 * 9) + 5) / 10) + WAM;
|
||||
SAvg5 = (((SAvg5 * 9) + 5) / 10) + USN;
|
||||
|
||||
#ifdef SMETERPIN
|
||||
float sval = 0;
|
||||
int16_t smeter = 0;
|
||||
|
||||
@@ -2986,6 +3014,7 @@ void ShowSignalLevel() {
|
||||
}
|
||||
|
||||
smeter = int16_t(sval);
|
||||
#endif
|
||||
SStatus = SAvg / 10;
|
||||
CN = SAvg2 / 10;
|
||||
MP = SAvg4 / 10;
|
||||
@@ -3021,7 +3050,9 @@ void ShowSignalLevel() {
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef SMETERPIN
|
||||
if (!menu) analogWrite(SMETERPIN, smeter);
|
||||
#endif
|
||||
|
||||
int SStatusprint = 0;
|
||||
if (unit == 0) SStatusprint = SStatus;
|
||||
|
||||
Reference in New Issue
Block a user