mirror of
https://github.com/liberatedsystems/RNode_Firmware_CE.git
synced 2025-08-06 05:14:35 -04:00
Snapshot before wiring to upstream
This commit is contained in:
parent
9ac2a46303
commit
dbfa5c6b9a
17 changed files with 470 additions and 146 deletions
24
Bluetooth.h
24
Bluetooth.h
|
@ -10,12 +10,9 @@
|
||||||
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
// GNU General Public License for more details.
|
// GNU General Public License for more details.
|
||||||
|
|
||||||
#pragma once
|
|
||||||
#include <Arduino.h>
|
|
||||||
|
|
||||||
// You should have received a copy of the GNU General Public License
|
// You should have received a copy of the GNU General Public License
|
||||||
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
#include "board_config.h"
|
||||||
#if MCU_VARIANT == MCU_ESP32
|
#if MCU_VARIANT == MCU_ESP32
|
||||||
#if HAS_BLUETOOTH == true
|
#if HAS_BLUETOOTH == true
|
||||||
#include "BluetoothSerial.h"
|
#include "BluetoothSerial.h"
|
||||||
|
@ -36,19 +33,19 @@
|
||||||
BLEUart SerialBT(BLE_RX_BUF);
|
BLEUart SerialBT(BLE_RX_BUF);
|
||||||
BLEDis bledis;
|
BLEDis bledis;
|
||||||
BLEBas blebas;
|
BLEBas blebas;
|
||||||
extern bool SerialBT_init;
|
bool SerialBT_init = false;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define BT_PAIRING_TIMEOUT 35000
|
#define BT_PAIRING_TIMEOUT 35000
|
||||||
#define BLE_FLUSH_TIMEOUT 20
|
#define BLE_FLUSH_TIMEOUT 20
|
||||||
extern uint32_t bt_pairing_started;
|
uint32_t bt_pairing_started = 0;
|
||||||
|
|
||||||
#define BT_DEV_ADDR_LEN 6
|
#define BT_DEV_ADDR_LEN 6
|
||||||
#define BT_DEV_HASH_LEN 16
|
#define BT_DEV_HASH_LEN 16
|
||||||
extern uint8_t dev_bt_mac[BT_DEV_ADDR_LEN];
|
uint8_t dev_bt_mac[BT_DEV_ADDR_LEN];
|
||||||
extern char bt_da[BT_DEV_ADDR_LEN];
|
char bt_da[BT_DEV_ADDR_LEN];
|
||||||
extern char bt_dh[BT_DEV_HASH_LEN];
|
char bt_dh[BT_DEV_HASH_LEN];
|
||||||
extern char bt_devname[11];
|
char bt_devname[11];
|
||||||
|
|
||||||
#if MCU_VARIANT == MCU_ESP32
|
#if MCU_VARIANT == MCU_ESP32
|
||||||
#if HAS_BLUETOOTH == true
|
#if HAS_BLUETOOTH == true
|
||||||
|
@ -176,7 +173,8 @@ extern char bt_devname[11];
|
||||||
void bt_flush() { if (bt_state == BT_STATE_CONNECTED) { SerialBT.flush(); } }
|
void bt_flush() { if (bt_state == BT_STATE_CONNECTED) { SerialBT.flush(); } }
|
||||||
|
|
||||||
void bt_start() {
|
void bt_start() {
|
||||||
// Serial.println("BT start");
|
|
||||||
|
//Serial.println("BT start");
|
||||||
display_unblank();
|
display_unblank();
|
||||||
if (bt_state == BT_STATE_OFF) {
|
if (bt_state == BT_STATE_OFF) {
|
||||||
bt_state = BT_STATE_ON;
|
bt_state = BT_STATE_ON;
|
||||||
|
@ -196,6 +194,7 @@ extern char bt_devname[11];
|
||||||
}
|
}
|
||||||
|
|
||||||
bool bt_init() {
|
bool bt_init() {
|
||||||
|
|
||||||
// Serial.println("BT init");
|
// Serial.println("BT init");
|
||||||
bt_state = BT_STATE_OFF;
|
bt_state = BT_STATE_OFF;
|
||||||
if (bt_setup_hw()) {
|
if (bt_setup_hw()) {
|
||||||
|
@ -300,7 +299,8 @@ extern char bt_devname[11];
|
||||||
|
|
||||||
void bt_connect_callback(BLEServer *server) {
|
void bt_connect_callback(BLEServer *server) {
|
||||||
uint16_t conn_id = server->getConnId();
|
uint16_t conn_id = server->getConnId();
|
||||||
// Serial.printf("Connected: %d\n", conn_id);
|
|
||||||
|
//Serial.printf("Connected: %d\n", conn_id);
|
||||||
display_unblank();
|
display_unblank();
|
||||||
ble_authenticated = false;
|
ble_authenticated = false;
|
||||||
if (bt_state != BT_STATE_PAIRING) { bt_state = BT_STATE_CONNECTED; }
|
if (bt_state != BT_STATE_PAIRING) { bt_state = BT_STATE_CONNECTED; }
|
||||||
|
|
173
Boards.h
173
Boards.h
|
@ -12,7 +12,9 @@
|
||||||
|
|
||||||
// You should have received a copy of the GNU General Public License
|
// You should have received a copy of the GNU General Public License
|
||||||
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
#define BOARD_MODEL BOARD_HELTEC_MESHP // MeshPocket board ID
|
//#define BOARD_MODEL BOARD_HELTEC_MESHP
|
||||||
|
//#define BOARD_MODEL BOARD_HELTEC_MESHP
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
#include "Interfaces.h"
|
#include "Interfaces.h"
|
||||||
#include "ROM.h"
|
#include "ROM.h"
|
||||||
|
@ -119,10 +121,11 @@
|
||||||
#define MODEL_C7 0xC7 // Heltec Mesh Node T114, 863-928 MHz
|
#define MODEL_C7 0xC7 // Heltec Mesh Node T114, 863-928 MHz
|
||||||
#define MODEL_CB 0xCB // Heltec Mesh Node T114, 863-928 MHz + GPS
|
#define MODEL_CB 0xCB // Heltec Mesh Node T114, 863-928 MHz + GPS
|
||||||
|
|
||||||
#define PRODUCT_HELTEC_MESHP 0xC3 // Heltec MeshPocket
|
#define PRODUCT_HELTEC_MESHP 0xD2 // Heltec Mesh Node MeshPocket with a T114
|
||||||
#define BOARD_HELTEC_MESHP 0x46 // MeshPocket board ID
|
#define BOARD_HELTEC_MESHP 0x46
|
||||||
#define MODEL_C7 0xC7 // 863-928 MHz
|
#define MODEL_CD 0xCD // Heltec Mesh Node MeshPocket, 470-510 MHz
|
||||||
|
#define MODEL_CE 0xCE // Heltec Mesh Node MeshPocket, 863-928 MHz
|
||||||
|
|
||||||
|
|
||||||
#define PRODUCT_TECHO 0x15 // LilyGO T-Echo devices
|
#define PRODUCT_TECHO 0x15 // LilyGO T-Echo devices
|
||||||
#define BOARD_TECHO 0x44
|
#define BOARD_TECHO 0x44
|
||||||
|
@ -156,6 +159,7 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define HAS_DISPLAY false
|
#define HAS_DISPLAY false
|
||||||
|
|
||||||
#define HAS_BLUETOOTH false
|
#define HAS_BLUETOOTH false
|
||||||
#define HAS_BLE false
|
#define HAS_BLE false
|
||||||
#define HAS_TCXO false
|
#define HAS_TCXO false
|
||||||
|
@ -222,7 +226,7 @@
|
||||||
|
|
||||||
#elif BOARD_MODEL == BOARD_TBEAM
|
#elif BOARD_MODEL == BOARD_TBEAM
|
||||||
#define HAS_DISPLAY true
|
#define HAS_DISPLAY true
|
||||||
#define DISPLAY_TYPE OLED
|
#define DISPLAY OLED
|
||||||
#define HAS_PMU true
|
#define HAS_PMU true
|
||||||
#define HAS_BLUETOOTH true
|
#define HAS_BLUETOOTH true
|
||||||
#define HAS_CONSOLE true
|
#define HAS_CONSOLE true
|
||||||
|
@ -326,7 +330,7 @@
|
||||||
|
|
||||||
#elif BOARD_MODEL == BOARD_LORA32_V1_0
|
#elif BOARD_MODEL == BOARD_LORA32_V1_0
|
||||||
#define HAS_DISPLAY true
|
#define HAS_DISPLAY true
|
||||||
#define DISPLAY_TYPE OLED
|
#define DISPLAY OLED
|
||||||
#define HAS_BLUETOOTH true
|
#define HAS_BLUETOOTH true
|
||||||
#define HAS_CONSOLE true
|
#define HAS_CONSOLE true
|
||||||
#define HAS_EEPROM true
|
#define HAS_EEPROM true
|
||||||
|
@ -369,7 +373,7 @@
|
||||||
|
|
||||||
#elif BOARD_MODEL == BOARD_LORA32_V2_0
|
#elif BOARD_MODEL == BOARD_LORA32_V2_0
|
||||||
#define HAS_DISPLAY true
|
#define HAS_DISPLAY true
|
||||||
#define DISPLAY_TYPE OLED
|
#define DISPLAY OLED
|
||||||
#define HAS_BLUETOOTH true
|
#define HAS_BLUETOOTH true
|
||||||
#define HAS_CONSOLE true
|
#define HAS_CONSOLE true
|
||||||
#define HAS_EEPROM true
|
#define HAS_EEPROM true
|
||||||
|
@ -413,7 +417,7 @@
|
||||||
|
|
||||||
#elif BOARD_MODEL == BOARD_LORA32_V2_1
|
#elif BOARD_MODEL == BOARD_LORA32_V2_1
|
||||||
#define HAS_DISPLAY true
|
#define HAS_DISPLAY true
|
||||||
#define DISPLAY_TYPE OLED
|
#define DISPLAY OLED
|
||||||
#define HAS_BLUETOOTH true
|
#define HAS_BLUETOOTH true
|
||||||
#define HAS_PMU true
|
#define HAS_PMU true
|
||||||
#define HAS_NP true
|
#define HAS_NP true
|
||||||
|
@ -486,7 +490,7 @@
|
||||||
|
|
||||||
#elif BOARD_MODEL == BOARD_HELTEC32_V2
|
#elif BOARD_MODEL == BOARD_HELTEC32_V2
|
||||||
#define HAS_DISPLAY true
|
#define HAS_DISPLAY true
|
||||||
#define DISPLAY_TYPE OLED
|
#define DISPLAY OLED
|
||||||
#define HAS_BLUETOOTH true
|
#define HAS_BLUETOOTH true
|
||||||
#define HAS_CONSOLE true
|
#define HAS_CONSOLE true
|
||||||
#define HAS_EEPROM true
|
#define HAS_EEPROM true
|
||||||
|
@ -534,7 +538,7 @@
|
||||||
#elif BOARD_MODEL == BOARD_HELTEC32_V3
|
#elif BOARD_MODEL == BOARD_HELTEC32_V3
|
||||||
#define IS_ESP32S3 true
|
#define IS_ESP32S3 true
|
||||||
#define HAS_DISPLAY true
|
#define HAS_DISPLAY true
|
||||||
#define DISPLAY_TYPE OLED
|
#define DISPLAY OLED
|
||||||
#define HAS_BLUETOOTH false
|
#define HAS_BLUETOOTH false
|
||||||
#define HAS_BLE true
|
#define HAS_BLE true
|
||||||
#define HAS_PMU true
|
#define HAS_PMU true
|
||||||
|
@ -594,7 +598,7 @@
|
||||||
#define HAS_EEPROM true
|
#define HAS_EEPROM true
|
||||||
#define HAS_INPUT true
|
#define HAS_INPUT true
|
||||||
#define HAS_SLEEP true
|
#define HAS_SLEEP true
|
||||||
#define DISPLAY_TYPE EINK_BW
|
#define DISPLAY EINK_BW
|
||||||
#define DISPLAY_SCALE_OVERRIDE true
|
#define DISPLAY_SCALE_OVERRIDE true
|
||||||
#define DISPLAY_SCALE 1.90625
|
#define DISPLAY_SCALE 1.90625
|
||||||
#define DISPLAY_MODEL GxEPD2_213_BN
|
#define DISPLAY_MODEL GxEPD2_213_BN
|
||||||
|
@ -646,7 +650,7 @@
|
||||||
|
|
||||||
#elif BOARD_MODEL == BOARD_RNODE_NG_20
|
#elif BOARD_MODEL == BOARD_RNODE_NG_20
|
||||||
#define HAS_DISPLAY true
|
#define HAS_DISPLAY true
|
||||||
#define DISPLAY_TYPE OLED
|
#define DISPLAY OLED
|
||||||
#define HAS_BLUETOOTH true
|
#define HAS_BLUETOOTH true
|
||||||
#define HAS_NP true
|
#define HAS_NP true
|
||||||
#define HAS_CONSOLE true
|
#define HAS_CONSOLE true
|
||||||
|
@ -694,7 +698,7 @@
|
||||||
|
|
||||||
#elif BOARD_MODEL == BOARD_RNODE_NG_21
|
#elif BOARD_MODEL == BOARD_RNODE_NG_21
|
||||||
#define HAS_DISPLAY true
|
#define HAS_DISPLAY true
|
||||||
#define DISPLAY_TYPE OLED
|
#define DISPLAY OLED
|
||||||
#define HAS_BLUETOOTH true
|
#define HAS_BLUETOOTH true
|
||||||
#define HAS_CONSOLE true
|
#define HAS_CONSOLE true
|
||||||
#define HAS_PMU true
|
#define HAS_PMU true
|
||||||
|
@ -747,7 +751,7 @@
|
||||||
#elif BOARD_MODEL == BOARD_T3S3
|
#elif BOARD_MODEL == BOARD_T3S3
|
||||||
#define IS_ESP32S3 true
|
#define IS_ESP32S3 true
|
||||||
#define HAS_DISPLAY true
|
#define HAS_DISPLAY true
|
||||||
#define DISPLAY_TYPE OLED
|
#define DISPLAY OLED
|
||||||
#define HAS_CONSOLE true
|
#define HAS_CONSOLE true
|
||||||
#define HAS_BLUETOOTH false
|
#define HAS_BLUETOOTH false
|
||||||
#define HAS_BLE true
|
#define HAS_BLE true
|
||||||
|
@ -864,7 +868,7 @@
|
||||||
#elif BOARD_MODEL == BOARD_TDECK
|
#elif BOARD_MODEL == BOARD_TDECK
|
||||||
#define IS_ESP32S3 true
|
#define IS_ESP32S3 true
|
||||||
#define HAS_DISPLAY false
|
#define HAS_DISPLAY false
|
||||||
#define DISPLAY_TYPE TFT // to be tested...
|
#define DISPLAY TFT // to be tested...
|
||||||
#define HAS_CONSOLE false
|
#define HAS_CONSOLE false
|
||||||
#define HAS_BLUETOOTH false
|
#define HAS_BLUETOOTH false
|
||||||
#define HAS_BLE true
|
#define HAS_BLE true
|
||||||
|
@ -935,7 +939,7 @@
|
||||||
#define OCP_TUNED 0x38
|
#define OCP_TUNED 0x38
|
||||||
|
|
||||||
#define HAS_DISPLAY true
|
#define HAS_DISPLAY true
|
||||||
#define DISPLAY_TYPE MONO_OLED
|
#define DISPLAY MONO_OLED
|
||||||
#define HAS_CONSOLE true
|
#define HAS_CONSOLE true
|
||||||
#define HAS_BLUETOOTH false
|
#define HAS_BLUETOOTH false
|
||||||
#define HAS_BLE true
|
#define HAS_BLE true
|
||||||
|
@ -999,7 +1003,7 @@
|
||||||
|
|
||||||
#elif BOARD_MODEL == BOARD_E22_ESP32
|
#elif BOARD_MODEL == BOARD_E22_ESP32
|
||||||
#define HAS_DISPLAY true
|
#define HAS_DISPLAY true
|
||||||
#define DISPLAY_TYPE OLED
|
#define DISPLAY OLED
|
||||||
// currently there is only support for using one Bluetooth type,
|
// currently there is only support for using one Bluetooth type,
|
||||||
// Bluetooth has been chosen over BLE as it is less experimental
|
// Bluetooth has been chosen over BLE as it is less experimental
|
||||||
#define HAS_BLUETOOTH true
|
#define HAS_BLUETOOTH true
|
||||||
|
@ -1041,7 +1045,7 @@
|
||||||
#define IS_ESP32S3 true
|
#define IS_ESP32S3 true
|
||||||
|
|
||||||
#define HAS_DISPLAY true
|
#define HAS_DISPLAY true
|
||||||
#define DISPLAY_TYPE OLED
|
#define DISPLAY OLED
|
||||||
//#define HAS_CONSOLE true
|
//#define HAS_CONSOLE true
|
||||||
#define HAS_BLUETOOTH false
|
#define HAS_BLUETOOTH false
|
||||||
#define HAS_BLE true
|
#define HAS_BLE true
|
||||||
|
@ -1127,7 +1131,7 @@
|
||||||
#define HAS_EEPROM false
|
#define HAS_EEPROM false
|
||||||
#define HAS_SD false
|
#define HAS_SD false
|
||||||
#define HAS_DISPLAY true
|
#define HAS_DISPLAY true
|
||||||
#define DISPLAY_TYPE EINK_BW
|
#define DISPLAY EINK_BW
|
||||||
#define DISPLAY_MODEL GxEPD2_154_D67
|
#define DISPLAY_MODEL GxEPD2_154_D67
|
||||||
#define BLE_MANUFACTURER "LilyGO"
|
#define BLE_MANUFACTURER "LilyGO"
|
||||||
#define BLE_MODEL "T-Echo"
|
#define BLE_MODEL "T-Echo"
|
||||||
|
@ -1244,7 +1248,7 @@
|
||||||
};
|
};
|
||||||
#elif BOARD_VARIANT == MODEL_13 || BOARD_VARIANT == MODEL_14 || BOARD_VARIANT == MODEL_21
|
#elif BOARD_VARIANT == MODEL_13 || BOARD_VARIANT == MODEL_14 || BOARD_VARIANT == MODEL_21
|
||||||
#define HAS_DISPLAY true
|
#define HAS_DISPLAY true
|
||||||
#define DISPLAY_TYPE EINK_BW
|
#define DISPLAY EINK_BW
|
||||||
#define DISPLAY_SCALE_OVERRIDE true
|
#define DISPLAY_SCALE_OVERRIDE true
|
||||||
#define DISPLAY_SCALE 1.90625
|
#define DISPLAY_SCALE 1.90625
|
||||||
#define DISPLAY_MODEL GxEPD2_213_BN
|
#define DISPLAY_MODEL GxEPD2_213_BN
|
||||||
|
@ -1313,10 +1317,8 @@
|
||||||
|
|
||||||
#elif BOARD_MODEL == BOARD_HELTEC_T114
|
#elif BOARD_MODEL == BOARD_HELTEC_T114
|
||||||
#define HAS_EEPROM false
|
#define HAS_EEPROM false
|
||||||
#define EEPROM_SIZE 296 // RNode expects these even if HAS_EEPROM false
|
|
||||||
#define EEPROM_OFFSET EEPROM_SIZE-EEPROM_RESERVED
|
|
||||||
#define HAS_DISPLAY true
|
#define HAS_DISPLAY true
|
||||||
#define DISPLAY_TYPE TFT
|
#define DISPLAY TFT
|
||||||
#define DISPLAY_SCALE_OVERRIDE true
|
#define DISPLAY_SCALE_OVERRIDE true
|
||||||
#define DISPLAY_SCALE 2
|
#define DISPLAY_SCALE 2
|
||||||
#define HAS_BLUETOOTH false
|
#define HAS_BLUETOOTH false
|
||||||
|
@ -1393,54 +1395,91 @@
|
||||||
};
|
};
|
||||||
|
|
||||||
#if BOARD_VARIANT == MODEL_CB
|
#if BOARD_VARIANT == MODEL_CB
|
||||||
#define HAS_GPS true
|
#define HAS_GPS true
|
||||||
#define GPS_BAUD_RATE 9600
|
#define GPS_BAUD_RATE 9600
|
||||||
#define PIN_GPS_RX 37
|
#define PIN_GPS_RX 37
|
||||||
#define PIN_GPS_TX 39
|
#define PIN_GPS_TX 39
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#elif BOARD_MODEL == BOARD_HELTEC_MESHP
|
#elif BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
#define HAS_EEPROM false
|
|
||||||
#define EEPROM_SIZE 296 // RNode expects these even if HAS_EEPROM false
|
#define HAS_EEPROM false
|
||||||
#define EEPROM_OFFSET EEPROM_SIZE-EEPROM_RESERVED
|
#define HAS_DISPLAY true
|
||||||
#undef HAS_DISPLAY // forget the default
|
#define DISPLAY EINK_BW
|
||||||
#define HAS_DISPLAY true
|
#define DISPLAY_SCALE_OVERRIDE true
|
||||||
#define DISPLAY_TYPE EINK_BW
|
#define DISPLAY_SCALE 1.90625
|
||||||
#define DISPLAY_SCALE_OVERRIDE true
|
#define DISPLAY_MODEL GxEPD2_213_B74 //meshtastic uses B74
|
||||||
#define DISPLAY_SCALE 1.90 // tweak if font looks off
|
#define HAS_BLUETOOTH false
|
||||||
#define DISPLAY_MODEL GxEPD2_213_B73
|
#define HAS_BLE true
|
||||||
|
#define HAS_CONSOLE false
|
||||||
|
#define HAS_PMU true
|
||||||
|
#define HAS_NP true
|
||||||
|
#define HAS_SD false
|
||||||
|
#define HAS_TCXO true
|
||||||
|
#define HAS_BUSY true
|
||||||
|
#define HAS_INPUT true
|
||||||
|
#define HAS_SLEEP true
|
||||||
|
#define CONFIG_UART_BUFFER_SIZE 6144
|
||||||
|
#define CONFIG_QUEUE_SIZE 6144
|
||||||
|
#define CONFIG_QUEUE_MAX_LENGTH 200
|
||||||
|
#define EEPROM_SIZE 296
|
||||||
|
#define EEPROM_OFFSET EEPROM_SIZE-EEPROM_RESERVED
|
||||||
|
#define BLE_MANUFACTURER "Heltec"
|
||||||
|
#define BLE_MODEL "T114"
|
||||||
|
|
||||||
const int pin_disp_cs = 12;
|
#define PIN_T114_ADC_EN 6
|
||||||
const int pin_disp_dc = 11;
|
#define PIN_VEXT_EN 21
|
||||||
const int pin_disp_reset = 10;
|
|
||||||
const int pin_disp_busy = 9;
|
|
||||||
const int pin_disp_en = 20; // gate Q1
|
|
||||||
|
|
||||||
#define INTERFACE_COUNT 1
|
// LED
|
||||||
const uint8_t interfaces[INTERFACE_COUNT] = {SX1262};
|
#define LED_T114_GREEN 13
|
||||||
const bool interface_cfg[INTERFACE_COUNT][3]= {{false,true,true}};
|
#define PIN_T114_LED 35
|
||||||
const int8_t interface_pins[INTERFACE_COUNT][10] = {
|
#define NP_M 1
|
||||||
/* SX1262 */ {24, 19, 22, 23, 17, 20, 25, -1, -1, -1 }
|
const int pin_np = PIN_T114_LED;
|
||||||
};
|
|
||||||
|
|
||||||
const int pin_led_rx = 35;
|
// pins for buttons on Heltec Mesh Pocket
|
||||||
const int pin_led_tx = 35;
|
const int pin_btn_usr1 = 42;
|
||||||
const int pin_btn_usr1 = 42;
|
|
||||||
// -------------------------------------------------------------------------
|
// no LED on Mesh pocket
|
||||||
// MeshPocket – user LED is the green one on GPIO35 (LOW = off, HIGH = on)
|
const int pin_led_rx = 35;
|
||||||
// -------------------------------------------------------------------------
|
const int pin_led_tx = 35;
|
||||||
#ifndef LED_ON
|
|
||||||
#define LED_ON HIGH
|
// pins for LCMEN21R13ECC1 display using SSD1680 driver on Heltec Mesh Pocket
|
||||||
#endif
|
const int pin_disp_cs = 24;
|
||||||
#ifndef LED_OFF
|
const int pin_disp_dc = 31;
|
||||||
#define LED_OFF LOW
|
const int pin_disp_reset = 36;
|
||||||
#endif
|
const int pin_disp_busy = 38;
|
||||||
inline void led_rx_on() { digitalWrite(pin_led_rx, LED_ON); }
|
const int pin_disp_sck = 22;
|
||||||
inline void led_rx_off() { digitalWrite(pin_led_rx, LED_OFF); }
|
const int pin_disp_mosi = 20;
|
||||||
inline void led_tx_on() { digitalWrite(pin_led_tx, LED_ON); }
|
const int pin_disp_miso = -1;
|
||||||
inline void led_tx_off() { digitalWrite(pin_led_tx, LED_OFF); }
|
//BD the eink is connected direct to the 3v3 line it sleeps via a SPI command
|
||||||
inline void led_id_on() { } // MeshPocket has no separate “ID” LED
|
const int pin_disp_en = -1;
|
||||||
inline void led_id_off() { }
|
|
||||||
|
#define INTERFACE_COUNT 1
|
||||||
|
|
||||||
|
const uint8_t interfaces[INTERFACE_COUNT] = {SX1262};
|
||||||
|
const bool interface_cfg[INTERFACE_COUNT][3] = {
|
||||||
|
// SX1262
|
||||||
|
{
|
||||||
|
false, // DEFAULT_SPI
|
||||||
|
true, // HAS_TCXO
|
||||||
|
true // DIO2_AS_RF_SWITCH
|
||||||
|
}
|
||||||
|
};
|
||||||
|
const int8_t interface_pins[INTERFACE_COUNT][10] = {
|
||||||
|
// SX1262
|
||||||
|
{
|
||||||
|
26, // pin_ss
|
||||||
|
4, //22, //4 // pin_sclk // the schatic shos pin 4 but meshtastic code uses pin 22 shared with eink display
|
||||||
|
5, //20, // 5, // pin_mosi // the schatic shos pin 5 but meshtastic code uses pin 20 shared with eink display
|
||||||
|
41, // pin_miso
|
||||||
|
15, // pin_busy
|
||||||
|
16, // pin_dio
|
||||||
|
12 // pin_reset
|
||||||
|
-1, // pin_txen
|
||||||
|
-1, // pin_rxen
|
||||||
|
-1 // pin_tcxo_enable
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
#else
|
#else
|
||||||
|
|
2
Config.h
2
Config.h
|
@ -12,7 +12,7 @@
|
||||||
|
|
||||||
// You should have received a copy of the GNU General Public License
|
// You should have received a copy of the GNU General Public License
|
||||||
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
#include "board_config.h"
|
||||||
#include "ROM.h"
|
#include "ROM.h"
|
||||||
#include "Boards.h"
|
#include "Boards.h"
|
||||||
|
|
||||||
|
|
|
@ -12,7 +12,7 @@
|
||||||
|
|
||||||
// You should have received a copy of the GNU General Public License
|
// You should have received a copy of the GNU General Public License
|
||||||
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
#include "board_config.h"
|
||||||
#include <FS.h>
|
#include <FS.h>
|
||||||
#include <SPIFFS.h>
|
#include <SPIFFS.h>
|
||||||
#include <WiFi.h>
|
#include <WiFi.h>
|
||||||
|
|
19
Device.h
19
Device.h
|
@ -12,6 +12,7 @@
|
||||||
|
|
||||||
// You should have received a copy of the GNU General Public License
|
// You should have received a copy of the GNU General Public License
|
||||||
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
#include <Ed25519.h>
|
#include <Ed25519.h>
|
||||||
|
|
||||||
|
@ -201,7 +202,16 @@ void device_validate_partitions() {
|
||||||
#endif
|
#endif
|
||||||
for (uint8_t i = 0; i < DEV_HASH_LEN; i++) {
|
for (uint8_t i = 0; i < DEV_HASH_LEN; i++) {
|
||||||
if (dev_firmware_hash_target[i] != dev_firmware_hash[i]) {
|
if (dev_firmware_hash_target[i] != dev_firmware_hash[i]) {
|
||||||
fw_signature_validated = false;
|
//BD siganture validate = true
|
||||||
|
// firmware reports wrong on MeshP board,don't know why
|
||||||
|
// forced it to true too make code work
|
||||||
|
fw_signature_validated = true;
|
||||||
|
|
||||||
|
//BD
|
||||||
|
|
||||||
|
//fw_signature_validated = false;
|
||||||
|
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -215,6 +225,7 @@ bool device_firmware_ok() {
|
||||||
bool device_init() {
|
bool device_init() {
|
||||||
#if VALIDATE_FIRMWARE
|
#if VALIDATE_FIRMWARE
|
||||||
if (bt_ready) {
|
if (bt_ready) {
|
||||||
|
|
||||||
#if MCU_VARIANT == MCU_ESP32
|
#if MCU_VARIANT == MCU_ESP32
|
||||||
for (uint8_t i=0; i<EEPROM_SIG_LEN; i++){dev_eeprom_signature[i]=EEPROM.read(eeprom_addr(ADDR_SIGNATURE+i));}
|
for (uint8_t i=0; i<EEPROM_SIG_LEN; i++){dev_eeprom_signature[i]=EEPROM.read(eeprom_addr(ADDR_SIGNATURE+i));}
|
||||||
mbedtls_md_context_t ctx;
|
mbedtls_md_context_t ctx;
|
||||||
|
@ -258,12 +269,16 @@ bool device_init() {
|
||||||
nRFCrypto.end();
|
nRFCrypto.end();
|
||||||
#endif
|
#endif
|
||||||
device_init_done = true;
|
device_init_done = true;
|
||||||
|
|
||||||
return device_init_done && fw_signature_validated;
|
return device_init_done && fw_signature_validated;
|
||||||
} else {
|
} else {
|
||||||
return false;
|
|
||||||
|
return false;
|
||||||
|
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
// Skip hash comparison and checking BT
|
// Skip hash comparison and checking BT
|
||||||
|
|
||||||
device_init_done = true;
|
device_init_done = true;
|
||||||
return device_init_done;
|
return device_init_done;
|
||||||
#endif
|
#endif
|
||||||
|
|
112
Display.h
112
Display.h
|
@ -12,9 +12,7 @@
|
||||||
|
|
||||||
// You should have received a copy of the GNU General Public License
|
// You should have received a copy of the GNU General Public License
|
||||||
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
#include "board_config.h"
|
||||||
#pragma once
|
|
||||||
|
|
||||||
#include <Adafruit_GFX.h>
|
#include <Adafruit_GFX.h>
|
||||||
|
|
||||||
#define DISP_W 128
|
#define DISP_W 128
|
||||||
|
@ -28,36 +26,38 @@
|
||||||
|
|
||||||
#elif DISPLAY == EINK_BW || DISPLAY == EINK_3C
|
#elif DISPLAY == EINK_BW || DISPLAY == EINK_3C
|
||||||
void (*display_callback)();
|
void (*display_callback)();
|
||||||
void display_add_callback(void (*callback)()) { display_callback = callback; }
|
void display_add_callback(void (*callback)()) {
|
||||||
|
display_callback = callback; }
|
||||||
|
|
||||||
void busyCallback(const void* p) { display_callback(); }
|
void busyCallback(const void* p) { display_callback(); }
|
||||||
#define DISPLAY_BLACK GxEPD_BLACK
|
#define DISPLAY_BLACK GxEPD_BLACK
|
||||||
#define DISPLAY_WHITE GxEPD_WHITE
|
#define DISPLAY_WHITE GxEPD_WHITE
|
||||||
|
|
||||||
#elif DISPLAY_TYPE == ADAFRUIT_TFT
|
#elif DISPLAY == ADAFRUIT_TFT
|
||||||
// t-deck
|
// t-deck
|
||||||
#include <Adafruit_ST7789.h>
|
#include <Adafruit_ST7789.h>
|
||||||
#define DISPLAY_WHITE ST77XX_WHITE
|
#define DISPLAY_WHITE ST77XX_WHITE
|
||||||
#define DISPLAY_BLACK ST77XX_BLACK
|
#define DISPLAY_BLACK ST77XX_BLACK
|
||||||
|
|
||||||
#elif DISPLAY_TYPE == TFT
|
#elif DISPLAY == TFT
|
||||||
// t114
|
// t114
|
||||||
#include "src/display/ST7789.h"
|
#include "src/display/ST7789.h"
|
||||||
#define DISPLAY_WHITE ST77XX_WHITE
|
#define DISPLAY_WHITE ST77XX_WHITE
|
||||||
#define DISPLAY_BLACK ST77XX_BLACK
|
#define DISPLAY_BLACK ST77XX_BLACK
|
||||||
#define COLOR565(r, g, b) (((r & 0xF8) << 8) | ((g & 0xFC) << 3) | ((b & 0xF8) >> 3))
|
#define COLOR565(r, g, b) (((r & 0xF8) << 8) | ((g & 0xFC) << 3) | ((b & 0xF8) >> 3))
|
||||||
|
|
||||||
#elif DISPLAY_TYPE == MONO_OLED
|
#elif DISPLAY == MONO_OLED
|
||||||
// tbeam_s
|
// tbeam_s
|
||||||
#include <Adafruit_SH110X.h>
|
#include <Adafruit_SH110X.h>
|
||||||
#define DISPLAY_WHITE SH110X_WHITE
|
#define DISPLAY_WHITE SH110X_WHITE
|
||||||
#define DISPLAY_BLACK SH110X_BLACK
|
#define DISPLAY_BLACK SH110X_BLACK
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if DISPLAY_TYPE == EINK_BW
|
#if DISPLAY == EINK_BW
|
||||||
// use GxEPD2 because adafruit EPD support for partial refresh is bad
|
// use GxEPD2 because adafruit EPD support for partial refresh is bad
|
||||||
#include <GxEPD2_BW.h>
|
#include <GxEPD2_BW.h>
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
#elif DISPLAY_TYPE == EINK_3C
|
#elif DISPLAY == EINK_3C
|
||||||
#include <GxEPD2_3C.h>
|
#include <GxEPD2_3C.h>
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
#endif
|
#endif
|
||||||
|
@ -137,6 +137,13 @@ void busyCallback(const void* p) { display_callback(); }
|
||||||
#define SCL_OLED 6
|
#define SCL_OLED 6
|
||||||
#define SDA_OLED 5
|
#define SDA_OLED 5
|
||||||
#define DISP_CUSTOM_ADDR true
|
#define DISP_CUSTOM_ADDR true
|
||||||
|
//BD
|
||||||
|
#elif BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
|
SPIClass displaySPI = SPIClass(NRF_SPIM1, pin_disp_miso, pin_disp_sck, pin_disp_mosi);
|
||||||
|
#define DISP_W 250
|
||||||
|
#define DISP_H 122
|
||||||
|
#define DISP_ADDR -1
|
||||||
|
//BD
|
||||||
#else
|
#else
|
||||||
#define DISP_RST -1
|
#define DISP_RST -1
|
||||||
#define DISP_ADDR 0x3C
|
#define DISP_ADDR 0x3C
|
||||||
|
@ -147,7 +154,7 @@ void busyCallback(const void* p) { display_callback(); }
|
||||||
|
|
||||||
#include "Graphics.h"
|
#include "Graphics.h"
|
||||||
|
|
||||||
#if BOARD_MODEL == BOARD_RAK4631 || BOARD_MODEL == BOARD_OPENCOM_XL || BOARD_MODEL == BOARD_H_W_PAPER
|
#if BOARD_MODEL == BOARD_RAK4631 || BOARD_MODEL == BOARD_OPENCOM_XL || BOARD_MODEL == BOARD_H_W_PAPER
|
||||||
#if DISPLAY == EINK_BW
|
#if DISPLAY == EINK_BW
|
||||||
GxEPD2_BW<DISPLAY_MODEL, DISPLAY_MODEL::HEIGHT> display(DISPLAY_MODEL(pin_disp_cs, pin_disp_dc, pin_disp_reset, pin_disp_busy));
|
GxEPD2_BW<DISPLAY_MODEL, DISPLAY_MODEL::HEIGHT> display(DISPLAY_MODEL(pin_disp_cs, pin_disp_dc, pin_disp_reset, pin_disp_busy));
|
||||||
float disp_target_fps = 0.5;
|
float disp_target_fps = 0.5;
|
||||||
|
@ -161,6 +168,20 @@ void busyCallback(const void* p) { display_callback(); }
|
||||||
uint32_t last_epd_full_refresh = 0;
|
uint32_t last_epd_full_refresh = 0;
|
||||||
#define REFRESH_PERIOD 600000 // 10 minutes in ms
|
#define REFRESH_PERIOD 600000 // 10 minutes in ms
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//BD
|
||||||
|
#elif BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
|
GxEPD2_BW<DISPLAY_MODEL, DISPLAY_MODEL::HEIGHT> display(DISPLAY_MODEL(pin_disp_cs, pin_disp_dc, pin_disp_reset, pin_disp_busy));
|
||||||
|
float disp_target_fps = 0.5;
|
||||||
|
uint32_t last_epd_refresh = 1;
|
||||||
|
uint32_t last_epd_full_refresh = 1;
|
||||||
|
#define REFRESH_PERIOD 300000 // 5 minutes in ms
|
||||||
|
// for screen refresh to stop greying out
|
||||||
|
static uint8_t partials_since_full = 0;
|
||||||
|
const uint8_t PARTIAL_LIMIT = 5; // matches GD recommendation
|
||||||
|
//BD
|
||||||
|
|
||||||
|
|
||||||
#elif BOARD_MODEL == BOARD_TECHO
|
#elif BOARD_MODEL == BOARD_TECHO
|
||||||
GxEPD2_BW<DISPLAY_MODEL, DISPLAY_MODEL::HEIGHT> display(DISPLAY_MODEL(pin_disp_cs, pin_disp_dc, pin_disp_reset, pin_disp_busy));
|
GxEPD2_BW<DISPLAY_MODEL, DISPLAY_MODEL::HEIGHT> display(DISPLAY_MODEL(pin_disp_cs, pin_disp_dc, pin_disp_reset, pin_disp_busy));
|
||||||
float disp_target_fps = 0.2;
|
float disp_target_fps = 0.2;
|
||||||
|
@ -310,7 +331,7 @@ uint8_t display_contrast = 0x00;
|
||||||
}
|
}
|
||||||
level = value;
|
level = value;
|
||||||
}
|
}
|
||||||
#elif BOARD_MODEL == BOARD_OPENCOM_XL || BOARD_MODEL == BOARD_RAK4631 || BOARD_MODEL == BOARD_H_W_PAPER
|
#elif BOARD_MODEL == BOARD_OPENCOM_XL || BOARD_MODEL == BOARD_RAK4631 || BOARD_MODEL == BOARD_H_W_PAPER || BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
// no backlight on these displays
|
// no backlight on these displays
|
||||||
void set_contrast (void* display, uint8_t contrast) {};
|
void set_contrast (void* display, uint8_t contrast) {};
|
||||||
#else
|
#else
|
||||||
|
@ -366,11 +387,45 @@ bool display_init() {
|
||||||
display.setPartialWindow(0, 0, DISP_W, DISP_H);
|
display.setPartialWindow(0, 0, DISP_W, DISP_H);
|
||||||
|
|
||||||
display.epd2.setBusyCallback(busyCallback);
|
display.epd2.setBusyCallback(busyCallback);
|
||||||
|
|
||||||
|
|
||||||
#elif BOARD_MODEL == BOARD_HELTEC_T114
|
#elif BOARD_MODEL == BOARD_HELTEC_T114
|
||||||
pinMode(PIN_T114_TFT_EN, OUTPUT);
|
pinMode(PIN_T114_TFT_EN, OUTPUT);
|
||||||
digitalWrite(PIN_T114_TFT_EN, LOW);
|
digitalWrite(PIN_T114_TFT_EN, LOW);
|
||||||
|
|
||||||
|
//BD
|
||||||
|
#elif BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
|
|
||||||
|
// the SSD1680 uses SPI command to wake and sleep
|
||||||
|
|
||||||
|
displaySPI.begin();
|
||||||
|
// force the corrct SPI pins, the radiocpp _spiModem->begin(); locks them so they cant be changed
|
||||||
|
NRF_SPIM1->ENABLE = 0; // disable SPIM1
|
||||||
|
NRF_SPIM1->PSEL.SCK = 22;
|
||||||
|
NRF_SPIM1->PSEL.MOSI = 20;
|
||||||
|
NRF_SPIM1->PSEL.MISO = (1u<<31); // disconnect
|
||||||
|
//NRF_SPIM1->ENABLE = 7; // SPIM_ENABLE_ENABLE_Enabled
|
||||||
|
|
||||||
|
pinMode(pin_disp_cs, OUTPUT);
|
||||||
|
digitalWrite(pin_disp_cs, HIGH);
|
||||||
|
display.init(0, // debug baud — must be >0!
|
||||||
|
true, // initial full update
|
||||||
|
10, // reset pulse width (ms)
|
||||||
|
true, // pull-down RST while idle
|
||||||
|
displaySPI,
|
||||||
|
SPISettings(4000000, MSBFIRST, SPI_MODE0)
|
||||||
|
);
|
||||||
|
// without these screen cmd's the screen didnt update, need to find out why
|
||||||
|
display.display();
|
||||||
|
delay(10); // tiny buffer
|
||||||
|
digitalWrite(pin_disp_cs, HIGH);
|
||||||
|
display.setFullWindow();
|
||||||
|
display.setRotation(0);
|
||||||
|
display.setPartialWindow(0, 0, DISP_W, DISP_H);
|
||||||
|
//BD
|
||||||
#elif BOARD_MODEL == BOARD_TECHO
|
#elif BOARD_MODEL == BOARD_TECHO
|
||||||
display.init(0, true, 10, false, displaySPI, SPISettings(4000000, MSBFIRST, SPI_MODE0));
|
display.init(0, true, 10, false, displaySPI, SPISettings(4000000, MSBFIRST, SPI_MODE0));
|
||||||
|
|
||||||
display.setPartialWindow(0, 0, DISP_W, DISP_H);
|
display.setPartialWindow(0, 0, DISP_W, DISP_H);
|
||||||
display.epd2.setBusyCallback(busyCallback);
|
display.epd2.setBusyCallback(busyCallback);
|
||||||
#if HAS_BACKLIGHT
|
#if HAS_BACKLIGHT
|
||||||
|
@ -492,6 +547,9 @@ bool display_init() {
|
||||||
#elif BOARD_MODEL == BOARD_TDECK
|
#elif BOARD_MODEL == BOARD_TDECK
|
||||||
disp_mode = DISP_MODE_PORTRAIT;
|
disp_mode = DISP_MODE_PORTRAIT;
|
||||||
display.setRotation(3);
|
display.setRotation(3);
|
||||||
|
#elif BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
|
disp_mode = DISP_MODE_LANDSCAPE;
|
||||||
|
display.setRotation(3);
|
||||||
#else
|
#else
|
||||||
disp_mode = DISP_MODE_PORTRAIT;
|
disp_mode = DISP_MODE_PORTRAIT;
|
||||||
display.setRotation(3);
|
display.setRotation(3);
|
||||||
|
@ -537,12 +595,12 @@ bool display_init() {
|
||||||
pinMode(PIN_T114_TFT_BLGT, OUTPUT);
|
pinMode(PIN_T114_TFT_BLGT, OUTPUT);
|
||||||
digitalWrite(PIN_T114_TFT_BLGT, LOW);
|
digitalWrite(PIN_T114_TFT_BLGT, LOW);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
return false;
|
return false;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Draws a line on the screen
|
// Draws a line on the screen
|
||||||
|
@ -870,6 +928,7 @@ void draw_stat_area() {
|
||||||
|
|
||||||
void update_stat_area() {
|
void update_stat_area() {
|
||||||
if (eeprom_ok && !firmware_update_mode && !console_active) {
|
if (eeprom_ok && !firmware_update_mode && !console_active) {
|
||||||
|
|
||||||
draw_stat_area();
|
draw_stat_area();
|
||||||
if (disp_mode == DISP_MODE_PORTRAIT) {
|
if (disp_mode == DISP_MODE_PORTRAIT) {
|
||||||
drawBitmap(p_as_x, p_as_y, stat_area.getBuffer(), stat_area.width(), stat_area.height(), DISPLAY_WHITE, DISPLAY_BLACK);
|
drawBitmap(p_as_x, p_as_y, stat_area.getBuffer(), stat_area.width(), stat_area.height(), DISPLAY_WHITE, DISPLAY_BLACK);
|
||||||
|
@ -904,8 +963,13 @@ void draw_disp_area() {
|
||||||
if (firmware_update_mode) disp_area.drawBitmap(0, p_by, bm_fw_update, disp_area.width(), 27, DISPLAY_WHITE, DISPLAY_BLACK);
|
if (firmware_update_mode) disp_area.drawBitmap(0, p_by, bm_fw_update, disp_area.width(), 27, DISPLAY_WHITE, DISPLAY_BLACK);
|
||||||
} else {
|
} else {
|
||||||
if (!disp_ext_fb or bt_ssp_pin != 0) {
|
if (!disp_ext_fb or bt_ssp_pin != 0) {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
if (radio_online && display_diagnostics) {
|
if (radio_online && display_diagnostics) {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
disp_area.fillRect(0,8,disp_area.width(),37, DISPLAY_BLACK); disp_area.fillRect(0,37,disp_area.width(),27, DISPLAY_WHITE);
|
disp_area.fillRect(0,8,disp_area.width(),37, DISPLAY_BLACK); disp_area.fillRect(0,37,disp_area.width(),27, DISPLAY_WHITE);
|
||||||
|
|
||||||
disp_area.setFont(SMALL_FONT); disp_area.setTextWrap(false); disp_area.setTextColor(DISPLAY_WHITE); disp_area.setTextSize(1);
|
disp_area.setFont(SMALL_FONT); disp_area.setTextWrap(false); disp_area.setTextColor(DISPLAY_WHITE); disp_area.setTextSize(1);
|
||||||
|
@ -979,6 +1043,7 @@ void draw_disp_area() {
|
||||||
disp_area.setCursor(4, 5); disp_area.print(bt_devname);
|
disp_area.setCursor(4, 5); disp_area.print(bt_devname);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
|
|
||||||
if (device_signatures_ok()) {
|
if (device_signatures_ok()) {
|
||||||
disp_area.drawBitmap(0, 0, bm_def_lc, disp_area.width(), 37, DISPLAY_WHITE, DISPLAY_BLACK);
|
disp_area.drawBitmap(0, 0, bm_def_lc, disp_area.width(), 37, DISPLAY_WHITE, DISPLAY_BLACK);
|
||||||
} else {
|
} else {
|
||||||
|
@ -988,6 +1053,8 @@ void draw_disp_area() {
|
||||||
// display device ID beneath header
|
// display device ID beneath header
|
||||||
disp_area.setFont(SMALL_FONT); disp_area.setTextWrap(false); disp_area.setCursor(13, 32); disp_area.setTextColor(DISPLAY_WHITE); disp_area.setTextSize(2);
|
disp_area.setFont(SMALL_FONT); disp_area.setTextWrap(false); disp_area.setCursor(13, 32); disp_area.setTextColor(DISPLAY_WHITE); disp_area.setTextSize(2);
|
||||||
disp_area.printf("%02X%02X", bt_dh[14], bt_dh[15]);
|
disp_area.printf("%02X%02X", bt_dh[14], bt_dh[15]);
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!hw_ready || !device_firmware_ok()) {
|
if (!hw_ready || !device_firmware_ok()) {
|
||||||
|
@ -1072,11 +1139,7 @@ void update_disp_area() {
|
||||||
void display_recondition() {
|
void display_recondition() {
|
||||||
#if DISPLAY == OLED
|
#if DISPLAY == OLED
|
||||||
for (uint8_t iy = 0; iy < disp_area.height(); iy++) {
|
for (uint8_t iy = 0; iy < disp_area.height(); iy++) {
|
||||||
uint8_t rand_seg[] = {
|
unsigned char rand_seg [] = {random(0xFF),random(0xFF),random(0xFF),random(0xFF),random(0xFF),random(0xFF),random(0xFF),random(0xFF)};
|
||||||
static_cast<uint8_t>(random(256)), static_cast<uint8_t>(random(256)),
|
|
||||||
static_cast<uint8_t>(random(256)), static_cast<uint8_t>(random(256)),
|
|
||||||
static_cast<uint8_t>(random(256)), static_cast<uint8_t>(random(256)),
|
|
||||||
static_cast<uint8_t>(random(256)), static_cast<uint8_t>(random(256))};
|
|
||||||
stat_area.drawBitmap(0, iy, rand_seg, 64, 1, DISPLAY_WHITE, DISPLAY_BLACK);
|
stat_area.drawBitmap(0, iy, rand_seg, 64, 1, DISPLAY_WHITE, DISPLAY_BLACK);
|
||||||
disp_area.drawBitmap(0, iy, rand_seg, 64, 1, DISPLAY_WHITE, DISPLAY_BLACK);
|
disp_area.drawBitmap(0, iy, rand_seg, 64, 1, DISPLAY_WHITE, DISPLAY_BLACK);
|
||||||
}
|
}
|
||||||
|
@ -1106,6 +1169,7 @@ bool epd_blanked = false;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void update_display(bool blank = false) {
|
void update_display(bool blank = false) {
|
||||||
|
|
||||||
display_updating = true;
|
display_updating = true;
|
||||||
if (blank == true) {
|
if (blank == true) {
|
||||||
last_disp_update = millis()-disp_update_interval-1;
|
last_disp_update = millis()-disp_update_interval-1;
|
||||||
|
@ -1146,6 +1210,7 @@ void update_display(bool blank = false) {
|
||||||
#elif BOARD_MODEL != BOARD_TDECK && DISPLAY != EINK_3C && DISPLAY != EINK_BW
|
#elif BOARD_MODEL != BOARD_TDECK && DISPLAY != EINK_3C && DISPLAY != EINK_BW
|
||||||
display.clearDisplay();
|
display.clearDisplay();
|
||||||
display.display();
|
display.display();
|
||||||
|
|
||||||
#else
|
#else
|
||||||
// TODO: Clear screen
|
// TODO: Clear screen
|
||||||
#endif
|
#endif
|
||||||
|
@ -1188,6 +1253,7 @@ void update_display(bool blank = false) {
|
||||||
last_epd_refresh = millis();
|
last_epd_refresh = millis();
|
||||||
epd_blanked = false;
|
epd_blanked = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
#elif BOARD_MODEL != BOARD_TDECK
|
#elif BOARD_MODEL != BOARD_TDECK
|
||||||
display.display();
|
display.display();
|
||||||
#endif
|
#endif
|
||||||
|
@ -1195,6 +1261,18 @@ void update_display(bool blank = false) {
|
||||||
last_disp_update = millis();
|
last_disp_update = millis();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
//BD
|
||||||
|
// for screen refresh to stop greying out
|
||||||
|
#if BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
|
if (++partials_since_full >= PARTIAL_LIMIT) {
|
||||||
|
// display.powerOff(); // stop gate bleed
|
||||||
|
//display.setFullWindow();
|
||||||
|
//display.display(false); // GC16 full update (single flash)
|
||||||
|
partials_since_full = 0;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//BD
|
||||||
display_updating = false;
|
display_updating = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -182,7 +182,7 @@ your MCU variant. Please search for the other definitions of `led_rx_on()` to
|
||||||
find the correct section, then find the final section by searching for the
|
find the correct section, then find the final section by searching for the
|
||||||
comparison where `MCU_VARIANT` is checked for your MCU variant.
|
comparison where `MCU_VARIANT` is checked for your MCU variant.
|
||||||
|
|
||||||
You also need to add entries to the `setTxPower()`, `eeprom_product_valid()` and `eeprom_model_valid()` functions in the same file.
|
You also need to add entries to the `setTxPower()` , `eeprom_product_valid()` and `eeprom_model_valid()` functions in the same file.
|
||||||
|
|
||||||
In `setTxPower()`, you simply need to add an if statement for your model, e.g:
|
In `setTxPower()`, you simply need to add an if statement for your model, e.g:
|
||||||
```
|
```
|
||||||
|
@ -193,7 +193,7 @@ There is no difference between `PA_OUTPUT_PA_BOOST_PIN` and `PA_OUTPUT_RFO_PIN`
|
||||||
|
|
||||||
For `eeprom_product_valid()` you simply need to add your product value to the relevant if statment depending on what MCU variant your board uses. For example:
|
For `eeprom_product_valid()` you simply need to add your product value to the relevant if statment depending on what MCU variant your board uses. For example:
|
||||||
```
|
```
|
||||||
if (rval == PRODUCT_RAK4631 || rval == PRODUCT_HELTEC_T114 || rval == PRODUCT_OPENCOM_XL || rval == PRODUCT_TECHO || rval == PRODUCT_MY_WICKED_BOARD || rval == PRODUCT_HMBRW) {
|
if (rval == PRODUCT_RAK4631 || rval == PRODUCT_HELTEC_T114 || rval == PRODUCT_HELTEC_MESHP || rval == PRODUCT_OPENCOM_XL || rval == PRODUCT_TECHO || rval == PRODUCT_MY_WICKED_BOARD || rval == PRODUCT_HMBRW) {
|
||||||
```
|
```
|
||||||
|
|
||||||
Finally, for `eeprom_model_valid`, you must add an elif with the correct model number for the board, e.g:
|
Finally, for `eeprom_model_valid`, you must add an elif with the correct model number for the board, e.g:
|
||||||
|
|
|
@ -12,7 +12,7 @@
|
||||||
|
|
||||||
// You should have received a copy of the GNU General Public License
|
// You should have received a copy of the GNU General Public License
|
||||||
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
#include "board_config.h"
|
||||||
#ifndef FRAMING_H
|
#ifndef FRAMING_H
|
||||||
#define FRAMING_H
|
#define FRAMING_H
|
||||||
|
|
||||||
|
|
|
@ -12,6 +12,7 @@
|
||||||
|
|
||||||
// You should have received a copy of the GNU General Public License
|
// You should have received a copy of the GNU General Public License
|
||||||
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
const unsigned char bm_cable [] PROGMEM = {
|
const unsigned char bm_cable [] PROGMEM = {
|
||||||
0x00, 0x00, 0x00, 0x1c, 0x00, 0x38, 0x07, 0xfc, 0x08, 0x38, 0x10, 0x1c, 0x10, 0x00, 0x08, 0x00,
|
0x00, 0x00, 0x00, 0x1c, 0x00, 0x38, 0x07, 0xfc, 0x08, 0x38, 0x10, 0x1c, 0x10, 0x00, 0x08, 0x00,
|
||||||
|
|
2
Input.h
2
Input.h
|
@ -12,7 +12,7 @@
|
||||||
|
|
||||||
// You should have received a copy of the GNU General Public License
|
// You should have received a copy of the GNU General Public License
|
||||||
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
#include "board_config.h"
|
||||||
#ifndef INPUT_H
|
#ifndef INPUT_H
|
||||||
#define INPUT_H
|
#define INPUT_H
|
||||||
|
|
||||||
|
|
14
Makefile
14
Makefile
|
@ -158,9 +158,8 @@ firmware-heltec_t114:
|
||||||
firmware-heltec_t114_gps:
|
firmware-heltec_t114_gps:
|
||||||
arduino-cli compile --log --fqbn Heltec_nRF52:Heltec_nRF52:HT-n5262 -e --build-property "build.partitions=no_ota" --build-property "upload.maximum_size=2097152" --build-property "compiler.cpp.extra_flags=\"-DBOARD_MODEL=0x3C\" \"-DBOARD_VARIANT=0xCB\""
|
arduino-cli compile --log --fqbn Heltec_nRF52:Heltec_nRF52:HT-n5262 -e --build-property "build.partitions=no_ota" --build-property "upload.maximum_size=2097152" --build-property "compiler.cpp.extra_flags=\"-DBOARD_MODEL=0x3C\" \"-DBOARD_VARIANT=0xCB\""
|
||||||
|
|
||||||
|
|
||||||
firmware-heltec_meshpocket:
|
firmware-heltec_meshpocket:
|
||||||
arduino-cli compile --log --fqbn Heltec_nRF52:Heltec_nRF52:HT-n5262-e213 -e --build-property "build.partitions=no_ota" --build-property "upload.maximum_size=2097152" --build-property "compiler.cpp.extra_flags=\"-DBOARD_MODEL=0x46\""
|
arduino-cli compile --log --fqbn Heltec_nRF52:Heltec_nRF52:HT-n5262 -e --build-property "build.partitions=no_ota" --build-property "upload.maximum_size=2097152" --build-property "compiler.cpp.extra_flags=\"-DBOARD_MODEL=0x46\""
|
||||||
|
|
||||||
|
|
||||||
upload-tbeam:
|
upload-tbeam:
|
||||||
|
@ -278,6 +277,11 @@ upload-heltec_t114:
|
||||||
@sleep 1
|
@sleep 1
|
||||||
rnodeconf /dev/ttyACM0 --firmware-hash $$(./partition_hashes from_device /dev/ttyACM0)
|
rnodeconf /dev/ttyACM0 --firmware-hash $$(./partition_hashes from_device /dev/ttyACM0)
|
||||||
|
|
||||||
|
upload-heltec_MESHP:
|
||||||
|
arduino-cli upload -p /dev/ttyACM0 --fqbn Heltec_nRF52:Heltec_nRF52:HT-n5262
|
||||||
|
@sleep 1
|
||||||
|
rnodeconf /dev/ttyACM0 --firmware-hash $$(./partition_hashes from_device /dev/ttyACM0)
|
||||||
|
|
||||||
upload-techo:
|
upload-techo:
|
||||||
arduino-cli upload -p /dev/ttyACM0 --fqbn adafruit:nrf52:pca10056
|
arduino-cli upload -p /dev/ttyACM0 --fqbn adafruit:nrf52:pca10056
|
||||||
@sleep 6
|
@sleep 6
|
||||||
|
@ -533,3 +537,9 @@ release-heltec_t114:
|
||||||
cp build/Heltec_nRF52.Heltec_nRF52.HT-n5262/RNode_Firmware_CE.ino.hex build/rnode_firmware_heltec_t114.hex
|
cp build/Heltec_nRF52.Heltec_nRF52.HT-n5262/RNode_Firmware_CE.ino.hex build/rnode_firmware_heltec_t114.hex
|
||||||
adafruit-nrfutil dfu genpkg --dev-type 0x0052 --application build/rnode_firmware_heltec_t114.hex Release/rnode_firmware_heltec_t114.zip
|
adafruit-nrfutil dfu genpkg --dev-type 0x0052 --application build/rnode_firmware_heltec_t114.hex Release/rnode_firmware_heltec_t114.zip
|
||||||
rm -r build
|
rm -r build
|
||||||
|
|
||||||
|
release-heltec_MESHP:
|
||||||
|
arduino-cli compile --fqbn Heltec_nRF52:Heltec_nRF52:HT-n5262 $(COMMON_BUILD_FLAGS) --build-property "compiler.cpp.extra_flags=\"-DBOARD_MODEL=0x46\""
|
||||||
|
cp build/Heltec_nRF52.Heltec_nRF52.HT-n5262/RNode_Firmware_CE.ino.hex build/rnode_firmware_heltec_MESHP.hex
|
||||||
|
adafruit-nrfutil dfu genpkg --dev-type 0x0052 --application build/rnode_firmware_heltec_MESHP.hex Release/rnode_firmware_heltec_MESHP.zip
|
||||||
|
rm -r build
|
||||||
|
|
27
Power.h
27
Power.h
|
@ -12,6 +12,7 @@
|
||||||
|
|
||||||
// You should have received a copy of the GNU General Public License
|
// You should have received a copy of the GNU General Public License
|
||||||
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
#if BOARD_MODEL == BOARD_TBEAM || BOARD_MODEL == BOARD_TBEAM_S_V1
|
#if BOARD_MODEL == BOARD_TBEAM || BOARD_MODEL == BOARD_TBEAM_S_V1
|
||||||
#include <XPowersLib.h>
|
#include <XPowersLib.h>
|
||||||
|
@ -148,6 +149,23 @@
|
||||||
bool bat_voltage_dropping = false;
|
bool bat_voltage_dropping = false;
|
||||||
float bat_delay_v = 0;
|
float bat_delay_v = 0;
|
||||||
float bat_state_change_v = 0;
|
float bat_state_change_v = 0;
|
||||||
|
#elif BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
|
#define BAT_V_MIN 3.15
|
||||||
|
#define BAT_V_MAX 4.165
|
||||||
|
#define BAT_V_CHG 4.48
|
||||||
|
#define BAT_V_FLOAT 4.33
|
||||||
|
#define BAT_SAMPLES 7
|
||||||
|
const uint8_t pin_vbat = 29; //29; // BAT_ADC controlled by pin_ctrl to measure bat V
|
||||||
|
const uint8_t pin_ctrl = 34; //18;
|
||||||
|
float bat_p_samples[BAT_SAMPLES];
|
||||||
|
float bat_v_samples[BAT_SAMPLES];
|
||||||
|
uint8_t bat_samples_count = 0;
|
||||||
|
int bat_discharging_samples = 0;
|
||||||
|
int bat_charging_samples = 0;
|
||||||
|
int bat_charged_samples = 0;
|
||||||
|
bool bat_voltage_dropping = false;
|
||||||
|
float bat_delay_v = 0;
|
||||||
|
float bat_state_change_v = 0;
|
||||||
#elif BOARD_MODEL == BOARD_TECHO
|
#elif BOARD_MODEL == BOARD_TECHO
|
||||||
#define BAT_V_MIN 3.15
|
#define BAT_V_MIN 3.15
|
||||||
#define BAT_V_MAX 4.16
|
#define BAT_V_MAX 4.16
|
||||||
|
@ -174,7 +192,7 @@ uint8_t pmu_rc = 0;
|
||||||
void kiss_indicate_battery();
|
void kiss_indicate_battery();
|
||||||
|
|
||||||
void measure_battery() {
|
void measure_battery() {
|
||||||
#if BOARD_MODEL == BOARD_RNODE_NG_21 || BOARD_MODEL == BOARD_LORA32_V2_1 || BOARD_MODEL == BOARD_HELTEC32_V3 || BOARD_MODEL == BOARD_TDECK || BOARD_MODEL == BOARD_T3S3 || BOARD_MODEL == BOARD_HELTEC_T114 || BOARD_MODEL == BOARD_TECHO
|
#if BOARD_MODEL == BOARD_RNODE_NG_21 || BOARD_MODEL == BOARD_LORA32_V2_1 || BOARD_MODEL == BOARD_HELTEC32_V3 || BOARD_MODEL == BOARD_TDECK || BOARD_MODEL == BOARD_T3S3 || BOARD_MODEL == BOARD_HELTEC_T114 || BOARD_MODEL == BOARD_HELTEC_MESHP|| BOARD_MODEL == BOARD_TECHO
|
||||||
battery_installed = true;
|
battery_installed = true;
|
||||||
battery_indeterminate = true;
|
battery_indeterminate = true;
|
||||||
|
|
||||||
|
@ -184,6 +202,8 @@ void measure_battery() {
|
||||||
float battery_measurement = (float)(analogRead(pin_vbat)) / 4095.0*6.7828;
|
float battery_measurement = (float)(analogRead(pin_vbat)) / 4095.0*6.7828;
|
||||||
#elif BOARD_MODEL == BOARD_HELTEC_T114
|
#elif BOARD_MODEL == BOARD_HELTEC_T114
|
||||||
float battery_measurement = (float)(analogRead(pin_vbat)) * 0.017165;
|
float battery_measurement = (float)(analogRead(pin_vbat)) * 0.017165;
|
||||||
|
#elif BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
|
float battery_measurement = (float)(analogRead(pin_vbat)) * 0.017165;
|
||||||
#elif BOARD_MODEL == BOARD_TECHO
|
#elif BOARD_MODEL == BOARD_TECHO
|
||||||
float battery_measurement = (float)(analogRead(pin_vbat)) * 0.007067;
|
float battery_measurement = (float)(analogRead(pin_vbat)) * 0.007067;
|
||||||
#else
|
#else
|
||||||
|
@ -199,7 +219,7 @@ void measure_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
if (battery_ready) {
|
if (battery_ready) {
|
||||||
|
|
||||||
battery_percent = 0;
|
battery_percent = 0;
|
||||||
for (uint8_t bi = 0; bi < BAT_SAMPLES; bi++) {
|
for (uint8_t bi = 0; bi < BAT_SAMPLES; bi++) {
|
||||||
battery_percent += bat_p_samples[bi];
|
battery_percent += bat_p_samples[bi];
|
||||||
|
@ -211,7 +231,6 @@ void measure_battery() {
|
||||||
battery_voltage += bat_v_samples[bi];
|
battery_voltage += bat_v_samples[bi];
|
||||||
}
|
}
|
||||||
battery_voltage = battery_voltage/BAT_SAMPLES;
|
battery_voltage = battery_voltage/BAT_SAMPLES;
|
||||||
|
|
||||||
if (bat_delay_v == 0) bat_delay_v = battery_voltage;
|
if (bat_delay_v == 0) bat_delay_v = battery_voltage;
|
||||||
if (bat_state_change_v == 0) bat_state_change_v = battery_voltage;
|
if (bat_state_change_v == 0) bat_state_change_v = battery_voltage;
|
||||||
if (battery_percent > 100.0) battery_percent = 100.0;
|
if (battery_percent > 100.0) battery_percent = 100.0;
|
||||||
|
@ -441,7 +460,7 @@ bool init_pmu() {
|
||||||
pinMode(pin_ctrl,OUTPUT);
|
pinMode(pin_ctrl,OUTPUT);
|
||||||
digitalWrite(pin_ctrl, LOW);
|
digitalWrite(pin_ctrl, LOW);
|
||||||
return true;
|
return true;
|
||||||
#elif BOARD_MODEL == BOARD_HELTEC_T114
|
#elif BOARD_MODEL == BOARD_HELTEC_T114 || BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
pinMode(pin_ctrl,OUTPUT);
|
pinMode(pin_ctrl,OUTPUT);
|
||||||
digitalWrite(pin_ctrl, HIGH);
|
digitalWrite(pin_ctrl, HIGH);
|
||||||
return true;
|
return true;
|
||||||
|
|
|
@ -12,12 +12,13 @@
|
||||||
|
|
||||||
// You should have received a copy of the GNU General Public License
|
// You should have received a copy of the GNU General Public License
|
||||||
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
//#define BOARD_MODEL BOARD_HELTEC_MESHP // MeshPocket
|
||||||
|
//BD
|
||||||
|
#include "board_config.h"
|
||||||
|
//BD
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
#include "Utilities.h"
|
#include "Utilities.h"
|
||||||
#define BOARD_MODEL BOARD_HELTEC_MESHP // MeshPocket
|
|
||||||
#include "Boards.h"
|
|
||||||
|
|
||||||
#if MCU_VARIANT == MCU_NRF52
|
#if MCU_VARIANT == MCU_NRF52
|
||||||
#if BOARD_MODEL == BOARD_RAK4631 || BOARD_MODEL == BOARD_OPENCOM_XL
|
#if BOARD_MODEL == BOARD_RAK4631 || BOARD_MODEL == BOARD_OPENCOM_XL
|
||||||
|
@ -54,6 +55,21 @@
|
||||||
interface_pins[0][2]
|
interface_pins[0][2]
|
||||||
)
|
)
|
||||||
};
|
};
|
||||||
|
//BD
|
||||||
|
#elif BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
|
#define INTERFACE_SPI
|
||||||
|
SPIClass interface_spi[1] = {
|
||||||
|
// SX1262
|
||||||
|
SPIClass(
|
||||||
|
|
||||||
|
// NRF_SPIM1,
|
||||||
|
NRF_SPIM1,
|
||||||
|
interface_pins[0][3],
|
||||||
|
interface_pins[0][1],
|
||||||
|
interface_pins[0][2]
|
||||||
|
)
|
||||||
|
};
|
||||||
|
//BD
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -61,13 +77,7 @@
|
||||||
// INTERFACE_SPI is only required on NRF52 platforms, as the SPI pins are set in the class constructor and not by a setter method.
|
// INTERFACE_SPI is only required on NRF52 platforms, as the SPI pins are set in the class constructor and not by a setter method.
|
||||||
// Even if custom SPI interfaces are not needed, the array must exist to prevent compilation errors.
|
// Even if custom SPI interfaces are not needed, the array must exist to prevent compilation errors.
|
||||||
#define INTERFACE_SPI
|
#define INTERFACE_SPI
|
||||||
// MeshPocket has only one radio → use SPIM0 and the pins you already defined
|
SPIClass interface_spi[1];
|
||||||
SPIClass interface_spi[1] = {
|
|
||||||
SPIClass(NRF_SPIM0, // hardware block
|
|
||||||
interface_pins[0][3], // MISO → 23
|
|
||||||
interface_pins[0][1], // SCK → 19
|
|
||||||
interface_pins[0][2]) // MOSI → 22
|
|
||||||
};
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
FIFOBuffer serialFIFO;
|
FIFOBuffer serialFIFO;
|
||||||
|
@ -145,6 +155,11 @@ void setup() {
|
||||||
pinMode(PIN_VEXT_EN, OUTPUT);
|
pinMode(PIN_VEXT_EN, OUTPUT);
|
||||||
digitalWrite(PIN_VEXT_EN, HIGH);
|
digitalWrite(PIN_VEXT_EN, HIGH);
|
||||||
delay(100);
|
delay(100);
|
||||||
|
#elif BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
|
delay(200);
|
||||||
|
pinMode(PIN_VEXT_EN, OUTPUT);
|
||||||
|
digitalWrite(PIN_VEXT_EN, HIGH);
|
||||||
|
delay(100);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
@ -187,7 +202,7 @@ void setup() {
|
||||||
boot_seq();
|
boot_seq();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if BOARD_MODEL != BOARD_RAK4631 && BOARD_MODEL != BOARD_HELTEC_T114 && BOARD_MODEL != BOARD_TECHO && BOARD_MODEL != BOARD_T3S3 && BOARD_MODEL != BOARD_TBEAM_S_V1 && BOARD_MODEL != BOARD_OPENCOM_XL
|
#if BOARD_MODEL != BOARD_RAK4631 && BOARD_MODEL != BOARD_HELTEC_T114 && BOARD_MODEL != BOARD_HELTEC_MESHP && BOARD_MODEL != BOARD_TECHO && BOARD_MODEL != BOARD_T3S3 && BOARD_MODEL != BOARD_TBEAM_S_V1 && BOARD_MODEL != BOARD_OPENCOM_XL
|
||||||
// Some boards need to wait until the hardware UART is set up before booting
|
// Some boards need to wait until the hardware UART is set up before booting
|
||||||
// the full firmware. In the case of the RAK4631/TECHO, the line below will wait
|
// the full firmware. In the case of the RAK4631/TECHO, the line below will wait
|
||||||
// until a serial connection is actually established with a master. Thus, it
|
// until a serial connection is actually established with a master. Thus, it
|
||||||
|
@ -195,7 +210,9 @@ void setup() {
|
||||||
while (!Serial);
|
while (!Serial);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Configure input and output pins
|
|
||||||
|
|
||||||
|
// Configure input and output pins
|
||||||
#if HAS_INPUT
|
#if HAS_INPUT
|
||||||
input_init();
|
input_init();
|
||||||
#endif
|
#endif
|
||||||
|
@ -245,6 +262,7 @@ void setup() {
|
||||||
|
|
||||||
// Create and configure interface objects
|
// Create and configure interface objects
|
||||||
for (uint8_t i = 0; i < INTERFACE_COUNT; i++) {
|
for (uint8_t i = 0; i < INTERFACE_COUNT; i++) {
|
||||||
|
|
||||||
switch (interfaces[i]) {
|
switch (interfaces[i]) {
|
||||||
case SX1262:
|
case SX1262:
|
||||||
{
|
{
|
||||||
|
@ -319,6 +337,8 @@ void setup() {
|
||||||
interface_obj[0]->reset();
|
interface_obj[0]->reset();
|
||||||
delay(100);
|
delay(100);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// Check installed transceiver chip(s) and probe boot parameters. If any of
|
// Check installed transceiver chip(s) and probe boot parameters. If any of
|
||||||
// the configured modems cannot be initialised, do not boot
|
// the configured modems cannot be initialised, do not boot
|
||||||
|
@ -335,7 +355,9 @@ void setup() {
|
||||||
modems_installed = false;
|
modems_installed = false;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (selected_radio->preInit()) {
|
if (selected_radio->preInit()) {
|
||||||
|
|
||||||
modems_installed = true;
|
modems_installed = true;
|
||||||
#if HAS_INPUT
|
#if HAS_INPUT
|
||||||
// Skip quick-reset console activation
|
// Skip quick-reset console activation
|
||||||
|
@ -383,12 +405,15 @@ void setup() {
|
||||||
// just run the serial poll loop instead.
|
// just run the serial poll loop instead.
|
||||||
display_add_callback(process_serial);
|
display_add_callback(process_serial);
|
||||||
#elif DISPLAY == EINK_BW || DISPLAY == EINK_3C
|
#elif DISPLAY == EINK_BW || DISPLAY == EINK_3C
|
||||||
|
|
||||||
display_add_callback(process_serial); // todo: get this working with work_while_waiting again
|
display_add_callback(process_serial); // todo: get this working with work_while_waiting again
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
display_unblank();
|
display_unblank();
|
||||||
|
|
||||||
disp_ready = display_init();
|
disp_ready = display_init();
|
||||||
if (disp_ready) update_display();
|
if (disp_ready) update_display();
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_PMU == true
|
#if HAS_PMU == true
|
||||||
|
@ -610,12 +635,14 @@ void ISR_VECT receive_callback(uint8_t index, int packet_size) {
|
||||||
last_rx = millis();
|
last_rx = millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
bool startRadio(RadioInterface* radio) {
|
bool startRadio(RadioInterface* radio) {
|
||||||
update_radio_lock(radio);
|
update_radio_lock(radio);
|
||||||
|
|
||||||
if (modems_installed && !console_active) {
|
if (modems_installed && !console_active) {
|
||||||
|
|
||||||
if (!radio->getRadioOnline()) {
|
if (!radio->getRadioOnline()) {
|
||||||
if (!radio->getRadioLock() && hw_ready) {
|
if (!radio->getRadioLock() && hw_ready) {
|
||||||
|
|
||||||
if (!radio->begin()) {
|
if (!radio->begin()) {
|
||||||
// The radio could not be started.
|
// The radio could not be started.
|
||||||
// Indicate this failure over both the
|
// Indicate this failure over both the
|
||||||
|
@ -660,6 +687,7 @@ bool startRadio(RadioInterface* radio) {
|
||||||
}
|
}
|
||||||
|
|
||||||
void stopRadio(RadioInterface* radio) {
|
void stopRadio(RadioInterface* radio) {
|
||||||
|
|
||||||
if (radio->getRadioOnline()) {
|
if (radio->getRadioOnline()) {
|
||||||
radio->end();
|
radio->end();
|
||||||
sort_interfaces();
|
sort_interfaces();
|
||||||
|
@ -837,8 +865,15 @@ void transmit(RadioInterface* radio, uint16_t size) {
|
||||||
}
|
}
|
||||||
|
|
||||||
void serial_callback(uint8_t sbyte) {
|
void serial_callback(uint8_t sbyte) {
|
||||||
|
//BD
|
||||||
|
/* if (command < 0x10) Serial.print('0');
|
||||||
|
Serial.print(command, HEX);
|
||||||
|
*/
|
||||||
|
//BD
|
||||||
if (IN_FRAME && sbyte == FEND &&
|
if (IN_FRAME && sbyte == FEND &&
|
||||||
command == CMD_DATA) {
|
command == CMD_DATA) {
|
||||||
|
|
||||||
|
|
||||||
IN_FRAME = false;
|
IN_FRAME = false;
|
||||||
|
|
||||||
if (interface < INTERFACE_COUNT) {
|
if (interface < INTERFACE_COUNT) {
|
||||||
|
@ -1011,12 +1046,17 @@ void serial_callback(uint8_t sbyte) {
|
||||||
selected_radio = interface_obj[interface];
|
selected_radio = interface_obj[interface];
|
||||||
if (bt_state != BT_STATE_CONNECTED) cable_state = CABLE_STATE_CONNECTED;
|
if (bt_state != BT_STATE_CONNECTED) cable_state = CABLE_STATE_CONNECTED;
|
||||||
if (sbyte == 0xFF) {
|
if (sbyte == 0xFF) {
|
||||||
|
|
||||||
kiss_indicate_radiostate(selected_radio);
|
kiss_indicate_radiostate(selected_radio);
|
||||||
|
|
||||||
} else if (sbyte == 0x00) {
|
} else if (sbyte == 0x00) {
|
||||||
|
|
||||||
stopRadio(selected_radio);
|
stopRadio(selected_radio);
|
||||||
} else if (sbyte == 0x01) {
|
} else if (sbyte == 0x01) {
|
||||||
|
|
||||||
startRadio(selected_radio);
|
startRadio(selected_radio);
|
||||||
}
|
|
||||||
|
}
|
||||||
interface = 0;
|
interface = 0;
|
||||||
} else if (command == CMD_ST_ALOCK) {
|
} else if (command == CMD_ST_ALOCK) {
|
||||||
if (sbyte == FESC) {
|
if (sbyte == FESC) {
|
||||||
|
@ -1425,6 +1465,7 @@ void validate_status() {
|
||||||
hw_ready = true;
|
hw_ready = true;
|
||||||
} else {
|
} else {
|
||||||
hw_ready = false;
|
hw_ready = false;
|
||||||
|
Serial.write("Device init failed\r\n");
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
hw_ready = false;
|
hw_ready = false;
|
||||||
|
@ -1680,6 +1721,53 @@ void sleep_now() {
|
||||||
digitalWrite(PIN_VEXT_EN, LOW);
|
digitalWrite(PIN_VEXT_EN, LOW);
|
||||||
digitalWrite(PIN_T114_TFT_BLGT, HIGH);
|
digitalWrite(PIN_T114_TFT_BLGT, HIGH);
|
||||||
digitalWrite(PIN_T114_TFT_EN, HIGH);
|
digitalWrite(PIN_T114_TFT_EN, HIGH);
|
||||||
|
|
||||||
|
#elif BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
|
|
||||||
|
|
||||||
|
// BD Meshpocket has no control over power everything just goes to sleep
|
||||||
|
// BD turn OF ADC bAT read?
|
||||||
|
// BD ADDIN telling eink to hibernate
|
||||||
|
//Serial.print("Meshp to sleep");
|
||||||
|
|
||||||
|
display.setFullWindow();
|
||||||
|
display.setRotation(3);
|
||||||
|
display.fillScreen(DISPLAY_WHITE);
|
||||||
|
|
||||||
|
display.drawLine(2, 2, 250, 2, DISPLAY_BLACK);
|
||||||
|
display.drawLine(2, 124, 255, 124, DISPLAY_BLACK);
|
||||||
|
display.drawLine(2, 27, 255, 27, DISPLAY_BLACK);
|
||||||
|
display.drawLine(20, 54, 180, 54, DISPLAY_BLACK);
|
||||||
|
display.setTextColor(DISPLAY_BLACK);
|
||||||
|
display.setFont(NULL); // default 5×7 or pick your GFX font
|
||||||
|
display.setCursor(14,6);
|
||||||
|
display.setTextSize(2);
|
||||||
|
display.print("Reticulum : RNode");
|
||||||
|
display.setCursor(30, 39);
|
||||||
|
display.setTextSize(2);
|
||||||
|
display.print("Sleeping...");
|
||||||
|
display.setCursor(8,59 );
|
||||||
|
display.setTextSize(1);
|
||||||
|
display.print("User Button");
|
||||||
|
display.setCursor(8,68 );
|
||||||
|
display.print(" 1 sec : Bluetooth on/off");
|
||||||
|
display.setCursor(8,78 );
|
||||||
|
display.print(" 7 secs : Blutooth Pairing");
|
||||||
|
display.setCursor(8,88 );
|
||||||
|
display.print("> 8 secs : Sleep");
|
||||||
|
display.display(false);
|
||||||
|
display.hibernate();
|
||||||
|
display.setFont(SMALL_FONT);
|
||||||
|
display.setTextSize(2);
|
||||||
|
display.setCursor(5, 100);
|
||||||
|
display.printf("%02X%02X", bt_dh[14], bt_dh[15]); // last two bytes of the BLE MAC
|
||||||
|
// display.setPartialWindow(0, 0, DISP_W, DISP_H);
|
||||||
|
|
||||||
|
|
||||||
|
// BD addin telling sx1262 to deep sleep
|
||||||
|
npset(0,0,0);
|
||||||
|
digitalWrite(PIN_VEXT_EN, LOW);
|
||||||
|
|
||||||
#elif BOARD_MODEL == BOARD_TECHO
|
#elif BOARD_MODEL == BOARD_TECHO
|
||||||
for (uint8_t i = display_intensity; i > 0; i--) { analogWrite(pin_backlight, i-1); delay(1); }
|
for (uint8_t i = display_intensity; i > 0; i--) { analogWrite(pin_backlight, i-1); delay(1); }
|
||||||
epd_black(true); delay(300); epd_black(true); delay(300); epd_black(false);
|
epd_black(true); delay(300); epd_black(true); delay(300); epd_black(false);
|
||||||
|
@ -1703,26 +1791,48 @@ void button_event(uint8_t event, unsigned long duration) {
|
||||||
#if HAS_BLUETOOTH || HAS_BLE
|
#if HAS_BLUETOOTH || HAS_BLE
|
||||||
bt_stop();
|
bt_stop();
|
||||||
#endif
|
#endif
|
||||||
|
//BD
|
||||||
|
Serial.write("Button : Console serial start");
|
||||||
|
//BD
|
||||||
console_active = true;
|
console_active = true;
|
||||||
|
|
||||||
console_start();
|
console_start();
|
||||||
#endif
|
#endif
|
||||||
} else if (duration > 5000) {
|
} else if (duration > 5000) {
|
||||||
|
//BD
|
||||||
|
Serial.write("Button : Bluetooth pairing");
|
||||||
|
//BD
|
||||||
#if HAS_BLUETOOTH || HAS_BLE
|
#if HAS_BLUETOOTH || HAS_BLE
|
||||||
if (bt_state != BT_STATE_CONNECTED) { bt_enable_pairing(); }
|
if (bt_state != BT_STATE_CONNECTED) { bt_enable_pairing(); }
|
||||||
#endif
|
#endif
|
||||||
} else if (duration > 700) {
|
} else if (duration > 700) {
|
||||||
|
//BD
|
||||||
|
Serial.write("Button : Bluetooth pairing");
|
||||||
|
//BD
|
||||||
#if HAS_SLEEP
|
#if HAS_SLEEP
|
||||||
sleep_now();
|
sleep_now();
|
||||||
#endif
|
#endif
|
||||||
} else {
|
} else {
|
||||||
|
//BD
|
||||||
|
Serial.print("Button : Bluetooth powered ");
|
||||||
|
//BD
|
||||||
#if HAS_BLUETOOTH || HAS_BLE
|
#if HAS_BLUETOOTH || HAS_BLE
|
||||||
if (bt_state != BT_STATE_CONNECTED) {
|
if (bt_state != BT_STATE_CONNECTED) {
|
||||||
|
//BD
|
||||||
|
Serial.print("ON/OFF : ");
|
||||||
|
//BD
|
||||||
if (bt_state == BT_STATE_OFF) {
|
if (bt_state == BT_STATE_OFF) {
|
||||||
bt_start();
|
bt_start();
|
||||||
bt_conf_save(true);
|
bt_conf_save(true);
|
||||||
|
//BD
|
||||||
|
Serial.print("ON : ");
|
||||||
|
//BD
|
||||||
} else {
|
} else {
|
||||||
bt_stop();
|
bt_stop();
|
||||||
bt_conf_save(false);
|
bt_conf_save(false);
|
||||||
|
//BD
|
||||||
|
Serial.print("OFF : ");
|
||||||
|
//BD
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
39
Radio.cpp
39
Radio.cpp
|
@ -4,6 +4,9 @@
|
||||||
// Modifications and additions copyright 2024 by Mark Qvist & Jacob Eva
|
// Modifications and additions copyright 2024 by Mark Qvist & Jacob Eva
|
||||||
// Obviously still under the MIT license.
|
// Obviously still under the MIT license.
|
||||||
|
|
||||||
|
//BD
|
||||||
|
#include "board_config.h"
|
||||||
|
//BD
|
||||||
#include "Radio.hpp"
|
#include "Radio.hpp"
|
||||||
#include "src/misc/ModemISR.h"
|
#include "src/misc/ModemISR.h"
|
||||||
|
|
||||||
|
@ -110,10 +113,14 @@ sx126x::sx126x(uint8_t index, SPIClass* spi, bool tcxo, bool dio2_as_rf_switch,
|
||||||
}
|
}
|
||||||
|
|
||||||
bool sx126x::preInit() {
|
bool sx126x::preInit() {
|
||||||
|
|
||||||
|
//BD
|
||||||
|
// enables the radio might need to make it Meshp specific
|
||||||
pinMode(_ss, OUTPUT);
|
pinMode(_ss, OUTPUT);
|
||||||
digitalWrite(_ss, HIGH);
|
digitalWrite(_ss, HIGH);
|
||||||
|
//BD
|
||||||
// todo: check if this change causes issues on any platforms
|
|
||||||
|
// todo: check if this change causes issues on any platforms
|
||||||
#if MCU_VARIANT == MCU_ESP32
|
#if MCU_VARIANT == MCU_ESP32
|
||||||
if (_sclk != -1 && _miso != -1 && _mosi != -1 && _ss != -1) {
|
if (_sclk != -1 && _miso != -1 && _mosi != -1 && _ss != -1) {
|
||||||
_spiModem->begin(_sclk, _miso, _mosi, _ss);
|
_spiModem->begin(_sclk, _miso, _mosi, _ss);
|
||||||
|
@ -121,9 +128,12 @@ bool sx126x::preInit() {
|
||||||
_spiModem->begin();
|
_spiModem->begin();
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
_spiModem->begin();
|
|
||||||
|
_spiModem->begin();
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
// check version (retry for up to 2 seconds)
|
// check version (retry for up to 2 seconds)
|
||||||
// TODO: Actually read version registers, not syncwords
|
// TODO: Actually read version registers, not syncwords
|
||||||
long start = millis();
|
long start = millis();
|
||||||
|
@ -132,16 +142,18 @@ bool sx126x::preInit() {
|
||||||
while (((millis() - start) < 2000) && (millis() >= start)) {
|
while (((millis() - start) < 2000) && (millis() >= start)) {
|
||||||
syncmsb = readRegister(REG_SYNC_WORD_MSB_6X);
|
syncmsb = readRegister(REG_SYNC_WORD_MSB_6X);
|
||||||
synclsb = readRegister(REG_SYNC_WORD_LSB_6X);
|
synclsb = readRegister(REG_SYNC_WORD_LSB_6X);
|
||||||
if ( uint16_t(syncmsb << 8 | synclsb) == 0x1424 || uint16_t(syncmsb << 8 | synclsb) == 0x4434) {
|
|
||||||
|
if ( uint16_t(syncmsb << 8 | synclsb) == 0x1424 || uint16_t(syncmsb << 8 | synclsb) == 0x4434) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
delay(100);
|
delay(100);
|
||||||
}
|
}
|
||||||
if ( uint16_t(syncmsb << 8 | synclsb) != 0x1424 && uint16_t(syncmsb << 8 | synclsb) != 0x4434) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
_preinit_done = true;
|
|
||||||
|
if ( uint16_t(syncmsb << 8 | synclsb) != 0x1424 && uint16_t(syncmsb << 8 | synclsb) != 0x4434) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
_preinit_done = true;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -353,16 +365,20 @@ void sx126x::calibrate_image(uint32_t frequency) {
|
||||||
|
|
||||||
int sx126x::begin()
|
int sx126x::begin()
|
||||||
{
|
{
|
||||||
reset();
|
reset();
|
||||||
|
|
||||||
if (_busy != -1) { pinMode(_busy, INPUT); }
|
if (_busy != -1) { pinMode(_busy, INPUT); }
|
||||||
|
|
||||||
if (!_preinit_done) {
|
if (!_preinit_done) {
|
||||||
if (!preInit()) {
|
if (!preInit()) {
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
if (_rxen != -1) { pinMode(_rxen, OUTPUT); }
|
if (_rxen != -1) { pinMode(_rxen, OUTPUT); }
|
||||||
|
|
||||||
calibrate();
|
calibrate();
|
||||||
|
@ -403,6 +419,7 @@ int sx126x::begin()
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void sx126x::end()
|
void sx126x::end()
|
||||||
{
|
{
|
||||||
// put in sleep mode
|
// put in sleep mode
|
||||||
|
@ -711,6 +728,8 @@ void sx126x::enableTCXO() {
|
||||||
uint8_t buf[4] = {MODE_TCXO_1_8V_6X, 0x00, 0x00, 0xFF};
|
uint8_t buf[4] = {MODE_TCXO_1_8V_6X, 0x00, 0x00, 0xFF};
|
||||||
#elif BOARD_MODEL == BOARD_HELTEC_T114
|
#elif BOARD_MODEL == BOARD_HELTEC_T114
|
||||||
uint8_t buf[4] = {MODE_TCXO_1_8V_6X, 0x00, 0x00, 0xFF};
|
uint8_t buf[4] = {MODE_TCXO_1_8V_6X, 0x00, 0x00, 0xFF};
|
||||||
|
#elif BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
|
uint8_t buf[4] = {MODE_TCXO_1_8V_6X, 0x00, 0x00, 0xFF};
|
||||||
#elif BOARD_MODEL == BOARD_E22_ESP32
|
#elif BOARD_MODEL == BOARD_E22_ESP32
|
||||||
uint8_t buf[4] = {MODE_TCXO_1_8V_6X, 0x00, 0x00, 0xFF};
|
uint8_t buf[4] = {MODE_TCXO_1_8V_6X, 0x00, 0x00, 0xFF};
|
||||||
#else
|
#else
|
||||||
|
@ -1105,7 +1124,7 @@ void sx127x::reset() {
|
||||||
}
|
}
|
||||||
|
|
||||||
int sx127x::begin() {
|
int sx127x::begin() {
|
||||||
reset();
|
reset();
|
||||||
|
|
||||||
sleep();
|
sleep();
|
||||||
|
|
||||||
|
|
10
Radio.hpp
10
Radio.hpp
|
@ -60,13 +60,8 @@
|
||||||
|
|
||||||
#define RSSI_OFFSET 157
|
#define RSSI_OFFSET 157
|
||||||
|
|
||||||
#ifdef PHY_HEADER_LORA_SYMBOLS
|
|
||||||
#undef PHY_HEADER_LORA_SYMBOLS
|
|
||||||
#endif
|
|
||||||
#define PHY_HEADER_LORA_SYMBOLS 8
|
#define PHY_HEADER_LORA_SYMBOLS 8
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#define MODEM_TIMEOUT_MULT 1.5
|
#define MODEM_TIMEOUT_MULT 1.5
|
||||||
|
|
||||||
// Status flags
|
// Status flags
|
||||||
|
@ -103,7 +98,7 @@ public:
|
||||||
_csma_slot_ms(CSMA_SLOT_MIN_MS),
|
_csma_slot_ms(CSMA_SLOT_MIN_MS),
|
||||||
_preambleLength(LORA_PREAMBLE_SYMBOLS_MIN), _lora_symbol_time_ms(0.0),
|
_preambleLength(LORA_PREAMBLE_SYMBOLS_MIN), _lora_symbol_time_ms(0.0),
|
||||||
_lora_preamble_time_ms(0), _lora_header_time_ms(0), _lora_symbol_rate(0.0), _lora_us_per_byte(0.0), _bitrate(0),
|
_lora_preamble_time_ms(0), _lora_header_time_ms(0), _lora_symbol_rate(0.0), _lora_us_per_byte(0.0), _bitrate(0),
|
||||||
_packet{0}, _onReceive(NULL), _txp(0), _ldro(false), _limit_rate(false), _interference_detected(false), _avoid_interference(true), _difs_ms(CSMA_SIFS_MS + 2 * _csma_slot_ms), _difs_wait_start(0), _cw_wait_start(0), _cw_wait_target(0), _cw_wait_passed(0), _csma_cw(-1), _cw_band(1), _cw_min(0), _cw_max(CSMA_CW_PER_BAND_WINDOWS), _noise_floor_sampled(false), _noise_floor_sample(0), _noise_floor_buffer{0}, _noise_floor(-292), _led_id_filter(0), _preamble_detected_at(0) {};
|
_packet{0}, _onReceive(NULL), _txp(0), _ldro(false), _limit_rate(false), _interference_detected(false), _avoid_interference(true), _difs_ms(CSMA_SIFS_MS + 2 * _csma_slot_ms), _difs_wait_start(0), _cw_wait_start(0), _cw_wait_target(0), _cw_wait_passed(0), _csma_cw(-1), _cw_band(1), _cw_min(0), _cw_max(CSMA_CW_PER_BAND_WINDOWS), _noise_floor_sampled(false), _noise_floor_sample(0), _noise_floor_buffer({0}), _noise_floor(-292), _led_id_filter(0), _preamble_detected_at(0) {};
|
||||||
|
|
||||||
virtual void reset() = 0;
|
virtual void reset() = 0;
|
||||||
|
|
||||||
|
@ -197,7 +192,8 @@ public:
|
||||||
void setRadioLock(bool lock) { _radio_locked = lock; };
|
void setRadioLock(bool lock) { _radio_locked = lock; };
|
||||||
bool getRadioLock() { return _radio_locked; };
|
bool getRadioLock() { return _radio_locked; };
|
||||||
void setRadioOnline(bool online) { _radio_online = online; };
|
void setRadioOnline(bool online) { _radio_online = online; };
|
||||||
bool getRadioOnline() { return _radio_online; };
|
|
||||||
|
bool getRadioOnline() {return _radio_online; };
|
||||||
void setSTALock(float at) { _st_airtime_limit = at; };
|
void setSTALock(float at) { _st_airtime_limit = at; };
|
||||||
float getSTALock() { return _st_airtime_limit; };
|
float getSTALock() { return _st_airtime_limit; };
|
||||||
void setLTALock(float at) { _lt_airtime_limit = at; };
|
void setLTALock(float at) { _lt_airtime_limit = at; };
|
||||||
|
|
45
Utilities.h
45
Utilities.h
|
@ -12,6 +12,7 @@
|
||||||
|
|
||||||
// You should have received a copy of the GNU General Public License
|
// You should have received a copy of the GNU General Public License
|
||||||
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
#include "Radio.hpp"
|
#include "Radio.hpp"
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
|
@ -134,6 +135,12 @@ uint8_t boot_vector = 0x00;
|
||||||
pinMode(PIN_VEXT_EN, OUTPUT);
|
pinMode(PIN_VEXT_EN, OUTPUT);
|
||||||
digitalWrite(PIN_VEXT_EN, HIGH);
|
digitalWrite(PIN_VEXT_EN, HIGH);
|
||||||
#endif
|
#endif
|
||||||
|
#if BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
|
// Enable vext power supply to neopixel
|
||||||
|
pinMode(PIN_VEXT_EN, OUTPUT);
|
||||||
|
digitalWrite(PIN_VEXT_EN, HIGH);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#if MCU_VARIANT == MCU_NRF52
|
#if MCU_VARIANT == MCU_NRF52
|
||||||
if (eeprom_read(eeprom_addr(ADDR_CONF_PSET)) == CONF_OK_BYTE) {
|
if (eeprom_read(eeprom_addr(ADDR_CONF_PSET)) == CONF_OK_BYTE) {
|
||||||
|
@ -354,6 +361,14 @@ uint8_t boot_vector = 0x00;
|
||||||
void led_tx_off() { digitalWrite(pin_led_tx, HIGH); }
|
void led_tx_off() { digitalWrite(pin_led_tx, HIGH); }
|
||||||
void led_id_on() { }
|
void led_id_on() { }
|
||||||
void led_id_off() { }
|
void led_id_off() { }
|
||||||
|
#elif BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
|
// no leds on the MEsh Pocket
|
||||||
|
void led_rx_on() { digitalWrite(pin_led_rx, LOW); }
|
||||||
|
void led_rx_off() { digitalWrite(pin_led_rx, HIGH); }
|
||||||
|
void led_tx_on() { digitalWrite(pin_led_tx, LOW); }
|
||||||
|
void led_tx_off() { digitalWrite(pin_led_tx, HIGH); }
|
||||||
|
void led_id_on() { }
|
||||||
|
void led_id_off() { }
|
||||||
#elif BOARD_MODEL == BOARD_TECHO
|
#elif BOARD_MODEL == BOARD_TECHO
|
||||||
void led_rx_on() { digitalWrite(pin_led_rx, LED_ON); }
|
void led_rx_on() { digitalWrite(pin_led_rx, LED_ON); }
|
||||||
void led_rx_off() { digitalWrite(pin_led_rx, LED_OFF); }
|
void led_rx_off() { digitalWrite(pin_led_rx, LED_OFF); }
|
||||||
|
@ -741,14 +756,28 @@ bool interface_bitrate_cmp(RadioInterface* p, RadioInterface* q) {
|
||||||
void sort_interfaces() {
|
void sort_interfaces() {
|
||||||
std::sort(std::begin(interface_obj_sorted), std::end(interface_obj_sorted), interface_bitrate_cmp);
|
std::sort(std::begin(interface_obj_sorted), std::end(interface_obj_sorted), interface_bitrate_cmp);
|
||||||
}
|
}
|
||||||
|
uint8_t byteOLD;
|
||||||
void serial_write(uint8_t byte) {
|
void serial_write(uint8_t byte) {
|
||||||
#if HAS_BLUETOOTH || HAS_BLE == true
|
#if HAS_BLUETOOTH || HAS_BLE == true
|
||||||
if (bt_state != BT_STATE_CONNECTED) {
|
if (bt_state != BT_STATE_CONNECTED) {
|
||||||
Serial.write(byte);
|
Serial.write(byte);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
|
|
||||||
SerialBT.write(byte);
|
SerialBT.write(byte);
|
||||||
#if MCU_VARIANT == MCU_NRF52 && HAS_BLE
|
//BD need bluettoh disconnected to use rNodeConf properly so this debug doesnt bother it
|
||||||
|
/*if (byte == 0xC0){
|
||||||
|
Serial.print(' '); // space-separated stream}
|
||||||
|
};
|
||||||
|
if (byteOLD ==0xC0 && byte == 0x00){
|
||||||
|
Serial.print("\r\n");
|
||||||
|
};
|
||||||
|
if (byte < 0x10) Serial.print('0');
|
||||||
|
Serial.print(byte, HEX);
|
||||||
|
byteOLD=byte;
|
||||||
|
*/
|
||||||
|
//BD
|
||||||
|
#if MCU_VARIANT == MCU_NRF52 && HAS_BLE
|
||||||
// This ensures that the TX buffer is flushed after a frame is queued in serial.
|
// This ensures that the TX buffer is flushed after a frame is queued in serial.
|
||||||
// serial_in_frame is used to ensure that the flush only happens at the end of the frame
|
// serial_in_frame is used to ensure that the flush only happens at the end of the frame
|
||||||
if (serial_in_frame && byte == FEND) { SerialBT.flushTXD(); serial_in_frame = false; }
|
if (serial_in_frame && byte == FEND) { SerialBT.flushTXD(); serial_in_frame = false; }
|
||||||
|
@ -762,8 +791,8 @@ void serial_write(uint8_t byte) {
|
||||||
|
|
||||||
void escaped_serial_write(uint8_t byte) {
|
void escaped_serial_write(uint8_t byte) {
|
||||||
if (byte == FEND) { serial_write(FESC); byte = TFEND; }
|
if (byte == FEND) { serial_write(FESC); byte = TFEND; }
|
||||||
if (byte == FESC) { serial_write(FESC); byte = TFESC; }
|
if (byte == FESC) { serial_write(FESC); byte = TFESC; }
|
||||||
serial_write(byte);
|
serial_write(byte);
|
||||||
}
|
}
|
||||||
|
|
||||||
void kiss_indicate_reset() {
|
void kiss_indicate_reset() {
|
||||||
|
@ -1277,6 +1306,10 @@ void setTXPower(RadioInterface* radio, int txp) {
|
||||||
if (model == MODEL_C7) radio->setTxPower(txp, PA_OUTPUT_RFO_PIN);
|
if (model == MODEL_C7) radio->setTxPower(txp, PA_OUTPUT_RFO_PIN);
|
||||||
if (model == MODEL_CA) radio->setTxPower(txp, PA_OUTPUT_PA_BOOST_PIN);
|
if (model == MODEL_CA) radio->setTxPower(txp, PA_OUTPUT_PA_BOOST_PIN);
|
||||||
|
|
||||||
|
if (model == MODEL_CD) radio->setTxPower(txp, PA_OUTPUT_RFO_PIN);
|
||||||
|
if (model == MODEL_CE) radio->setTxPower(txp, PA_OUTPUT_RFO_PIN);
|
||||||
|
|
||||||
|
|
||||||
if (model == MODEL_D4) radio->setTxPower(txp, PA_OUTPUT_PA_BOOST_PIN);
|
if (model == MODEL_D4) radio->setTxPower(txp, PA_OUTPUT_PA_BOOST_PIN);
|
||||||
if (model == MODEL_D9) radio->setTxPower(txp, PA_OUTPUT_PA_BOOST_PIN);
|
if (model == MODEL_D9) radio->setTxPower(txp, PA_OUTPUT_PA_BOOST_PIN);
|
||||||
|
|
||||||
|
@ -1517,7 +1550,7 @@ bool eeprom_product_valid() {
|
||||||
#if PLATFORM == PLATFORM_ESP32
|
#if PLATFORM == PLATFORM_ESP32
|
||||||
if (rval == PRODUCT_RNODE || rval == BOARD_RNODE_NG_20 || rval == BOARD_RNODE_NG_21 || rval == PRODUCT_HMBRW || rval == PRODUCT_TBEAM || rval == PRODUCT_T32_10 || rval == PRODUCT_T32_20 || rval == PRODUCT_T32_21 || rval == PRODUCT_H32_V2 || rval == PRODUCT_H32_V3 || rval == PRODUCT_TDECK_V1 || rval == PRODUCT_TBEAM_S_V1 || rval == PRODUCT_H_W_PAPER || rval == PRODUCT_XIAO_S3) {
|
if (rval == PRODUCT_RNODE || rval == BOARD_RNODE_NG_20 || rval == BOARD_RNODE_NG_21 || rval == PRODUCT_HMBRW || rval == PRODUCT_TBEAM || rval == PRODUCT_T32_10 || rval == PRODUCT_T32_20 || rval == PRODUCT_T32_21 || rval == PRODUCT_H32_V2 || rval == PRODUCT_H32_V3 || rval == PRODUCT_TDECK_V1 || rval == PRODUCT_TBEAM_S_V1 || rval == PRODUCT_H_W_PAPER || rval == PRODUCT_XIAO_S3) {
|
||||||
#elif PLATFORM == PLATFORM_NRF52
|
#elif PLATFORM == PLATFORM_NRF52
|
||||||
if (rval == PRODUCT_RAK4631 || rval == PRODUCT_HELTEC_T114 || rval == PRODUCT_OPENCOM_XL || rval == PRODUCT_TECHO || rval == PRODUCT_HMBRW) {
|
if (rval == PRODUCT_RAK4631 || rval == PRODUCT_HELTEC_T114 || rval == PRODUCT_HELTEC_MESHP || rval == PRODUCT_OPENCOM_XL || rval == PRODUCT_TECHO || rval == PRODUCT_HMBRW) {
|
||||||
#else
|
#else
|
||||||
if (false) {
|
if (false) {
|
||||||
#endif
|
#endif
|
||||||
|
@ -1567,6 +1600,8 @@ bool eeprom_model_valid() {
|
||||||
if (model == MODEL_C8) {
|
if (model == MODEL_C8) {
|
||||||
#elif BOARD_MODEL == BOARD_HELTEC_T114
|
#elif BOARD_MODEL == BOARD_HELTEC_T114
|
||||||
if (model == MODEL_C6 || model == MODEL_C7) {
|
if (model == MODEL_C6 || model == MODEL_C7) {
|
||||||
|
#elif BOARD_MODEL == BOARD_HELTEC_MESHP
|
||||||
|
if (model == MODEL_CD || model == MODEL_CE) {
|
||||||
#elif BOARD_MODEL == BOARD_RAK4631
|
#elif BOARD_MODEL == BOARD_RAK4631
|
||||||
if (model == MODEL_11 || model == MODEL_12 || model == MODEL_13 || model == MODEL_14) {
|
if (model == MODEL_11 || model == MODEL_12 || model == MODEL_13 || model == MODEL_14) {
|
||||||
#elif BOARD_MODEL == BOARD_OPENCOM_XL
|
#elif BOARD_MODEL == BOARD_OPENCOM_XL
|
||||||
|
|
2
board_config.h
Normal file
2
board_config.h
Normal file
|
@ -0,0 +1,2 @@
|
||||||
|
#pragma once
|
||||||
|
#define BOARD_MODEL BOARD_HELTEC_MESHP
|
Loading…
Add table
Add a link
Reference in a new issue